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

Rosbag playback with Rtabmap

asked 2020-05-24 11:57:55 -0500

Exhodus gravatar image

updated 2020-05-24 12:00:00 -0500

gvdhoorn gravatar image

Hi

I've tried everything but I can't get rtabmap working with a rosbag playback, done some searching for a solution, and it should be to set the use_sim_time parameter, which I did but for no avail. Please help! (I'm running Melodic on Jetson Xavier Agx)

I'm using the Rosbag A from here: http://wiki.ros.org/rtabmap_ros/Tutor... (running it with the clock enabled: rosbag play --clock stereo_outdoorA.bag) with this launch file:

<launch>

    <arg name="rtabmapviz" default="true" />
    <param name="use_sim_time" type="bool" value="true"/>

    <node name="republish_left" type="republish" pkg="image_transport" args="compressed 
    in:=/stereo_camera/left/image_raw_throttle raw 
    out:=/stereo/left/image_raw" />
    <node name="republish_right" type="republish" pkg="image_transport" args="compressed 
    in:=/stereo_camera/right/image_raw_throttle raw 
    out:=/stereo/right/image_raw" />

    <remap from="/stereo/left/camera_info"  to="/stereo_camera/left/camera_info_throttle"/>
    <remap from="/stereo/right/camera_info"  to="/stereo_camera/right/camera_info_throttle"/>

    <group ns="stereo">

    <node name="stereo_image_proc" pkg="stereo_image_proc" type="stereo_image_proc" output="screen"  >

       <remap from="/stereo/left/image" to="/stereo/left/image_raw"/>
       <remap from="/stereo/right/image" to="/stereo/right/image_raw"/>
       <param name="prefilter_size"            value="5"/>
           <param name="prefilter_cap"             value="38"/>
           <param name="correlation_window_size"   value="25"/>
           <param name="min_disparity"             value="0"/>
           <param name="disparity_range"           value="64"/>
           <param name="uniqueness_ratio"          value="1.0"/>
           <param name="texture_threshold"         value="2287"/>
           <param name="speckle_size"              value="875"/>
           <param name="speckle_range"             value="25"/>
       <param name="use_sim_time" type="bool" value="true"/>

    </node>

    </group>

<!--
   <node name="stereo_cam" pkg="image_view" type="stereo_view" output="screen" >    
    <remap from="/stereo/left/image" to="/stereo/left/image_raw"/>
    <remap from="/stereo/right/image" to="/stereo/right/image_raw"/>
   </node>
-->  

<!-- rotate camera so z axis is up and x forward. -->
   <arg name="pi/2" value="1.5707963267948966" />
   <node pkg="tf" type="static_transform_publisher" name="camera_base_link" args="0 0 0 -$(arg pi/2) 0 -$(arg pi/2)         camera_link stereo_camera 100" >    
   </node>

   <group ns="rtabmap">   

        <!-- Stereo Odometry -->   
    <node pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="screen">
           <remap from="left/image_rect"       to="/stereo/left/image_rect"/>
           <remap from="right/image_rect"      to="/stereo/right/image_rect"/>
       <remap from="left/camera_info"  to="/stereo_camera/left/camera_info_throttle"/>
           <remap from="right/camera_info"  to="/stereo_camera/right/camera_info_throttle"/>


           <param name="use_sim_time" type="bool" value="true"/>
           <param name="frame_id"                      type="string"   value="camera_link"/>
           <param name="odom_frame_id"                 type="string"   value="odom"/>
      <!-- <param name="approx_sync"                   type="bool"     value="true"/> 
           <param name="queue_size"                    type="int"      value="5"/> -->
       </node>

   </group>
</launch>

Keep getting the following error:

[ WARN] [1590337936.234554157, 1415737845.599683697]: odometry: Could not get transform from camera_link to stereo_camera (stamp=1415737845.429450) after 0.100000 seconds ("wait_for_transform_duration"=0.100000)! Error="Lookup would require extrapolation into the future.  Requested time 1415737845.429450035 but the latest data is at time 1415737830.056226969, when looking up transform from frame [stereo_camera] to frame [camera_link]. canTransform returned after 0.100854 timeout was 0.1."
edit retag flag offensive close merge delete

Comments

Do not use external sites to host .launch files (or similar files). They will go away and then this question will have lost a significant part of its value.

The site even mentions it:

This cl1p will be deleted in in 30 days.

So after 30 days no one will understand what you are referring to.

gvdhoorn gravatar image gvdhoorn  ( 2020-05-24 12:00:58 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-05-25 11:31:13 -0500

matlabbe gravatar image

That bag contains already a TF tree, no need to publish another static transform for the camera. On a robot, the frame_id should be the base frame of the robot. In this case, the base frame is base_footprint. Remove your static transform publisher for camera_link to stereo_link and set the following for stereo_odometry node:

<param name="frame_id" type="string" value="base_footprint"/>

Here is the tf tree in the bag:

$ roscore
$ rosparam set use_sim_time true
$ rosbag play --clock stereo_outdoorA.bag
$ rosrun tf_view_frames
$ evince frames.pdf

image description

(Note that in this example, wheel odometry of azimut was detached of the TF tree because we are using visual odometry instead)

If you don't have a robot urdf, you could look at this example.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-05-24 11:57:55 -0500

Seen: 843 times

Last updated: May 25 '20