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

Will RTAB-MAP work without /tf topic ?

asked 2016-12-13 08:49:55 -0600

ap gravatar image

updated 2016-12-15 05:44:02 -0600

Hi I have some kinect bags that I'd like to try out with RTAB-MAP but they don't have a " /tf " topic. Will RTAB-MAP work without " /tf " topic ?

Based on the answer below. I tried to use a launch file to run the static_transform_publisher line but I don't seem to be getting a map. The launch file is based on rgbdslam_datasets.launch and 2.5 Kinect. The launch file is below:

<launch>

 <!-- Eg from  http://wiki.ros.org/rtabmap_ros/Tutorials/SetupOnYourRobot - Kinect & rgbdslam_datasets.launch -->

 <!-- Choose visualization -->
   <arg name="rviz" default="true" />
   <arg name="rtabmapviz" default="false" /> 

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


<!-- TF FRAMES -->
  <node pkg="tf" type="static_transform_publisher" name="world_to_map" 
    args="0.0 0.0 0.0 0.0 0.0 0.0 /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_registered/image_raw"/>
      <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>

      <param name="frame_id" type="string" value="camera_link"/>
    </node>


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

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

          <param name="queue_size" type="int" value="10"/> 

          <!-- RTAB-Map's parameters -->
          <param name="RGBD/AngularUpdate" type="string" value="0"/>
          <param name="RGBD/LinearUpdate" type="string" value="0"/>
          <param name="Rtabmap/TimeThr" type="string" value="700"/>
          <param name="Mem/RehearsalSimilarity" type="string" value="0.45"/>
          <param name="RGBD/OptimizeFromGraphEnd" type="string" value="true"/> 

    </node>

   <!-- Visualisation  -->
    <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen">
      <param name="subscribe_depth" type="bool" value="true"/>
      <param name="subscribe_laserScan" type="bool" value="false"/>
      <param name="subscribe_odom_info" type="bool" value="true"/>
      <param name="queue_size" type="int" value="30"/>

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

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

  </group>

  <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(find rtabmap_ros)/launch/config/rgbdslam_datasets.rviz"/>
  <node if="$(arg rviz)" pkg="nodelet" type="nodelet" name="points_xyzrgb" args="standalone rtabmap_ros/point_cloud_xyzrgb">
    <remap from="rgb/image"       to="/camera/rgb/image_color"/>
    <remap from="depth/image"     to="/camera/depth_registered/image_raw"/>
    <remap from="rgb/camera_info" to="/camera/rgb/camera_info"/>
    <remap from="cloud"           to="voxel_cloud" />

    <param name="queue_size" type="int" value="10"/>
    <param name="decimation" type="double" value="4"/>
  </node>

</launch>

The output after launching the file is attached sum1.png sum2.png.

Rqt_graph is below.

image description

tf view_frames says "no tf data received"

In RVIZ I changed world in fixed frame to /camera_link. But still no map, only coordinate frame.

Sorry, not sure what I'm doing wrong here. Thank you

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-12-13 09:54:15 -0600

matlabbe gravatar image

updated 2016-12-19 13:02:42 -0600

No, you should have at least transforms from /base_link to sensor frames. For example, you can look at this file rgbd_launch/launch/kinect_frames.launch to see how Kinect's frames are configured. Then to link to /base_link:

$ rosrun tf static_transform_publisher 0 0 0.2 0 0 0 base_link camera_link 100
$ rosrun tf static_transform_publisher 0 0 0.15 0 0 0 base_link base_scan 100

Here the camera is 20 cm over /base_link and the laser is 15 cm over /base_link.

EDIT

The rgbd_slam dataset launch file assumed some defined TF in the rosbag and have a hacky solution to show both ground truth (/world->/kinect) and estimated trajectory in RVIZ at the same time. Normally, if you have standard topics recorded in your rosbag, you could follow this tutorial. Assuming you don't have any TF in the bag (only /camera/rgb/image_color, /camera/depth_registered/image_raw and /camera/rgb/camera_info):

$ roscore
$ rosparam set use_sim_time true
$ roslaunch rgbd_launch kinect_frames.launch
$ roslaunch rtabmap_ros rtabmap.launch
$ rosbag play --clock recorded.bag

Here kinect_frames.launch will publish /camera_link to rgb and depth camera optical links. By default rtabmap.launch uses camera_link as fixed frame, so nothing to change.

cheers

edit flag offensive delete link more

Comments

Thanks for the reply. So if I understand correctly, I would have to record a new bag file but before I record I should run the rosrun tf static_transform_publisher ... line above to get the correct transform from camera_link to base_link stored in topic /tf ? Thanks

ap gravatar image ap  ( 2016-12-14 05:07:00 -0600 )edit

Either record a new bag while recording these TF or launch these static_transform_publisher at the same time as the bag (make sure you run the bag with --clock option so that time in TF will be the same as the bag).

matlabbe gravatar image matlabbe  ( 2016-12-14 07:51:49 -0600 )edit

Thank you, sorry to bother you. I tried the above but could not get a map. Please see edited question. Thanks

ap gravatar image ap  ( 2016-12-15 05:45:05 -0600 )edit

Thanks, it worked great! Just had to remap rgb_topic:=/camera/rgb/image_color Sorry for the confusion.

ap gravatar image ap  ( 2016-12-20 03:09:38 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2016-12-13 08:49:55 -0600

Seen: 1,961 times

Last updated: Dec 19 '16