Skip to content

Commit

Permalink
Merge PR IntelRealSense#2865 from PrasRsRos: add live camera tests
Browse files Browse the repository at this point in the history
  • Loading branch information
SamerKhshiboun authored Oct 5, 2023
2 parents 7762d8d + 8e499f1 commit 8de679b
Show file tree
Hide file tree
Showing 15 changed files with 1,896 additions and 73 deletions.
30 changes: 30 additions & 0 deletions realsense2_camera/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -304,6 +304,36 @@ if(BUILD_TESTING)
)
endforeach()
endforeach()

unset(_pytest_folders)

set(rs_query_cmd "rs-enumerate-devices -s")
execute_process(COMMAND bash -c ${rs_query_cmd}
WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}
RESULT_VARIABLE rs_result
OUTPUT_VARIABLE RS_DEVICE_INFO)
message(STATUS "rs_device_info:")
message(STATUS "${RS_DEVICE_INFO}")
if((RS_DEVICE_INFO MATCHES "D455") OR (RS_DEVICE_INFO MATCHES "D415") OR (RS_DEVICE_INFO MATCHES "D435"))
message(STATUS "D455 device found")
set(_pytest_live_folders
test/live_camera
)
endif()

foreach(test_folder ${_pytest_live_folders})
file(GLOB files "${test_folder}/test_*.py")
foreach(file ${files})

get_filename_component(_test_name ${file} NAME_WE)
ament_add_pytest_test(${_test_name} ${file}
APPEND_ENV PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR}:${CMAKE_SOURCE_DIR}/test/utils:${CMAKE_SOURCE_DIR}/launch:${CMAKE_SOURCE_DIR}/scripts
TIMEOUT 500
WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}
)
endforeach()
endforeach()

endif()

# Ament exports
Expand Down
3 changes: 2 additions & 1 deletion realsense2_camera/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@
<test_depend>sensor_msgs_py</test_depend>
<test_depend>python3-requests</test_depend>
<test_depend>tf2_ros_py</test_depend>

<test_depend>ros2topic</test_depend>

<exec_depend>launch_ros</exec_depend>
<build_depend>ros_environment</build_depend>

Expand Down
31 changes: 28 additions & 3 deletions realsense2_camera/test/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,32 @@ The below command finds the test with the name test_static_tf_1 in realsense2_ca

pytest-3 -s -k test_static_tf_1 realsense2_camera/test/

### Points to be noted while writing pytests
The tests that are in one file are nromally run in parallel. So if there are multiple tests in one file, the system capacity can influence the test execution. It's recomended to have 3-4 tests in file, more than that can affect the test results due to delays.

### Marking tests as regression tests
Some of the tests, especially the live tests with multiple runs, for e.g., all profile tests (test_camera_all_profile_tests.py) take a long time. Such tests are marked are skipped with condition so that "colcon test" skips it.
If a user wants to add a test to this conditional skip, user can add by adding a marker as below.

@pytest.mark.skipif (os.getenv('RS_ROS_REGRESSION', "not found") == "not found",reason="Regression is not enabled, define RS_ROS_REGRESSION")

### Running skipped regression tests
1. Set the environment variable RS_ROS_REGRESSION as 1 and run the "colcon test"
2. pytest example:
RS_ROS_REGRESSION=1 PYTHONPATH=$PYTHONPATH:$PWD/realsense2_camera/test/utils:$PWD/realsense2_camera//launch:$PWD/realsense2_camera//scripts pytest-3 -s realsense2_camera/test/live_camera/test_camera_aligned_tests.py -k test_camera_align_depth_color_all -m d415

## Points to be noted while writing pytests
The tests that are in one file are normally run in parallel, there could also be changes in the pytest plugin. So if there are multiple tests in one file, the system capacity can influence the test execution. It's recomended to have 3-4 tests in file, more than that can affect the test results due to delays.
### Passing/changing parameters
The parameters passed while creating the node can be initialized individually for each test, please see the test_parameterized_template example for reference. The default values are taken from rs_launch.py and the passed parameters are used for overriding the default values. The parameters that can be dynamically modified can be changed using the param interface provided. However, the function create_param_ifs has to be called to create this interface. Please see the test_d455_basic_tests.py for reference. There are specific functions to change the string, integer and bool parameters, the utils can be extended if any more types are needed.
### Difference in setting the bool parameters
There is a difference between setting the default values of bool parameters and setting them dynamically.
The bool test params are assinged withn quotes as below.
test_params_all_profiles_d455 = {
'camera_name': 'D455',
'device_type': 'D455',
'enable_accel':"True",
'enable_gyro':"True",
'unite_imu_method':1,
}

However the function that implements the setting of bool parameter dynamically takes the python bool datatype. For example:
self.set_bool_param('enable_accel', False)

279 changes: 279 additions & 0 deletions realsense2_camera/test/live_camera/test_camera_aligned_tests.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,279 @@
# Copyright 2023 Intel Corporation. All Rights Reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.


import os
import sys
import itertools


