Difference between revisions of "Modelo para simulación MYRAbot (urdf+gazebo)"

From robotica.unileon.es
Jump to: navigation, search
(Carga del modelo en gazebo)
(Programa de prueba (Vuela al ruedo))
Line 1,418: Line 1,418:
 
===Programa de prueba (Vuela al ruedo)===
 
===Programa de prueba (Vuela al ruedo)===
  
Se ha realizado un pequeño programa para probar el funconamiento del modelo del MYRAbot, que simplemente hace girar en circulo al robot y gira el brazo de un lado a otro en posición vertical. Primero vamos a [[ crear un package]] que va a contener nuestro programa y que llamaremos "myrabot_fer", conlas dependencias: brazo_fer geometry_msgs std_msgs nav_msgs sensor_msgs image_transport roscpp.
+
Se ha realizado un pequeño programa para probar el funconamiento del modelo del MYRAbot, que simplemente hace girar en circulo al robot y gira el brazo de un lado a otro en posición vertical. Primero vamos a [[[[Fernando-TFM-ROS02#Creando un package| crear un package]] que va a contener nuestro programa y que llamaremos "myrabot_fer", con las siguientes dependencias: brazo_fer geometry_msgs std_msgs nav_msgs sensor_msgs image_transport roscpp.
  
 +
Dentro de este ''package'' vamos a crear un archivo llamado "vuelta_al_ruedo.cpp" en el directorio "src" con el siguiente contenido:
  
 +
<syntaxhighlight lang="cpp" anclose="div">
 +
 +
  #include "ros/ros.h"
 +
  #include "brazo_fer/Servos.h"
 +
  #include "brazo_fer/WriteServos.h" 
 +
  #include "brazo_fer/ReadServos.h"
 +
  #include "geometry_msgs/Twist.h"
 +
  #include "std_msgs/Bool.h" 
 +
 +
  int cont = 0;
 +
  int cont1= 0;
 +
  int encendido = 0;
 +
  brazo_fer::Servos move, on, vel;
 +
 
 +
 +
  void home()
 +
  {
 +
if (cont1 == 0)
 +
{
 +
ros::NodeHandle n;
 +
 +
ros::Publisher move_arm_pub_=n.advertise<brazo_fer::WriteServos>("move_arm", 1);
 +
ros::Publisher hand_pub_=n.advertise<brazo_fer::WriteServos>("hand_arm", 1); 
 +
ros::Publisher move_base_pub_=n.advertise<geometry_msgs::Twist>("cmd_vel", 1); 
 +
 +
brazo_fer::WriteServos home;
 +
 +
::move.base = 511;
 +
::move.arti1 = 511;
 +
::move.arti2 = 511;
 +
::move.arti3 = 511;
 +
::move.pinza = 511;
 +
 +
::on.base = 1;
 +
::on.arti1 = 1;
 +
::on.arti2 = 1;
 +
::on.arti3 = 1;
 +
::on.pinza = 1;
 +
 +
::vel.base = 400;
 +
::vel.arti1 = 400;
 +
::vel.arti2 = 400;
 +
::vel.arti3 = 400;
 +
::vel.pinza = 400;
 +
 +
home.posicion = ::move;
 +
home.par = ::on;
 +
home.velocidad = ::vel;
 +
 +
move_arm_pub_.publish(home);
 +
hand_pub_.publish(home);
 +
 +
::cont1 = 1;
 +
 +
}
 +
  }
 +
 
 +
  void inicio(const std_msgs::Bool& inicio)
 +
  {
 +
if (inicio.data == true && ::cont == 0)
 +
{
 +
::encendido = 1;
 +
::cont = 1;
 +
}
 +
else if (inicio.data == true && ::cont == 1)
 +
{
 +
::encendido = 0;
 +
::cont = 0;
 +
}
 +
  }
 +
 
 +
  void posicion(const brazo_fer::ReadServos& posicion)
 +
  {
 +
ros::NodeHandle n;
 +
 +
  ros::Publisher move_arm_pub_=n.advertise<brazo_fer::WriteServos>("move_arm", 1);
 +
  ros::Publisher move_base_pub_=n.advertise<geometry_msgs::Twist>("cmd_vel", 1);   
 +
 +
brazo_fer::Servos p = posicion.posicion;
 +
brazo_fer::WriteServos mover_brazo;
 +
 +
home();
 +
 +
if (::encendido == 1)
 +
{
 +
geometry_msgs::Twist mover_base;
 +
 +
mover_base.linear.x = 0.1;
 +
mover_base.angular.z = 0.3;
 +
 +
move_base_pub_.publish(mover_base);
 +
 +
if (::cont1 ==  1)
 +
{
 +
::move.base = 818;
 +
::cont1 = 2;
 +
mover_brazo.posicion = ::move;
 +
mover_brazo.par = ::on;
 +
mover_brazo.velocidad = ::vel;
 +
move_arm_pub_.publish(mover_brazo);
 +
}
 +
else if ((p.base-110) < ::move.base && ::move.base < (p.base+110))
 +
{
 +
if (::cont1 ==  2)
 +
{
 +
::move.base = 204;
 +
::cont1 = 3;
 +
mover_brazo.posicion = ::move;
 +
mover_brazo.par = ::on;
 +
mover_brazo.velocidad = ::vel;
 +
move_arm_pub_.publish(mover_brazo);
 +
}
 +
else
 +
{
 +
::cont1 = 1;
 +
}
 +
}
 +
}
 +
  }
 +
 +
  int main(int argc, char **argv)
 +
  {
 +
 +
ros::init(argc, argv, "vuelta_al_ruedo"); 
 +
 +
ros::NodeHandle n;
 +
 +
 +
  ros::Subscriber pose_sub_= n.subscribe("pose_arm", 1, posicion);
 +
  ros::Subscriber button_sub_= n.subscribe("start_button", 1, inicio);
 +
 +
  ros::Publisher move_arm_pub_=n.advertise<brazo_fer::WriteServos>("move_arm", 1); 
 +
  ros::Publisher hand_pub_=n.advertise<brazo_fer::WriteServos>("hand_arm", 1);
 +
  ros::Publisher move_base_pub_=n.advertise<geometry_msgs::Twist>("cmd_vel", 1);   
 +
 +
ros::spin(); 
 +
 +
        return 0;
 +
  }
 +
 +
</syntaxhighlight>
  
 
<!--<center><videoflash>fhbSTuGQxkg</videoflash></center>
 
<!--<center><videoflash>fhbSTuGQxkg</videoflash></center>

Revision as of 11:43, 13 November 2013

< volver a principal

Componentes del modelo del MYRAbot

Se ha comenzado realizado un modelo de la estructura del MYRAbot a le que se le ha añadido la base Roomba, la cámara kinect y el brazo modelado. Hemos comenzado creando un package que va a contener el modelo de nuestro robot, que llamaremos "myrabot_fer_modelo", con la dependencia urdf.

URDF estructura MYRAbot

Se ha realizado previamente un modelo 3D de la estructura con un programa CAD, del que vamos a emplear las partes con una geometria singular, ya que el diseño empleando los elementos geométricos básicos sería complicado.

Diseño CAD 3D de la estructura del MYRAbot

Para el archivo principal crearemos un archivo llamdo "estructura-myrabot.xacro" en el directorio "urdf" de el package anteriormente creado, con el siguiente contenido:

<?xml version="1.0"?>

<robot>

	<include filename="$(find myrabot_fer_modelo)/urdf/estructura-myrabot-macros.xacro" />

<macro name="estructura_myrabot" params="parent *origin">	

<joint name="world_joint" type="fixed">
  <parent link="${parent}"/>
  <child link="e_base_1_link"/>
  <insert_block name="origin" />
</joint>
       
  <link name="e_base_1_link">
    <inertial>
      <mass value="0.05"/>
      <origin rpy="0 0 0" xyz="0.135 0.135 ${0.015/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0.135 0.135 ${0.015/2}"/>
      <geometry>
        <cylinder radius="0.135" length="0.015" />
      </geometry>
      <material name="wood">
		<color rgba="${205/255} ${133/255} ${63/255} 1" />
	  </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.135 0.135 ${0.015/2}"/>
      <geometry>
        <cylinder radius="0.135" length="0.015" />
      </geometry>
    </collision>
  </link> 

<separador_base id="1" />
<e_separador_base id="1" xsim="1" ysim="1" />

<separador_base id="2" />
<e_separador_base id="2" xsim="1" ysim="-1" />

<separador_base id="3" />
<e_separador_base id="3" xsim="-1" ysim="-1" />

<separador_base id="4" />
<e_separador_base id="4" xsim="-1" ysim="1" />


<joint name="base_2" type="fixed">
  <parent link="e_base_1_link"/>
  <child link="e_base_2_link"/>
  <origin xyz="0 0 0.135" rpy="0 0 0" />
</joint>

  <link name="e_base_2_link">
    <inertial>
      <mass value="0.05"/>
      <origin rpy="0 0 0" xyz="0.135 0.135 ${0.02/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0.135 0.135 ${0.02/2}"/>
      <geometry>
        <cylinder radius="0.135" length="0.02" />
      </geometry>
      <material name="wood">
		<color rgba="${205/255} ${133/255} ${63/255} 1" />
	  </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.135 0.135 ${0.02/2}"/>
      <geometry>
        <cylinder radius="0.135" length="0.02" />
      </geometry>
    </collision>
  </link>

<joint name="pilar" type="fixed">
  <parent link="e_base_2_link"/>
  <child link="e_pilar_link"/>
  <origin xyz="0 0 0.02" rpy="0 0 0" />
</joint>
  
<link name="e_pilar_link">
    <inertial>
      <mass value="0.08"/>
      <origin rpy="0 0 0" xyz="0 0 ${0.7/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_pilar.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="wood" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_pilar.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
  </link>
 
<joint name="botonera" type="fixed">
  <parent link="e_base_2_link"/>
  <child link="e_botonera_link"/>
  <origin xyz="0 0 0.02" rpy="0 0 0" />
</joint>
  
<link name="e_botonera_link">
    <inertial>
      <mass value="0.06"/>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.1/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.1/2}"/>
      <geometry>
        <box size="0.2 0.09 0.1"/>
      </geometry>
      <material name="wood" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.1/2}"/>
      <geometry>
        <box size="0.2 0.09 0.1"/>
      </geometry>
    </collision>
  </link>
  
<joint name="start_button_1" type="fixed">
  <parent link="e_botonera_link"/>
  <child link="e_start_button_1_link"/>
  <origin xyz="-0.06 0 0.1" rpy="0 0 0" />
</joint>

<link name="e_start_button_1_link">
    <inertial>
      <mass value="0.001"/>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.002/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.002/2}"/>
      <geometry>
        <cylinder radius="0.009" length="0.002"/>
      </geometry>
      <material name="black">
		  <color rgba="0 0 0 1"/>
      </material>		  
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.002/2}"/>
      <geometry>
        <cylinder radius="0.009" length="0.002"/>
      </geometry>
    </collision>
  </link>
  
