Simuler et faire marcher Darwin OP avec Gazebo et ROS

Le robot Darwin OP est un des rares robots humanoïdes complètement open-source et disponible dans le commerce (un autre étant le robot Poppy, bientôt disponible à la vente !). Cela en fait une plateforme de choix pour de nombreux hobbyistes et chercheurs.

Le Darwin OP représente cependant un certain investissement, et un simulateur peut alors se révéler bien utile ! (également pratique si vous souhaitez tester des comportements risqués).

Nous allons donc vous expliquer ici comment utiliser le simulateur open-source Gazebo avec un modèle de Dawin OP, puis comment l'exploiter avec le middleware ROS, notamment sur des simulations de marche.

Ce guide se base sur les concepts présentés dans notre tutoriel "Scénarios de simulation robotique avec Gazebo et ROS" (en anglais). Sa lecture est donc fortement recommandée.

Darwin OP marchant dans Gazebo

Préparation

Tout d'abord, il vous faut vérifier que vous avez bien installé toutes les dépendances.

Il existe quelques complexités liées à la version de Gazebo et la version de ROS. Ce guide est basé sur les versions ROS Hydro et Gazebo 1.9, mais le code également compatible avec ROS Indigo.

  1. Suivez les instructions d'installation de Gazebo

  2. Puis celles de ROS Hydro

  3. Pour finir l'étape préparation, entrez la commande suivante :

Commande apt-get

sudo apt-get install git ros-hydro-desktop-full gazebo ros-hydro-gazebo-plugins ros-hydro-gazebo-ros ros-hydro-gazebo-ros-control ros-hydro-hector-gazebo ros-hydro-hector-gazebo-plugins ros-hydro-effort-controllers ros-hydro-joint-state-controller ros-hydro-joint-state-publisher ros-hydro-turtlebot-teleop 

Paquets ROS de simulation Darwin OP

Comme pour notre tutoriel précédent, commencez par créer et configurer un nouveau workspace :

cd ~
mkdir -p ros-darwin/src
cd ros-darwin/src
source /opt/ros/hydro/setup.bash
catkin_init_workspace

Vous allez maintenant récupérer les paquets ROS Darwin OP qui sont à votre disposition sur notre GitHub HumaRobotics, puis construire et sourcer le workspace :

git clone https://github.com/HumaRobotics/darwin_description.git
git clone https://github.com/HumaRobotics/darwin_control.git
git clone https://github.com/HumaRobotics/darwin_gazebo.git
cd ..
catkin_make
source devel/setup.bash

N'oubliez pas que dans chaque terminal que vous lancez il vous faudra sourcer ~/ros-darwin/devel/setup.bash

Premier lancement

Tout est prêt; il est temps de passer à la phase de test !

roslaunch darwin_gazebo darwin_gazebo.launch

Après avoir tapé cette commande, Gazebo doit se lancer et le modèle du robot Darwin OP doit normalement apparaître.

Regardez bien les messages de sortie, et cherchez une série de messages "Loading controller: ..." puis "Controller Spawner: Loaded controllers:..." (vous devriez les voir passer vers la fin).

