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

Rtabmap_ros with realsense odometry: Could not get transform from base_link to camera_color_optical_frame

asked 2016-01-15 19:27:23 -0500

sevense77 gravatar image

updated 2016-01-18 18:20:39 -0500

I am trying to use RTABMAP_ROS with realsense as the RGB-D input.

Thanks to the useful tips from the post of http://answers.ros.org/question/21895...

I am able to see the data and get the rtabmap node running, but I am keep getting the warning of

[ WARN] [1452906467.763968588]: odometry: Could not get transform from base_link to camera_color_optical_frame (stamp=1452906467.632809) after 0.100000 seconds ("wait_for_transform_duration"=0.100000)!

and no map was shown in the rtabmapviz.

command used:

roslaunch realsense realsense_r200_launch.launch dHeight:=240 dWidth:=320 dFPS:=30 cHeight:=240 cWidth:=320 cFPS:=30

roslaunch rtabmap_ros 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

My rqt_graph: https://drive.google.com/file/d/0B_NR.. . Thank you very much !

The rosbag recorded are shared here: https://drive.google.com/file/d/0B2pu... Does any body know the reason ?

edit retag flag offensive close merge delete

Comments

1

Can you add the TF tree to your question?
$ rosrun tf view_frames$ evince frames.pdf

matlabbe gravatar image matlabbe  ( 2016-01-15 20:19:57 -0500 )edit

I don't have the right to attach, shared the frames.pdf in google drive: https://drive.google.com/open?id=0B2p...

Thank you very much !

sevense77 gravatar image sevense77  ( 2016-01-16 14:45:22 -0500 )edit

The realsense_frame is not connected to TF tree. What is your launch file, or commands used? Normally, if you have RGB image + Registered depth image + RGB camera info topics and corresponding frames in TF, you should be good to map.

matlabbe gravatar image matlabbe  ( 2016-01-16 15:51:33 -0500 )edit

I just attached the files I used, i thought I was following your advices in http://answers.ros.org/question/21895... Thank you. Maybe I miss something.

sevense77 gravatar image sevense77  ( 2016-01-17 17:23:09 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2016-01-18 22:10:28 -0500

matlabbe gravatar image

updated 2016-01-19 09:31:57 -0500

I tried the bag with your modified rgbd_mapping.launch. 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

edit flag offensive delete link more

Comments

Yes, I recorded the bag with only realsense_r200_launch, it is the default launch file of realsense_ros.

Thank you for your help. Your answer is very clear, thank you !

sevense77 gravatar image sevense77  ( 2016-01-19 20:38:25 -0500 )edit

Hi Mathieu, after following your suggestion above, I still couldn' get the result, Same warning appears. The frame image is https://drive.google.com/file/d/0B2pu... Seems map and odom haven't been linked.

sevense77 gravatar image sevense77  ( 2016-01-20 13:40:02 -0500 )edit

The /map and /odom frames will be published only if odometry is working. Doing it live, you should not use compressed:=true and rosparam set use_sim_time true. You can increase the wait time with argument wait_for_transform:=1 for 1 sec instead of 0.1 sec.

matlabbe gravatar image matlabbe  ( 2016-01-20 14:05:37 -0500 )edit

Thanks, Mathieu. Finally got the live version worked. RTABMAP is awesome. Seems the realsense_ros is not very stable though.

sevense77 gravatar image sevense77  ( 2016-01-20 18:10:06 -0500 )edit

Hey sevense77, how exactly did you get it to work? Because I tried the frame_id thing in the launch file but I am still getting "odometry: Could not get transform from base_link to camera_depth_optical_frame (stamp=1452906467.632809) after 0.100000 seconds ("wait_for_transform_duration"=0.100000)!"

Gabee gravatar image Gabee  ( 2016-08-03 03:35:02 -0500 )edit

I am also getting the error : "rtabmapviz: Could not get transform from odom to camera_link after 1.000000 seconds (for stamp=1470155388.571447)!" . Thanks for the help :)

Gabee gravatar image Gabee  ( 2016-08-03 03:35:49 -0500 )edit

Tutorial http://wiki.ros.org/rtabmap_ros/Tutor... has been updated for RealSense R200

matlabbe gravatar image matlabbe  ( 2016-08-03 11:36:15 -0500 )edit
0

answered 2016-01-17 17:19:49 -0500

sevense77 gravatar image

the launch file of rtabmap_ros https://drive.google.com/open?id=0B_N...

the launch file of realsense https://drive.google.com/open?id=0B_N...

command used:

roslaunch realsense realsense_r200_launch.launch dHeight:=240 dWidth:=320 dFPS:=30 cHeight:=240 cWidth:=320 cFPS:=30

roslaunch rtabmap_ros 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

My rqt_graph: https://drive.google.com/file/d/0B_NR... Thank you very much !

edit flag offensive delete link more

Comments

It is preferred that you edit your main question to put this extra info. At the same time, can you record a small rosbag (5-10 sec)? $ rosbag record /camera/color/image_raw/compressed /camera/depth/image_raw/compressedDepth /camera/color/camera_info /tf

matlabbe gravatar image matlabbe  ( 2016-01-17 20:00:17 -0500 )edit

Thank you for your prompt reply and suggestion. A rosbag has been recoreded and shared in original post.

sevense77 gravatar image sevense77  ( 2016-01-18 18:23:49 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-01-15 19:27:23 -0500

Seen: 4,360 times

Last updated: Jan 19 '16