Demo RTAB-Map on Turtlebot

classic Classic list List threaded Threaded
66 messages Options
1234
Reply | Threaded
Open this post in threaded view
|

Demo RTAB-Map on Turtlebot

matlabbe
Administrator
This post was updated on .

I had many questions about running rtabmap on Turtlebot. I don't own a turtlebot, but the launch files are available online. So I've made a launch from what I can test without the actual robot. The launch file demo_turtlebot_mapping.launch is a one to one replacement of the gmapping_demo.launch of the official SLAM Map Building with TurtleBot tutorial.

Requirements:
$ sudo apt-get install ros-indigo-turtlebot-bringup ros-indigo-turtlebot-navigation

Usage:

 $ roslaunch turtlebot_bringup minimal.launch
 $ roslaunch rtabmap_ros demo_turtlebot_mapping.launch
Visualization (turtlebot_navigation.rviz):
 $ roslaunch rtabmap_ros demo_turtlebot_rviz.launch
or
 $ rosrun rviz rviz -d turtlebot_navigation.rviz

You should see a 2D map and a 3D map. For the navigation stuff, see below. By default, rtabmap re-uses always the same database after each mapping session. To delete the old one and start fresh, delete the database saved here "~/.ros/rtabmap.db" or use argument "args:="--delete_db_on_start" when launching the demo_turtlebot_mapping.launch:

 $ roslaunch rtabmap_ros demo_turtlebot_mapping.launch args:="--delete_db_on_start"

UPDATE : Localization mode and Autonomous Navigation
I've updated the launch file with "localization" argument. After a mapping session as above, a database is saved here "~/.ros/rtabmap.db". Now restart the demo_turtlebot_mapping.launch with argument "localization:=true":

 $ roslaunch rtabmap_ros demo_turtlebot_mapping.launch localization:=true
Move the robot around until it can relocalize in the previous map, then the 2D map would re-appear again when a loop closure is found. You can then follow the same steps from 3.3.2 of the "Autonomous Navigation of a Known Map with TurtleBot" tutorial to navigate in the map.

Normally, you only have to "drop" a navigation goal on the map with RVIZ to see the robot moving autonomously to it. Click on "2D Nav Goal" button in RVIZ to set a goal. You should see a planned path (red line) like this to the goal set (green arrow):

The commands sent by move_base: $ rostopic echo /mobile_base/commands/velocity

UPDATE 2: hydro binaries 0.8.3 (binaries are now 0.8.12)
The binaries for hydro are still at 0.8.3 (checked on June 3 2015). I don't know if there will be new binary releases on Hydro as ROS Jade is officially out. However, I've modified the launch above to handle 0.8.3, so the grid map will be created:

 $ roslaunch rtabmap_ros demo_turtlebot_mapping.launch version083:=true

UPDATE 3: Freenect/OpenNI2 on Indigo
By default, OpenNI2 is used from the included 3dsensor.launch (TURTLEBOT_3D_SENSOR=asus_xtion_pro). If you want to use Freenect driver, set this before launching demo_turtlebot_mapping.launch:

$ export TURTLEBOT_3D_SENSOR=kinect

UPDATE 4: If you don't have the robot
If you don't have the robot and you just want to see what it could look like if you have one, you can still generate an odometry like this (with rgbd_odometry:=true):

$ roslaunch turtlebot_bringup minimal.launch
$ roslaunch rtabmap_ros demo_turtlebot_mapping.launch args:="--delete_db_on_start" rgbd_odometry:=true
$ roslaunch rtabmap_ros demo_turtlebot_rviz.launch

UPDATE 5: Demo moved to ROS wiki
Moved this demonstration on rtabmap_ros tutorials.

UPDATE 6: New demo for Turtlebot3 on Melodic [burger, waffle, waffle_pi]
See rtabmap_ros tutorials.

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

Re: Demo RTAB-Map on Turtlebot

Hideya Yamamura
Hi,

I tried demo_turtlebot_mapping.launch on Turtlebot2
with Kinect and Hokuyo's LaserScanner, and could test
without incident.

My evaluation environment is as follows:
Ubuntu 14.04
Ros indigo

Could you tell me how to implement
"Localization mode"?

Regards
Hideya
Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

matlabbe
Administrator
This post was updated on .
Hi,

Thank you for testing on a Turtlebot2! I've updated the post above for the localization part.


       
Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

Mike
This post was updated on .
In reply to this post by matlabbe
Hi,



Mr. Labbe

Thank you for giving attention to turtlebot platform 2, tested the launchs up but had the sequintes results when running demo_turtlebot_mapping.launch and rviz not visualized anything!



turtlebot@turtlebot:~/rgbdslam_catkin_ws$ roslaunch rtabmap_ros demo_turtlebot_mapping.launch args:="--delete_db_on_start"
... logging to /home/turtlebot/.ros/log/5434decc-02fb-11e5-8cff-40167ee4ef9e/roslaunch-turtlebot-5677.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://localhost:59642/

