Odométrie (F1TENTH) - vaul-ulaval/vaul-wiki GitHub Wiki

C'est quoi l'odométrie ?

L'odométrie du robot est la mesure de son déplacement relatif entre deux pas de temps. On se sert principalement des encodeurs de moteurs (qui permettent d'estimer sa vitesse de rotation) et de la centrale inertielle intégrée (qui donne l'accélération en x-y-z et la vitesse angulaire en roll-pitch-yaw).

Ajustement de l'odométrie des encodeurs

Le moteur du F1TENTH possède des capteurs à effet hall intégrés, qui permettent d'asservir sa vitesse précisément, mais aussi d'obtenir une estimation de celle-ci. Le VESC (Vedder Electronic Speed Controller) envoie des commandes au moteur et lis la vitesse mesurées du moteur. Dans le code, le package "vesc" gère la communication avec le contrôleur et l'estimation de l'odométrie du robot. Pour calibrer l'odométrie, il faut ajuster certains paramètres dans les fichiers suivants:

vesc.yaml (dans ~/f1tenth_ws/src/main/vaul_f1tenth_system/config/) :

/**:
  ros__parameters:
--> speed_to_erpm_gain: 4000.0  # Adjusted by comparing a 180 degrees rotation in real life vs Rviz Odometry arrows
    speed_to_erpm_offset: 0.0

--> steering_angle_to_servo_gain: -0.909 # -0.909 for RENEGADE (#1) / -1.0 for BLITZ (#2)
    steering_angle_to_servo_offset: 0.5

Ces paramètres sont utilisés pour convertir une commande ackermann (donc, speed en m/s et steering en rad) vers une commande reconnue par le VESC (speed en ERPM et steering entre 0 et 1). On a déterminé empiriquement que l'intervalle réel permettant de contrôler l'orientation des roues dans le VESC est de 0.1 à 0.9. Étapes de calibration à faire :

  1. Allumer le robot et vérifier qu'il est contrôlable avec la manette.
  2. Ajuster mécaniquement l'angle de braquage des roues en laissant steering_angle_to_servo_offset à 0.5. Vous pouvez suivre le guide d'ajustement de Traxxas, dont les liens se trouve à la page Mécanique. Toucher seulement au "Toe-In" des roues avant. Si jamais vous n'arrivez pas à faire rouler le robot en ligne droite avec l'ajustement mécanique, alors changez le paramètre steering_angle_to_servo_offset.
  3. Ajuster le steering_angle_to_servo_gain en trouvant l'angle de rotation maximal du robot. Pour ce faire, on utilise un modèle bicyclette, tel que présenté ici :

image

La procédure consiste à aligner le robot avec les tuiles du plancher, puis à marquer le centre des roues arrière avec un morceau de tape. On fait faire un demi-tour au robot en mettant le joystick de steering au maximum. On marque à nouveau le centre des roues arrière avec un tape, puis on mesure la distance entre les 2 tapes (donc, le diamètre de rotation minimal du robot). À partir du modèle cinématique bicyclette, on peut calculer l'angle de steering maximal et le gain à appliquer avec les relations suivantes :

max_steering_angle = arctan(L / R)
steering_angle_to_servo_gain = -0.4 / max_steering_angle 

avec L = 32.4 cm, la distance entre les roues avant et arrière du robot et R = D/2, soit le diamètre mesuré divisé par 2. Le 0.4 vient de l'intervalle réel de la plage du servomoteur de direction (0.4) calculé préalablement. On met la valeur négative pour respecter la convention de ROS.

  1. Ajuster le speed_to_erpm_gain en ouvrant RViz affichant l'odométrie (flèches rouges), puis en faisant tourner le robot d'un demi-tour. Mettez RViz en vue de dessus pour bien voir les déplacements. Ajuster le paramètre de sorte que le robot effectue bien un demi-tour dans RViz. Par la même occasion, vérifiez que le diamètre de rotation correspond bien à ce que vous aviez mesuré en (2). Petit truc : les carrés de la grille de base dans RViz mesurent 1 mètre.

joy_teleop_xbox.yaml (dans ~/f1tenth_ws/src/main/vaul_f1tenth_system/config/) :

joy_teleop_node:
  ros__parameters:
    human_control:
      axis_mappings:
        drive-steering_angle:
     -->  scale: 0.44  # Equal to max steering angle in rad - 0.44 for RENEGADE (#1) / 0.40 for BLITZ (#2) **

Ce paramètre ajuste l'angle maximal de rotation (max_steering_angle) des roues tel que commandé par la manette. Mettre la valeur en radians mesurée précédemment.

Centrale inertielle

Le VESC possède également une centrale inertielle (IMU) intégrée. Celle-ci permet de mesurer des accélérations linéaires et des vitesses angulaires. Pour l'instant, l'IMU n'est pas utilisée dans les estimations d'odométrie, mais il serait pertinent de combiner ses mesures avec l'odométrie du moteur dans le futur.