<joint name="start_button_2" type="fixed">
  <parent link="e_start_button_1_link"/>
  <child link="e_start_button_2_link"/>
  <origin xyz="0.0 0 0.002" rpy="0 0 0" />
</joint>

<link name="e_start_button_2_link">
    <inertial>
      <mass value="0.001"/>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.004/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.004/2}"/>
      <geometry>
        <cylinder radius="0.0075" length="0.004"/>
      </geometry>
      <material name="green">
		  <color rgba="0 1 0 1"/>
      </material>		  
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.004/2}"/>
      <geometry>
        <cylinder radius="0.0075" length="0.004"/>
      </geometry>
    </collision>
  </link>
  
<joint name="emergency_button_1" type="fixed">
  <parent link="e_botonera_link"/>
  <child link="e_emergency_button_1_link"/>
  <origin xyz="0.06 0 0.1" rpy="0 0 0" />
</joint>

<link name="e_emergency_button_1_link">
    <inertial>
      <mass value="0.001"/>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.015/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.015/2}"/>
      <geometry>
        <cylinder radius="0.0125" length="0.015"/>
      </geometry>
      <material name="metal" />		  
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.015/2}"/>
      <geometry>
        <cylinder radius="0.0125" length="0.015"/>
      </geometry>
    </collision>
  </link>
  
<joint name="emergency_button_2" type="fixed">
  <parent link="e_emergency_button_1_link"/>
  <child link="e_emergency_button_2_link"/>
  <origin xyz="0.0 0 0.015" rpy="0 0 0" />
</joint>

<link name="e_emergency_button_2_link">
    <inertial>
      <mass value="0.001"/>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.003/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.003/2}"/>
      <geometry>
        <cylinder radius="0.018" length="0.003"/>
      </geometry>
      <material name="red">
		  <color rgba="1 0 0 1"/>
      </material>		  
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.135 ${0.165-(0.09/2)} ${0.003/2}"/>
      <geometry>
        <cylinder radius="0.018" length="0.003"/>
      </geometry>
    </collision>
  </link>              

<joint name="base_kinect" type="fixed">
  <parent link="e_pilar_link"/>
  <child link="e_base_kinect_link"/>
  <origin xyz="0 0 ${0.395-0.155}" rpy="0 0 0" />