SUMMARY
========

PARAMETERS
 * /camera/camera_nodelet_manager/num_worker_threads
 * /camera/depth_rectify_depth/interpolation
 * /camera/depth_registered_rectify_depth/interpolation
 * /camera/disparity_depth/max_range
 * /camera/disparity_depth/min_range
 * /camera/disparity_registered_hw/max_range
 * /camera/disparity_registered_hw/min_range
 * /camera/disparity_registered_sw/max_range
 * /camera/disparity_registered_sw/min_range
 * /camera/driver/depth_camera_info_url
 * /camera/driver/depth_frame_id
 * /camera/driver/depth_registration
 * /camera/driver/device_id
 * /camera/driver/rgb_camera_info_url
 * /camera/driver/rgb_frame_id
 * /depthimage_to_laserscan/output_frame_id
 * /depthimage_to_laserscan/range_min
 * /depthimage_to_laserscan/scan_height
 * /move_base/TrajectoryPlannerROS/acc_lim_theta
 * /move_base/TrajectoryPlannerROS/acc_lim_x
 * /move_base/TrajectoryPlannerROS/acc_lim_y
 * /move_base/TrajectoryPlannerROS/dwa
 * /move_base/TrajectoryPlannerROS/gdist_scale
 * /move_base/TrajectoryPlannerROS/heading_lookahead
 * /move_base/TrajectoryPlannerROS/holonomic_robot
 * /move_base/TrajectoryPlannerROS/max_vel_theta
 * /move_base/TrajectoryPlannerROS/max_vel_x
 * /move_base/TrajectoryPlannerROS/max_vel_y
 * /move_base/TrajectoryPlannerROS/meter_scoring
 * /move_base/TrajectoryPlannerROS/min_in_place_vel_theta
 * /move_base/TrajectoryPlannerROS/min_vel_theta
 * /move_base/TrajectoryPlannerROS/min_vel_x
 * /move_base/TrajectoryPlannerROS/min_vel_y
 * /move_base/TrajectoryPlannerROS/occdist_scale
 * /move_base/TrajectoryPlannerROS/oscillation_reset_dist
 * /move_base/TrajectoryPlannerROS/pdist_scale
 * /move_base/TrajectoryPlannerROS/sim_time
 * /move_base/TrajectoryPlannerROS/vtheta_samples
 * /move_base/TrajectoryPlannerROS/vx_samples
 * /move_base/TrajectoryPlannerROS/vy_samples
 * /move_base/TrajectoryPlannerROS/xy_goal_tolerance
 * /move_base/TrajectoryPlannerROS/yaw_goal_tolerance
 * /move_base/controller_frequency
 * /move_base/controller_patience
 * /move_base/global_costmap/bump/clearing
 * /move_base/global_costmap/bump/data_type
 * /move_base/global_costmap/bump/marking
 * /move_base/global_costmap/bump/max_obstacle_height
 * /move_base/global_costmap/bump/min_obstacle_height
 * /move_base/global_costmap/bump/topic
 * /move_base/global_costmap/global_frame
 * /move_base/global_costmap/inflation_radius
 * /move_base/global_costmap/map_type
 * /move_base/global_costmap/max_obstacle_height
 * /move_base/global_costmap/observation_sources
 * /move_base/global_costmap/obstacle_range
 * /move_base/global_costmap/origin_z
 * /move_base/global_costmap/publish_frequency
 * /move_base/global_costmap/publish_voxel_map
 * /move_base/global_costmap/raytrace_range
 * /move_base/global_costmap/robot_base_frame
 * /move_base/global_costmap/robot_radius
 * /move_base/global_costmap/scan/clearing
 * /move_base/global_costmap/scan/data_type
 * /move_base/global_costmap/scan/marking
 * /move_base/global_costmap/scan/max_obstacle_height
 * /move_base/global_costmap/scan/min_obstacle_height
 * /move_base/global_costmap/scan/topic
 * /move_base/global_costmap/static_map
 * /move_base/global_costmap/transform_tolerance
 * /move_base/global_costmap/update_frequency
 * /move_base/global_costmap/z_resolution
 * /move_base/global_costmap/z_voxels
 * /move_base/local_costmap/bump/clearing
 * /move_base/local_costmap/bump/data_type
 * /move_base/local_costmap/bump/marking
 * /move_base/local_costmap/bump/max_obstacle_height
 * /move_base/local_costmap/bump/min_obstacle_height
 * /move_base/local_costmap/bump/topic
 * /move_base/local_costmap/global_frame
 * /move_base/local_costmap/height
 * /move_base/local_costmap/inflation_radius
 * /move_base/local_costmap/map_type
 * /move_base/local_costmap/max_obstacle_height
 * /move_base/local_costmap/observation_sources
 * /move_base/local_costmap/obstacle_range
 * /move_base/local_costmap/origin_z
 * /move_base/local_costmap/publish_frequency
 * /move_base/local_costmap/publish_voxel_map
 * /move_base/local_costmap/raytrace_range
 * /move_base/local_costmap/resolution
 * /move_base/local_costmap/robot_base_frame
 * /move_base/local_costmap/robot_radius
 * /move_base/local_costmap/rolling_window
 * /move_base/local_costmap/scan/clearing
 * /move_base/local_costmap/scan/data_type
 * /move_base/local_costmap/scan/marking
 * /move_base/local_costmap/scan/max_obstacle_height
 * /move_base/local_costmap/scan/min_obstacle_height
 * /move_base/local_costmap/scan/topic
 * /move_base/local_costmap/static_map
 * /move_base/local_costmap/transform_tolerance
 * /move_base/local_costmap/update_frequency
 * /move_base/local_costmap/width
 * /move_base/local_costmap/z_resolution
 * /move_base/local_costmap/z_voxels
 * /move_base/oscillation_distance
 * /move_base/oscillation_timeout
 * /move_base/planner_frequency
 * /move_base/planner_patience
 * /move_base/shutdown_costmaps
 * /navigation_velocity_smoother/accel_lim_v
 * /navigation_velocity_smoother/accel_lim_w
 * /navigation_velocity_smoother/decel_factor
 * /navigation_velocity_smoother/frequency
 * /navigation_velocity_smoother/robot_feedback
 * /navigation_velocity_smoother/speed_lim_v
 * /navigation_velocity_smoother/speed_lim_w
 * /rosdistro
 * /rosversion
 * /rtabmap/rtabmap/Kp/MaxDepth
 * /rtabmap/rtabmap/LccBow/InlierDistance
 * /rtabmap/rtabmap/LccBow/MinInliers
 * /rtabmap/rtabmap/LccIcp/Type
 * /rtabmap/rtabmap/LccIcp2/CorrespondenceRatio
 * /rtabmap/rtabmap/Mem/IncrementalMemory
 * /rtabmap/rtabmap/Mem/InitWMWithAllNodes
 * /rtabmap/rtabmap/Mem/RehearsalSimilarity
 * /rtabmap/rtabmap/RGBD/AngularUpdate
 * /rtabmap/rtabmap/RGBD/LinearUpdate
 * /rtabmap/rtabmap/RGBD/LocalLoopDetectionSpace
 * /rtabmap/rtabmap/RGBD/OptimizeFromGraphEnd
 * /rtabmap/rtabmap/Rtabmap/TimeThr
 * /rtabmap/rtabmap/database_path
 * /rtabmap/rtabmap/frame_id
 * /rtabmap/rtabmap/odom_frame_id
 * /rtabmap/rtabmap/subscribe_depth
 * /rtabmap/rtabmap/subscribe_laserScan
 * /rtabmap/rtabmap/wait_for_transform

