# ROS 2 Cartographer ## 1. Introduction - The goal of this tutorial is to - use Cartographer to create a map of environment - The packages that will be used: - cartographer - cartographer-ros - turtlebot3_cartographer - turtlebot3_teleop - turtlebot3_gazebo This tutorial explains how to use the Cartographer for mapping and localization. * Lines beginning with `$` indicates the syntax of these commands. Commands are executed in a terminal: * Open a new terminal → use the shortcut ctrl+alt+t. Open a new tab inside an existing terminal → use the shortcut ctrl+shift+t. * Info: The computer of the real robot will be accessed from your local computer remotely. For every further command, a tag will inform which computer has to be used. It can be either `[TurtleBot]` or `[Remote PC]`. ## 2. General approach The main problem in mobile robotics is localization and mapping. To estimate the position of the robot in an environment, you need some kind of map from this environment to determine the actual position in this environment. On the other hand, you need the actual position of robots to create a map related to its position. Therefore you can use SLAM – Simultaneous Localization and Mapping. ROS provides different packages to solve this problem: * **2D**: gmapping, hector_slam, cartographer, ohm_tsd_slam... * **3D**: rgbdslam, ccny_rgbd, lsd_slam, rtabmap... For ground-based robots, it is often sufficient to use 2D SLAM to navigate through the environment. In the following tutorial, cartographer will be used. Cartographer SLAM builds a map of the environment and simultaneously estimates the platform's 2D pose. The localization is based on a laser scan and the odometry of the robot. ## 3. Start Cartographer ### 3.1. Technical Overview ![Technical Overview](../../_static/high_level_system_overview.png) Figure 1: Technical Overview source: [cartographer](https://google-cartographer.readthedocs.io/en/latest/) ### 3.2. Check packages #### 3.2.1. Check if there are cartographer packages ```bash # source ROS 2 $ source /opt/ros/foxy/setup.bash $ ros2 pkg list |grep cartographer # You will get # cartographer_ros # cartographer_ros_msgs ``` If you don't have "cartographer_ros" and "cartographer_ros_msgs", you can install cartographer by performing the following: **Before installing package, you need to make sure which ROS distribution you are using.** ```bash $ sudo apt install ros-$ROS_DISTRO-cartographer ``` #### 3.2.2. Check if there are turtlebot3* packages ```bash $ ros2 pkg list | grep turtlebot3 ``` If you don't have turtlebot3 packages, you can install debian packages or from source code. A. Install debian packages ```bash sudo apt install ros-foxy-turtlebot3* ``` B. Install from source code First entering your workspace ```bash $ wget https://raw.githubusercontent.com/ROBOTIS-GIT/turtlebot3/foxy-devel/turtlebot3.repos ``` Make sure you have "src" folder, then run this command to get source code for turtlebot3 ```bash $ vcs import src