0
$\begingroup$

Rosanswers logo

Hello,

I'm running Ubuntu 12.04, Ros Hydro, I have rtabmap_ros compiled from source (as per instructions). I am using a stereo camera with (I think) the Stereo B configuration. I have modified the demo_stereo_outdoor.launch file accordingly, by removing the node republishing, remapping to stereo_camera namespace, and set use_sim_time to false. The rtabmap node is running when I launch this file. I also changed base_footprint to base_link.

I also set up a tf broadcaster between base_link frame and camera, and set it to a constant value (0 translation), since I am holding the camera. Now the issue is that all my rtabmap/cloud_map, rtabmap/map rtabmap/path ... (blah blah blah) topics are empty when I echo them. In rviz, my camera frame is moving around with respect to the map frame, but I cannot view the map, the path, or any clouds (optimized or not).

I think the issue could be arising from the following -

  1. rviz file could be incorrectly set up since it is the one being used for the demo stereo outdoor.
  2. tf tree / frame ID's could be incorrect. This is surprising, since my tf tree is - map --> odom --> base_link --> camera, which seems correct to me.

Also, another glitch that is occurring (but should not make a difference), is that I am supplying the camera frame id, which is an optical frame, but pointcloud frames are defined with a different orientation.

  1. Any suggestions on how to solve the mapping issue?
  2. Can anyone confirm what frame I am expected to supply to the node?

Here is my rqt_graph: image description

Here is my tf tree:

image description

Thanks!

[UPDATE]

Hi Mathieu,

Sorry to bother you, my RTAB is now giving me this graph output after setting up my approximate stereo camera pair. I modified the approx params as you mentioned. I added a queue size to the rtabmap, rtabmap optimizer, and rtabmap assembler nodes. Notice how the odometry still seems to be working - I get the position of the camera too. However, I can only view /camera/points2 cloud, not the rtabmap/mapData topics or assembled clouds, etc.

Any suggestions?

I just updated the rqt_graph by adding topics to the display - here it is. It seems to be connected correctly as far as I can tell, but still no output.

Here is my launch file just in case.

<launch>
-->
     <!-- <remap from="left/image_rect"       to="/camera/left/image_rect"/>
     <remap from="right/image_rect"      to="/camera/right/image_rect"/>
     <remap from="left/camera_info"      to="/camera/left/camera_info"/>
     <remap from="right/camera_info"     to="/camera/right/camera_info"/> -->
     <remap from="odom"                  to="/stereo_odometer/odometry"/>

     <param name="frame_id" type="string" value="base_link"/>
     <param name="odom_frame_id" type="string" value="odom"/>

     <param name="queue_size" type="int" value="100"/>
     <!-- <param name="approximate_sync" type="bool" value="true"/> -->
     <param name="approx_sync" type="bool" value="true"/>
     
     <param name="Odom/InlierDistance" type="string" value="0.1"/>
     <param name="Odom/MinInliers" type="string" value="10"/>
     <param name="Odom/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/>
     <param name="Odom/MaxDepth" type="string" value="10"/>
     <!-- <param name="OdomBow/NNDR" type="string" value="0.8"/> -->
     <param name="GFTT/MaxCorners" type="string" value="500"/>
     <param name="GFTT/MinDistance" type="string" value="5"/>
     <param name="Odom/FillInfoData" type="string" value="$(arg rtabmapviz)"/>
  </node>
     <remap from="left/image_rect" to="/camera/left/image_rect_color"/>
     <!-- <remap from="left/image_rect" to="/camera/left/image_rect"/> -->
     <!-- <remap from="right/image_rect" to="/camera/right/image_rect"/> -->
     <remap from="right/image_rect" to="/camera/right/image_rect_color"/>
     <remap from="left/camera_info" to="/camera/left/camera_info"/>
     <remap from="right/camera_info" to="/camera/right/camera_info"/>

     <remap from="odom" to="/stereo_odometer/odometry"/>
     <!-- <remap from="odom" to="/camera/odometry"/> -->

     <param name="queue_size" type="int" value="100"/>
     <param name="approximate_sync" type="bool" value="true"/>
     <param name="approx_sync" type="bool" value="true"/>
     <!-- <param -->
     <param name="stereo_approx_sync" type="bool" value="true"/>
     <!-- RTAB-Map's parameters -->
     <param name="Rtabmap/TimeThr" type="string" value="700"/>
     <param name="Rtabmap/DetectionRate" type="string" value="1"/>
     
     <param name="Kp/WordsPerImage" type="string" value="200"/>
     <param name="Kp/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/>
     <param name="Kp/DetectorStrategy" type="string" value="0"/>   <!-- use SURF -->
     <param name="Kp/NNStrategy" type="string" value="1"/>         <!-- kdTree -->

     <param name="SURF/HessianThreshold" type="string" value="1000"/>

     <param name="LccBow/MaxDepth" type="string" value="5"/>
     <param name="LccBow/MinInliers" type="string" value="10"/>
     <param name="LccBow/InlierDistance" type="string" value="0.02"/>

     <param name="LccReextract/Activated" type="string" value="true"/>
     <param name="LccReextract/MaxWords" type="string" value="500"/>
     
     <!-- Disable graph optimization because we use map_optimizer node below -->
     <!-- <param name="RGBD/ToroIterations" type="string" value="0"/>  -->
     <param name="RGBD/OptimizeIterations" type="string" value="0"/> 
  </node>

  <!-- Optimizing outside rtabmap node makes it able to optimize always the global map -->
  <node pkg="rtabmap_ros" type="map_optimizer" name="map_optimizer">
     <param name="approximate_sync" type="bool" value="true"/>
     <param name="approx_sync" type="bool" value="true"/>
     <param name="queue_size" type="int" value="100"/>
     <!-- <param -->
     <param name="stereo_approx_sync" type="bool" value="true"/>
  </node>
  <node if="$(arg rviz)" pkg="rtabmap_ros" type="map_assembler" name="map_assembler">
     <param name="occupancy_grid" type="bool" value="true"/>
     <remap from="mapData" to="/rtabmap/mapData_optimized"/>
     <remap from="grid_projection_map" to="/rtabmap/map"/>
     <param name="approximate_sync" type="bool" value="true"/>
     <param name="approx_sync" type="bool" value="true"/>
     <!-- <param -->
     <param name="stereo_approx_sync" type="bool" value="true"/>
     <param name="queue_size" type="int" value="100"/>
  <!-- </node> -->
  </node>        
  <!-- Visualisation RTAB-Map -->
  <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_stereo" type="bool" value="true"/>
     <param name="subscribe_odom_info" type="bool" value="true"/>
     <param name="queue_size" type="int" value="10"/>
     <param name="frame_id" type="string" value="base_link"/>
     <remap from="left/image_rect" to="/camera/left/image_rect_color"/>
     <remap from="right/image_rect" to="/camera/right/image_rect_color"/>
     <remap from="left/camera_info" to="/camera/left/camera_info"/>
     <remap from="right/camera_info" to="/camera/right/camera_info"/>
     <remap from="odom_info" to="/odom_info"/>
     <remap from="odom" to="/odometry"/>
     <remap from="mapData" to="mapData_optimized"/>
  </node>
     