NODES
  /camera/
    camera_nodelet_manager (nodelet/nodelet)
    debayer (nodelet/nodelet)
    depth_metric (nodelet/nodelet)
    depth_metric_rect (nodelet/nodelet)
    depth_points (nodelet/nodelet)
    depth_rectify_depth (nodelet/nodelet)
    depth_registered_rectify_depth (nodelet/nodelet)
    disparity_depth (nodelet/nodelet)
    disparity_registered_hw (nodelet/nodelet)
    disparity_registered_sw (nodelet/nodelet)
    driver (nodelet/nodelet)
    points_xyzrgb_hw_registered (nodelet/nodelet)
    points_xyzrgb_sw_registered (nodelet/nodelet)
    rectify_color (nodelet/nodelet)
    rectify_ir (nodelet/nodelet)
    rectify_mono (nodelet/nodelet)
    register_depth_rgb (nodelet/nodelet)
  /rtabmap/
    rtabmap (rtabmap_ros/rtabmap)
  /
    depthimage_to_laserscan (nodelet/nodelet)
    kobuki_safety_controller (nodelet/nodelet)
    move_base (move_base/move_base)
    navigation_velocity_smoother (nodelet/nodelet)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[camera/camera_nodelet_manager-1]: started with pid [5695]
[ INFO] [1432572014.859180579]: Initializing nodelet with 4 worker threads.
process[camera/driver-2]: started with pid [5717]
process[camera/debayer-3]: started with pid [5734]
process[camera/rectify_mono-4]: started with pid [5749]
process[camera/rectify_color-5]: started with pid [5764]
process[camera/rectify_ir-6]: started with pid [5779]
process[camera/depth_rectify_depth-7]: started with pid [5796]
process[camera/depth_metric_rect-8]: started with pid [5811]
process[camera/depth_metric-9]: started with pid [5826]
process[camera/depth_points-10]: started with pid [5841]
process[camera/register_depth_rgb-11]: started with pid [5856]
process[camera/points_xyzrgb_sw_registered-12]: started with pid [5871]
process[camera/depth_registered_rectify_depth-13]: started with pid [5886]
process[camera/points_xyzrgb_hw_registered-14]: started with pid [5903]
process[camera/disparity_depth-15]: started with pid [5918]
[ INFO] [1432572017.812030875]: Number devices connected: 1
[ INFO] [1432572017.813122455]: 1. device on bus 001:11 is a SensorV2 (2ae) from PrimeSense (45e) with serial id '0000000000000000'
[ INFO] [1432572017.816085871]: Searching for device with index = 1
[ INFO] [1432572017.910283420]: Opened 'SensorV2' on bus 1:11 with serial number '0000000000000000'
process[camera/disparity_registered_sw-16]: started with pid [5959]
process[camera/disparity_registered_hw-17]: started with pid [5996]
process[depthimage_to_laserscan-18]: started with pid [6011]
process[navigation_velocity_smoother-19]: started with pid [6026]
process[kobuki_safety_controller-20]: started with pid [6084]
process[move_base-21]: started with pid [6110]
process[rtabmap/rtabmap-22]: started with pid [6124]
[ INFO] [1432572020.522267455]: rgb_frame_id = '/camera_rgb_optical_frame'
[ INFO] [1432572020.530454428]: depth_frame_id = '/camera_depth_optical_frame'
[ WARN] [1432572020.575064484]: Camera calibration file /home/turtlebot/.ros/camera_info/rgb_0000000000000000.yaml not found.
[ WARN] [1432572020.575249487]: Using default parameters for RGB camera calibration.
[ WARN] [1432572020.576240192]: Camera calibration file /home/turtlebot/.ros/camera_info/depth_0000000000000000.yaml not found.
[ WARN] [1432572020.577015430]: Using default parameters for IR camera calibration.
[ INFO] [1432572021.071749714]: Starting node...
[ INFO] [1432572021.245423364]: rtabmap: frame_id = base_footprint
[ INFO] [1432572021.245580339]: rtabmap: map_frame_id = map
[ INFO] [1432572021.245647321]: rtabmap: queue_size = 10
[ INFO] [1432572021.245712901]: rtabmap: tf_delay = 0.050000
[ INFO] [1432572021.738225145]: Setting RTAB-Map parameter "Kp/MaxDepth"="4.0"
[ INFO] [1432572021.925760292]: Setting RTAB-Map parameter "LccBow/InlierDistance"="0.1"
[ INFO] [1432572021.972854207]: Setting RTAB-Map parameter "LccBow/MinInliers"="5"
[ INFO] [1432572022.014460826]: Setting RTAB-Map parameter "LccIcp/Type"="2"
[ INFO] [1432572022.025842899]: Setting RTAB-Map parameter "LccIcp2/CorrespondenceRatio"="0.05"
[ INFO] [1432572022.553437127]: Setting RTAB-Map parameter "Mem/IncrementalMemory"="true"
[ INFO] [1432572022.556014180]: Setting RTAB-Map parameter "Mem/InitWMWithAllNodes"="false"
[ INFO] [1432572022.596886970]: Setting RTAB-Map parameter "Mem/RehearsalSimilarity"="0.30"
[ INFO] [1432572023.230113896]: Setting RTAB-Map parameter "RGBD/AngularUpdate"="0.1"
[ INFO] [1432572023.248104116]: Setting RTAB-Map parameter "RGBD/LinearUpdate"="0.1"
[ INFO] [1432572023.342643373]: Setting RTAB-Map parameter "RGBD/LocalLoopDetectionSpace"="true"
[ INFO] [1432572023.394048949]: Setting RTAB-Map parameter "RGBD/OptimizeFromGraphEnd"="false"
[ INFO] [1432572023.717671503]: Setting RTAB-Map parameter "Rtabmap/TimeThr"="700"
[ INFO] [1432572024.823675930]: RTAB-Map rate detection = 1.000000 Hz
[FATAL] (2015-05-26 01:40:24.825) DBDriverSqlite3.cpp:343::connectDatabaseQuery() DB error : unable to open database file

