Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ROS live cam test fixes #3098

Merged
merged 1 commit into from
May 14, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 13 additions & 13 deletions realsense2_camera/test/live_camera/test_camera_aligned_tests.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,17 +46,17 @@
'device_type': 'D455',
'enable_color':'true',
'enable_depth':'true',
'depth_module.profile':'848x480x30',
'rgb_camera.profile':'640x480x30',
'depth_module.depth_profile':'848x480x30',
'rgb_camera.color_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',
'depth_module.depth_profile':'848x480x30',
'rgb_camera.color_profile':'640x480x30',
'align_depth.enable':'true'
}
'''
Expand Down Expand Up @@ -112,7 +112,7 @@ def test_camera_align_depth_color(self,launch_descr_with_parameters):
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_string_param('rgb_camera.color_profile', '1280x720x30')
self.set_bool_param('enable_color', True)
themes[0]['width'] = 1280
themes[0]['height'] = 720
Expand All @@ -132,26 +132,26 @@ def test_camera_align_depth_color(self,launch_descr_with_parameters):
'device_type': 'D455',
'enable_color':'true',
'enable_depth':'true',
'depth_module.profile':'848x480x30',
'rgb_camera.profile':'640x480x30',
'depth_module.depth_profile':'848x480x30',
'rgb_camera.color_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',
'depth_module.depth_profile':'848x480x30',
'rgb_camera.color_profile':'640x480x30',
'align_depth.enable':'true'
}
test_params_all_profiles_d435i = {
'camera_name': 'D435I',
'device_type': 'D435I',
'enable_color':'true',
'enable_depth':'true',
'depth_module.profile':'848x480x30',
'rgb_camera.profile':'640x480x30',
'depth_module.depth_profile':'848x480x30',
'rgb_camera.color_profile':'640x480x30',
'align_depth.enable':'true'
}

Expand Down Expand Up @@ -236,8 +236,8 @@ def test_camera_all_align_depth_color(self,launch_descr_with_parameters):
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_string_param('rgb_camera.color_profile', color_profile)
self.set_string_param('depth_module.depth_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)
Expand Down
13 changes: 10 additions & 3 deletions realsense2_camera/test/live_camera/test_camera_fps_tests.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,13 +93,17 @@ def test_camera_test_fps(self,launch_descr_with_parameters):
}
]
profiles = test_profiles[params['camera_name']]['depth_test_profiles']
self.spin_for_time(wait_time=0.5)
assert self.set_bool_param('enable_color', False)
self.spin_for_time(wait_time=0.5)

for profile in profiles:
print("Testing profile: ", profile)
themes[0]['expected_fps_in_hz'] = float(profile.split('x')[2])
assert self.set_string_param('depth_module.profile', profile)
assert self.set_string_param('depth_module.depth_profile', profile)
self.spin_for_time(wait_time=0.5)
assert self.set_bool_param('enable_depth', True)
self.spin_for_time(0.5)
self.spin_for_time(wait_time=0.5)
ret = self.run_test(themes, timeout=25.0)
assert ret[0], ret[1]
assert self.process_data(themes)
Expand All @@ -111,12 +115,15 @@ def test_camera_test_fps(self,launch_descr_with_parameters):
}
]
assert self.set_bool_param('enable_depth', False)
self.spin_for_time(wait_time=0.5)
profiles = test_profiles[params['camera_name']]['color_test_profiles']
for profile in profiles:
print("Testing profile: ", profile)
themes[0]['expected_fps_in_hz'] = float(profile.split('x')[2])
assert self.set_string_param('rgb_camera.profile', profile)
assert self.set_string_param('rgb_camera.color_profile', profile)
self.spin_for_time(wait_time=0.5)
assert self.set_bool_param('enable_color', True)
self.spin_for_time(wait_time=0.5)
ret = self.run_test(themes, timeout=25.0)
assert ret[0], ret[1]
assert self.process_data(themes)
Expand Down
37 changes: 24 additions & 13 deletions realsense2_camera/test/live_camera/test_d415_basic_tests.py
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,6 @@ def test_D415_Change_Resolution(self,launch_descr_with_parameters):
config["Infrared2"]["default_profile2"] = "1280x720x6"

cap = [
#['Infrared1', '1920x1080x25', 'Y8'],
#['Infrared1', '1920x1080x15', 'Y16'],
['Infrared', '848x100x100', 'BGRA8'],
['Infrared', '848x480x60', 'RGBA8'],
['Infrared', '640x480x60', 'RGBA8'],
Expand All @@ -89,16 +87,23 @@ def test_D415_Change_Resolution(self,launch_descr_with_parameters):
['Infrared', '480x270x60', 'BGRA8'],
['Infrared', '480x270x60', 'RGB8'],
['Infrared', '424x240x60', 'BGRA8'],

['Infrared1', '848x100x100', 'Y8'],
['Infrared1', '848x480x6', 'Y8'],
['Infrared1', '1920x1080x25', 'Y16'],
['Infrared2', '848x100x100', 'Y8'],
['Infrared2', '848x480x6', 'Y8'],
['Infrared2', '1920x1080x25', 'Y16'],
]

try:
'''
initialize, run and check the data
'''
self.init_test("RsTest"+params['camera_name'])
self.spin_for_time(wait_time=1.0)
self.create_param_ifs(get_node_heirarchy(params))

self.spin_for_time(wait_time=1.0)

for key in cap:
profile_type = key[0]
profile = key[1]
Expand All @@ -108,21 +113,22 @@ def test_D415_Change_Resolution(self,launch_descr_with_parameters):
themes[0]['width'] = int(profile.split('x')[0])
themes[0]['height'] = int(profile.split('x')[1])
#'''
self.disable_all_streams()
if themes[0]['width'] == int(config[profile_type]["default_profile2"].split('x')[0]):
self.set_string_param(config[profile_type]["profile"], config[profile_type]["default_profile1"])
else:
self.set_string_param(config[profile_type]["profile"], config[profile_type]["default_profile2"])
self.set_bool_param(config[profile_type]["param"], True)
self.disable_all_params()
#self.set_string_param("depth_profile", "640x480x6")
#self.set_bool_param("enable_depth", True)
#'''
self.spin_for_time(wait_time=0.2)
self.spin_for_time(wait_time=1.0)

