Créer votre première map avec slam_toolbox – French ROS2 Tutorial

22/08/2024


Cours: ROS2 Basics in 5 Days C++: https://app.theconstructsim.com/courses/133

Le but de ce tutoriel est d’apprendre à utiliser slam_toolbox pour créer des maps, les sauvegarder et les réutiliser avec map_server. slam_toolbox est un package regroupant un ensemble d’outils pour la localisation et la cartographie simultanées (SLAM) en robotique, permettant la création de cartes en temps réel et le suivi de la position. La cartographie est essentielle en robotique pour la navigation, la planification efficace de la trajectoire et l’évitement des obstacles. Elle améliore l’autonomie et la précision des robots dans les environnements dynamiques.

Prérequis: Utiliser une installation ROS2 avec Gazebo, turtlebot3 et slam_toolbox

Installation ROS2

Vous pouvez vous connecter au site TheConstruct pour accéder à des machines virtuelles préconfigurées avec une installation ROS2. Pour lancer et tester le code, vous devez lancer la simulation du turtlebot3 sur gazebo. Pour faire cela, entez les commandes suivantes dans le terminal:

# Declare le model de turtlebot3 à simuler
export TURTLEBOT3_MODEL=waffle_pi
# Lance la simulation du turtlebot dans gazebo
ros2 launch turtlebot3_gazebo turtlebot3_world.launch.py

Une fois la simulation du turtlebot3 lancée, celle-ci va publier les tf du turtlebot3 et les données obtenues avec son laserscan sur le topic /scan que nous allons utiliser durant le tutoriel. Après avoir exécuté ces commandes, appuyez sur le bouton de l’interface gazebo et sélectionnez Open Gazebo.

Vous devriez obtenir le résultat suivant:
alternative text
Si vous voulez effectuer le tutoriel sur votre installation local, vous devez avoir ROS2 installé (https://docs.ros.org/en/humble/Installation.html), avoir configuré un workspace (https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html) et avoir installé le turtlebot3.
# pour installer tous les packages du turtlebot3
# remplacez humble par votre distro ROS2cd ~/ros2_ws
sudo apt-get install ros-humble-turtlebot3*
# n'oubliez pas d'exporter le modèle de Turtlebot3 que vous souhaitez utiliser
export TURTLEBOT3_MODEL=waffle_pi

Installer slam_toolbox

Vous pouvez installer slam_toolbox avec la commande suivante:

# Pour install slam_toolbox
sudo apt-get install ros-humble-slam-toolbox

Partie 1: Configurer son package

Nous allons commencer par créer un package ROS2 pour stocker les fichiers launch et yaml necessaires:

cd ros2_ws/src/
# Créer le package
ros2 pkg create slam_setup_tutorial
cd slam_setup_tutorial
# Créer les dossiers pour stocker les launch et params files
mkdir launch
mkdir params

Nous allons maintenant éditer le Cmakelist.txt:

cmake_minimum_required(VERSION 3.8)
project(slam_setup_tutorial)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)

# On declare les dossiers launch et params dans les installs
install(DIRECTORY
  launch
  params
  DESTINATION share/${PROJECT_NAME}/
)

if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  # the following line skips the linter which checks for copyrights
  # comment the line when a copyright and license is added to all source files
  set(ament_cmake_copyright_FOUND TRUE)
  # the following line skips cpplint (only works in a git repo)
  # comment the line when this package is in a git repo and when
  # a copyright and license is added to all source files
  set(ament_cmake_cpplint_FOUND TRUE)
  ament_lint_auto_find_test_dependencies()
endif()

ament_package()

Vous pouvez build votre workspace pour verifier si la configuration du CmakeList.txt fonctionne:

cd ~/ros2_ws
colcon build
source install/setup.bash

Partie 2: Setup slam_toolbox

Les maps générées par slam_toolbox sont au format “occupancy grid”. Ce format représente l’environnement en une grille régulière de cellules, où chaque cellule correspond à une petite zone de l’espace. Voici une map au format occupancy grid:

image pgm map

  • Résolution : La résolution de la carte indique la taille de chaque cellule en mètres par pixel.
  • Valeurs des cellules : Chaque cellule de la grille contient une valeur indiquant le niveau d’occupation :
    • 0 représente un espace libre (en blanc sur la représentation de la map).
    • 100 représente un obstacle (en noir).
    • -1 indique une cellule inconnue ou non explorée (en gris).
  • TF de référence : La carte est associée à un transform de référence global, souvent nommé “map”, qui permet de situer les cellules dans l’espace réel. Cette représentation permet aux robots de naviguer et de planifier des trajectoires en évitant les obstacles et en se déplaçant à travers les espaces libres détectés par leurs capteurs.

Pour pouvoir utiliser slam_toolbox, les tf du robot doivent être configurées en respectant les conventions du REP105 : Coordinate Frames for Mobile Platforms. Une explication plus pratique de cette configuration est décrite dans la documentation de Nav2 sur la configuration des transforms. Ces notions sont paraticulièrement importantes si vous voulez effectuer du slam sur un robot custom. Dans ce tutoriel nous allons utiliser le turtlebot3 qui possède déjà une implementation compléte de ses TF locales. Vous pouvez visuliser le TF tree du robot en appelant le node view_frames du package tf2_tools:

ros2 run tf2_tools view_frames

Ce node va génerer deux fichiers à l’emplacement où vous avez executé la commande: frames_date_hour.pdf and frames_date_hour.gv. En ouvrant le fichier pdf, vous pourrez voir le tf tree du turtlebot3 executé en simulation:

Robot tf_tree

Vous devriez avoir les frames suivantes:

  • La frame odom est la frame de réference pour la localisation locale du robot.
  • La frame base_link represente la frame principale du robot, c’est relativement à celle ci que les differentes treansforms des capteurs et autres links du robot sont déclarées.
  • Les frames des differents capteurs définis relativement à base_link

Le package slam_toolbox va generer une nouvelle frame map qui va servir de réference globale pour la localisation du robot par rapport à l’espace. Si la localisation du robot dans la frame odom est sujet à une dérive et une accumulation d’erreurs à cause de la nature de ses capteurs (odometry visuelle ou via roues codeuses, accélerometre) qui ne possède que des informations relatives, la localisation du robot dans la frame map va souvent être effectuée avec la fusion des sources de localisations “globales”. Dans le cas des robots d’exterieurs, le GPS fait souvent office de reference globale. Pour les robots d’interieurs les lidars vont souvent fournir cette information.

Nous allons utiliser le package crée dans la partie précedante. On va d’abord créer le fichier yaml qui va contenir les parametres pour slam_toolbox:

cd ~/ros2_ws/src/slam_setup_tutorial/
cd params
touch slam_toolbox_params.yaml

Une fois le fichier créer, ouvrez le dans votre éditeur de code et copiez y la configuration suivante:

slam_toolbox:
  ros__parameters:
    # Le robot est lancé en simulation, synchroniser le temps du robot avec la clock de la simulation
    use_sim_time: true
    # Fréquence de mise à jour du SLAM en Hz
    update_rate: 1.0
    # Période de publication de la carte en secondes
    publish_period: 0.1
    # Résolution de la carte créée, en mètres/pixel
    resolution: 0.05
    # Portée maximale considérée pour les valeurs du laser scan
    max_laser_range: 8.0
    # Topic sur lequel le robot publie les données du laser scan
    scan_topic: /scan
    # Frame de référence pour la localisation locale (souvent "odom" par convention)
    odom_frame: odom
    # Frame de référence attachée au robot (souvent "base_link" par convention)
    base_frame: base_link
    # Mode d'opération de slam_toolbox (mapping ou localisation)
    mode: mapping
    # Activer les logs de debug
    debug_logging: true

    # Intervalle de mise à jour de la carte en secondes
    map_update_interval: 5.0
    # Seuil maximal d'occupation pour considérer une cellule comme occupée
    max_occupied_threshold: 0.65
    # Seuil minimal pour considérer une cellule comme libre
    min_free_threshold: 0.196
    # Intervalle de temps minimal entre deux mises à jour de pose en secondes
    minimum_time_interval: 0.5
    # Période de publication des transformations en secondes
    transform_publish_period: 0.02
    # Distance minimale parcourue pour déclencher une mise à jour en mètres
    linear_update: 0.1
    # Rotation minimale effectuée pour déclencher une mise à jour en radians
    angular_update: 0.1
    # Taille du buffer pour les scans laser
    scan_buffer_size: 10
    # Distance maximale des scans stockés dans le buffer en mètres
    scan_buffer_maximum_scan_distance: 8.0
    # Timeout pour la recherche de transformation en secondes
    lookup_transform_timeout_sec: 0.5
    submap:
      # Nombre de cellules dans chaque sous-carte
      number_of_cells: 3500