*******
FATAL message occurred! Application will now exit.

*******
[rtabmap/rtabmap-22] process has died [pid 6124, exit code 1, cmd /home/turtlebot/rgbdslam_catkin_ws/devel/lib/rtabmap_ros/rtabmap --delete_db_on_start scan:=/scan rgb/image:=/camera/rgb/image_rect_color depth/image:=/camera/depth_registered/image_raw rgb/camera_info:=/camera/rgb/camera_info grid_map:=/map __name:=rtabmap __log:=/home/turtlebot/.ros/log/5434decc-02fb-11e5-8cff-40167ee4ef9e/rtabmap-rtabmap-22.log].
log file: /home/turtlebot/.ros/log/5434decc-02fb-11e5-8cff-40167ee4ef9e/rtabmap-rtabmap-22*.log
[ WARN] [1432572025.562526780]: Waiting on transform from base_footprint to map to become available before running costmap, tf error:
[ WARN] [1432572030.648655232]: Waiting on transform from base_footprint to map to become available before running costmap, tf error:
[ WARN] [1432572035.731965490]: Waiting on transform from base_footprint to map to become available before running costmap, tf error:


And After running Rosbag play --clock demo_mapping.bag i receive the warnings in terminals of rviz and demo_turtlebot_mapping.launch:

Warning: TF_OLD_DATA ignoring data from the past for frame base_footprint at time 1.36873e+09 according to authority /play_1432574762913009039
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
         at line 260 in /tmp/buildd/ros-hydro-tf2-0.4.11-0precise-20140617-0510/src/buffer_core.cpp



graciously



Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

matlabbe
Administrator
Hello Mike,

It should be the "~" that I've put in the database_path parameter. Normally, newer rtabmap versions >0.8.12 (Indigo/Jade) should handle this. I've still updated the launch file to not use it (so the older versions should work).

For Hydro, the packages are still at 0.8.3. To have the grid map, you should add the grid_map_assembler node in the rtabmap namespace and remap its output to /map so move_base can use it:
<group ns="rtabmap">
  ...
  <node pkg="rtabmap_ros" type="grid_map_assembler" name="grid_map_assembler">
    <remap from="grid_map" to="/map"/>
  </node>
<group/>
Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

Hideya Yamamura
In reply to this post by matlabbe
Hi,

Mr. Labbe

Thank you for your advise.

1. Visualization mode:  

I modified demo_turtlebot_mapping.launch file as follows because database_path does not create db file.

 <arg name="database_path" default="~/.ros/rtabmap.db"/>
 
2. Localization mode:

$ roslaunch rtabmap_ros demo_turtlebot_mapping.launch localization:=true
  :     <snip>                :
  :     <snip>                             :
/rtabmap/rtabmap subscribed to:
   /camera/rgb/image_rect_color,
   /camera/depth_registered/image_raw,
   /camera/rgb/camera_info,
   /scan
[ INFO] [1432634121.634731516]: rtabmap 0.9.0 started...
[ INFO] [1432634121.713520325]: Using plugin "static_layer"
[ INFO] [1432634121.800205591]: Requesting the map...
[ WARN] (2015-05-26 18:55:23.221) Memory.cpp:600::update() The working memory is empty and the memory is not incremental (Mem/IncrementalMemory=False), no loop closure can be detected! Please set Mem/IncrementalMemory=true to increase the memory with new images or decrease the STM size (which is 1 including the new one added).
[ INFO] [1432634123.222415833]: rtabmap: Rate=1.00s, Limit=0.700s, RTAB-Map=0.0193s, Pub=0.0000s (local map=0, WM=0)
  :     <snip>                :
  :     <snip>                             :

Move the robot around for a while, but a loop closure is not found.
I appreciate any suggestions or comments.

Regards,
Hideya
Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

matlabbe
Administrator
Hello Hideya,

1. I've updated the launch file with only "rtabmap.db" as database name, though I've also updated the code to show the full path of the database when its path is relative. By default "rtabmap.db" will be created here "~/.ros/rtabmap.db".

2. The error "The working memory is empty and the memory is not incremental (Mem/IncrementalMemory=False), no loop closure can be detected! Please set Mem/IncrementalMemory=true to increase the memory with new images or decrease the STM size (which is 1 including the new one added). " tells that the database is empty or there are not enough nodes in it. With STM=1 (including the new one added), it seems that the database is empty. Make sure to run in mapping mode to create a database/map enough big (>15 nodes) before launching again in localization mode.

Well, you can verify after the mapping session that the database is correctly created by looking inside using this tool:
$ rtabmap-databaseViewer ~/.ros/rtabmap.db

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

Re: Demo RTAB-Map on Turtlebot

Hideya Yamamura
Hello Mathieu,

Thank you so much for your advise.

According to update `fixed empty database for demo_turtlebot_mapping.launch`,
Localization mode worked out.

My regards,
Hideya
Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

André
In reply to this post by matlabbe
Hello Mr. Labbe

After upgrading the demo_turtlebot_mapping.launch FATAL error was corrected as shown above, however the warninns and continue to run demo_turtlebot_rviz.launch can not see anything in rviz the Global Status go wrong : Fix frame does not exist


