| Note: Dans ce tutoriel on considère que vous êtes familier du langage de balisage xml. | 
|   | 
utiliser un urdf avec le robot state publisher
Description: Ce tutoriel donne un exemple complet d'un modèle de robot avec un URDF utilisant robot_state_publisher. D'abord nous créons un modèle URDF avec toutes les pièces nécessaires. Ensuite nous ecrivons un node qui publie l'état des articulations et les transformations. Enfin, on exécute le total ensemble.Keywords: robot_state_publisher urdf
Tutorial Level: INTERMEDIATE
Contents
Créer un fichier URDF
Ici il y a un fichier URDF pour un modèle à 7-link (liaisons) ressemblant aproximativement à R2-D2. Sauvegardez le lien suivant sur votre ordinateur: model.xml
Certaines des principales caractéristiques
Error: No code_block found
Publier l'état
Maintenant nous avons besoin d'une méthode pour spécifier dans quel état est le robot. Pour cela, nous devons spécifier les trois articulations et l'odométrie globale. Créez un package contenant le code source ci-dessous (tout au long de cet exemple, nous appellerons le package "r2d2" et le node "state_publisher"):
   1 #include <string>
   2 #include <ros/ros.h>
   3 #include <sensor_msgs/JointState.h>
   4 #include <tf/transform_broadcaster.h>
   5 
   6 int main(int argc, char** argv) {
   7     ros::init(argc, argv, "state_publisher");
   8     ros::NodeHandle n;
   9     ros::Publisher joint_pub = n.advertise<sensor_msgs::JointState>("joint_states", 1);
  10     tf::TransformBroadcaster broadcaster;
  11     ros::Rate loop_rate(30);
  12 
  13     const double degree = M_PI/180;
  14 
  15     // robot state
  16     double tilt = 0, tinc = degree, swivel=0, angle=0, height=0, hinc=0.005;
  17 
  18     // message declarations
  19     geometry_msgs::TransformStamped odom_trans;
  20     sensor_msgs::JointState joint_state;
  21     odom_trans.header.frame_id = "odom";
  22     odom_trans.child_frame_id = "axis";
  23 
  24     while (ros::ok()) {
  25         //update joint_state
  26         joint_state.header.stamp = ros::Time::now();
  27         joint_state.name.resize(3);
  28         joint_state.position.resize(3);
  29         joint_state.name[0] ="swivel";
  30         joint_state.position[0] = swivel;
  31         joint_state.name[1] ="tilt";
  32         joint_state.position[1] = tilt;
  33         joint_state.name[2] ="periscope";
  34         joint_state.position[2] = height;
  35 
  36 
  37         // update transform
  38         // (moving in a circle with radius=2)
  39         odom_trans.header.stamp = ros::Time::now();
  40         odom_trans.transform.translation.x = cos(angle)*2;
  41         odom_trans.transform.translation.y = sin(angle)*2;
  42         odom_trans.transform.translation.z = .7;
  43         odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(angle+M_PI/2);
  44 
  45         //send the joint state and transform
  46         joint_pub.publish(joint_state);
  47         broadcaster.sendTransform(odom_trans);
  48 
  49         // Create new robot state
  50         tilt += tinc;
  51         if (tilt<-.5 || tilt>0) tinc *= -1;
  52         height += hinc;
  53         if (height>.2 || height<0) hinc *= -1;
  54         swivel += degree;
  55         angle += degree/4;
  56 
  57         // This will adjust as needed per iteration
  58         loop_rate.sleep();
  59     }
  60 
  61 
  62     return 0;
  63 }
Fichier Launch
Ce fichier launch considère que le nom du package est "r2d2" et celui du node "state_publisher".
   1 <launch>
   2         <param name="robot_description" command="cat $(find r2d2)/model.xml" />
   3         <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
   4         <node name="state_publisher" pkg="r2d2" type="state_publisher" />
   5 </launch>
Affichage du résultat
Exécuter rviz, choisissez odom comme repère d'origine fixe (fixed frame sous Global Options). Alors choisir "Add Display" et ajouter un affichage de modèle de robot (Robot Model Display) et un affichage de TF (TF Display) voir http://www.ros.org/wiki/rviz/UserGuide. Run rviz, choosing odom as your fixed frame (under Global Options). Then choose "Add Display" and add a Robot Model Display and a TF Display (see http://www.ros.org/wiki/rviz/UserGuide).