There is some redundancy, but it should work all the same.

image description


Originally posted by Tanmay on ROS Answers with karma: 110 on 2015-06-04

Post score: 1

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

  1. In your rqt_graph, the left image and camera info are not shown, are they correctly connected to stereo_img_proc, stereo_odometry and rtabmap? If you are holding your camera, you may do something like a mix of test_stereo_odometry.launch and demo_stereo_outdoor.launch as the Stereo B configuration:

    <!-- Odometry -->
    <node pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="screen">
        <remap from="left/image_rect"       to="left/image_rect"/>
        <remap from="right/image_rect"      to="right/image_rect"/>
        <remap from="left/camera_info"      to="left/camera_info"/>
        <remap from="right/camera_info"     to="right/camera_info"/>
    
        <param name="frame_id" type="string" value="base_link"/>
        <param name="odom_frame_id" type="string" value="odom"/>
        <param name="approx_sync" type="bool" value="false"/>
        <param name="queue_size" type="int" value="5"/>
    
        <param name="Odom/InlierDistance" type="string" value="0.1"/>
        <param name="Odom/MinInliers" type="string" value="10"/>
        <param name="Odom/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/>
        <param name="Odom/MaxDepth" type="string" value="10"/>
    
        <param name="GFTT/MaxCorners" type="string" value="500"/>
        <param name="GFTT/MinDistance" type="string" value="5"/>
    </node>     
    
     <remap from="left/image_rect" to="/stereo_camera/left/image_rect_color"/>
     <remap from="right/image_rect" to="/stereo_camera/right/image_rect"/>
     <remap from="left/camera_info" to="/stereo_camera/left/camera_info"/>
     <remap from="right/camera_info" to="/stereo_camera/right/camera_info"/>
    
     <remap from="odom" to="/stereo_camera/odom"/>
    
     <param name="queue_size" type="int" value="30"/>
    
     <!-- RTAB-Map's parameters -->
     <param name="Rtabmap/TimeThr" type="string" value="700"/>
     <param name="Rtabmap/DetectionRate" type="string" value="1"/>
    
     <param name="Kp/WordsPerImage" type="string" value="200"/>
     <param name="Kp/RoiRatios" type="string" value="0.03 0.03 0.04 0.04"/>
     <param name="Kp/DetectorStrategy" type="string" value="0"/>   <!-- use SURF -->
     <param name="Kp/NNStrategy" type="string" value="1"/>         <!-- kdTree -->
    
     <param name="SURF/HessianThreshold" type="string" value="1000"/>
    
     <param name="LccBow/MaxDepth" type="string" value="5"/>
     <param name="LccBow/MinInliers" type="string" value="10"/>
     <param name="LccBow/InlierDistance" type="string" value="0.02"/>
    
     <param name="LccReextract/Activated" type="string" value="true"/>
     <param name="LccReextract/MaxWords" type="string" value="500"/>
    