[ INFO] [1432818021.521137703]: Setting RTAB-Map parameter "RGBD/OptimizeFromGraphEnd"="false"
[ INFO] [1432818021.764206316]: Setting RTAB-Map parameter "Rtabmap/TimeThr"="700"
[ INFO] [1432818022.559368795]: RTAB-Map rate detection = 1.000000 Hz
[ INFO] [1432818022.563629982]: rtabmap: Using database from "rtabmap.db".
[ INFO] [1432818023.376187592]: Registering Depth+LaserScan callback...
[ INFO] [1432818023.386642754]: rtabmap started...
[ WARN] [1432818024.439497022]: Waiting on transform from base_footprint to map to become available before running costmap, tf error:
[ WARN] [1432818029.451174338]: Waiting on transform from base_footprint to map to become available before running costmap, tf error:
available before running costmap, tf error:

Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

matlabbe
Administrator
Hello,
Are you launching on turtlebot? The /odom -> /base_footprint TF should be already published when launching turtlebot_bringup/minimal.launch. If not, the mapping cannot work.

If you don't have the robot and you just want to see what it could look like if you have one, you can still generate an odometry like this (with rgbd_odometry:=true):
$ roslaunch turtlebot_bringup minimal.launch
$ roslaunch rtabmap_ros demo_turtlebot_mapping.launch rgbd_odometry:=true args:="--delete_db_on_start"
$ roslaunch rtabmap_ros demo_turtlebot_rviz.launch

When rtabmap is actually mapping, you should see this message shown on the console at 1Hz:
[ INFO] [1432823397.685455468]: rtabmap 0.9.0 started...
[ INFO] [1432823402.653807786]: rtabmap: Rate=1.00s, Limit=0.700s, RTAB-Map=0.3038s, Pub=0.0045s (local map=1, WM=1)
[ INFO] [1432823403.666776194]: rtabmap: Rate=1.00s, Limit=0.700s, RTAB-Map=0.3164s, Pub=0.0025s (local map=1, WM=1)
...
Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

Mike
This post was updated on .
Hey Mr. Labble

I'm having the same problem as André, and I rather turtlebot 2 but'm having an error when running minimal.launch referencing the rtabmap believe is the cause of this error in the TF mapping follows the error.

Turning the minimal.launch:

process [robot_state_publisher-2]: started with pid [11187]
process [diagnostic_aggregator-3]: started with pid [11208]
process [mobile_base_nodelet_manager-4]: started with pid [11223]
[ERROR] [1433249303.056507050]: Skipping XML Document "/opt/ros/hydro/share/rtabmap_ros/nodelet_plugins.xml" which had the Root Element. Likely this means the XML is malformed or missing.
process [mobile_base-5]: started with pid [11267]
process [cmd_vel_mux-6]: started with pid [11314]
process [bumper2pointcloud-7]: started with pid [11338]
process [turtlebot_laptop_battery-8]: started with pid [11395]

Turning the launch showed ; presented the following messages only:


2 roslaunch rtabmap_ros demo_turtlebot_mapping.launch rgbd_odometry: = true args: = "- delete_db_on_start".


[INFO] [1433250311.397060290]: rtabmap: Deleted database "rtabmap.db" (--delete_db_on_start is set).
[WARN] [1433250311.429969779]: Waiting on transform from base_footprint to map to Become available before running costmap, tf error:
[INFO] [1433250314.006630149]: rtabmap: Using database from "rtabmap.db".
[INFO] [1433250314.792228083]: Registering Depth + LaserScan callback ...
[INFO] [1433250314.809703165]: rtabmap started ...
[INFO] [1433250316.037499055]: Odom: quality = 0, std dev = 0.000000m, update time = 0.074587s
[WARN] (06/02/2015 22: 05: 16,213) Odometry.cpp: 377 :: computeTransform () Transform not valid (inliers = 15/25)
[INFO] [1433250316.216543434]: Odom: quality = 15, std dev = 0.000000m, update time = 0.126866s
[WARN] (06/02/2015 22: 05: 16,330) Odometry.cpp: 382 :: computeTransform () Not enough inliers 19 <20
[INFO] [1433250316.331263324]: Odom: quality = 0, std dev = 0.000000m, update time = 0.100024s
[WARN] (06/02/2015 22: 05: 16,420) Odometry.cpp: 377 :: computeTransform () Transform not valid (inliers = 16/26)
[INFO] [1433250316.421180111]: Odom: quality = 16, std dev = 0.000000m, update time = 0.069703s
[WARN] [1433250316.501404960]: Waiting on transform from base_footprint to map to Become available before running costmap, tf error:
[WARN] (06/02/2015 22: 05: 16,525) Odometry.cpp: 377 :: computeTransform () Transform not valid (inliers = 10/27)
[INFO] [1433250316.526646573]: Odom: quality = 10, std dev = 0.000000m, update time = 0.071024s



So I believe that ran normally when running rviz not had the error in the global status as before, but we are yet to see the map on the grid !!
Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

matlabbe
Administrator
I have updated the first post above for Hydro binaries to create a grid map (backward compatibility issue). For convenience, I also updated how to launch rviz for those using rtabmap from the binaries (Hydro/Indigo/Jade) and not have yet the launch file above already installed.

