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

Automatic multi-session mapping for RTABMap. [closed]

asked 2015-07-15 16:58:00 -0600

Tanmay gravatar image

updated 2015-07-16 00:38:52 -0600

Hello,

I have RTABMap set up on Ubuntu 12.04, ROS Hydro, with a stereo camera pair. I also have an IMU, but it is not currently being used for pose estimation.

My issue is that when my camera moves too fast, the Stereo odometry loses track of where it is. Ideally I should return the camera to a position it has seen before, and it regains tracking.

In my application (SLAM on a UAV), this is not always feasible, especially since i am trying to achieve autonomous flying of the UAV.

I'd like to be able to start a "new session" of mapping, as and when my odometry loses track for a large amount of time (say 5 seconds), without having to bring my camera back to a known location. I want this map to be merged to my previously existing map. To do this online, here is a scheme I thought of -

  1. Launch RTAB in mapping mode.
  2. From another client node, subscribe to the odometry topic, and check it is a null transform for more than 10 consecutive transforms.
  3. If (2) is true, call the services backup, reset_odom / reset_odom_to_pose, and trigger_new_map in that order.
  4. Continue mapping.

I am not sure if this will work, because trigger_new_map probably deletes the old one. Additionally, this won't let me merge each "session" with the previous one online. I know rtabmap is by default in "multi-session" mode, is there a fault with my understanding? Any suggestions on how to do this?

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by Tanmay
close date 2015-07-19 01:52:03.003939

1 Answer

Sort by ยป oldest newest most voted
2

answered 2015-07-17 14:17:54 -0600

matlabbe gravatar image

Hi Tanmay,

There is a RTAB-Map's parameter in stereo_odometry node that can automatically reset odometry after a number of frames lost.

  • Odom/ResetCountdown (default 0): Automatically reset odometry after X consecutive images on which odometry cannot be computed (value=0 disables auto-reset). In the launch file:
    <param name="Odom/ResetCountdown" type="string" value="0"/>

This parameter will make the odometry reset after X frames to Identify transform. When rtabmap node detects an Identity transform, a new map is created automatically. The previous map will disappear (from RVIZ or rtabmapviz) but it is still in memory, so if the robot comes back in the area of the previous map(s) AND detects a loop closure, the maps will be merged together (and the previous map will show up again in RVIZ or rtabmapviz).

In this approach, the odometry is reset to Identity, the robot may think that it jumped back to its initial position. If you want the odometry to reset to the last known pose (while creating a new map), you should do it externally like in your example:

  • If (2) is true, call /rtabmap/trigger_new_map then /rtabmap/reset_odom_to_pose (rtabmap_ros/ResetOdom). You don't have to call /rtabmap/backup.

If you have an IMU, you may track the position when the visual odometry is lost, and call directly /rtabmap/reset_odom_to_pose to the last estimated pose from the IMU without calling /rtabmap/trigger_new_map. No new map will be created, it will be like it is continuing mapping the same map.

cheers,

Mathieu

edit flag offensive delete link more

Comments

Hi Mathieu,

I think this is exactly what I wanted! I really want to say RTAB is one of the most comprehensive and well written pieces of software I've used - cheers to that.

Tanmay gravatar image Tanmay  ( 2015-07-19 01:48:08 -0600 )edit

Just to check - lets say I assume I either have an IMU, or that the camera doesn't move when tracking is lost. 1) Set Reset odom param in the launch file 2) If the odometry loses track, check this in a separate node, and then reset the odometry to last known / IMU pose using the service. Is that ok?

Tanmay gravatar image Tanmay  ( 2015-07-19 01:49:58 -0600 )edit

I also want to confirm how I should be calling the service. Does this look ok?

ros::ServiceClient client = nh.serviceClient<rtabmap_ros::resetpose>("rtabmap/reset_odom_to_pose");

rtabmap_ros::ResetPose p; p.req.x = ... (for all 6 variables),

and then client.call(p);

Tanmay gravatar image Tanmay  ( 2015-07-19 13:24:22 -0600 )edit

rtabmap_ros::ResetPose srv; srv.request.x = ...; % same for y,z, roll, pitch,yaw. if(!ros::service::call("reset_odom_to_pose", srv)) { ROS_WARN("Can't call \"reset_odom_to_pose\" service"); } If your node is in "rtabmap" namespace, you can remap the srv name in the launch

matlabbe gravatar image matlabbe  ( 2015-07-19 15:39:07 -0600 )edit

If you manually reset odom to a pose from an external node, you may not want to set Odom/ResetCountdown.

matlabbe gravatar image matlabbe  ( 2015-07-19 15:42:54 -0600 )edit

@Tanmay Hi, can i bother you to ask what stereo camera pair are you using for this project? i'm looking to choosing one with a reasonably cheap price tag (for indoor applications) at the moment, or even a guide to building a DIY one. Thank you!

sobot gravatar image sobot  ( 2015-09-22 10:50:44 -0600 )edit

Hi @sobot , sorry, I only took a look at this now. I was using the Mobius web camera's, both normal and wide angle versions (two different sets of each). You can use any usual webcam that is interfaced with a suitable camera driver, as long as the camera driver supports synchronized images.

Tanmay gravatar image Tanmay  ( 2015-10-10 07:18:32 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2015-07-15 16:58:00 -0600

Seen: 1,732 times

Last updated: Jul 17 '15