ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

I tried the bag with your modified rgbd_mapping.launch. Di you record the bag with only realsense_r200_launch.launch? If yes, the realsense camera node publishes already transforms /realsense_frame->/camera_depth_optical_frame and /realsense_frame->/camera_color_optical_frame. The warning you are getting is because there are static_transform_publishers publishing also the same transforms when launching rgbd_mapping.launch.

Use this:

<!-- Frames: tf  -->
<node pkg="tf" type="static_transform_publisher"  name="base_to_realsense"
      args="0 0 0 -1.5707963 0 -1.5707963 /base_link /realsense_frame 100" />

instead of

<!-- Frames: tf  -->
<node pkg="tf" type="static_transform_publisher"  name="base_to_color"
      args="0 0 0 -1.5707963 0 -1.5707963 /base_link /camera_color_optical_frame 100" /> 
<node pkg="tf" type="static_transform_publisher" name="color_to_depth"
      args="-0.1325 -0.1975 0.0 -1.570796327 0.0 0.0 /camera_color_optical_frame /camera_depth_optical_frame 100" />

So with your rosbag:

$ rosbag info 2016-01-18-16-14-41.bag
topics:      /camera/color/camera_info                  555 msgs    : sensor_msgs/CameraInfo     
             /camera/color/image_raw/compressed         554 msgs    : sensor_msgs/CompressedImage
             /camera/depth/image_raw/compressedDepth    555 msgs    : sensor_msgs/CompressedImage
             /tf                                       1110 msgs    : tf2_msgs/TFMessage

Launch the example like that:

$ roslaunch rgbd_mapping.launch rgb_topic:=/camera/color/image_raw depth_registered_topic:=/camera/depth/image_raw camera_info_topic:=/camera/color/camera_info frame_id:=base_link rtabmap_args:="--delete_db_on_start" estimation:=1 compressed:=true
$ rosparam set use_sim_time true
$ rosbag play --clock 2016-01-18-16-14-41.bag

The warning may apppear on start 2-3 times but after it is ok:

[ INFO] [1453176055.454777214]: rtabmap 0.10.12 started...
[ WARN] [1453176067.382156280, 1453162481.896671693]: odometry: Could not get transform from base_link to camera_color_optical_frame (stamp=1453162481.777381) after 0.100000 seconds ("wait_for_transform_duration"=0.100000)!
[ WARN] [1453176067.479223601, 1453162482.000379765]: odometry: Could not get transform from base_link to camera_color_optical_frame (stamp=1453162481.886188) after 0.100000 seconds ("wait_for_transform_duration"=0.100000)!
[ INFO] [1453176067.531584531]: Odom: quality=0, std dev=1.000000m, update time=0.042757s
[ INFO] [1453176067.700283209]: Odom: quality=30, std dev=0.182574m, update time=0.141564s
[ INFO] [1453176067.835296760]: rtabmap: Rate=1.00s, Limit=0.000s, RTAB-Map=0.3025s, Pub=0.0020s (local map=1, WM=1)
[ INFO] [1453176067.874122050]: Odom: quality=65, std dev=0.124035m, update time=0.150594s

Here some screenshots: image description image description

cheers

I tried the bag with your modified rgbd_mapping.launch. Di Did you record the bag with only realsense_r200_launch.launch? If yes, the realsense camera node publishes already transforms /realsense_frame->/camera_depth_optical_frame and /realsense_frame->/camera_color_optical_frame. The warning you are getting is because there are static_transform_publishers publishing also the same transforms when launching rgbd_mapping.launch.

Use this:

<!-- Frames: tf  -->
<node pkg="tf" type="static_transform_publisher"  name="base_to_realsense"
      args="0 0 0 -1.5707963 0 -1.5707963 /base_link /realsense_frame 100" />

instead of

<!-- Frames: tf  -->
<node pkg="tf" type="static_transform_publisher"  name="base_to_color"
      args="0 0 0 -1.5707963 0 -1.5707963 /base_link /camera_color_optical_frame 100" /> 
<node pkg="tf" type="static_transform_publisher" name="color_to_depth"
      args="-0.1325 -0.1975 0.0 -1.570796327 0.0 0.0 /camera_color_optical_frame /camera_depth_optical_frame 100" />

So with your rosbag:

$ rosbag info 2016-01-18-16-14-41.bag
topics:      /camera/color/camera_info                  555 msgs    : sensor_msgs/CameraInfo     
             /camera/color/image_raw/compressed         554 msgs    : sensor_msgs/CompressedImage
             /camera/depth/image_raw/compressedDepth    555 msgs    : sensor_msgs/CompressedImage
             /tf                                       1110 msgs    : tf2_msgs/TFMessage

Launch the example like that:

$ roslaunch rgbd_mapping.launch rgb_topic:=/camera/color/image_raw depth_registered_topic:=/camera/depth/image_raw camera_info_topic:=/camera/color/camera_info frame_id:=base_link rtabmap_args:="--delete_db_on_start" estimation:=1 compressed:=true
$ rosparam set use_sim_time true
$ rosbag play --clock 2016-01-18-16-14-41.bag

The warning may apppear on start 2-3 times but after it is ok:

[ INFO] [1453176055.454777214]: rtabmap 0.10.12 started...
[ WARN] [1453176067.382156280, 1453162481.896671693]: odometry: Could not get transform from base_link to camera_color_optical_frame (stamp=1453162481.777381) after 0.100000 seconds ("wait_for_transform_duration"=0.100000)!
[ WARN] [1453176067.479223601, 1453162482.000379765]: odometry: Could not get transform from base_link to camera_color_optical_frame (stamp=1453162481.886188) after 0.100000 seconds ("wait_for_transform_duration"=0.100000)!
[ INFO] [1453176067.531584531]: Odom: quality=0, std dev=1.000000m, update time=0.042757s
[ INFO] [1453176067.700283209]: Odom: quality=30, std dev=0.182574m, update time=0.141564s
[ INFO] [1453176067.835296760]: rtabmap: Rate=1.00s, Limit=0.000s, RTAB-Map=0.3025s, Pub=0.0020s (local map=1, WM=1)
[ INFO] [1453176067.874122050]: Odom: quality=65, std dev=0.124035m, update time=0.150594s

Here some screenshots: image description image description

cheers