diff --git a/config/realsense_d435_depth_sim_config.yaml b/config/realsense_d435_depth_sim_config.yaml index 7611d09221c6441c8f8ff4df013afd45d0ece9bb..f7e14830aee6c5c1d4ee8f2f1f65e87a2d1730d1 100644 --- a/config/realsense_d435_depth_sim_config.yaml +++ b/config/realsense_d435_depth_sim_config.yaml @@ -1,18 +1,19 @@ -rate: 60.0 +rate: 10.0 horizontal_fov: 1.047 -image_width: 640 -image_height: 480 +image_width: 1280 +image_height: 720 image_format: 'R8G8B8' clip_near: 0.2 clip_far: 100.0 noise_type: 'gaussian' noise_mean: 0.0 noise_stddev: 0.007 -image_topic_name: '/camera/color/image_raw' -camera_info_topic_name: '/camera/color/camera_info' -depth_image_topic_name: '/camera/depth/image_rect_raw' -point_cloud_topic_name: '/camera/depth_registered/points' -depth_image_camera_info_topic_name: '/camera/depth/camera_info' +#camera_name passed in xacro is added as prefix to the following topics +image_topic_name: 'color/image_raw' +camera_info_topic_name: 'color/camera_info' +depth_image_topic_name: 'aligned_depth_to_color/image_raw' +point_cloud_topic_name: 'aligned_depth_to_color/points' +depth_image_camera_info_topic_name: 'aligned_depth_to_color/camera_info' point_cloud_cut_off: 0.4 hack_baseline: 0.007 cx_prime: 0.0 diff --git a/launch/realsense_d435_depth_sim.launch b/launch/realsense_d435_depth_sim.launch index 2db47c7bc65a766d7f96ef84ccad3d6b9e867428..d0dbd63174654a285d89e68dcfe72faa57f806b8 100644 --- a/launch/realsense_d435_depth_sim.launch +++ b/launch/realsense_d435_depth_sim.launch @@ -21,7 +21,7 @@ </include> <param name="robot_description" - command="$(find xacro)/xacro --inorder '$(find iri_realsense_camera_description)/urdf/realsense_example.xacro' name:=$(arg node_name)" /> + command="$(find xacro)/xacro --inorder '$(find iri_realsense_depth_description)/urdf/realsense_example.xacro' name:=$(arg node_name)" /> <node pkg="robot_state_publisher" type="robot_state_publisher" name="realsense_tf_broadcaster"> <param name="tf_prefix" type="string" value="$(arg node_name)"/> diff --git a/urdf/realsense.gazebo b/urdf/realsense.gazebo index b822728341bdf1972ddce5f1367bed75551bd3ce..471c443c3495e9a5b3535c3a4521c601437e9de8 100644 --- a/urdf/realsense.gazebo +++ b/urdf/realsense.gazebo @@ -33,11 +33,11 @@ <updateRate>${properties['rate']}</updateRate> <cameraName>${name}</cameraName> <frameName>${name}_color_optical_frame</frameName> - <imageTopicName>${properties['image_topic_name']}</imageTopicName> - <cameraInfoTopicName>${properties['camera_info_topic_name']}</cameraInfoTopicName> - <depthImageTopicName>${properties['depth_image_topic_name']}</depthImageTopicName> - <pointCloudTopicName>${properties['point_cloud_topic_name']}</pointCloudTopicName> - <depthImageCameraInfoTopicName>${properties['depth_image_camera_info_topic_name']}</depthImageCameraInfoTopicName> + <imageTopicName>/${name}/${properties['image_topic_name']}</imageTopicName> + <cameraInfoTopicName>/${name}/${properties['camera_info_topic_name']}</cameraInfoTopicName> + <depthImageTopicName>/${name}/${properties['depth_image_topic_name']}</depthImageTopicName> + <pointCloudTopicName>/${name}/${properties['point_cloud_topic_name']}</pointCloudTopicName> + <depthImageCameraInfoTopicName>/${name}/${properties['depth_image_camera_info_topic_name']}</depthImageCameraInfoTopicName> <pointCloudCutoff>${properties['point_cloud_cut_off']}</pointCloudCutoff> <hackBaseline>${properties['hack_baseline']}</hackBaseline> <CxPrime>${properties['cx_prime']}</CxPrime>