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

Running rtabmap on bag of rgb and depth images

asked 2019-01-24 15:34:25 -0500

Avner gravatar image

updated 2019-01-24 15:37:26 -0500

jayess gravatar image

Hi,

I want to run ros rtabmap on a bag of rgb and depth images, with the following topics:

rostopic  list
/camera/depth/camera_info
/camera/depth/image
/camera/rgb/camera_info
/camera/rgb/image_color

I am using the well known canned bag rgbd_dataset_freiburg1_xyz as a reference example. This bag has the following topics:

rosbag info /mnt/hdd3/avnerm/avner/slam/data/rgbd_dataset_freiburg1_xyz/rgbd_dataset_freiburg1_xyz.bag
...
topics:      /camera/depth/camera_info
             /camera/depth/image      
             /camera/rgb/camera_info  
             /camera/rgb/image_color  
             /cortex_marker_array     
             /imu                     
             /tf

In my bag I don't have /imu, /tf topics.

To get the program to flow, I added the following transforms. I added the transform with 0 values for x,y,z,rot,pitch,yaw (i.e. no effect), except for the yaw argument to align the orientation of 3d points with the image

<node pkg="tf" type="static_transform_publisher" name="openni_rgb_optical_frame_to_world" args="0 0 0 0.0 0 -$(arg pi) /openni_rgb_optical_frame /world 100" />
<node pkg="tf" type="static_transform_publisher" name="world_to_kinect" args="0.0 0.0 0.0 0.0 0.0 0.0 /world /kinect 100" />
<node pkg="tf" type="static_transform_publisher" name="world_to_map" args="0.0 0.0 0.0 0.0 0.0 0.0 /world /map 100" />

If I just play my bag, I can see in rviz the images (rgb, depth) and the 3d points (via /voxel_cloud), but in local frame coordinates. With these tf nodes the rtabmap runs, but the /rtabmap/mapData shows incorrect - the 3d points are just laid on top of each other without a proper 3d model.

I created a bag rgbd_dataset_freiburg1_xyz_no_tf.bag without the topics: /cortex_marker_array /imu /tf, (and replaced with static transforms)

With this setting, rtabmap creates the mapData incorrectly as well.

So it looks like the launch file that I am using from here requires the topics that were filtered above.

My questions:

  • Can rtabmap handle a bag with just rgb and depth images?
  • Is there an example canned bag that only uses rgb and depth images?

Thanks,

Avner

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2019-02-11 14:01:11 -0500

Avner gravatar image

I was able to run ros rtabmap on a bag of rgb and depth images.

The solution was to follow the guidelines in here.

I also had to run static_transform_publisher and produce the following static transformations:

  • camera_link camera_depth_frame
  • camera_link camera_rgb_frame
  • camera_depth_frame camera_depth_optical_frame
  • camera_rgb_frame camera_rgb_optical_frame
  • base_link camera_link
  • base_link base_scan
  • world map
edit flag offensive delete link more
2

answered 2019-01-28 10:23:56 -0500

matlabbe gravatar image

It is possible to map from a rosbag containing only image topics. If we break down to only minimal info from this launch file, we could have something like this with the topics you specified:

  <launch>
  <param name="use_sim_time" type="bool" value="True"/>

  <arg name="pi/2" value="1.5707963267948966" />
  <arg name="optical_rotate" value="0 0 0 -$(arg pi/2) 0 -$(arg pi/2)" />
  <node pkg="tf" type="static_transform_publisher" name="camera_base_link"
        args="$(arg optical_rotate) base_link camera_link 100" />  

  <group ns="rtabmap">

    <!-- Odometry -->
    <node pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen">
      <remap from="rgb/image"       to="/camera/rgb/image_color"/>
      <remap from="depth/image"     to="/camera/depth/image"/>
      <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>
      <param name="frame_id" type="string" value="base_link"/>
    </node>

    <!-- SLAM -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
      <param name="subscribe_depth" type="bool" value="true"/>  
      <param name="frame_id" type="string" value="base_link"/>

      <remap from="rgb/image" to="/camera/rgb/image_color"/>
      <remap from="depth/image" to="/camera/depth/image"/>
      <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>
      <remap from="odom" to="odom"/>
    </node>

  </group>
  </launch>

Replace camera_link by the frame contained in the /camera/rgb/image_color topic. Then play the bag:

$ roslaunch example_above.launch
$ rosbag play --clock recorded.bag
edit flag offensive delete link more

Comments

Thanks. This helped me to find the solution to my problem (see below)

Avner gravatar image Avner  ( 2019-02-11 14:01:55 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-01-24 15:34:25 -0500

Seen: 1,863 times

Last updated: Feb 11 '19