RTAB-map only for mapping

classic Classic list List threaded Threaded
37 messages Options
12
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

matlabbe
Administrator
Hi,

Yes, the map can be reassembled afterward offline with different parameters. The SLAM approach doesn't use a grid map, loop closures are detected by using images-only (and laser scans if available). The grid map is an output (generated from laser scans or projected depth images depending on the inputs and parameters). You can see for example the ROS hand-held tutorial or standalone hand-held tutorial, where it does 6DoF mapping. The tutorial Setup On Your Robot gives also another possible configurations (e.g., rtabmap can be either a 2D SLAM or 3D SLAM approach depending on your application).

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

Shirantha
Hi Sir,

when I tried to map a rosbag file using rtabmap, I keep getting below warnings.


[ WARN] [1490330880.278342196]: TF_OLD_DATA ignoring data from the past for frame odom at time 1.48809e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
[ WARN] [1490330880.278409006]: TF_OLD_DATA ignoring data from the past for frame odom at time 1.48809e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
[ WARN] [1490330880.432851349]: TF_OLD_DATA ignoring data from the past for frame odom at time 1.48809e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
[ WARN] [1490330880.432961642]: TF_OLD_DATA ignoring data from the past for frame odom at time 1.48809e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
[ WARN] [1490330880.434543461]: TF_OLD_DATA ignoring data from the past for frame odom at time 1.48809e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
[ WARN] [1490330880.434715378]: TF_OLD_DATA ignoring data from the past for frame odom at time 1.48809e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
[ WARN] [1490330880.581951988]: TF_OLD_DATA ignoring data from the past for frame odom at time 1.48809e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
[ WARN] [1490330880.582229125]: TF_OLD_DATA ignoring data from the past for frame odom at time 1.48809e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
[ WARN] [1490330880.582857548]: TF_OLD_DATA ignoring data from the past for frame odom at time 1.48809e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
[ WARN] [1490330880.583036318]: TF_OLD_DATA ignoring data from the past for frame odom at time 1.48809e+09 according to authority unknown_publisher


what could be the possible reason for this. i read about this error on ros wiki but I still don't get what it could be. this is the launch file I used.


<launch>
       
  <arg name="rviz" default="false" />
  <arg name="rtabmapviz" default="true" /> 
  <group ns="rtabmap">
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
         
         

         
         

          <remap from="odom" to="/odom"/>
          <remap from="scan" to="/scan"/>

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

         

         
         
         
         
         
         
         
           
         
         
         
         
         
    </node>
       
       
      <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d  $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen">
     
     
     
     
     
   
      <remap from="rgb/image"       to="/camera/rgb/image_rect_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"/>
      <remap from="scan" to="/scan"/>
     
     
     
    </node>
  </group>
</launch>


and this is the bag file I used


path:        2017-02-26-13-12-03.bag
version:     2.0
duration:    10:46s (646s)
start:       Feb 26 2017 13:12:03.96 (1488094923.96)
end:         Feb 26 2017 13:22:50.63 (1488095570.63)
size:        70.7 GB
messages:    84703
compression: none [14351/14351 chunks]
types:       nav_msgs/Odometry       [cd5e73d190d741a2f92e81eda573aca7]
             sensor_msgs/CameraInfo  [c9a58c1b0b154e0e6da7578cb991d214]
             sensor_msgs/Image       [060021388200f6f0f447d0fcd9c64743]
             sensor_msgs/LaserScan   [90c7ef2dc6895d81024acba2ac42f369]
             sensor_msgs/PointCloud2 [1158d486dd51d683ce2f1be655c3c181]
             tf2_msgs/TFMessage      [94810edda583a504dfda3829e70d7eec]
topics:      /camera/depth_registered/camera_info    7477 msgs    : sensor_msgs/CameraInfo
             /camera/depth_registered/image_raw      7495 msgs    : sensor_msgs/Image      
             /camera/depth_registered/points         6536 msgs    : sensor_msgs/PointCloud2
             /camera/rgb/camera_info                 7559 msgs    : sensor_msgs/CameraInfo
             /camera/rgb/image_rect_color            7563 msgs    : sensor_msgs/Image      
             /odom                                  12706 msgs    : nav_msgs/Odometry      
             /scan                                   2508 msgs    : sensor_msgs/LaserScan  
             /tf                                    32859 msgs    : tf2_msgs/TFMessage


Shirantha
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

matlabbe
Administrator
Hi,