import pytest
import rclpy

from sensor_msgs.msg import Image as msg_Image
from sensor_msgs.msg import Imu as msg_Imu
from sensor_msgs.msg import PointCloud2 as msg_PointCloud2

import numpy as np

sys.path.append(os.path.abspath(os.path.dirname(__file__)+"/../utils"))
import pytest_rs_utils
from pytest_rs_utils import launch_descr_with_parameters
from pytest_rs_utils import delayed_launch_descr_with_parameters
from pytest_rs_utils import get_rosbag_file_path
from pytest_rs_utils import get_node_heirarchy
import pytest_live_camera_utils
from rclpy.parameter import Parameter
from rcl_interfaces.msg import ParameterValue
from rcl_interfaces.srv import SetParameters, GetParameters, ListParameters
from pytest_live_camera_utils import debug_print



test_params_align_depth_color_d455 = {
'camera_name': 'D455',
'device_type': 'D455',
'enable_color':'true',
'enable_depth':'true',
'depth_module.profile':'848x480x30',
'rgb_camera.profile':'640x480x30',
'align_depth.enable':'true'
}
test_params_align_depth_color_d415 = {
'camera_name': 'D415',
'device_type': 'D415',
'enable_color':'true',
'enable_depth':'true',
'depth_module.profile':'848x480x30',
'rgb_camera.profile':'640x480x30',
'align_depth.enable':'true'
}
'''
This test was implemented as a template to set the parameters and run the test.
This directory is not added to the CMakeLists.txt so as to avoid the colcon failure in the
machines that don't have the D455 connected.
1. Only a subset of parameter types are implemented in py_rs_utils, it has to be extended for others
2. After setting the param, rclpy.spin_once may be needed.Test passes even without this though.
'''

@pytest.mark.parametrize("launch_descr_with_parameters",[
pytest.param(test_params_align_depth_color_d455, marks=pytest.mark.d455),
pytest.param(test_params_align_depth_color_d415, marks=pytest.mark.d415),
#pytest.param(test_params_align_depth_color_d435, marks=pytest.mark.d435),
]
,indirect=True)
@pytest.mark.launch(fixture=launch_descr_with_parameters)
class TestCamera_AlignDepthColor(pytest_rs_utils.RsTestBaseClass):
def test_camera_align_depth_color(self,launch_descr_with_parameters):
params = launch_descr_with_parameters[1]
if pytest_live_camera_utils.check_if_camera_connected(params['device_type']) == False:
print("Device not found? : " + params['device_type'])
return
themes = [
{'topic':get_node_heirarchy(params)+'/color/image_raw',
'msg_type':msg_Image,
'expected_data_chunks':1,
'width':640,
'height':480,
},
{'topic':get_node_heirarchy(params)+'/depth/image_rect_raw',
'msg_type':msg_Image,
'expected_data_chunks':1,
'width':848,
'height':480,
},
{'topic':get_node_heirarchy(params)+'/aligned_depth_to_color/image_raw',
'msg_type':msg_Image,
'expected_data_chunks':1,
'width':640,
'height':480,
},
]
try:
'''
initialize, run and check the data
'''
print("Starting camera test...")
self.init_test("RsTest"+params['camera_name'])
self.wait_for_node(params['camera_name'])
self.create_param_ifs(get_node_heirarchy(params))
ret = self.run_test(themes)
assert ret[0], ret[1]
assert self.process_data(themes)
self.set_string_param('rgb_camera.profile', '1280x720x30')
self.set_bool_param('enable_color', True)
themes[0]['width'] = 1280
themes[0]['height'] = 720
themes[2]['width'] = 1280
themes[2]['height'] = 720

ret = self.run_test(themes)
assert ret[0], ret[1]
assert self.process_data(themes)
finally:
#this step is important because the test will fail next time
pytest_rs_utils.kill_realsense2_camera_node()
self.shutdown()

test_params_all_profiles_d455 = {
'camera_name': 'D455',
'device_type': 'D455',
'enable_color':'true',
'enable_depth':'true',
'depth_module.profile':'848x480x30',
'rgb_camera.profile':'640x480x30',
'align_depth.enable':'true'
}
test_params_all_profiles_d415 = {
'camera_name': 'D415',
'device_type': 'D415',
'enable_color':'true',
'enable_depth':'true',
'depth_module.profile':'848x480x30',
'rgb_camera.profile':'640x480x30',
'align_depth.enable':'true'
}
test_params_all_profiles_d435 = {
'camera_name': 'D435',
'device_type': 'D435',
'enable_color':'true',
'enable_depth':'true',
'depth_module.profile':'848x480x30',
'rgb_camera.profile':'640x480x30',
'align_depth.enable':'true'
}