</joint>
  
<link name="e_base_kinect_link">
    <inertial>
      <mass value="0.02"/>
      <origin rpy="0 0 0" xyz="0 0 ${0.005/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_base_kinect.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="wood" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_base_kinect.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
  </link>
  
<joint name="base_brazo_1" type="fixed">
  <parent link="e_pilar_link"/>
  <child link="e_base_brazo_1_link"/>
  <origin xyz="0 0 ${0.708-(0.395-0.155)}" rpy="0 0 0" />
</joint>
  
<link name="e_base_brazo_1_link">
    <inertial>
      <mass value="0.03"/>
      <origin rpy="0 0 0" xyz="0 0 ${0.005/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_base_brazo_1.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="wood" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_base_brazo_1.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
  </link>

<separador_base_brazo id="1" />
<e_separador_base_brazo id="1" xsim="1" ysim="1" />

<separador_base_brazo id="2" />
<e_separador_base_brazo id="2" xsim="1" ysim="-1" />

<separador_base_brazo id="3" />
<e_separador_base_brazo id="3" xsim="-1" ysim="-1" />

<separador_base_brazo id="4" />
<e_separador_base_brazo id="4" xsim="-1" ysim="1" />

<joint name="base_brazo_2" type="fixed">
  <parent link="e_base_brazo_1_link"/>
  <child link="e_base_brazo_2_link"/>
  <origin xyz="0 0 0.074" rpy="0 0 0" />
</joint>
  
<link name="e_base_brazo_2_link">
    <inertial>
      <mass value="0.005"/>
      <origin rpy="0 0 0" xyz="0 0 ${0.005/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_base_brazo_2.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="wood" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_base_brazo_2.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
  </link>    

<joint name="soporte_1" type="fixed">
  <parent link="e_pilar_link"/>
  <child link="e_soporte_1_link"/>
  <origin xyz="0 0 ${0.995-(0.708-0.155)-(0.395-0.155)}" rpy="0 0 0" />
</joint>
  
<link name="e_soporte_1_link">
    <inertial>
      <mass value="0.05"/>
      <origin rpy="0 0 0" xyz="0 0 ${0.64/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_soporte_1.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="wood" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_soporte_1.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
  </link>
  
<joint name="soporte_2" type="fixed">
  <parent link="e_soporte_1_link"/>
  <child link="e_soporte_2_link"/>
  <origin xyz="0 0.2 0.61" rpy="-0.12 0 0" />
</joint>
  
<link name="e_soporte_2_link">
    <inertial>
      <mass value="0.01"/>
      <origin rpy="0 0 0" xyz="0 0 ${0.06/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 -0.2 -0.03"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_soporte_2.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="wood" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 -0.2 -0.03"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_soporte_2.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
  </link>   

<joint name="monitor" type="fixed">
  <parent link="e_soporte_2_link"/>
  <child link="e_monitor_link"/>
  <origin xyz="0 -0.2 -0.09" rpy="0 0 0" />
</joint>
  
<link name="e_monitor_link">
    <inertial>
      <mass value="0.1"/>
      <origin rpy="0 0 0" xyz="0 0 ${0.180/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_monitor.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="wood" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/e_monitor.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
  </link>
  
<joint name="pantalla" type="fixed">
  <parent link="e_monitor_link"/>
  <child link="e_pantalla_link"/>
  <origin xyz="0.135 ${0.135-0.005-0.03-0.0001} 0.086" rpy="0 0 0" />
</joint>
  
<link name="e_pantalla_link">
    <inertial>
      <mass value="0.0001"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="0.22 0.0001 0.130" />
      </geometry>
      <material name="black" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="0.22 0.0001 0.127" />
      </geometry>
    </collision>
  </link>       
 
<gazebo_propiedades nombre="e_base_1_link" material="LightWood" />

<gazebo_propiedades nombre="e_base_2_link" material="LightWood" />

<gazebo_propiedades nombre="e_separador_base_1_link" material="Grey" />

<gazebo_propiedades nombre="e_separador_base_2_link" material="Grey" />

<gazebo_propiedades nombre="e_separador_base_3_link" material="Grey" />

<gazebo_propiedades nombre="e_separador_base_4_link" material="Grey" />

<gazebo_propiedades nombre="e_separador_base_brazo_1_link" material="Grey" />

<gazebo_propiedades nombre="e_separador_base_brazo_2_link" material="Grey" />

<gazebo_propiedades nombre="e_separador_base_brazo_3_link" material="Grey" />

<gazebo_propiedades nombre="e_separador_base_brazo_4_link" material="Grey" />

<gazebo_propiedades nombre="e_pilar_link" material="LightWood" />

<gazebo_propiedades nombre="e_base_kinect_link" material="LightWood" />

<gazebo_propiedades nombre="e_base_brazo_1_link" material="LightWood" />

<gazebo_propiedades nombre="e_base_brazo_2_link" material="LightWood" />

<gazebo_propiedades nombre="e_botonera_link" material="LightWood" />

<gazebo_propiedades nombre="e_start_button_1_link" material="Black" />

<gazebo_propiedades nombre="e_start_button_2_link" material="Green" />

<gazebo_propiedades nombre="e_emergency_button_1_link" material="Grey" />

<gazebo_propiedades nombre="e_emergency_button_2_link" material="Red" />

<gazebo_propiedades nombre="e_soporte_1_link" material="LightWood" />

<gazebo_propiedades nombre="e_soporte_2_link" material="LightWood" />

<gazebo_propiedades nombre="e_monitor_link" material="LightWood" />

<gazebo_propiedades nombre="e_pantalla_link" material="Black" />

</macro>
  
</robot>

Los archivos empleados, con los modelos de malla 3D ".stl", en la descrición de la estructura del robot se pueden descargar a continuación, deben guardarse en el directorio "meshes" de nuestro package:

Los macros que estamos usando en el archivo principal del URDF son los que se muestran continuación, que guardaremos en un archivo llamado "estructura-myrabot-macros.xacro" en el directorio "urdf" de nuestro package:

<?xml version="1.0"?>

<robot>

<macro name="default_inertia_e">
	<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/>
</macro>

<macro name="separador_base" params="id"> 
<joint name="separador_base_${id}" type="fixed">
  <parent link="e_base_1_link"/>
  <child link="e_separador_base_${id}_link"/>
  <origin xyz="0.135 0.135 0.015" rpy="0 0 0" />
</joint>
</macro>