self.set_string_param(config[profile_type]["profile"], profile)
self.spin_for_time(wait_time=1.0)
self.set_string_param(config[profile_type]["format"], format)
self.spin_for_time(wait_time=1.0)
self.set_bool_param(config[profile_type]["param"], True)
self.spin_for_time(wait_time=1.0)
try:
ret = self.run_test(themes, timeout=5.0)
ret = self.run_test(themes, timeout=10.0)
assert ret[0], ret[1]
assert self.process_data(themes), " ".join(key) + " failed"
num_passed += 1
Expand All @@ -144,13 +150,18 @@ def test_D415_Change_Resolution(self,launch_descr_with_parameters):
assert False, " Tests failed"


def disable_all_params(self):
'''
def disable_all_streams(self):

self.set_bool_param('enable_color', False)
self.spin_for_time(wait_time=1.0)
self.set_bool_param('enable_depth', False)
self.spin_for_time(wait_time=1.0)
self.set_bool_param('enable_infra', False)
self.spin_for_time(wait_time=1.0)
self.set_bool_param('enable_infra1', False)
self.spin_for_time(wait_time=1.0)
self.set_bool_param('enable_infra2', False)
'''
self.spin_for_time(wait_time=1.0)

pass

10 changes: 7 additions & 3 deletions realsense2_camera/test/live_camera/test_d455_basic_tests.py
Original file line number Diff line number Diff line change
Expand Up @@ -78,13 +78,17 @@ def test_D455_Change_Resolution(self,launch_descr_with_parameters):
self.init_test("RsTest"+params['camera_name'])
self.wait_for_node(params['camera_name'])
self.create_param_ifs(get_node_heirarchy(params))
#assert self.set_bool_param('enable_color', False)
assert self.set_string_param('rgb_camera.profile', '640x480x30')
self.spin_for_time(0.5)
assert self.set_bool_param('enable_color', False)
self.spin_for_time(0.5)
assert self.set_string_param('rgb_camera.color_profile', '640x480x30')
self.spin_for_time(0.5)
assert self.set_bool_param('enable_color', True)
self.spin_for_time(0.5)
ret = self.run_test(themes)
assert ret[0], ret[1]
assert self.process_data(themes)
self.set_string_param('rgb_camera.profile', '1280x800x5')
self.set_string_param('rgb_camera.color_profile', '1280x800x5')
self.set_bool_param('enable_color', True)
themes[0]['width'] = 1280
themes[0]['height'] = 800
Expand Down
10 changes: 5 additions & 5 deletions realsense2_camera/test/utils/pytest_live_camera_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,11 +24,11 @@

def get_profile_config(camera_name):
config = {
"Color":{"profile":"rgb_camera.profile", "format":'rgb_camera.color_format', "param":"enable_color", "topic":camera_name+'/color/image_raw',},
"Depth":{"profile":"depth_module.profile", "format":'depth_module.depth_format', "param":"enable_depth", 'topic':camera_name+'/depth/image_rect_raw'},
"Infrared":{"profile":"depth_module.profile", "format":'depth_module.infra_format', "param":"enable_infra", 'topic':camera_name+'/infra/image_rect_raw'},
"Infrared1":{"profile":"depth_module.profile", "format":'depth_module.infra1_format',"param":"enable_infra1", 'topic':camera_name+'/infra/image_rect_raw'},
"Infrared2":{"profile":"depth_module.profile", "format":'depth_module.infra2_format',"param":"enable_infra2", 'topic':camera_name+'/infra/image_rect_raw'},
"Color":{"profile":"rgb_camera.color_profile", "format":'rgb_camera.color_format', "param":"enable_color", "topic":camera_name+'/color/image_raw',},
"Depth":{"profile":"depth_module.depth_profile", "format":'depth_module.depth_format', "param":"enable_depth", 'topic':camera_name+'/depth/image_rect_raw'},
"Infrared":{"profile":"depth_module.infra_profile", "format":'depth_module.infra_format', "param":"enable_infra", 'topic':camera_name+'/infra/image_rect_raw'},
"Infrared1":{"profile":"depth_module.infra_profile", "format":'depth_module.infra1_format',"param":"enable_infra1", 'topic':camera_name+'/infra1/image_rect_raw'},
"Infrared2":{"profile":"depth_module.infra_profile", "format":'depth_module.infra2_format',"param":"enable_infra2", 'topic':camera_name+'/infra2/image_rect_raw'},
}
return config

Expand Down
Loading