Here some screenshots of the connections: image description image description image description

Note that stereo_odometry and rtabmap nodes assume by default that left and right images' (and respective camera infos) timestamps are exact. If your cameras are not synchronized, you can set "stereo_approx_sync" to true for the rtabmap node and "approx_sync" to true for the stereo_odometry node.

  1. the Tf looks ok. The only TF required is a transform from /base_link to the camera link set in the image messages. In RVIZ, make sure you set your fixed frame id to /map.

[UPDATE]

a) The odometry is working, but the quality is quite low. You can try the parameters of this stereo tutorial. In ROS, copy the parameters under stereo_odometry node in your launch file.

b) rtabmap node doesn't seem to be correctly connected, so without inputs, there is no output. Make sure to have the same connections as the second rqt_graph that I have shown above for rtabmap node: /camera/left/camera_info, /camera/right/camera_info, /camera/left/image_rect_color, /camera/right/image_rect and /camera/odom.

cheers


Originally posted by matlabbe with karma: 6409 on 2015-06-07

This answer was ACCEPTED on the original site

Post score: 1


Original comments

Comment by Tanmay on 2015-06-08:
Hi Mathieu,

My stereocamera is synchronized and working fine, no idea why the rqt_graph came out wrong. It turns out the issue wasn't with tf or rviz. There was an issue with the namespaces the nodes were called in and the remaps, for which I noticed you were resolving namespaces in Corewrapper.

Comment by Tanmay on 2015-06-08:
The private nodehandler namespace resolution was giving me some trouble - I explicitly changed it to the topic names and it got rtabmap working. This was before I saw your custom launch file (thanks for that!), I shall try the right group namespaces setup and get back to you -hopefully that works.

Comment by Tanmay on 2015-06-08:
Also, one thing I couldn't get my head around - why is it that left and right image topics are remapped to the rect_color and rect respectively? Is this a necessary feature? Thanks again!

Comment by matlabbe on 2015-06-08:
The right image doesn't have to be RGB because it is only used for disparity computation (only a Grayscale image is required). By using directly the grayscale image, no conversion is done in rtabmap nodes. It is the left image that gives color to generated point clouds of the 3D map.

Comment by Tanmay on 2015-06-08:
I was under the impression both image topics required rect_color. If I understand right - you are only sending rect on the right image, to save on transmitting 1 channel instead of 3?

Comment by Tanmay on 2015-06-08:
Also, thanks for taking the trouble to customize the above launch file in so much detail. I really appreciate it!

Comment by matlabbe on 2015-06-08:
Yes, using 1 channel for the right image saves some transmitting time too.

Comment by Tanmay on 2015-06-25:
Hi Mathieu, thanks for the inputs. I've updated a glitch I'm having in the question - with a screenshot of my rqt_graph and the terminal output rtab is giving me. Any suggestions?

Comment by Tanmay on 2015-06-25:
Hello,

I changed the /left/image_rect_color to /left/image_rect, and it published data on rtabmap/mapData. This data was obviously black and white, so I couldn't verify how well the SLAM is working. It seems your comment and the wiki are in contrast. Do I modify my launch / source to correct this?

Comment by matlabbe on 2015-06-25:
rtabmap can use either grayscale or color images. For some reasons, /camera/left/image_rect_color doesn't seem to be published by stereo_image_proc. Can you verify that?

  1. $rostopic hz /camera/left/image_rect_color

Comment by Tanmay on 2015-06-25:
I updated my rqt_graph - image_rect_color is published. I view this on rviz and image_view / stereo_view as well.

Comment by matlabbe on 2015-06-25:
rtabmap node requires a grayscale image for the right image (normally there is a warning/error shown on the console). You should use /camera/right/image_rect instead of /camera/right/image_rect_color.

Comment by Tanmay on 2015-06-26:
I had tried that configuration - it still doesn't work. It only works when Both image topics are /image_rect, and neither are colored. This results in the problem I mentioned about my map itself being a colorless collection of points.

Comment by matlabbe on 2015-06-26:
Do you have the code built from source? You could put a ROS_WARN at the beginning of the CoreWrapper::StereoCallback() to see if at least the callback is called to see if there is a problem with the synchronization.

Comment by Tanmay on 2015-06-30:
Hi Mathieu,

The stereo callback was always called. When I ran the code entirely on my laptop, it worked alright - it was giving me nice results. What I am also trying to do is run stereo_image_proc on an Odroid, and RTABMAP on my laptop, and have them communicate.

Comment by Tanmay on 2015-06-30:
When I do this, rtabmap/mapData is empty. I think it is very possible that my connection is proving troublesome - I shall go through the documentation on visualization on a remote machine.

Comment by Tanmay on 2015-07-15:
I fiddled around with the launch files, replacing "image_rect_color" and "image_rect" with each other. Somehow the original configuration started working again! Thanks for the help!

Comment by matlabbe on 2015-07-17:
Good to know! cheers

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.