<macro name="e_separador_base" params="id xsim ysim">
  <link name="e_separador_base_${id}_link">
    <inertial>
      <mass value="0.02"/>
      <origin rpy="0 0 0" xyz="${xsim*0.040} ${ysim*0.105} ${0.120/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="${xsim*0.040} ${ysim*0.105} ${0.120/2}"/>
      <geometry>
        <cylinder radius="0.0075" length="0.120" />
      </geometry>
      <material name="metal">
		<color rgba="${211/255} ${211/255} ${211/255} 1" />
	  </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="${xsim*0.040} ${ysim*0.105} ${0.120/2}"/>
      <geometry>
        <cylinder radius="0.0075" length="0.120" />
      </geometry>
    </collision>
  </link> 
</macro> 

<macro name="separador_base_brazo" params="id"> 
<joint name="separador_base_brazo_${id}" type="fixed">
  <parent link="e_base_brazo_1_link"/>
  <child link="e_separador_base_brazo_${id}_link"/>
  <origin xyz="0.135 ${0.135-0.082} 0.075" rpy="0 0 0" />
</joint>
</macro> 

<macro name="e_separador_base_brazo" params="id xsim ysim">
  <link name="e_separador_base_brazo_${id}_link">
    <inertial>
      <mass value="0.002"/>
      <origin rpy="0 0 0" xyz="${xsim*0.029} ${ysim*0.019} ${0.034/2}"/>
      <default_inertia_e />
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="${xsim*0.029} ${ysim*0.019} ${0.034/2}"/>
      <geometry>
        <cylinder radius="0.002" length="0.034" />
      </geometry>
      <material name="metal" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="${xsim*0.029} ${ysim*0.019} ${0.034/2}"/>
      <geometry>
        <cylinder radius="0.002" length="0.034" />
      </geometry>
    </collision>
  </link> 
</macro>

<macro name="gazebo_propiedades" params="nombre material">
<gazebo reference="${nombre}">
  <material>Gazebo/${material}</material>
  <mu1>0.5</mu1>
  <mu2>0.5</mu2>
  <selfCollide>true</selfCollide>
  <turnGravityOff>false</turnGravityOff>  
</gazebo> 
</macro>

</robot>

URDF Roomba

Para la base móvil Roomba se ha empleado el modelo del turtlebot, aunque equipado con una base móvil create, esta tiene unas físicas y sensores similares a la nuestra. Para esto necesitamos instalar los stacks turtlebot y turtlebot_simulator, que contienen el modelo y los plugins para gazebo, respectivamente. Eliminando lo que no necesitamos del modelo del turtlebot y modificacndo el elemento de la base, el contenido del archivo que guardaremos con el nombre "roomba.xacro" en el directorio "urdf" de nuestro package, es el siguiente:

<?xml version="1.0"?>

