Localization for Indoor Testing - ArcturusNavigation/all_seaing_vehicle GitHub Wiki

Back: Tutorials

Unlike outdoor testing, we do not have access to accurate GPS signals when testing indoors. Instead, we use Nav2's Adaptive Monte Carlo Localization (AMCL) on a map created by the real-time SLAM system, Cartographer.

Publishing the correct transforms

Before progressing in this tutorial, it is important to understand that AMCL will provide the map->odom transform to "correct" the robot localization on the given map. The odom->base_link transform must be provided by some other node. Currently, we rely on the ZED 2i's integrated visual inertial odometry (VIO) system to provide this transform. The VIO provides a short-term but continuous odometry data while AMCL provides a long-term (global) and accurate but discontinuous corrections to the odom frame. Since AMCL is providing the corrections, we also disable loop closures performed by the ZED.

You can launch the ZED using the following command:

ros2 launch all_seaing_driver zed2i.launch.py

Installation

sudo apt install \
ros-humble-cartographer \
ros-humble-nav2-amcl \
ros-humble-nav2-map-server \
ros-humble-nav2-lifecycle-manager

Generating a 2D occupancy grid using Cartographer

Make sure the LiDAR is connected and running. See here for instructions. You should see the velodyne_points and scan topics.

Launch Cartographer using

ros2 launch all_seaing_bringup cartographer.launch.py

where the parameters are set at all_seaing_bringup/config/localization/cartographer.lua. When you open rviz2 and add the map topic, you should be able to see the map being slowly generated! For example, here is a 2D occupancy grid of the Sea Grant conference room:

room_grid

Wait until the map looks "complete," occasionally slowly moving the robot around.

Once a map of the environment has been created, use the following command to save the map to a .pgm and .yaml file:

ros2 run nav2_map_server map_saver_cli -f <map_name>

where <map_name> is the name of the saved map. The maps are saved into the all_seaing_bringup/map directory.

Using the generated map for AMCL

First, open rviz2 and add the map topic and the TF display type.

Then, run AMCL using

ros2 launch all_seaing_bringup amcl.launch.py location:=<location_name>

<location_name> is chosen from all_seaing_bringup/map (it is conference by default for use at the conference room). For permanent indoor locations, you should also add its information in all_seaing_bringup/config/localization/locations.yaml.

This will run two nodes: the map_server to publish the saved map and amcl to run the AMCL algorithm using the laserscan and occupancy grid. Both of these nodes are managed nodes, so they must be activated via lifecycle commands (this is so that they can be activated and deactivated in the correct order). The map_server is automatically activated using the nav2-lifecycle-manager, but amcl must be configured and activated manually:

ros2 lifecycle set /amcl configure
ros2 lifecycle set /amcl activate

You can also reactivate the map_server (e.g. if you ran RViz after the map server so the map doesn't show up):

ros2 lifecycle set /map_server deactivate
ros2 lifecycle set /map_server activate

On RViz, drag the "2D Pose Estimate" arrow on the estimated initial pose on the map. As the robot moves, you should see the map->odom TF being updated to correct the robot odometry!

⚠️ **GitHub.com Fallback** ⚠️