Cartographer SLAM with ROS 2 in SITL¶
This page shows how to setup ROS 2 with ArduPilot SITL and run Google Cartographer as a SLAM source.
Installation¶
This page assumes that you’ve successfully followed the ROS 2 basic setups from this wiki: ROS 2, ROS 2 with SITL and ROS 2 with gazebo.
Once that’s done, simply run:
cd ~/ardu_ws/src
git clone git@github.com:ArduPilot/ardupilot_ros.git
cd ~/ardu_ws
rosdep install --from-paths src --ignore-src -r --skip-keys gazebo-ros-pkgs
Now source your workspace and build ardupilot_ros:
cd ~/ardu_ws
source ./install/setup.bash
colcon build --packages-up-to ardupilot_ros ardupilot_gz_bringup
Usage¶
This package is used in combination with ardupilot_gz, first we will launch a simulation containing a copter equipped with a 360 degress 2D lidar in a maze world. To launch rviz and gazebo, run:
source ~/ardu_ws/install/setup.sh
ros2 launch ardupilot_gz_bringup iris_maze.launch.py
Now, we can launch Google Cartographer to generate SLAM, check if a map is being generated correctly in RVIZ. In another terminal, run:
source ~/ardu_ws/install/setup.sh
ros2 launch ardupilot_ros cartographer.launch.py
Configure ArduPilot¶
If you’d like to get the information from Cartographer to go into ArduPilot’s extended kalman filter, you will need to change some parameters, you can do that through any GCS, including mavproxy:
AHRS_EKF_TYPE = 3 to use EKF3
EK2_ENABLE = 0 to disable EKF2
EK3_ENABLE = 1 to enable EKF3
EK3_SRC1_POSXY = 6 to set position horizontal source to ExternalNAV
EK3_SRC1_POSZ = 1 to set position vertical source to Baro
EK3_SRC1_VELXY = 6 to set velocity horizontal source to ExternalNAV
EK3_SRC1_VELZ = 6 to set vertical velocity source to ExternalNAV
EK3_SRC1_YAW = 6 to set yaw source to ExternalNAV
VISO_TYPE = 1 to enable visual odometry
ARMING_CHECK = 388598 (optional, to disable GPS checks)
After changing the values above, reboot the flight controller.
Warning
The parameters above are recommended for SITL. If you plan on using this on a real copter, it is a good idea to setup a second source of EKF. This way the robot doesn’t crash if the external odometry you are providing stops publishing or gets lost.
Please refer to this link for more information on Common EKF Sources as well as this guide on GPS / Non-GPS Transitions.
Demo¶
Here’s a quick video showcasing the results expected from this tutorial:
For more information regarding the ardupilot_ros package refer to ardupilot_ros’s github page.