Size: 7278
Comment:
|
Size: 7512
Comment:
|
Deletions are marked like this. | Additions are marked like this. |
Line 130: | Line 130: |
Since recent versions, [[https://github.com/introlab/rtabmap_ros/blob/master/launch/rtabmap.launch|rtabmap.launch]] has "localization" argument for convenience: {{{ $ roslaunch rtabmap_ros rtabmap.launch localization:=true }}} |
![]() |
RGB-D Handheld Mapping
Description: This tutorial shows how to use rtabmap_ros out-of-the-box with a Kinect-like sensor in mapping mode or localization mode.Tutorial Level: BEGINNER
Next Tutorial: Stereo Handheld Mapping
Contents
RGB and depth sensors
The RGB-D sensors which are OpenNI and OpenNI2 compliant would work out-of-the-box using openni_launch, openni2_launch, freenect_launch, iai_kinect2 or Zed packages. Sensors tested:
Kinect for Xbox 360
$ roslaunch openni_launch openni.launch depth_registration:=true
or$ roslaunch freenect_launch freenect.launch depth_registration:=true
XtionPRO Live
$ roslaunch openni2_launch openni2.launch depth_registration:=true
Kinect v2 (Xbox One)
$ roslaunch kinect2_bridge kinect2_bridge.launch publish_tf:=true
Zed camera (tested with zed-ros-wrapper 9ac1dba)
$ roscore $ export ROS_NAMESPACE=camera $ rosrun zed_wrapper zed_wrapper_node
RealSense R200
$ roslaunch realsense_camera r200_nodelet_rgbd.launch
Mapping mode
There are two choices for online visualization: rtabmapviz or rviz. With the RVIZ plugin rtabmap/MapCloud, the clouds can be incrementally added to RVIZ. However using rtabmapviz, the interface should look like the tutorials of the standalone version.
Launch (rtabmapviz): rgbd_mapping.launch
$ roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start"
If you are using kinect2_bridge:
$ rosrun tf static_transform_publisher 0 0 0 -1.5707963267948966 0 -1.5707963267948966 camera_link kinect2_link 100 $ roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" rgb_topic:=/kinect2/qhd/image_color_rect depth_registered_topic:=/kinect2/qhd/image_depth_rect camera_info_topic:=/kinect2/qhd/camera_info
or for convenience: rgbd_mapping_kinect2.launch
$ roslaunch rtabmap_ros rgbd_mapping_kinect2.launch resolution:=qhd
Zed camera (tested with zed-ros-wrapper 9ac1dba)
$ rosrun tf static_transform_publisher 0 0 0 -1.5707963267948966 0 -1.5707963267948966 camera_link zed_initial_frame 100 $ roslaunch rtabmap_ros rtabmap.launch rtabmap_args:="--delete_db_on_start" depth_topic:=/camera/depth/depth_registered
RealSense R200
$ roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" depth_registered_topic:=/camera/depth_registered/sw_registered/image_rect_raw
- Launch (rviz):
$ roslaunch rtabmap_ros rgbd_mapping.launch rtabmap_args:="--delete_db_on_start" rviz:=true rtabmapviz:=false
The rtabmap argument "--delete_db_on_start" is used to start mapping from a clean database. You can also reset the memory from rtabmapviz using the action "Edit->Delete memory", or by using this service :
$ rosservice call /rtabmap/reset
You should see something like this:
If the background of the map turns RED, it is because the odometry is lost. Visit this page under Lost Odometry (RED screens!) section to know why this happens! To track again the odometry, replace the camera to the last position before the RED appeared and it should be able to recompute the odometry. Another way is to reset the odometry using the menu option "Edit->Reset odometry" (note that a new map is created each time the odometry is reset). See Odometry Auto-Reset for another way to handle odometry lost (reset and continue the same map).
Use external odometry
If you want to use external odometry (e.g., you want to use odometry from your robot), you can set these arguments: "visual_odometry:=false odom_topic:=/my_odometry".
Where is the map saved?
~/.ros/rtabmap.db
RTAB-Map provides a tool to browse data in the database:
$ rtabmap-databaseViewer ~/.ros/rtabmap.db
Localization mode
In localization mode, a map large enough (>30 locations) must be already created (using rgbd_mapping.launch above).
In rtabmapviz (GUI), click on "Localization" in the "Detection" menu. By looking over locations in the map, RTAB-Map would localize itself in it by finding a loop closure. Once a loop closure is found, the odometry is corrected and the current cloud will be aligned to the map.
You can play with the relocation behaviour by resetting the odometry. You can use form the GUI the Detection->"Reset odometry" action or call the service on the terminal like:
$ rosservice call /rtabmap/reset_odom
Advanced
You can also start the launch file above directly in Localization mode with a previously built database. Set the parameter "Mem/IncrementalMemory" to "false". Also, when starting the rtabmap node, the argument "--delete_db_on_start" must not be set!
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args=""> ... <param name="Mem/IncrementalMemory" type="string" value="false"/> </node>
Since recent versions, rtabmap.launch has "localization" argument for convenience:
$ roslaunch rtabmap_ros rtabmap.launch localization:=true
In the GUI, do Edit->"Download map" to download the map from the rtabmap node. At the start, you should see that the current displayed cloud is not aligned to the map, it is normal because the odometry is reset on each start. By looking over locations in the map, RTAB-Map would localize itself in it by finding a loop closure. Once a loop closure is found, the odometry is corrected and the map will appear with the current cloud aligned to it.