Difference between revisions of "MYRAbot's arm model for simulation (urdf+gazebo)"

From robotica.unileon.es
Jump to: navigation, search
(Creation of URDF model)
(Creation of URDF model)
Line 5: Line 5:
 
[http://wiki.ros.org/urdf/Tutorials URDF] (Unified Robot Description Format) is the format used to define the model of the [[MYRAbot's arm control (bioloid+arduino)|arm]] ([http://es.wikipedia.org/wiki/Extensible_Markup_Language xml]) in order to simulate it in [http://wiki.ros.org/simulator_gazebo?distro=electric gazebo]. It consists of a tree of geometrical elements (''links'') plugged through joints(''joints''). This joints can be fixed or mobile, the mobile joints can be rotating, linear or floating.
 
[http://wiki.ros.org/urdf/Tutorials URDF] (Unified Robot Description Format) is the format used to define the model of the [[MYRAbot's arm control (bioloid+arduino)|arm]] ([http://es.wikipedia.org/wiki/Extensible_Markup_Language xml]) in order to simulate it in [http://wiki.ros.org/simulator_gazebo?distro=electric gazebo]. It consists of a tree of geometrical elements (''links'') plugged through joints(''joints''). This joints can be fixed or mobile, the mobile joints can be rotating, linear or floating.
  
 +
First, we will create a new ''package'' with the necessary dependences for our programs (urdf [[Control brazo MYRAbot (bioloid+arduino)|brazo_fer]] std_msgs sensor_msgs tf roscpp). We will execute the next commands in a terminal:
  
<!--
+
<syntaxhighlight>
 +
cd ~/ros_workspace
 +
roscreate-pkg brazo_fer_modelo urdf [[Control brazo MYRAbot (bioloid+arduino)|brazo_fer]] std_msgs sensor_msgs tf roscpp</syntaxhighlight>
  
 
+
We have divided the model in three files, main file, ''macros'' file and placement file. For the main file, we will create a file named "brazo.xacro" within the folder "urdf" of the created ''package'' with the content that is shown below:
Comenzaremos [[Fernando-TFM-ROS02#Creando un package|creando el package]] "brazo_fer_modelo" que va a contener el modelo de nuestro brazo, con las siguientes pependencias: urdf [[Control brazo MYRAbot (bioloid+arduino)|brazo_fer]] std_msgs sensor_msgs tf roscpp
 
 
 
El modelo planteado para nuestro brazo se compone de tres archivos, uno que contiene los ''macros'' que vamos a utilizar en el archivo principal del modelo y un archivo en el que marcamos el ''link'' al que está unido el modelo. El contenido del arcivo principal del modelo es el siguiente, que guardaremos en el directorio "urdf" del ''package'' creado en un archivo llamado "brazo.xacro":
 
  
 
<syntaxhighlight lang="xml">
 
<syntaxhighlight lang="xml">
Line 91: Line 91:
 
   </joint>
 
   </joint>
 
    
 
    
 
+
<!--Brazo-->
  
 
<servo nombre="brazo" />
 
<servo nombre="brazo" />
Line 131: Line 131:
 
   </joint>
 
   </joint>
 
    
 
    
 
+
<!--Antebrazo-->
 
    
 
    
 
<servo nombre="antebrazo" />  
 
<servo nombre="antebrazo" />  
Line 171: Line 171:
 
   </joint>
 
   </joint>
 
    
 
    
 
+
<!--Muñeca-->
 
    
 
    
 
   <link name="muneca_link">
 
   <link name="muneca_link">
Line 291: Line 291:
 
   </joint>   
 
   </joint>   
  
 
+
<!--Pinza fija-->
 
    
 
    
 
   <link name="muneca_link_P">     
 
   <link name="muneca_link_P">     
Line 355: Line 355:
 
   </joint>
 
   </joint>
 
    
 
    
 
+
<!--Pinza móvil-->
 
    
 
    
 
   <link name="pinza_link">     
 
   <link name="pinza_link">     
Line 475: Line 475:
  
 
</syntaxhighlight>
 
</syntaxhighlight>
 +
 +
<!--
  
 
El contenido del archivo que contiene los macros, el controlador y transmisiones, que empleamos en el rachivo principal, es el siguiente, que guardaremos en el mismo directorio con el nombre "brazo-macros.xacro":
 
El contenido del archivo que contiene los macros, el controlador y transmisiones, que empleamos en el rachivo principal, es el siguiente, que guardaremos en el mismo directorio con el nombre "brazo-macros.xacro":

Revision as of 09:42, 7 January 2014

< go back to main

Creation of URDF model

URDF (Unified Robot Description Format) is the format used to define the model of the arm (xml) in order to simulate it in gazebo. It consists of a tree of geometrical elements (links) plugged through joints(joints). This joints can be fixed or mobile, the mobile joints can be rotating, linear or floating.

First, we will create a new package with the necessary dependences for our programs (urdf brazo_fer std_msgs sensor_msgs tf roscpp). We will execute the next commands in a terminal:

cd ~/ros_workspace
roscreate-pkg brazo_fer_modelo urdf [[Control brazo MYRAbot (bioloid+arduino)|brazo_fer]] std_msgs sensor_msgs tf roscpp

We have divided the model in three files, main file, macros file and placement file. For the main file, we will create a file named "brazo.xacro" within the folder "urdf" of the created package with the content that is shown below:

<?xml version="1.0"?>

<robot>

	<include filename="$(find brazo_fer_modelo)/urdf/brazo-macros.xacro" />

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

  <joint name="fixed" type="fixed">
    <parent link="${parent}"/>
    <child link="base_brazo_link"/>
    <insert_block name="origin" />
    <axis xyz="0 0 1" />  
  </joint>
    
  <link name="base_brazo_link">
    <visual>
      <geometry>
        <box size="0.032 0.05 0.04"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0 -0.0135 0.020"/>
      <material name="black">
        <color rgba="0 0 0 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 -0.0135 0.020"/>		
      <geometry>
        <box size="0.032 0.05 0.04"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 -0.0135 0.020"/>			
      <mass value="0.055"/>
	  <default_inertia_servos />
    </inertial>       
  </link>

  <joint name="base" type="revolute">
    <parent link="base_brazo_link"/>
    <child link="hombro_link"/>
    <origin xyz="0 0 0.04" rpy="0 0 0" />
    <axis xyz="0 0 1" />
	<default_limit />
	<default_dynamics />          
  </joint>
  
  <link name="hombro_link">
    <visual>
      <geometry>
        <box size="0.04 0.032 0.05"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0 0 0.025"/>
      <material name="black" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0.025"/>		
	  <geometry>
        <box size="0.04 0.032 0.05"/>
      </geometry>       
    </collision> 
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0.025"/>			
      <mass value="0.055"/>
	  <default_inertia_servos />
    </inertial>        
  </link>  

  <joint name="arti1" type="revolute">
    <parent link="hombro_link"/>
    <child link="brazo_link"/>  
    <origin xyz="0 0 0.0385" rpy="0 0 0" />
	<axis xyz="1 0 0" />
	<default_limit />
	<default_dynamics />        
  </joint>
  
<!--Brazo-->

<servo nombre="brazo" />
  
  <joint name="servo_arti1_B" type="fixed">
    <parent link="brazo_link"/>
    <child link="brazo_link_B"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  

<base nombre="brazo" /> 
  
  <joint name="servo_arti1_D" type="fixed">
    <parent link="brazo_link"/>
    <child link="brazo_link_SI"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  

<soporte nombre="brazo" simetrico="1" lado="I" />  
  
  <joint name="servo_arti1_I" type="fixed">
    <parent link="brazo_link"/>
    <child link="brazo_link_SD"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  
  
<soporte nombre="brazo" simetrico="-1" lado="D" />     
  
  <joint name="arti2" type="revolute">
    <parent link="brazo_link"/>
    <child link="antebrazo_link"/>
    <origin xyz="0 0 0.104" rpy="0 0 0" />
    <axis xyz="1 0 0" />
	<default_limit />
	<default_dynamics />            
  </joint>
  
<!--Antebrazo-->
  
<servo nombre="antebrazo" /> 
  
  <joint name="servo_arti2_B" type="fixed">
    <parent link="antebrazo_link"/>
    <child link="antebrazo_link_B"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  
  
<base nombre="antebrazo" />
  
  <joint name="servo_arti2_D" type="fixed">
    <parent link="antebrazo_link"/>
    <child link="antebrazo_link_SI"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  
  
<soporte nombre="antebrazo" simetrico="1" lado="I" />  
  
  <joint name="servo_arti2_I" type="fixed">
    <parent link="antebrazo_link"/>
    <child link="antebrazo_link_SD"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  
  
<soporte nombre="antebrazo" simetrico="-1" lado="D" />     

  <joint name="arti3" type="revolute">
    <parent link="antebrazo_link"/>
    <child link="muneca_link"/>
    <origin xyz="0 0 0.104" rpy="0 0 0" />
    <axis xyz="1 0 0" />
	<default_limit />
	<default_dynamics />             
  </joint>
  
<!--Muñeca-->
  
  <link name="muneca_link">
    <visual>
      <geometry>
        <box size="0.05 0.04 0.032"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0.00625 0 0.06"/>
      <material name="black" />
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.00625 0 0.06"/>		
	  <geometry>
        <box size="0.05 0.04 0.032"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0.00625 0 0.06"/>			
      <mass value="0.055"/>
	  <default_inertia_servos />
    </inertial>            
  </link>  
  
  <joint name="servo_arti3_B" type="fixed">
    <parent link="muneca_link"/>
    <child link="muneca_link_B"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  
  
  <link name="muneca_link_B">    
	<visual>
      <geometry>
        <box size="0.05325 0.04 0.005"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0.004625 0 0.0415"/>
      <material name="white">
		<color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.004625 0 0.0415"/>		
	  <geometry>
        <box size="0.05325 0.04 0.005"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0.004625 0 0.0415"/>		
      <mass value="0.0005"/>
	  <default_inertia />
    </inertial>              
  </link>
  
  <joint name="servo_arti3_D" type="fixed">
    <parent link="muneca_link"/>
    <child link="muneca_link_SI"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  
  
  <link name="muneca_link_SI">    
	<visual>
      <geometry>
        <box size="0.002 0.032 0.0555"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0.021 0 0.01625"/>
      <material name="white">
		<color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.021 0 0.01625"/>		
	  <geometry>
        <box size="0.002 0.032 0.0555"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0.021 0 0.01625"/>		
      <mass value="0.0005"/>
	  <default_inertia />
    </inertial>           
  </link>
  
  <joint name="servo_arti3_I" type="fixed">
    <parent link="muneca_link"/>
    <child link="muneca_link_SD"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  
  
  <link name="muneca_link_SD">    
	<visual>
      <geometry>
        <box size="0.002 0.032 0.0555"/>
      </geometry>
      <origin rpy="0 0 0" xyz="-0.021 0 0.01625"/>
      <material name="white">
		<color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="-0.021 0 0.01625"/>		
	  <geometry>
        <box size="0.002 0.032 0.0555"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-0.021 0 0.01625"/>			
      <mass value="0.0005"/>
	  <default_inertia />
    </inertial>            
  </link>
  
  <joint name="servo_arti3_P" type="fixed">
    <parent link="muneca_link"/>
    <child link="muneca_link_P"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  

<!--Pinza fija-->
  
  <link name="muneca_link_P">    
	<visual>
      <geometry>
        <box size="0.002 0.04 0.092"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0.03425 0 0.090"/>
      <material name="white">
		<color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.03425 0 0.090"/>		
	  <geometry>
        <box size="0.002 0.04 0.092"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0.03425 0 0.090"/>			
      <mass value="0.001"/>
	  <default_inertia />
    </inertial>           
  </link>
  
  <joint name="servo_arti3_PS" type="fixed">
    <parent link="muneca_link"/>
    <child link="muneca_link_PS"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>
  
  <link name="muneca_link_PS">    
	<visual>
      <geometry>
        <box size="0.002 0.04 0.037"/>
      </geometry>
      <origin rpy="0 0 0" xyz="0.03225 0 0.0575"/>
      <material name="white">
		<color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.03225 0 0.0575"/>	
	  <geometry>
        <box size="0.002 0.04 0.037"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0.03225 0 0.0575"/>			
      <mass value="0.0005"/>
	  <default_inertia />
    </inertial>            
  </link>             
  
  <joint name="pinza" type="revolute">
    <parent link="muneca_link"/>
    <child link="pinza_link"/>
    <origin xyz="-0.00725 0 0.06" rpy="0 0 0" />
    <axis xyz="0 1 0" />
	<default_limit />
	<default_dynamics />     
  </joint>
  
<!--Pinza móvil-->
  
  <link name="pinza_link">    
	<visual>
      <geometry>
        <box size="0.002 0.04 0.092"/>
      </geometry>
      <origin rpy="0 0 0" xyz="-0.027 0 0.030"/>
      <material name="white">
		<color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="-0.027 0 0.030"/>		
	  <geometry>
        <box size="0.002 0.04 0.092"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-0.027 0 0.030"/>		
      <mass value="0.001"/>
 	  <default_inertia />
    </inertial>           
  </link>  
  
  <joint name="servo_pinza_B" type="fixed">
    <parent link="pinza_link"/>
    <child link="pinza_link_B"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  
  
  <link name="pinza_link_B">    
	<visual>
      <geometry>
        <box size="0.002 0.04 0.032"/>
      </geometry>
      <origin rpy="0 0 0" xyz="-0.025 0 0"/>
      <material name="white">
		<color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="-0.025 0 0"/>		
	  <geometry>
        <box size="0.002 0.04 0.032"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-0.025 0 0"/>		
      <mass value="0.0005"/>
	  <default_inertia />
    </inertial>           
  </link>
  
  <joint name="servo_pinza_D" type="fixed">
    <parent link="pinza_link"/>
    <child link="pinza_link_SI"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  
  
  <link name="pinza_link_SI">    
	<visual>
      <geometry>
        <box size="0.0375 0.002 0.032"/>
      </geometry>
      <origin rpy="0 0 0" xyz="-0.00725 0.021 0"/>
      <material name="white">
		<color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="-0.00725 0.021 0"/>		
	  <geometry>
        <box size="0.0375 0.002 0.032"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-0.00725 0.021 0"/>			
      <mass value="0.0005"/>
	  <default_inertia />
    </inertial>        
  </link>
  
  <joint name="servo_pinza_I" type="fixed">
    <parent link="pinza_link"/>
    <child link="pinza_link_SD"/>  
    <origin xyz="0 0 0" rpy="0 0 0" />
	<axis xyz="1 0 0" />    
  </joint>  
  
  <link name="pinza_link_SD">    
	<visual>
      <geometry>
        <box size="0.0375 0.002 0.032"/>
      </geometry>
      <origin rpy="0 0 0" xyz="-0.00725 -0.021 0"/>
      <material name="white">
		<color rgba="1 1 1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="-0.00725 -0.021 0"/>		
	  <geometry>
        <box size="0.0375 0.002 0.032"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-0.00725 -0.021 0"/>			
      <mass value="0.0005"/>
	  <default_inertia />
    </inertial>            
  </link>

</macro>
     
</robot>


< go back to main