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

From robotica.unileon.es
Jump to: navigation, search
(URDF MYRAbot's structure)
(URDF MYRAbot's structure)
Line 531: Line 531:
 
* [http://www.fernando.casadogarcia.es/files/e_monitor.stl e_monitor.stl]
 
* [http://www.fernando.casadogarcia.es/files/e_monitor.stl e_monitor.stl]
  
<!--
+
For the macros file, we will create a file named "estructura-myrabot-macros.xacro" within the folder "urdf" of our package with the content that is shown below:  
 
 
Los macros que estamos usando en el archivo principal del [http://wiki.ros.org/urdf/Tutorials 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'':
 
  
 
<syntaxhighlight lang="xml">
 
<syntaxhighlight lang="xml">
Line 622: Line 620:
  
 
</syntaxhighlight>
 
</syntaxhighlight>
 +
 +
===URDF Roomba===
 +
 +
 +
<!--
  
 
===URDF Roomba===
 
===URDF Roomba===

Revision as of 17:03, 13 January 2014

< go back to main

Components of MYRAbot model

We have started creating a model of the MYRAbot's structure and we have added the mobile base Roomba, the kinect camera, the arm model and the webcam Logitech Webcam Pro 9000.

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

cd ~/ros_workspace
roscreate-pkg myrabot_fer_modelo urdf std_msgs sensor_msgs tf roscpp

URDF MYRAbot's structure

We have made the 3D model of the structure with a CAD software from which we use the parts with a complex geometry.

3D CAD design of MYRAbot's structure

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

<?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>

We will add the next files within the folder "meshes" of our package:

For the macros file, we will create a file named "estructura-myrabot-macros.xacro" within the folder "urdf" of our package with the content that is shown below:

<?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

< go back to main