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

rtabmap_ros: Is it possible to continue running SLAM when a sensor is disabled?

asked 2019-02-15 07:03:31 -0600

renangm gravatar image

Hardware: Turtlebot 2 (Kobuki), Hokuyo URG-04LX, PrimeSense RGB-D

Software: ROS Kinetic (ubuntu 16.04), turtlebot_bringup, turtlebot_description, urg_node, openni2_camera, rtabmap_ros

Context: I am developing an algorithm for fault tolerance in mobile robots, in which we aim to compensate for faulty sensors at run-time. The experiments require me to disconnect a sensor and verify the fault's effects in the robot's operation, and later if the algorithm is correctly compensating them.

Problem: I need to test the effects of a faulty sensor in the rtabmap_ros package (i.e., how it affects SLAM), however when I disconnect a sensor to simulate a failure (either laser or camera), the package stops transmitting map and localization data, as it probably should. When the sensor is reconnected, the package resumes operation. I have tried to change the "subscribe_depth" and "subscribe_scan" parameters, then calling the "update_parameters" service, as well as the "reset" and "resume" services, all to no avail.

Question: Is it possible for RTABMAP to continue performing SLAM in the event of a sensor disconnection? Could it be a simple tweak in the source code, to not check for a certain flag? If this is not possible with RTABMAP, are there any recommendations for packages which allow for this behavior?

Thanks in advance!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2019-02-23 15:43:19 -0600

matlabbe gravatar image

Rtabmap node updates the map only when it receives all its input topics. If one of the topics is not published, rtabmap will "idle" (the TF /map -> /odom will still be published though). If the input topics are republished again (under same topic name), rtabmap should resume mapping. Same thing for rtabmap's odometry nodes.

In the case we setup rtabmap to use both camera and lidar, if one fails, SLAM is stopped. With how rtabmap is built, we cannot easily switch to single sensor mapping if one fails. rtabmap uses ApproximateTime or ExactTime synchronizers from ROS API, so if we would want to change a preconfigured synchronizer with camera and lidar to only camera, we would have to delete the synchronizer, set subscribe_scan to false, then re-call the function which setups the callbacks. We may also want changing other parameters that depended on both sensors. So overall, we cannot do that with rtabmap in its state right now without changing the code (it is not a simple flag to turn off).

We cannot change subscribe_depth and subscribe_scan parameters at runtime, only those listed by $ rtabmap --params (for which we can use rtabmapviz for convenience).

Another approach (not quite efficient) when a sensor fails would be to kill rtabmap node, then restart it with a different configuration using the same saved database. The downside is that we would force rtabmap to create a new map (even if odometry is still consistent), which may not be connected to first one (if no loop closures are found at restart).

cheers,
Mathieu

edit flag offensive delete link more

Comments

Thanks Mathieu! This seems to be the standard behavior of the packages I tested (e.g., gmapping, hector, etc). It is interesting to know that the map -> odom TF is still published. I can check and see if I can keep the TF consistent in case of a sensor failure (not SLAM but it's a start).

renangm gravatar image renangm  ( 2019-02-24 00:10:17 -0600 )edit

In the case above, the TF tree won't be broken, but map->odom value will stay the same as long rtabmap is idling (that TF changes only when there is a loop closure or on localization).

matlabbe gravatar image matlabbe  ( 2019-02-25 11:25:51 -0600 )edit

Oh, that's unfortunate. Thanks for letting me know!

renangm gravatar image renangm  ( 2019-02-26 16:09:07 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2019-02-15 07:03:31 -0600

Seen: 366 times

Last updated: Feb 23 '19