Cette configuration est adaptée pour le turtlebot3 dans un environemment indoor, pour des en fonction des contraintes de votre plateforme (capteurs, puissance de calcul…) vous devrez optimiser les parametres. Tous les parametres du node slam_toolbox sont listés sur la documentation que vous pouvez trouver ici. Maintenant que nous avons les parametres, nous devons écrire un launch file pour executer le node:

cd ~/ros2_ws/src/slam_setup_tutorial/
cd launch
touch start_slam_toolbox.launch.py
import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import (DeclareLaunchArgument)
from launch.substitutions import (LaunchConfiguration)
from launch_ros.actions import LifecycleNode

def generate_launch_description():
    use_sim_time = LaunchConfiguration('use_sim_time')
    slam_params_file = LaunchConfiguration('slam_params_file')

    declare_use_sim_time_argument = DeclareLaunchArgument(
        'use_sim_time',
        default_value='true',
        description='Use simulation/Gazebo clock')
    # Déclare comme parametre le fichier yaml que nous avons créé precedemment
    declare_slam_params_file_cmd = DeclareLaunchArgument(
        'slam_params_file',
        default_value=os.path.join(get_package_share_directory("slam_setup_tutorial"),
                                   'params', 'slam_toolbox_param.yaml'),
        description='Full path to the ROS2 parameters file to use for the slam_toolbox node')

    # Déclare le node slam_toolbox
    start_async_slam_toolbox_node = LifecycleNode(
        parameters=[
          slam_params_file,
          {
            'use_sim_time': use_sim_time
          }
        ],
        package='slam_toolbox',
        executable='async_slam_toolbox_node',
        name='slam_toolbox',
        output='screen',
        namespace=''
    )

    ld = LaunchDescription()
    ld.add_action(declare_use_sim_time_argument)
    ld.add_action(declare_slam_params_file_cmd)
    ld.add_action(start_async_slam_toolbox_node)

    return ld

On peut maintenant compiler le package avec les commandes suivantes:

cd ~/ros2_ws
colcon build --symlink-install
source install/setup.bash

Vous pouvez maintenant lancer le node avec la commande suivante:

ros2 launch slam_setup_tutorial start_slam_toolbox.launch.py

Vous pouvez ouvrir rviz2 avec le fichier à la racine du projet avec la commande suivant:

rviz2 -d ~/ros2_ws/slam_toolbox_rviz_config.rviz

En ouvrant rviz2 avec la configuration à la racine du tutoriel vous devriez avoir ce visuel:

Image de map incomplete dans rviz

Le robot peut commencer à mapper son environnement en utilisant sa localisation et les valeurs de ses données, c’est ce cycle de localization couplé au mapping que l’on appelle SLAM (Simultaneous Localization And Mapping). Le node de slam_toolbox publie également la tf map utilisée pour la référence de localisation globale qui est une frame parente de la frame odom:

Image tf tree avec la frame map

Partie 3: Sauvegarder la map et la réutiliser

Maintenant que l’on a démarré slam_toolbox, on peut effectuer le mapping de la zone. Pour faire cela vous devez déplacer le robot pour lui permettre de mapper toute la zone. Vous pouvez téléopérer le robot avec la commande suivante:

ros2 run turtlebot3_teleop teleop_keyboard

Une fois la zone totalement explorée par le robot, vous devriez avoir le résultat suivant dans rviz2:

map dans rviz2 completée

Maintenant que nous avons mapper la zone, la prochaine étape est de sauvegarder cette carte pour pouvoir la réutiliser. Pour sauvegarder la carte, vous pouvez appeler le service /slam_toolbox/save_map qui est une wrapper simplifié de map_saver en effectuant la commande suivante:

ros2 service call /slam_toolbox/save_map slam_toolbox/srv/SaveMap "name: {data: 'my_map'}"

Cette commande subscribe sur le topic map et crée des fichiers my_map.pgm et my_map.yaml qui vont être utilisé pour décrire notre map. Le fichier my_map.pgm est une image qui représente l’environnement:

image pgm map

Le fichier my_map.yaml est le fichier de configuration suivant:

# Fichier de l'image de la map
image: my_map.pgm
mode: trinary
# Resolution de la carte en metre/pixel
resolution: 0.05
# origin de la carte dans le referentiel de la frame map
origin: [-2.95, -2.58, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25

Maintenant que notre map est sauvegardée, nous pouvons la republier sur le topic map en utilisant le node map_server. Ce node va cette fois publier la map comme une static map, les points du laserscan ne vont plus mettre à jour la carte. Pour localiser le robot sur cette carte déjà crée, nous allons utiliser le package AMCL pour localiser le robot par rapport à la static map et à publier la map frame à la place slam_toolbox. Le package amcl (Adaptive Monte Carlo Localization) permet à un robot de se localiser dans un environnement connu. Voici comment il fonctionne :

  • Initialisation : Utilise une carte déjà définie comme celle que nous avons créé avec slam_toolbox.
  • Particules : Génère des hypothèses de pose (position + orientation) sous forme de particules.
  • Mise à jour des capteurs : Compare les mesures des capteurs (lidar) avec la carte pour évaluer la pertinence des particules.
  • Resampling : Renforce les particules pertinentes et élimine les autres pour affiner la position estimée.
  • Estimation de la position : Calcule la position moyenne pondérée des particules.
  • Boucle continue : Répète ce processus pour une localisation précise et continue. amcl utilise des fitres à particules et des données de capteurs pour localiser un robot sur une carte connue.

Vous pouvez utiliser lancer le node map_server et amcl avec le fichier launch suivant:

cd ~/ros2_ws/src/slam_setup_tutorial/
cd launch
touch start_map_server_amcl.launch.py
import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node


def generate_launch_description():

    map_file = os.path.join(get_package_share_directory(
        'slam_setup_tutorial'), 'params', 'my_map.yaml')
    
    amcl_file = os.path.join(get_package_share_directory(
        'slam_setup_tutorial'), 'params', 'amcl.yaml')

    return LaunchDescription([
        Node(
            package='nav2_map_server',
            executable='map_server',
            name='map_server',
            output='screen',
            parameters=[{'use_sim_time': True},
                        {'yaml_filename': map_file}]
        ),
        Node(
                package='nav2_amcl',
                executable='amcl',
                name='amcl',
                parameters=[amcl_file],
        ),
        Node(
            package='nav2_lifecycle_manager',
            executable='lifecycle_manager',
            name='lifecycle_manager_localization',
            output='screen',
            parameters=[{'use_sim_time': True},
                        {'autostart': True},
                        {'node_names': ['amcl','map_server']}]
        )
    ])

Il faut également créer le fichier de parametres amcl.yaml dans le fichier params:

amcl:
  ros__parameters:
    # Utiliser le temps de simulation au lieu du temps réel
    use_sim_time: True
    # Coefficients pour les bruits de mouvement
    alpha1: 0.2
    alpha2: 0.2
    alpha3: 0.2
    alpha4: 0.2
    alpha5: 0.2
    # Identifiant de la frame de base du robot
    base_frame_id: "base_footprint"
    # Distance seuil pour ignorer les faisceaux de laser
    beam_skip_distance: 0.5
    # Seuil d'erreur pour ignorer les faisceaux de laser
    beam_skip_error_threshold: 0.9
    # Seuil pour commencer à ignorer les faisceaux de laser
    beam_skip_threshold: 0.3
    # Activer ou désactiver le saut de faisceaux
    do_beamskip: false
    # Identifiant de la frame globale (carte)
    global_frame_id: "map"
    # Paramètre lambda pour le modèle de faisceau court
    lambda_short: 0.1
    # Distance maximale pour considérer les probabilités de faisceau laser
    laser_likelihood_max_dist: 2.0
    # Portée maximale du laser
    laser_max_range: 100.0
    # Portée minimale du laser
    laser_min_range: -1.0
    # Type de modèle de laser utilisé
    laser_model_type: "likelihood_field"
    # Nombre maximal de faisceaux laser utilisés
    max_beams: 60
    # Nombre maximal de particules
    max_particles: 2000
    # Nombre minimal de particules
    min_particles: 500
    # Identifiant de la frame odométrique
    odom_frame_id: "odom"
    # Erreur maximale permise pour le filtre particulaire
    pf_err: 0.05
    # Confiance dans les mesures de position
    pf_z: 0.99
    # Paramètre de récupération rapide pour le filtre particulaire
    recovery_alpha_fast: 0.0
    # Paramètre de récupération lente pour le filtre particulaire
    recovery_alpha_slow: 0.0
    # Intervalle de rééchantillonnage des particules
    resample_interval: 1
    # Type de modèle de mouvement du robot
    robot_model_type: "nav2_amcl::DifferentialMotionModel"
    # Fréquence de sauvegarde de la pose estimée (en secondes)
    save_pose_rate: 0.5
    # Écart type pour le modèle de capteur "hit"
    sigma_hit: 0.2
    # Activer ou désactiver la diffusion des transformations
    tf_broadcast: true
    # Tolérance pour la transformation des coordonnées (en secondes)
    transform_tolerance: 1.0
    # Seuil minimal de rotation pour mettre à jour la pose
    update_min_a: 0.2
    # Seuil minimal de translation pour mettre à jour la pose
    update_min_d: 0.25
    # Poids du modèle de capteur "hit"
    z_hit: 0.5
    # Poids du modèle de capteur "max"
    z_max: 0.05
    # Poids du modèle de capteur "rand"
    z_rand: 0.5
    # Poids du modèle de capteur "short"
    z_short: 0.05
    # Topic fournissant les données du scan laser
    scan_topic: scan
    # Topic sur lequel la carte est publiée
    map_topic: map
    # Utiliser seulement la première carte reçue
    first_map_only: false
    # Permet de définir la pose initiale avec le paramètre initial_pose
    set_initial_pose: true
    # Pose initiale du robot
    initial_pose:
      x: -2.0
      y: -0.5
      z: 0.0
      yaw: 0.0

Vous pouvez trouver la documentation de amcl avec la liste des paramètre ici: https://docs.nav2.org/configuration/packages/configuring-amcl.html. Vous pouvez réutiliser le fichier de configuration rviz2 du projet pour visualiser les résultats:

rviz2 -d ~/ros2_ws/slam_toolbox_rviz_config.rviz

Une fois rviz lancé pour visualiser la carte, vous pouvez build le package et executer le launch file pour voir la map crée précédemment:

cd ~/ros2_ws 
colcon build --symlink-install 
source install/setup.bash 
ros2 launch slam_setup_tutorial start_slam_tool_box.launch.py

Vous devriez maintenant voir la map que nous avons généré dans rviz avec le robot positionné dessus:

alternative text

La TF map est republiée et la pose du robot sur la frame map est publiée sur le topic /amcl_pose. Nous avons donc vu comment générer une static map avec slam_toolbox et comment la réutiliser en utilisant map_server et amcl.

Feedback

Cet article vous a plu ? Avez-vous des questions sur ce qui est expliqué ? Quoi qu’il en soit, n’hésitez pas à laisser un commentaire dans la section des commentaires ci-dessous, afin que nous puissions interagir et apprendre les uns des autres.

Si vous souhaitez en savoir plus sur d’autres sujets liés à ROS, faites le nous savoir dans l’espace commentaires et nous ferons une vidéo ou un article à ce sujet.
Topics: ROS Q&A | ros2

This tutorial is created by Robotics Ambassador Enzo.

Video Tutorial

Topics: amcl | mapping | ros2 | slam
Masterclass 2023 batch2 blog banner

Check Out These Related Posts

129. ros2ai

129. ros2ai

I would like to dedicate this episode to all the ROS Developers who believe that ChatGPT or...

read more

0 Comments

Pin It on Pinterest

Share This