Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Running NDT-MCL examples
Description: This tutorial goes through the steps to set up and run the ndt_mcl examplesKeywords: Localization, NDT-MCL
Tutorial Level: BEGINNER
Contents
Getting Started
For running the examples you need to have downloaded the complete perception-oru stack. Before compiling you should also install MRPT-GUI (used for the visualization). Instructions for installing it can be found from MRPT's home page.
Once that is complete and necessary ROS_PACKAGE_PATH is set, go to the ndt_mcl and compile
roscd ndt_mcl rosmake
Next, download the necessary datasets:
cd data ./get_localization_data.sh ./get_mapping_data.sh
Now you should have mapping.bag and localization.bag in the ndt_mcl/data folder.
Running basic examples
There are two basic examples that can be executed:
roslaunch ndt_mcl 2d_ndt_mcl_node.launch roslaunch ndt_mcl ndt_mcl_2d_offline.launch
Both of these use the localization.bag from the data folder and maps/ndt_0040.ndmap, which comes with the package. 2d_ndt_mcl_node.launch plays back the bag file and works as a node, while the offline version is an example for processing directly from the bag file.
Node subscribes to a sensor_msgs::LaserScan for input scans and uses tf tree to read the odometry. Please note that our implementation also expects that there is a "state topic", which is the ground truth information in our example files. When modifying the code for yourself, you should probably remove this.
Generating Map with fuser and localizing against it
First generate the map using the fuser. Start fuser:
roslaunch ndt_fuser fuser_2dlaser.launch
then on another terminal go to ndt_mcl/data, and start mapping set:
roscd ndt_mcl cd data rosbag play mapping.bag
Once the mapping.bag is finalized, in terminal execute:
rosservice call /laser_fuser_2d/save_map "{}"
Now copy the saved map to ndt_mcl:
roscd ndt_fuser cd maps cp basement2d_map.jff ../../ndt_mcl/maps
Next change the name of the map in 2d_ndt_mcl_node.launch file to the basement2d_map.jff. Execute:
roslaunch ndt_mcl 2d_ndt_mcl_node.launch
Notes
The initial position in current version can be given through launch file or by having the ground truth information in the bag file (or system). In a near future there will be an option to set this from the rviz as well.