<robot xmlns:xacro="http://ros.org/wiki/xacro">

  <property name="M_PI" value="3.14159"/>

  <include filename="$(find myrabot_fer_modelo)/urdf/roomba-gazebo.xacro"/>

  <property name="base_x" value="0.33" />
  <property name="base_y" value="0.33" />

  <xacro:macro name="create">
    <material name="Green">
      <color rgba="0.0 0.8 0.0 1.0"/>
    </material>

  <link name="base_footprint">
    <inertial>
      <mass value="0.0001" />
      <origin xyz="0 0 0" />
      <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
              iyy="0.0001" iyz="0.0" 
              izz="0.0001" />
    </inertial>

    <visual>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <box size="0.001 0.001 0.001" />
      </geometry>
      <material name="Green" />
    </visual>

    <collision>
      <origin xyz="0 0 0.017" rpy="0 0 0" />
      <geometry>
       <box size="0.001 0.001 0.001" />
      </geometry>
    </collision>
  </link>

  <link name="base_link">
    <inertial>
      <mass value="3.6" />
      <origin xyz="0 0 ${0.092/2}" />
      <inertia ixx="0.01" ixy="0.0" ixz="0.0"
        iyy="0.01" iyz="0.0" izz="0.5" />
    </inertial>

    <visual>
      <origin xyz=" 0 0 ${0.092/2}" rpy="0 0 0" />
      <geometry>
        <cylinder length="0.092" radius="0.17"/>
      </geometry>
      <material name="white">
	    <color rgba="1 1 1 1" />  
      </material>
    </visual>

    <collision>
      <origin xyz="0.0 0.0 ${0.092/2}" rpy="0 0 0" />
      <geometry>
        <cylinder length="0.092" radius="0.17"/>
      </geometry>
    </collision>
  </link>

  <link name="wall_sensor_link">
    <inertial>
      <mass value="0.01" />
      <origin xyz="0 0 0"/>
      <inertia ixx="0.001" ixy="0.0" ixz="0.0"
        iyy="0.001" iyz="0.0" izz="0.001" />
    </inertial>
  </link>


  <link name="left_cliff_sensor_link">
    <inertial>
      <mass value="0.01" />
      <origin xyz="0 0 0"/>
      <inertia ixx="0.001" ixy="0.0" ixz="0.0"
        iyy="0.001" iyz="0.0" izz="0.001" />
    </inertial>
  </link>

  <link name="right_cliff_sensor_link">
    <inertial>
      <mass value="0.01" />
      <origin xyz="0 0 0"/>
      <inertia ixx="0.001" ixy="0.0" ixz="0.0"
        iyy="0.001" iyz="0.0" izz="0.001" />
    </inertial>
  </link>



  <link name="leftfront_cliff_sensor_link">
    <inertial>
      <mass value="0.01" />
      <origin xyz="0 0 0"/>
      <inertia ixx="1.0" ixy="0.0" ixz="0.0"
        iyy="0.01" iyz="0.0" izz="0.01" />
    </inertial>
  </link>

  <link name="rightfront_cliff_sensor_link">
    <inertial>
      <mass value="0.01" />
      <origin xyz="0 0 0"/>
      <inertia ixx="0.001" ixy="0.0" ixz="0.0"
        iyy="0.001" iyz="0.0" izz="0.001" />
    </inertial>
  </link>


  <joint name="base_footprint_joint" type="fixed">
    <origin xyz="0 0 0.017" rpy="0 0 0" />        
    <parent link="base_footprint"/>
    <child link="base_link" />
  </joint>

  <joint name="base_wall_sensor_joint" type="fixed">
    <origin xyz="0.09 -0.120 0.042" rpy="0 0 -1.0" />        
    <parent link="base_link"/>
    <child link="wall_sensor_link" />
  </joint>

  <joint name="base_left_cliff_sensor_joint" type="fixed">
    <origin xyz="0.07 0.14 0.01" rpy="0 1.57079 0" />        
    <parent link="base_link"/>
    <child link="left_cliff_sensor_link" />
  </joint>

  <joint name="base_right_cliff_sensor_joint" type="fixed">
    <origin xyz="0.07 -0.14 0.01" rpy="0 1.57079 0" />        
    <parent link="base_link"/>
    <child link="right_cliff_sensor_link" />
  </joint>

  <joint name="base_leftfront_cliff_sensor_joint" type="fixed">
    <origin xyz="0.15 0.04 0.01" rpy="0 1.57079 0" />        
    <parent link="base_link"/>
    <child link="leftfront_cliff_sensor_link" />
  </joint>

  <joint name="base_rightfront_cliff_sensor_joint" type="fixed">
    <origin xyz="0.15 -0.04 0.01" rpy="0 1.57079 0" />        
    <parent link="base_link"/>
    <child link="rightfront_cliff_sensor_link" />
  </joint>

  <link name="left_wheel_link">
    <inertial>
      <origin xyz="0 0 0"/>
      <mass value="0.01" />
      <inertia ixx="0.001" ixy="0.0" ixz="0.0"
        iyy="0.001" iyz="0.0" izz="0.001" />
    </inertial>

    <visual>
      <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
      <geometry>
        <cylinder radius="0.033" length = "0.023"/>
      </geometry>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
      <geometry>
        <cylinder radius="0.033" length = "0.023"/>
      </geometry>
    </collision>
  </link>

  <joint name="left_wheel_joint" type="continuous">
    <origin xyz="0 0.13 0.015" rpy="0 0 0"/>
    <parent link="base_link"/>
    <child link="left_wheel_link"/>
    <axis xyz="0 1 0"/>
  </joint>

  <link name="right_wheel_link">
    <inertial>
      <origin xyz="0 0 0"/>
      <mass value="0.01" />
      <inertia ixx="0.001" ixy="0.0" ixz="0.0"
        iyy="0.001" iyz="0.0" izz="0.001" />
    </inertial>

    <visual>
      <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
      <geometry>
        <cylinder radius="0.033" length = "0.023"/>
      </geometry>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
      <geometry>
        <cylinder radius="0.033" length = "0.023"/>
      </geometry>
    </collision>
  </link>

  <joint name="right_wheel_joint" type="continuous">
    <origin xyz="0 -0.13 0.015" rpy="0 0 0"/>
    <parent link="base_link"/>
    <child link="right_wheel_link"/>
    <axis xyz="0 1 0"/>
  </joint>

  <link name="rear_wheel_link">
    <inertial>
      <origin xyz="0 0 0"/>
      <mass value="0.001" />
      <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
        iyy="0.0001" iyz="0.0" izz="0.0001" />
    </inertial>

    <visual>
      <origin xyz="0 0 0" rpy="0 1.5707 1.5707"/>
      <geometry>
        <sphere radius="0.015" />
      </geometry>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
      <geometry>
        <sphere radius="0.015" />
      </geometry>
    </collision>
  </link>

  <joint name="rear_castor_joint" type="fixed">
    <origin xyz="-0.13 0 0.0" rpy="0 0 0"/>
    <parent link="base_link"/>
    <child link="rear_wheel_link"/>
    <axis xyz="0 1 0"/>
  </joint>

  <link name="front_wheel_link">
    <inertial>
      <origin xyz="0 0 0" />
      <mass value="0.01" />
      <inertia ixx="0.001" ixy="0.0" ixz="0.0"
        iyy="0.001" iyz="0.0" izz="0.001" />
    </inertial>

    <visual>
      <origin xyz="0 0 0" rpy="0 1.5707 1.5707"/>
      <geometry>
        <sphere radius="0.018" />
      </geometry>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 1.5707 1.5707" />
      <geometry>
        <sphere radius="0.018" />
      </geometry>
    </collision>
  </link>

  <joint name="front_castor_joint" type="fixed">
    <origin xyz="0.13 0 0.0" rpy="0 0 0"/>
    <parent link="base_link"/>
    <child link="front_wheel_link"/>
    <axis xyz="0 1 0"/>
  </joint>


  <joint name="gyro_joint" type="fixed">
    <axis xyz="0 1 0" />
    <origin xyz="0 0 0.04" rpy="0 0 0" />
    <parent link="base_link"/>
    <child link="gyro_link"/>
  </joint>
  <link name="gyro_link">
    <inertial>
      <mass value="0.001" />
      <origin xyz="0 0 0" rpy="0 0 0" />
      <inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001" />
    </inertial>
  </link>

  <joint name="laser_joint" type="fixed">
    <origin xyz="-0.065 0 0.075" rpy="0 0 0" />
    <parent link="base_link" />
    <child link="laser" />
  </joint>

  <link name="laser">
    <visual>
      <geometry>
        <box size="0.02 0.035 0.002" />
      </geometry>
      <material name="Green" />
    </visual>
    <inertial>
      <mass value="0.001" />
      <origin xyz="0 0 0" />
      <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
        iyy="0.0001" iyz="0.0"
        izz="0.0001" />
    </inertial>
  </link>
  
<gaezebo>
  <material>Gazebo/White</material>
</gaezebo>  
  
  <turtlebot_sim_imu/>
  <turtlebot_sim_laser/>
  <turtlebot_sim_create/>
  <turtlebot_sim_wall_sensors/>  
  
</xacro:macro>
  
</robot>

Para su uso en el simulador gazebo debemos añadir los plugins de los diferentes sensores de la base. Crearemos un archivo llamado "roomba-gazebo.xacro" en el directorio "urdf" de nuestro package con el siguiente contenido:

<?xml version="1.0"?>

<robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://ros.org/wiki/xacro">


<xacro:macro name="turtlebot_sim_imu">
  <gazebo>
    <controller:gazebo_ros_imu name="imu_controller" plugin="libgazebo_ros_imu.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>30</updateRate>
      <bodyName>gyro_link</bodyName>
      <topicName>imu/data</topicName>
      <gaussianNoise>${0.0017*0.0017}</gaussianNoise>
      <xyzOffsets>0 0 0</xyzOffsets> 
      <rpyOffsets>0 0 0</rpyOffsets>
      <interface:position name="imu_position"/>
    </controller:gazebo_ros_imu>
  </gazebo>
</xacro:macro>

<xacro:macro name="turtlebot_sim_laser">
  <gazebo reference="laser">
    <sensor:ray name="laser">
      <rayCount>180</rayCount>
      <rangeCount>180</rangeCount>
      <laserCount>1</laserCount>
      
      <origin>0.0 0.0 0.0</origin>
      <displayRays>false</displayRays>
      
      <minAngle>-130</minAngle>
      <maxAngle>130</maxAngle>
      
      <minRange>0.08</minRange>
      <maxRange>10.0</maxRange>
      <resRange>0.01</resRange>
      <updateRate>20</updateRate>
      <controller:gazebo_ros_laser name="gazebo_ros_laser_controller" plugin="libgazebo_ros_laser.so">
	<gaussianNoise>0.005</gaussianNoise>
	<alwaysOn>true</alwaysOn>
	<updateRate>20</updateRate>
	<topicName>scan</topicName>
	<frameName>laser</frameName>
	<interface:laser name="gazebo_ros_laser_iface" />
      </controller:gazebo_ros_laser>
    </sensor:ray>
  </gazebo>