'''
This test was implemented as a template to set the parameters and run the test.
This directory is not added to the CMakeLists.txt so as to avoid the colcon failure in the
machines that don't have the D455 connected.
1. Only a subset of parameter types are implemented in py_rs_utils, it has to be extended for others
2. After setting the param, rclpy.spin_once may be needed.Test passes even without this though.
'''
@pytest.mark.skipif (os.getenv('RS_ROS_REGRESSION', "not found") == "not found",reason="Regression is not enabled, define RS_ROS_REGRESSION")
@pytest.mark.parametrize("launch_descr_with_parameters", [
pytest.param(test_params_all_profiles_d455, marks=pytest.mark.d455),
pytest.param(test_params_all_profiles_d415, marks=pytest.mark.d415),
pytest.param(test_params_all_profiles_d435, marks=pytest.mark.d435),]
,indirect=True)
@pytest.mark.launch(fixture=launch_descr_with_parameters)
class TestCamera_AllAlignDepthColor(pytest_rs_utils.RsTestBaseClass):
def test_camera_all_align_depth_color(self,launch_descr_with_parameters):
skipped_tests = []
failed_tests = []
num_passed = 0
num_failed = 0
params = launch_descr_with_parameters[1]
if pytest_live_camera_utils.check_if_camera_connected(params['device_type']) == False:
print("Device not found? : " + params['device_type'])
return
themes = [
{'topic':get_node_heirarchy(params)+'/color/image_raw',
'msg_type':msg_Image,
'expected_data_chunks':1,
'width':640,
'height':480,
},
{'topic':get_node_heirarchy(params)+'/depth/image_rect_raw',
'msg_type':msg_Image,
'expected_data_chunks':1,
'width':848,
'height':480,
},
{'topic':get_node_heirarchy(params)+'/aligned_depth_to_color/image_raw',
'msg_type':msg_Image,
'expected_data_chunks':1,
'width':640,
'height':480,
},
]
try:
'''
initialize, run and check the data
'''
self.init_test("RsTest"+params['camera_name'])
self.spin_for_time(wait_time=1.0)
cap = pytest_live_camera_utils.get_camera_capabilities(params['device_type'])
if cap == None:
debug_print("Device not found? : " + params['device_type'])
return
self.create_param_ifs(get_node_heirarchy(params))
color_profiles = set([i[1] for i in cap["color_profile"] if i[2] == "RGB8"])
depth_profiles = set([i[1] for i in cap["depth_profile"] if i[0] == "Depth"])
for color_profile in color_profiles:
for depth_profile in depth_profiles:
if depth_profile == color_profile:
continue
print("Testing the alignment of Depth:", depth_profile, " and Color:", color_profile)
self.set_bool_param('enable_color', False)
self.set_bool_param('enable_color', False)
self.set_bool_param('align_depth.enable', False)

themes[0]['width'] = themes[2]['width'] = int(color_profile.split('x')[0])
themes[0]['height'] = themes[2]['height'] = int(color_profile.split('x')[1])
themes[1]['width'] = int(depth_profile.split('x')[0])
themes[1]['height'] = int(depth_profile.split('x')[1])
dfps = int(depth_profile.split('x')[2])
cfps = int(color_profile.split('x')[2])
if dfps > cfps:
fps = cfps
else:
fps = dfps
timeout=100.0/fps
#for the changes to take effect
self.spin_for_time(wait_time=timeout/20)
self.set_string_param('rgb_camera.profile', color_profile)
self.set_string_param('depth_module.profile', depth_profile)
self.set_bool_param('enable_color', True)
self.set_bool_param('enable_color', True)
self.set_bool_param('align_depth.enable', True)
#for the changes to take effect
self.spin_for_time(wait_time=timeout/20)
try:
ret = self.run_test(themes, timeout=timeout)
assert ret[0], ret[1]
assert self.process_data(themes), "".join(str(depth_profile) + " " + str(color_profile)) + " failed"
num_passed += 1
except Exception as e:
exc_type, exc_obj, exc_tb = sys.exc_info()
fname = os.path.split(exc_tb.tb_frame.f_code.co_filename)[1]
print("Test failed")
print("Tested the alignment of Depth:", depth_profile, " and Color:", color_profile, " with timeout ", timeout)
print(e)
print(exc_type, fname, exc_tb.tb_lineno)
num_failed += 1
failed_tests.append("".join(str(depth_profile) + " " + str(color_profile)))

finally:
#this step is important because the test will fail next time
pytest_rs_utils.kill_realsense2_camera_node()
self.shutdown()
print("Tests passed " + str(num_passed))
print("Tests skipped " + str(len(skipped_tests)))
if len(skipped_tests):
debug_print("\nSkipped tests:" + params['device_type'])
debug_print("\n".join(skipped_tests))
print("Tests failed " + str(num_failed))
if len(failed_tests):
print("\nFailed tests:" + params['device_type'])
print("\n".join(failed_tests))

def disable_all_params(self):
self.set_bool_param('enable_color', False)
self.set_bool_param('enable_depth', False)
self.set_bool_param('enable_infra', False)
self.set_bool_param('enable_infra1', False)
self.set_bool_param('enable_infra2', False)

Loading

0 comments on commit 8de679b

Please sign in to comment.