@@ -50,10 +50,10 @@ def generate_launch_description():
5050 'encoding_desired' : 'rgb8' ,
5151 }],
5252 remappings = [
53- ('camera_info' , 'front_stereo_camera/right_rgb/camerainfo ' ),
54- ('image' , 'front_stereo_camera/right_rgb/image_raw ' ),
55- ('resize/camera_info' , 'front_stereo_camera/right_rgb/camerainfo_resize ' ),
56- ('resize/image' , 'front_stereo_camera/right_rgb /image_resize' )]
53+ ('camera_info' , 'front_stereo_camera/right/camera_info ' ),
54+ ('image' , 'front_stereo_camera/right/image_rect_color ' ),
55+ ('resize/camera_info' , 'front_stereo_camera/right/camera_info_resize ' ),
56+ ('resize/image' , 'front_stereo_camera/right /image_resize' )]
5757 )
5858
5959 image_resize_node_left = ComposableNode (
@@ -66,10 +66,10 @@ def generate_launch_description():
6666 'encoding_desired' : 'rgb8' ,
6767 }],
6868 remappings = [
69- ('camera_info' , 'front_stereo_camera/left_rgb/camerainfo ' ),
70- ('image' , 'front_stereo_camera/left_rgb/image_raw ' ),
71- ('resize/camera_info' , 'front_stereo_camera/left_rgb/camerainfo_resize ' ),
72- ('resize/image' , 'front_stereo_camera/left_rgb /image_resize' )]
69+ ('camera_info' , 'front_stereo_camera/left/camera_info ' ),
70+ ('image' , 'front_stereo_camera/left/image_rect_color ' ),
71+ ('resize/camera_info' , 'front_stereo_camera/left/camera_info_resize ' ),
72+ ('resize/image' , 'front_stereo_camera/left /image_resize' )]
7373 )
7474
7575 disparity_node = ComposableNode (
@@ -80,11 +80,11 @@ def generate_launch_description():
8080 'threshold' : threshold ,
8181 'input_layer_width' : 960 ,
8282 'input_layer_height' : 576 }],
83- remappings = [('left/image_rect' , 'front_stereo_camera/left_rgb /image_resize' ),
83+ remappings = [('left/image_rect' , 'front_stereo_camera/left /image_resize' ),
8484 ('left/camera_info' ,
85- 'front_stereo_camera/left_rgb/camerainfo_resize ' ),
86- ('right/image_rect' , 'front_stereo_camera/right_rgb /image_resize' ),
87- ('right/camera_info' , 'front_stereo_camera/right_rgb/camerainfo_resize ' )])
85+ 'front_stereo_camera/left/camera_info_resize ' ),
86+ ('right/image_rect' , 'front_stereo_camera/right /image_resize' ),
87+ ('right/camera_info' , 'front_stereo_camera/right/camera_info_resize ' )])
8888
8989 pointcloud_node = ComposableNode (
9090 package = 'isaac_ros_stereo_image_proc' ,
@@ -93,10 +93,10 @@ def generate_launch_description():
9393 'use_color' : True ,
9494 'unit_scaling' : 1.0
9595 }],
96- remappings = [('left/image_rect_color' , 'front_stereo_camera/left_rgb /image_resize' ),
96+ remappings = [('left/image_rect_color' , 'front_stereo_camera/left /image_resize' ),
9797 ('left/camera_info' ,
98- 'front_stereo_camera/left_rgb/camerainfo_resize ' ),
99- ('right/camera_info' , 'front_stereo_camera/right_rgb/camerainfo_resize ' )])
98+ 'front_stereo_camera/left/camera_info_resize ' ),
99+ ('right/camera_info' , 'front_stereo_camera/right/camera_info_resize ' )])
100100
101101 container = ComposableNodeContainer (
102102 name = 'disparity_container' ,
0 commit comments