</xacro:macro>

<xacro:macro name="turtlebot_sim_create">
  <gazebo>
    <controller:gazebo_ros_create name="create_controller" plugin="libgazebo_ros_create.so">
      <alwaysOn>true</alwaysOn>
      <node_namespace>turtlebot_node</node_namespace>
      <left_wheel_joint>left_wheel_joint</left_wheel_joint>
      <right_wheel_joint>right_wheel_joint</right_wheel_joint>
      <front_castor_joint>front_castor_joint</front_castor_joint>
      <rear_castor_joint>rear_castor_joint</rear_castor_joint>
      <wheel_separation>.260</wheel_separation>
      <wheel_diameter>0.066</wheel_diameter>
      <base_geom>base_link_geom_base_link</base_geom>
      <updateRate>40</updateRate>
      <torque>1.0</torque>
    </controller:gazebo_ros_create>
  </gazebo>
</xacro:macro>

<xacro:macro name="turtlebot_sim_wall_sensors">
  <gazebo reference="wall_sensor_link">
    <sensor:ray name="wall_sensor">
      <alwaysActive>true</alwaysActive>
      <rayCount>1</rayCount>
      <rangeCount>1</rangeCount>
      <resRange>0.1</resRange>

      <minAngle>0</minAngle>
      <maxAngle>0</maxAngle>

      <minRange>0.0160</minRange>
      <maxRange>0.04</maxRange>
      <displayRays>false</displayRays>
    </sensor:ray>
  </gazebo>

  <gazebo reference="left_cliff_sensor_link">
    <sensor:ray name="left_cliff_sensor">
      <alwaysActive>true</alwaysActive>
      <rayCount>1</rayCount>
      <rangeCount>1</rangeCount>
      <resRange>0.1</resRange>

      <minAngle>0</minAngle>
      <maxAngle>0</maxAngle>

      <minRange>0.01</minRange>
      <maxRange>0.04</maxRange>
      <displayRays>false</displayRays>
    </sensor:ray>
  </gazebo>

  <gazebo reference="right_cliff_sensor_link">
    <sensor:ray name="right_cliff_sensor">
      <alwaysActive>true</alwaysActive>
      <rayCount>1</rayCount>
      <rangeCount>1</rangeCount>
      <resRange>0.1</resRange>

      <minAngle>0</minAngle>
      <maxAngle>0</maxAngle>

      <minRange>0.01</minRange>
      <maxRange>0.04</maxRange>
      <displayRays>false</displayRays>
    </sensor:ray>
  </gazebo>


  <gazebo reference="leftfront_cliff_sensor_link">
    <sensor:ray name="leftfront_cliff_sensor">
      <alwaysActive>true</alwaysActive>
      <rayCount>1</rayCount>
      <rangeCount>1</rangeCount>
      <resRange>0.1</resRange>

      <minAngle>0</minAngle>
      <maxAngle>0</maxAngle>

      <minRange>0.01</minRange>
      <maxRange>0.04</maxRange>
      <displayRays>false</displayRays>
    </sensor:ray>
  </gazebo>

  <gazebo reference="rightfront_cliff_sensor_link">
    <sensor:ray name="rightfront_cliff_sensor">
      <alwaysActive>true</alwaysActive>
      <rayCount>1</rayCount>
      <rangeCount>1</rangeCount>
      <resRange>0.1</resRange>

      <minAngle>0</minAngle>
      <maxAngle>0</maxAngle>

      <minRange>0.01</minRange>
      <maxRange>0.04</maxRange>
      <displayRays>fan</displayRays>
    </sensor:ray>
  </gazebo>



  <gazebo reference="left_wheel_link">
    <mu1 value="10"/>
    <mu2 value="10"/>
    <kp value="100000000.0"/>
    <kd value="10000.0"/>
    <fdir value="1 0 0"/>
  </gazebo>

  <gazebo reference="right_wheel_link">
    <mu1 value="10"/>
    <mu2 value="10"/>
    <kp value="100000000.0"/>
    <kd value="10000.0"/>
    <fdir value="1 0 0"/>
  </gazebo>
  <gazebo reference="rear_wheel_link">
    <mu1 value="0"/>
    <mu2 value="0"/>
    <kp value="100000000.0"/>
    <kd value="10000.0"/>
  </gazebo>

  <gazebo reference="front_wheel_link">
    <mu1 value="0"/>
    <mu2 value="0"/>
    <kp value="100000000.0"/>
    <kd value="10000.0"/>
  </gazebo>
</xacro:macro>
</robot>

URDF kinect

Para la cámara kinect incluiremos el modelo y el plugin para el simulador en un solo archivo. Crearemos un archivo llamado "kinect.xacro" dentro del directorio "urdf" de nuestro package con el siguiente contenido:

<?xml version="1.0"?>

<robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://ros.org/wiki/xacro">
	
  <property name="M_PI" value="3.14159"/>