Ces messages signifient que les contrôleurs ROS sont actifs et bloqueront les moteurs en position 0 (comme sur l'image), vous pouvez cliquer sur le bouton "Play" dans Gazebo pour lancer effectivement la simulation (si vous n'attendez pas assez, vous risquez de voir Darwin d'effondrer sur lui-même avant que les contrôleurs ne soient en place).

Lancement Gazebo avec le modèle de Darwin OP

Bon, c'est bien joli, mais il ne se passe pas grand chose pour l'instant. En effet, tout ce que nous avons fait pour l'instant, c'est d'exposer Darwin OP dans ROS.

Faisons donc bouger un peu notre ami Darwin, nous avons mis une démo à votre disposition qu'il vous suffit simplement de lancer dans un second terminal (sourcé) :

rosrun darwin_gazebo walker_demo.py

Voici ce que cela donne en vidéo:

Exposition ROS

L'objectif de cette section est de fournir un modèle du robot exposé dans ROS afin d'être pilotable par d'autres noeuds, et à terme de pouvoir piloter le vrai robot ou la simulation avec le même code.

Faisons le tour des éléments déjà disponibles :

rostopic list

Dans la liste ainsi obtenue, un certain nombre de topics permettent d'accéder aux capteurs du robot:

/darwin/camera/image_raw #   =>   Donne accès à l'image caméra
/darwin/imu #                =>   Fournit les informations de la centrale inertielle
/darwin/joint_states #       =>   Fournit les informations de position/vitesse/couple de chaque articulation

La caméra et la centrale inertielle sont fournies par des plugins Gazebo déclarés dans darwindescription/urdf/darwin.urdf. La partie jointstates est fournie par le robot_statepublisher dont l'appel et la configuration sont décrits dans le package darwincontrol.

Vous pouvez directement oberver les données issues de ces capteurs en faisant:

rostopic echo /darwin/imu
rostopic echo /darwin/joint_states

Pour avoir l'image caméra vous pouvez utiliser le package image_view:

rosrun image_view image_view image:=/darwin/camera/image_raw

Pour les effecteurs, chaque articulation est pilotable en position (radians) en envoyant des messages sur les topics suivants:

/darwin/j_ankle1_l_position_controller/command
/darwin/j_ankle1_r_position_controller/command
/darwin/j_ankle2_l_position_controller/command
/darwin/j_ankle2_r_position_controller/command
/darwin/j_gripper_l_position_controller/command
/darwin/j_gripper_r_position_controller/command
/darwin/j_high_arm_l_position_controller/command
/darwin/j_high_arm_r_position_controller/command
/darwin/j_low_arm_l_position_controller/command
/darwin/j_low_arm_r_position_controller/command
/darwin/j_pan_position_controller/command
/darwin/j_pelvis_l_position_controller/command
/darwin/j_pelvis_r_position_controller/command
/darwin/j_shoulder_l_position_controller/command
/darwin/j_shoulder_r_position_controller/command
/darwin/j_thigh2_l_position_controller/command
/darwin/j_thigh2_r_position_controller/command
/darwin/j_thigh2_l_position_controller/command
/darwin/j_thigh2_r_position_controller/command
/darwin/j_tibia_l_position_controller/command
/darwin/j_tibia_r_position_controller/command
/darwin/j_tilt_position_controller/command
/darwin/j_wrist_l_position_controller/command
/darwin/j_wrist_r_position_controller/command

Par exemple, pour faire tourner la tête du robot vers la gauche puis vers la droite, il suffit de faire :

rostopic pub /darwin/j_pan_position_controller/command std_msgs/Float64 -- 1
rostopic pub /darwin/j_pan_position_controller/command std_msgs/Float64 -- -1

Marche et téléopération

Pour la marche, un noeud dédié darwingazebo/scripts/walker.py attend des commandes de marche sur le topic /darwin/cmdvel.

Par exemple, vous pouvez faire avancer le robot puis s'arrêter en faisant:

rostopic pub /darwin/cmd_vel geometry_msgs/Twist '[1,0,0]' '[0,0,0]' # Vitesse en X: 1
rostopic pub /darwin/cmd_vel geometry_msgs/Twist '[0,0,0]' '[0,0,0]' # Vitesse nulle: arrêt

La plupart des robots mobiles sous ROS exploitent le même topic cmd_vel pour recevoir leurs commandes de déplacement. Ceci veut dire que, modulant un remapping des noms de topic, vous pouvez réutiliser des noeuds de téléopération existants.

Par exemple celui de téléopération clavier de turtlesim (peu recommandé car les vitesses ne sont pas adaptées) :

rosrun turtlesim turtle_teleop_key /turtle1/cmd_vel:=/darwin/cmd_vel

Plus adapté, le noeud de téléoperation clavier du Turtlebot vous permettra d'ajuster les vitesses mais aussi de pouvoir stopper le robot. Par contre il ne permet pas d'envoyer des commandes de déplacement latéral. Pour l'utiliser:

rosrun turtlebot_teleop turtlebot_teleop_key /turtlebot_teleop/cmd_vel:=/darwin/cmd_vel

API Python

Afin de faciliter l'utilisation du robot, nous avons écrit une API client ROS en Python. Cela veut dire que cette API communique uniquement à travers les services ROS et est donc transparente en termes de réseau. Elle se moque donc de savoir si le robot derrière est réel ou simulé.

Pour tester cette API, le plus simple est de regarder le script de démo darwingazebo/scripts/walkerdemo.py:


#!/usr/bin/env python
import rospy
from darwin_gazebo.darwin import Darwin


if __name__=="__main__":
    rospy.init_node("walker_demo")


    rospy.loginfo("Instantiating Darwin Client")
    darwin=Darwin()
    rospy.sleep(1)


    rospy.loginfo("Darwin Walker Demo Starting")


    darwin.set_walk_velocity(0.2,0,0)
    rospy.sleep(3)
    darwin.set_walk_velocity(1,0,0)
    rospy.sleep(3)
    darwin.set_walk_velocity(0,1,0)
    rospy.sleep(3)
    darwin.set_walk_velocity(0,-1,0)
    rospy.sleep(3)
    darwin.set_walk_velocity(-1,0,0)
    rospy.sleep(3)
    darwin.set_walk_velocity(1,1,0)
    rospy.sleep(5)
    darwin.set_walk_velocity(0,0,0)
    rospy.loginfo("Darwin Walker Demo Finished")

Décomposons ensemble ce code:


#!/usr/bin/env python

import rospy from darwin_gazebo.darwin import Darwin 

Ici nous signalons que notre script doit être interprété par Python, puis nous chargeons la librairie ROS et notre API Darwin.


if __name__=="__main__":
    rospy.init_node("walker_demo")
    
    rospy.loginfo("Instantiating Darwin Client")
    darwin=Darwin()
    rospy.sleep(1)

Dans cette section, on créé un noeud ROS appelé walker_demo, élément nécessaire pour communiquer avec l'infrastructure ROS. On créé ensuite une instance de la classe Darwin qui encapsule notre API Python. L'attente de 1 seconde permet d'être sûr que tous les topics se sont bien mis en place.


    darwin.set_walk_velocity(0.2,0,0)
    rospy.sleep(3)
    darwin.set_walk_velocity(1,1,0)
    rospy.sleep(5)
    darwin.set_walk_velocity(0,0,0)    

Ici on fait appel à l'API proprement dite, en envoyant des commandes de vitesse, pouvant combiner plusieurs composantes (translations en X, Y, et rotation Theta). La vitesse 0 permet de stopper le robot. Les appels sont non bloquants, c'est pourquoi on ajoute une attente afin de laisser le temps au robot d'effectuer un peu de marche à la vitesse demandée.

Il est aussi possible de contrôler directement les articulations grâce à la fonction set_angles.

Par exemple pour tourner la tête à gauche puis à droite il suffit de faire:


    darwin.set_angles({"j_pan":1})
    rospy.sleep(1)
    darwin.set_angles({"j_pan":-1})
    rospy.sleep(1) 

Conclusion

Tout n'a pas pu être couvert dans ce tutoriel, mais vous avez des bonnes bases pour commencer à jouer avec Darwin et Gazebo.

Dans un prochain article, nous étudierons plus en détail les API de mouvement pour décrire des animations complexes, et nous verrons aussi comment fonctionne le noeud qui permet à Darwin de marcher.

Et si vous êtes sages d'ici là, je vous donnerai peut-être un modèle pour un autre robot. Qui a parlé d'hexapode?

Dr. Philippe Capdepuy, ingénieur chercheur chez Génération Robots et HumaRobotics