Difference between revisions of "Modelo para simulación brazo MYRAbot (urdf+gazebo)"
From robotica.unileon.es
(→Creación del modelo URDF) |
(→Creación del modelo URDF) |
||
Line 96: | Line 96: | ||
<!--brazo--> | <!--brazo--> | ||
− | + | ||
− | <link name=" | + | <xacro:macro name="servo" params="nombre"> |
+ | <link name="${nombre}_link"> | ||
<visual> | <visual> | ||
<geometry> | <geometry> | ||
Line 117: | Line 118: | ||
</inertial> | </inertial> | ||
</link> | </link> | ||
+ | </xacro:macro> | ||
+ | |||
+ | <xacro:servo nombre="brazo" /> | ||
<joint name="servo_arti1_B" type="fixed"> | <joint name="servo_arti1_B" type="fixed"> | ||
Line 124: | Line 128: | ||
<axis xyz="1 0 0" /> | <axis xyz="1 0 0" /> | ||
</joint> | </joint> | ||
− | + | ||
− | <link name=" | + | <xacro:macro name="base" params="nombre"> |
+ | <link name="${nombre}_link_B"> | ||
<visual> | <visual> | ||
<geometry> | <geometry> | ||
Line 147: | Line 152: | ||
</inertial> | </inertial> | ||
</link> | </link> | ||
+ | </xacro:macro> | ||
+ | |||
+ | <xacro:base nombre="brazo" /> | ||
<joint name="servo_arti1_D" type="fixed"> | <joint name="servo_arti1_D" type="fixed"> | ||
Line 155: | Line 163: | ||
</joint> | </joint> | ||
− | <link name=" | + | <xacro:macro name="soporte" params="nombre simetrico lado"> |
+ | <link name="${nombre}_link_S${lado}"> | ||
<visual> | <visual> | ||
<geometry> | <geometry> | ||
<box size="0.002 0.032 0.067"/> | <box size="0.002 0.032 0.067"/> | ||
</geometry> | </geometry> | ||
− | <origin rpy="0 0 0" xyz="0.021 0 0.022"/> | + | <origin rpy="0 0 0" xyz="${simetrico*0.021} 0 0.022"/> |
<material name="white"> | <material name="white"> | ||
<color rgba="1 1 1 1"/> | <color rgba="1 1 1 1"/> | ||
Line 166: | Line 175: | ||
</visual> | </visual> | ||
<collision> | <collision> | ||
− | <origin rpy="0 0 0" xyz="0.021 0 0.022"/> | + | <origin rpy="0 0 0" xyz="${simetrico*0.021} 0 0.022"/> |
<geometry> | <geometry> | ||
<box size="0.002 0.032 0.067"/> | <box size="0.002 0.032 0.067"/> | ||
Line 172: | Line 181: | ||
</collision> | </collision> | ||
<inertial> | <inertial> | ||
− | <origin rpy="0 0 0" xyz="0.021 0 0.022"/> | + | <origin rpy="0 0 0" xyz="${simetrico*0.021} 0 0.022"/> |
<mass value="0.001"/> | <mass value="0.001"/> | ||
<xacro:default_inertia /> | <xacro:default_inertia /> | ||
</inertial> | </inertial> | ||
</link> | </link> | ||
+ | </xacro:macro> | ||
+ | |||
+ | <xacro:soporte nombre="brazo" simetrico="1" lado="I" /> | ||
<joint name="servo_arti1_I" type="fixed"> | <joint name="servo_arti1_I" type="fixed"> | ||
Line 185: | Line 197: | ||
</joint> | </joint> | ||
− | + | <xacro:soporte nombre="brazo" simetrico="-1" lado="D" /> | |
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
<joint name="arti2" type="revolute"> | <joint name="arti2" type="revolute"> | ||
Line 219: | Line 210: | ||
<!--antebrazo--> | <!--antebrazo--> | ||
− | + | <xacro:servo nombre="antebrazo" /> | |
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
<joint name="servo_arti2_B" type="fixed"> | <joint name="servo_arti2_B" type="fixed"> | ||
Line 247: | Line 219: | ||
</joint> | </joint> | ||
− | + | <xacro:base nombre="antebrazo" /> | |
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
<joint name="servo_arti2_D" type="fixed"> | <joint name="servo_arti2_D" type="fixed"> | ||
Line 277: | Line 228: | ||
</joint> | </joint> | ||
− | + | <xacro:soporte nombre="antebrazo" simetrico="1" lado="I" /> | |
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
<joint name="servo_arti2_I" type="fixed"> | <joint name="servo_arti2_I" type="fixed"> | ||
Line 307: | Line 237: | ||
</joint> | </joint> | ||
− | + | <xacro:soporte nombre="antebrazo" simetrico="-1" lado="D" /> | |
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
− | |||
<joint name="arti3" type="revolute"> | <joint name="arti3" type="revolute"> | ||
Line 494: | Line 403: | ||
<visual> | <visual> | ||
<geometry> | <geometry> | ||
− | <box size="0.002 0.04 0. | + | <box size="0.002 0.04 0.037"/> |
</geometry> | </geometry> | ||
− | <origin rpy="0 0 0" xyz="0.03225 0 0. | + | <origin rpy="0 0 0" xyz="0.03225 0 0.0575"/> |
<material name="white"> | <material name="white"> | ||
<color rgba="1 1 1 1"/> | <color rgba="1 1 1 1"/> | ||
Line 637: | Line 546: | ||
</inertial> | </inertial> | ||
</link> | </link> | ||
− | + | ||
</robot> | </robot> | ||
− | |||
</syntaxhighlight> | </syntaxhighlight> |
Revision as of 12:04, 4 November 2013
Creación del modelo URDF
El formato empleado para el modelo del brazo está denominado por el acrónimo inglés URDF (Unified Robot Description Format), que emplea el lenguaje xml. Consiste en un arbol de lementos geométricos (links) conectados entre sí mediante uniones (joints) que determinan el parentesco entre ellos. Estas uniones puden ser fijas o móviles, las móviles pueden ser a su vez rotacionales o lineales.
Comenzaremos creando el package "brazo_fer_modelo" que va a contener el modelo de nuestro brazo, con las siguientes pedendencias: urdf brazo_fer std_msgs sensor_msgs tf roscpp
El modelo planteado para nuestro brazo es el siguiente, que guardaremos en el directorio "urdf" del package creado en un archivo llamado "brazo.urdf.xacro":
<?xml version="1.0"?>
<robot name="MYRAbot_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="default_inertia">
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
</xacro:macro>
<xacro:macro name="default_inertia_servos">
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/>
</xacro:macro>
<xacro:macro name="default_dynamics">
<dynamics fricction="0" damping="0" />
</xacro:macro>
<link name="world" />
<joint name="fixed" type="fixed">
<parent link="world"/>
<child link="base_link"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<axis xyz="0 0 1" />
</joint>
<link name="base_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"/>
<xacro:default_inertia_servos />
</inertial>
</link>
<joint name="base" type="revolute">
<parent link="base_link"/>
<child link="hombro_link"/>
<origin xyz="0 0 0.04" rpy="0 0 0" />
<axis xyz="0 0 1" />
<limit effort="30.0" lower="-2.62" upper="2.62" velocity="2"/>
<xacro: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.020"/>
<material name="black" />
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.020"/>
<geometry>
<box size="0.04 0.032 0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.020"/>
<mass value="0.055"/>
<xacro: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" />
<limit effort="30.0" lower="-2.62" upper="2.62" velocity="2"/>
<xacro:default_dynamics />
</joint>
<!--brazo-->
<xacro:macro name="servo" params="nombre">
<link name="${nombre}_link">
<visual>
<geometry>
<box size="0.04 0.032 0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.0905"/>
<material name="black" />
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0905"/>
<geometry>
<box size="0.04 0.032 0.05"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.0905"/>
<mass value="0.055"/>
<xacro:default_inertia_servos />
</inertial>
</link>
</xacro:macro>
<xacro: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>
<xacro:macro name="base" params="nombre">
<link name="${nombre}_link_B">
<visual>
<geometry>
<box size="0.04 0.032 0.015"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0.058"/>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.058"/>
<geometry>
<box size="0.04 0.032 0.015"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.058"/>
<mass value="0.001"/>
<xacro:default_inertia />
</inertial>
</link>
</xacro:macro>
<xacro: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>
<xacro:macro name="soporte" params="nombre simetrico lado">
<link name="${nombre}_link_S${lado}">
<visual>
<geometry>
<box size="0.002 0.032 0.067"/>
</geometry>
<origin rpy="0 0 0" xyz="${simetrico*0.021} 0 0.022"/>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="${simetrico*0.021} 0 0.022"/>
<geometry>
<box size="0.002 0.032 0.067"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="${simetrico*0.021} 0 0.022"/>
<mass value="0.001"/>
<xacro:default_inertia />
</inertial>
</link>
</xacro:macro>
<xacro: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>
<xacro: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" />
<limit effort="30.0" lower="-2.62" upper="2.62" velocity="2"/>
<xacro:default_dynamics />
</joint>
<!--antebrazo-->
<xacro: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>
<xacro: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>
<xacro: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>
<xacro: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" />
<limit effort="1000.0" lower="-2.62" upper="2.62" velocity="2"/>
<xacro:default_dynamics />
</joint>
<!--muneca-->
<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"/>
<xacro: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"/>
<xacro: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"/>
<xacro: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"/>
<xacro: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 izquierda 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"/>
<xacro: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.060"/>
<geometry>
<box size="0.002 0.04 0.032"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.03225 0 0.060"/>
<mass value="0.0005"/>
<xacro: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" />
<limit effort="30.0" lower="-2.62" upper="2.62" velocity="2"/>
<xacro:default_dynamics />
</joint>
<!--pinza-->
<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"/>
<xacro: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"/>
<xacro: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"/>
<xacro: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"/>
<xacro:default_inertia />
</inertial>
</link>
</robot>