<xacro:macro name="kinect" params="parent *origin">
  
  <joint name="base_camera_joint" type="fixed">
	<insert_block name="origin" />
    <parent link="${parent}" />
    <child link="camera_link" />
  </joint>

  <link name="camera_link">
    <inertial>
      <mass value="0.01" />
      <origin xyz="0 0 0" />
      <inertia ixx="0.001" ixy="0.0" ixz="0.0"
        iyy="0.001" iyz="0.0"
        izz="0.001" />
    </inertial>

    <visual>
      <origin xyz=" 0 0 0 " rpy="0 0 0" />
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/kinect.dae"/>
      </geometry>
    </visual>

    <collision>
      <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://myrabot_fer_modelo/meshes/kinect.dae"/>
      </geometry>
    </collision>

  </link>

  <joint name="camera_depth_joint" type="fixed">
    <origin xyz="0 0.018 0" rpy="0 0 0" />
    <parent link="camera_link" />
    <child link="camera_depth_frame" />
  </joint>

  <link name="camera_depth_frame">
    <inertial>
      <mass value="0.01" />
      <origin xyz="0 0 0" />
      <inertia ixx="0.001" ixy="0.0" ixz="0.0"
        iyy="0.001" iyz="0.0"
        izz="0.001" />
    </inertial>
  </link>

  <joint name="camera_depth_optical_joint" type="fixed">
    <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
    <parent link="camera_depth_frame" />
    <child link="camera_depth_optical_frame" />
  </joint>

  <link name="camera_depth_optical_frame">
    <inertial>
      <mass value="0.001" />
      <origin xyz="0 0 0" />
      <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
        iyy="0.0001" iyz="0.0"
        izz="0.0001" />
    </inertial>
  </link>

  <joint name="camera_rgb_joint" type="fixed">
    <origin xyz="0 -0.005 0" rpy="0 0 0" />
    <parent link="camera_link" />
    <child link="camera_rgb_frame" />
  </joint>

  <link name="camera_rgb_frame">
    <inertial>
      <mass value="0.001" />
      <origin xyz="0 0 0" />
      <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
        iyy="0.0001" iyz="0.0"
        izz="0.0001" />
    </inertial>
  </link>

  <joint name="camera_rgb_optical_joint" type="fixed">
    <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
    <parent link="camera_rgb_frame" />
    <child link="camera_rgb_optical_frame" />
  </joint>

  <link name="camera_rgb_optical_frame">
    <inertial>
      <mass value="0.001" />
      <origin xyz="0 0 0" />
      <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
        iyy="0.0001" iyz="0.0"
        izz="0.0001" />
    </inertial>
  </link>

  <gazebo reference="camera_link">
    <sensor:camera name="camera">
      <imageFormat>R8G8B8</imageFormat>
      <imageSize>640 480</imageSize>
      <hfov>60</hfov>
      <nearClip>0.05</nearClip>
      <farClip>3</farClip>
      <updateRate>20</updateRate>
      <baseline>0.1</baseline>
      <controller:gazebo_ros_openni_kinect name="kinect_camera_controller" plugin="libgazebo_ros_openni_kinect.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>20</updateRate>
        <imageTopicName>/camera/image_raw</imageTopicName>
        <pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
        <cameraInfoTopicName>/camera/camera_info</cameraInfoTopicName>
        <frameName>camera_depth_optical_frame</frameName>
        <distortion_k1>0.0</distortion_k1>
        <distortion_k2>0.0</distortion_k2>
        <distortion_k3>0.0</distortion_k3>
        <distortion_t1>0.0</distortion_t1>
        <distortion_t2>0.0</distortion_t2>
      </controller:gazebo_ros_openni_kinect>
    </sensor:camera>
  </gazebo>
  
</xacro:macro>

</robot>

Ensamblado del modelo del MYRAbot

Para poder formar el modelo de nuestro robot tenemos que ensamblar las diferentes partes que lo componen, y que hemos modelado previamente. Los componentes individuales se han definido como macros con los parámetros de link parent y origen, con lo que deberemos indicar el link y el origen al que tienen que unirse de los otros componentes. Crearemos un archivo llamado "myrabot.urdf.xacro" dentro del directorio "urdf" de nuestro package con el siguiente contenido:

<?xml version="1.0"?>

<robot name="MYRAbot"
       xmlns:xi="http://www.w3.org/2001/XInclude"
       xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
       xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
       xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
       xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
       xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
       xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
       xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
       xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
       xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
       xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
       xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics">
	
	<include filename="$(find myrabot_fer_modelo)/urdf/roomba.xacro" />		
	
	<include filename="$(find myrabot_fer_modelo)/urdf/estructura-myrabot.xacro" />
	
	<include filename="$(find myrabot_fer_modelo)/urdf/kinect.xacro" />	
	
	<include filename="$(find brazo_fer_modelo)/urdf/brazo.xacro" />	
	
	<roomba />
	
	<estructura_myrabot parent="base_link">
		<origin rpy="0 0 1.57" xyz="0.135 -0.135 0.092"/>	
	</estructura_myrabot> 
	
	<kinect parent="e_base_kinect_link">
		<origin rpy="0 0 -1.57" xyz="0.135 0.090 0.112"/>
	</kinect>
	
	<brazo parent="e_base_brazo_1_link">
		<origin rpy="0 0 3.1416" xyz="0.135 0.0335 0.075"/>
	</brazo>
	
		

</robot>

Visualización del modelo en rviz

Para la comprobación y visualización del correcto ensamblado del modelo, así como la prueba de las uniones móviles, se ha creado un launcher para cargar el modelo en rviz. Crearemos un archivo llamado "myrabot_rviz.launch" dentro del directorio "launch" de nuestro package con el siguiente contenido:

<launch>

	<param name="robot_description" command="$(find xacro)/xacro.py '$(find myrabot_fer_modelo)/urdf/myrabot.urdf.xacro'" />

	<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />

	<param name="use_gui" value="true"/>

	<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />

	<node name="rviz" pkg="rviz" type="rviz" />

</launch>

Para iniciar el launcher debemos ejecutar en un terminal el siguiente comando:

roslaunch myrabot_fer_modelo myrabot_rviz.launch

Si todo va bien, se ejecutará rviz y el interfaz del joint_state_publisher, sobre el cual al modificar los controles deslizables observaremos como se modifica la posición de las uniones móviles en el modelo 3D cargado en rviz. Para que se muestre correctamente nuestro modelo en rviz debemos seleccionar el elemento link que se va ha tomar como elemento fijo "fixed frame", en nuestro caso en "Global Options" el "Fixed Frame" será el link "/base_footprint". El resultado es el que se muestra a continuación:

Modelo MYRAbot en rviz e interfaz joint_state_publisher

Carga del modelo en gazebo

Para poder cargar el modelo en gazebo e iniciar los controladores de todos sus componentes, se ha creado un launcher. Crearemos un archivo llamado "myrabot_gazebo.launch" dentro del directorio "launch" de nuestro package con el siguiente contenido:

<launch>

  <include file="$(find gazebo_worlds)/launch/empty_world.launch"/>

  <param name="robot_description" command="$(find xacro)/xacro.py '$(find myrabot_fer_modelo)/urdf/myrabot.urdf.xacro'" />

  <node name="spawn_brazo" pkg="gazebo" type="spawn_model" args="-urdf -param robot_description -model MYRAbot" respawn="false" output="screen" />

  <rosparam file="$(find brazo_fer_modelo)/controller.yaml" command="load"/>

  <node name="spawn_controller" pkg="pr2_controller_manager" type="spawner" args="base_pos_controller arti1_pos_controller arti2_pos_controller arti3_pos_controller pinza_pos_controller base_vel_controller arti1_vel_controller arti2_vel_controller arti3_vel_controller pinza_vel_controller" respawn="false" output="screen" />
  
  <node name="modelo_brazo" pkg="brazo_fer_modelo" type="modelo_brazo" />

  <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf">
    <param name="freq" value="30.0"/>
    <param name="sensor_timeout" value="1.0"/>
    <param name="publish_tf" value="true"/>
    <param name="odom_used" value="true"/>
    <param name="imu_used" value="false"/>
    <param name="vo_used" value="false"/>
    <param name="output_frame" value="odom"/>
  </node>

  <node pkg="nodelet" type="nodelet" name="pointcloud_throttle" args="load pointcloud_to_laserscan/CloudThrottle openni_manager" respawn="true">
    <param name="max_rate" value="20.0"/>
    <remap from="cloud_in" to="/camera/depth/points"/>
    <remap from="cloud_out" to="cloud_throttled"/>
  </node>

  <node pkg="nodelet" type="nodelet" name="kinect_laser" args="load pointcloud_to_laserscan/CloudToScan openni_manager" respawn="true">
    <param name="output_frame_id" value="/camera_depth_frame"/>
    <param name="min_height" value="-0.15"/>
    <param name="max_height" value="0.15"/>
    <remap from="cloud" to="/cloud_throttled"/>
  </node>

  <node pkg="nodelet" type="nodelet" name="kinect_laser_narrow" args="load pointcloud_to_laserscan/CloudToScan openni_manager" respawn="true">
    <param name="output_frame_id" value="/camera_depth_frame"/>
    <param name="min_height" value="-0.025"/>
    <param name="max_height" value="0.025"/>
    <remap from="cloud" to="/cloud_throttled"/>
    <remap from="scan" to="/narrow_scan"/>
  </node>  
  
</launch>

Para lanzar el launcher ejecutaremos el siguiente comando en un terminal:

roslaunch brazo_fer_modelo brazo.gazebo.launch

Si todo va bien podremos ver en la ventana gráfica de gazebo el modelo del MYRAbot situado en un mundo vacío, tal como se muestra en la siguiente imagen:

Modelo MYRAbot en gazebo

Programa de prueba (Vuela al ruedo)

Se ha realizado un pequeño programa para probar el funconamiento del modelo del MYRAbot, que simplemente hace girar en circulo al robot y gira el brazo de un lado a otro en posición vertical. Primero vamos a [[ crear un package que va a contener nuestro programa y que llamaremos "myrabot_fer", con las siguientes dependencias: brazo_fer geometry_msgs std_msgs nav_msgs sensor_msgs image_transport roscpp.

Dentro de este package vamos a crear un archivo llamado "vuelta_al_ruedo.cpp" en el directorio "src" con el siguiente contenido:

  #include "ros/ros.h"
  #include "brazo_fer/Servos.h"
  #include "brazo_fer/WriteServos.h"  
  #include "brazo_fer/ReadServos.h"
  #include "geometry_msgs/Twist.h"
  #include "std_msgs/Bool.h"  

  int cont = 0;
  int cont1= 0;
  int encendido = 0;
  brazo_fer::Servos move, on, vel;
  

  void home()
  {
	if (cont1 == 0)
	{
		ros::NodeHandle n;

		ros::Publisher move_arm_pub_=n.advertise<brazo_fer::WriteServos>("move_arm", 1);
		ros::Publisher hand_pub_=n.advertise<brazo_fer::WriteServos>("hand_arm", 1);  		
		ros::Publisher move_base_pub_=n.advertise<geometry_msgs::Twist>("cmd_vel", 1);   
		
		brazo_fer::WriteServos home;
		
		::move.base = 511;
		::move.arti1 = 511;
		::move.arti2 = 511;
		::move.arti3 = 511;
		::move.pinza = 511;
		
		::on.base = 1;
		::on.arti1 = 1;
		::on.arti2 = 1;
		::on.arti3 = 1;
		::on.pinza = 1;
		
		::vel.base = 400;
		::vel.arti1 = 400;
		::vel.arti2 = 400;
		::vel.arti3 = 400;
		::vel.pinza = 400;
		
		home.posicion = ::move;
		home.par = ::on;
		home.velocidad = ::vel;
		
		move_arm_pub_.publish(home);
		hand_pub_.publish(home);
		
		::cont1 = 1;
		
	}
  }
  
  void inicio(const std_msgs::Bool& inicio)
  {
	if (inicio.data == true && ::cont == 0)
	{
		::encendido = 1;
		::cont = 1;
	}
	else if (inicio.data == true && ::cont == 1)
	{
		::encendido = 0;
		::cont = 0;
	}
  }
  
  void posicion(const brazo_fer::ReadServos& posicion)
  {
	ros::NodeHandle n;

  	ros::Publisher move_arm_pub_=n.advertise<brazo_fer::WriteServos>("move_arm", 1);
  	ros::Publisher move_base_pub_=n.advertise<geometry_msgs::Twist>("cmd_vel", 1);    	 	
	
	brazo_fer::Servos p = posicion.posicion;
	brazo_fer::WriteServos mover_brazo;
	
	home();
	
	if (::encendido == 1)
	{	
		geometry_msgs::Twist mover_base;
		
		mover_base.linear.x = 0.1;
		mover_base.angular.z = 0.3;
		
		move_base_pub_.publish(mover_base);		
		
		if (::cont1 ==  1)
		{
			::move.base = 818;
			::cont1 = 2;
			mover_brazo.posicion = ::move;
			mover_brazo.par = ::on;
			mover_brazo.velocidad = ::vel;
			move_arm_pub_.publish(mover_brazo);
		}
		else if ((p.base-110) < ::move.base && ::move.base < (p.base+110))		
		{
			if (::cont1 ==  2)
			{
				::move.base = 204;
				::cont1 = 3;
				mover_brazo.posicion = ::move;
				mover_brazo.par = ::on;
				mover_brazo.velocidad = ::vel;
				move_arm_pub_.publish(mover_brazo);				
			}
			else
			{
				::cont1 = 1;
			}
		}
	}
  }

  int main(int argc, char **argv)
  {
 
	ros::init(argc, argv, "vuelta_al_ruedo");   
 
	ros::NodeHandle n;
 
 
  	ros::Subscriber pose_sub_= n.subscribe("pose_arm", 1, posicion); 
  	ros::Subscriber button_sub_= n.subscribe("start_button", 1, inicio); 
 
  	ros::Publisher move_arm_pub_=n.advertise<brazo_fer::WriteServos>("move_arm", 1);   
  	ros::Publisher hand_pub_=n.advertise<brazo_fer::WriteServos>("hand_arm", 1);
  	ros::Publisher move_base_pub_=n.advertise<geometry_msgs::Twist>("cmd_vel", 1);  	 	   
 
	ros::spin();  
 
        return 0;
  }


< volver a principal