Example (if you are on the robot, you don't have to set "rgbd_odometry:=true"):
 $ roslaunch turtlebot_bringup minimal.launch
 $ roslaunch rtabmap_ros demo_turtlebot_mapping.launch rgbd_odometry:=true args="--delete_db_on_start" version083:=true
 $ rosrun rviz rviz -d turtlebot_navigation.rviz 

Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

Mike
Hey mr. Labble have the same mistakes for the Tf_old in real turtlebot 2, with topics past and new launchs I downloaded as indicated stopped seeing errors in Rviz for the global status however the "Tf_error from base_footprint to map" still here and not tb I have any kind of visualization in rviz. So I thought I should update all rtabmap_ros I have installed to verify that pose this be the cause However when trying to update as indicated have an error below:


turtlebot@turtlebot:/opt/ros/hydro/share/rtabmap_ros$ sudo git pull origin master
fatal: Not a git repository (or any of the parent directories): .git
turtlebot@turtlebot:/opt/ros/hydro/share/rtabmap_ros$


Thanks For the Helps.


Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

matlabbe
Administrator
Helo Mike,

To update any ROS binary packages, you should do:
$ sudo apt-get upgrade

but as I said in the last post, the Hydro binaries are stuck at 0.8.3 on the ROS servers. To use the latest version, you should uninstall ros-hydro-rtabmap and ros-hydro-rtabmap-ros:
$ sudo apt-get remove ros-hydro-rtabmap ros-hydro-rtabmap-ros
then build rtabmap from source. Follow carefully all steps in Build from source.

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

Re: Demo RTAB-Map on Turtlebot

Mike
This post was updated on .
In reply to this post by Mike
Hello Mr. Labble,



Thank you for taking my doubts once again, this time getting run rtabmap version ros and view the mapping in rviz after upgrading the version You Were using, but I Could que report the mapping in rviz is still duplicating the images causing the map DO NOT STAY viable the turtlebot initiate the spinning endlessly in Rviz have some pictures if Necessary and the Following doubts Sepharose me:


The rtabmap has the ability to do the mapping autonomously? example would run mapping and turtlebot go walking around the area That Is inserted without mapping the environment that needs to be teleoperated if so would like to know how can I use this function.


another doubt is after mapping how do I export the information Regarding the location say the coordinates generated the x, y, o, is if we use the ground truth (knowing some system of groudtruth you can use would be very good for me) with rtabmap have to import this information to compare believe me. the standalone version I believe it has the option to cared such date would like to know the version ros.


Thanks For the Helps.
Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

matlabbe
Administrator
Hello Mike,

I don't know if I understand well the "spinning" problem you are seeing. Some pictures may help...

RTAB-Map doesn't do exploration autonomously, but you can do autonomous navigation with the map created. See "You can then follow the same steps from 3.3.2 of the "Autonomous Navigation of a Known Map with TurtleBot" tutorial to navigate in the map." on the first post above.

RTAB-Map publishes the graph at each map update. The graph contains position of each nodes in the map. See rtabmap_ros/MapData topic. For example, to show only poses:
[git master] $ rostopic echo /rtabmap/mapData/graph/poses
[git devel] $ rostopic echo /rtabmap/mapData/poses

You can also open the database created by turtlebot in RTAB-Map standalone to get data you want.

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

Re: Demo RTAB-Map on Turtlebot

jerry-qin
In reply to this post by matlabbe
Hi,
Mr. Labbe

I am trying to complete the experiment on turtlebot1 as you described.But I encounter some problems
After I  input $ roslaunch rtabmap_ros demo_turtlebot_mapping.launch args:="--delete_db_on_start"

There are several error information,Thanks For the Helps.


[ INFO] [1457354527.099352043]: Searching for device with index = 1
[ INFO] [1457354527.257953996]: Starting a 3s RGB and Depth stream flush.
[ INFO] [1457354527.258148084]: Opened 'Xbox NUI Camera' on bus 0:0 with serial number 'A00362W02857209A'
[ WARN] [1457354527.710689751]: Could not find any compatible depth output mode for 1. Falling back to default depth output mode 1.
[ INFO] [1457354527.729813419]: rgb_frame_id = 'camera_rgb_optical_frame'
[ INFO] [1457354527.729894057]: depth_frame_id = 'camera_depth_optical_frame'
[ WARN] [1457354527.769296156]: Camera calibration file /home/qincao/.ros/camera_info/rgb_A00362W02857209A.yaml not found.
[ WARN] [1457354527.769528144]: Using default parameters for RGB camera calibration.
[ WARN] [1457354527.769893064]: Camera calibration file /home/qincao/.ros/camera_info/depth_A00362W02857209A.yaml not found.
[ WARN] [1457354527.770756180]: Using default parameters for IR camera calibration.
[ INFO] [1457354530.259362744]: Stopping device RGB and Depth stream flush.
[ WARN] [1457354530.628989922]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354530.740167112]: rtabmap: Rate=1.00s, Limit=0.700s, RTAB-Map=0.0335s, Pub=0.0035s (local map=1, WM=1)
[ INFO] [1457354530.781340131]: Resizing costmap to 111 X 63 at 0.050000 m/pix
[ WARN] [1457354530.855138343]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354530.881298672]: Received a 111 X 63 map at 0.050000 m/pix
[ INFO] [1457354530.893831844]: Using plugin "obstacle_layer"
[ INFO] [1457354530.899008749]:     Subscribed to Topics: scan bump
[ WARN] [1457354530.976200790]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354531.027887175]: Using plugin "inflation_layer"
[ WARN] [1457354531.089263309]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354531.208837783]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354531.302590065]: Using plugin "obstacle_layer"
[ WARN] [1457354531.394102613]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354531.399392442]:     Subscribed to Topics: scan bump
[ INFO] [1457354531.512527517]: Using plugin "inflation_layer"
[ WARN] [1457354531.606016326]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354531.710656258]: Created local_planner dwa_local_planner/DWAPlannerROS
[ INFO] [1457354531.718793769]: Sim period is set to 0.20
[ WARN] [1457354531.804211380]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354531.950652693]: rtabmap: Rate=1.00s, Limit=0.700s, RTAB-Map=0.0424s, Pub=0.0044s (local map=1, WM=1)
[ WARN] [1457354532.079241954]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354532.195947361]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354532.299353584]: Recovery behavior will clear layer obstacles
[ INFO] [1457354532.401673873]: Recovery behavior will clear layer obstacles
[ WARN] [1457354532.407250566]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354532.493697918]: odom received!
[ WARN] [1457354532.612338474]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354532.721641554]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354532.839957196]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354533.011284721]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354533.140537106]: rtabmap: Rate=1.00s, Limit=0.700s, RTAB-Map=0.0396s, Pub=0.0020s (local map=1, WM=1)
[ INFO] [1457354533.140801602]: Resizing costmap to 111 X 64 at 0.050000 m/pix
[ WARN] [1457354533.254014666]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354533.412591899]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354533.598665778]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354533.806687257]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354534.015087576]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354534.213462003]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354534.330087331]: rtabmap: Rate=1.00s, Limit=0.700s, RTAB-Map=0.0327s, Pub=0.0009s (local map=1, WM=1)
[ INFO] [1457354534.330457563]: Resizing costmap to 111 X 63 at 0.050000 m/pix
[ WARN] [1457354534.440889732]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354534.561975300]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354534.680180245]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354534.784149180]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354535.010801848]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354535.119959361]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354535.250476165]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354535.379179706]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354535.526272270]: rtabmap: Rate=1.00s, Limit=0.700s, RTAB-Map=0.0284s, Pub=0.0008s (local map=1, WM=1)
[ WARN] [1457354535.630045257]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354535.816018588]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354536.015575005]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354536.214151867]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354536.413773559]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354536.597317526]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ INFO] [1457354536.728203541]: rtabmap: Rate=1.00s, Limit=0.700s, RTAB-Map=0.0288s, Pub=0.0008s (local map=1, WM=1)
[ INFO] [1457354536.728337555]: Resizing costmap to 112 X 64 at 0.050000 m/pix
[ WARN] [1457354536.848518078]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354536.981829983]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354537.086579918]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354537.195191801]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!
[ WARN] [1457354537.412242950]: rtabmap: Could not get transform from odom to base_footprint after 0.100000 second!


Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

matlabbe
Administrator
Hi,

Which commands did you use to bring-up the robot? It seems to be a TF problem where /odom to /base_footprint is not found. Can you show your TF tree while this is running?
$ rosrun tf view_frames
$ evince frames.pdf

cheers
Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

jerry-qin
Hi,

Mr. Labbe

Thanks for your reply
1.I use the command  $ roslaunch turtlebot_bringup minimal.launch  to bring-up the robot

2.the TF tree frames.pdf

Thanks For the Helps.
Reply | Threaded
Open this post in threaded view
|

Re: Demo RTAB-Map on Turtlebot

matlabbe
Administrator
This post was updated on .
The TF seems not published very fas (5-10 Hz). Try increasing maximum time to wait for transform (default is 0.1 s):
$ roslaunch rtabmap_ros demo_turtlebot_mapping.launch args:="--delete_db_on_start" wait_for_transform:=1

EDIT
You can also increase the publish_frequency of the robot_state_publisher from 5 Hz to 10 Hz in:
/opt/ros/indigo/share/turtlebot_bringup/launch/includes/robot.launch.xml
so that odometry can be computed faster than 5Hz.
1234