Did you activate simulated time?

add  at the top of your launch file. Then start the rosbag with "$rosbag play --clock 2017-02-26-13-12-03.bag"

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

Shirantha
Thank you Sir!

I tried rtabmap along with laser data refining(setting ). in our robot we've installed frontier explorer, move_base and gmapping for 2d navigation. and currently we're using the entire rtabmap node to generate the 3D map of the environment. but when we watch the process through rviz, base link frame seem to oscillate a bit throughout the process.

what I wanted to know is, when link refining is enabled on rtabmap, does it affect the tf node itself? my idea was it only refines the transform between two consecrative depth data frames.

thanks

Shirantha
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

matlabbe
Administrator
Hi,

Having both gmapping and rtabmap running at the same time would add conflicts on TF (two nodes would publish /map ->/odom). Also, the maps from gmapping and rtabmap will not match together at some time. Normally, you have to choose between gmapping or rtabmap for mapping, as they are not compatible.

When activating neighbor link refining in rtabmap, TF /map ->/odom will be updated not only on loop closures, but also when links are refined (mostly always if refining succeeded).

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

Shirantha
Sir,

What I wanted is to refine visual odometry for 3D mapping with the help of wheel odometry or laser data obtained without affecting the navigation. since we're using gmapping for that which is almost tuned. is there a way to get it done? as in, running rtabmap without influencing gmapping.

thanks
Shirantha.
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

matlabbe
Administrator
Hi,

gmapping should be already refining odometry while mapping (with laser). The problem is that RTAB-Map reconstruction is done in another map representation (graph-based map) than gmapping (which is a particle filter). RTAB-Map cannot know from gmapping when a loop closure is detected or odometry is refined. Well, it can detect that current pose has been corrected, but it cannot know how the whole map has been corrected.

For example, if we set RTAB-Map just in mapping mode without its loop closure detection or its odometry refining, then just subscribe to camera and last estimated pose from gmapping, the maps will correspond until gmapping does a map correction (loop closure, odometry correction). Then from there, the maps (rtabmap map vs gmapping map) will diverge from each other.

If gmapping would maintain a graph of key poses with its map, it would be possible (with some code modifications) for RTAB-Map to subscribe on this graph and update the whole 3D map when gmapping corrects the map, so that maps are always synchronized.

cheers,
Mathieu

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

Shirantha
Sir,

In maintaining such a graph, how often do we have to create a new node and corresponding links? does it have to be a constant rate or any other criteria.

Thanks
Shirantha
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

matlabbe
Administrator
To give you an idea, map update rate of rtabmap is 1 Hz (one node created each second).
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

Shirantha
Sir,

what is meant by the parameter voxel size in rtabmap? what we have to adjust when exporting the cloud in pcd or ply format.

thanks

Shirantha
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

matlabbe
Administrator
Hi,

Voxel parameter does a Voxel Grid filtering on the cloud. This downsamples the cloud at the fixed resolution. See this PCL tutorial for example: http://pointclouds.org/documentation/tutorials/voxel_grid.php

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

Shirantha
Sir,

what are the ros wrappers used to update the map (graph) in rtabmap-ros. to get some idea on how the graph nodes and links are updated.

thanks
Shirantha.
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

matlabbe
Administrator
Hi Shirantha,

rtabmap_ros/rtabmap node is a ROS wrapper of Rtabmap class of the standalone library. The graph is optimize here in Rtabmap::process().

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

Shirantha
Sir,

What is the approach you are using to find the transform in between two nodes in the graph, using robot pose in two positions. Is it by getting the difference between distance and orientation?

Also, since Kinect has a high frame rate 30Hz, how  does rtabmap extract sample frames into a single node at a rate of 1Hz? Or do you take multiple frames into a single node?

Thanks for your help!

Shirantha
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

matlabbe
Administrator
Hi,

Yes, the transform between two nodes is computed from odometry poses: T = odomPose1.inv() * odomPoseP2.

The mapping (rtabmap) keeps only one image per node each Hz. The visual odometry tries to process as many frames as it can.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

Shirantha
Sir,
Generally Odompose1 and Odompose2 are 3x4 matrices. With quartenion of orientation and position vector. Is Odompose1.inv() the pseudo inverse of odompose1 ? Since in general we do not find inverse for non square matrices??
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-map only for mapping

matlabbe
Administrator
Under the hood, Eigen::Matrix4f::inverse() is called.
12