|
|
Line 108: |
Line 108: |
| | | |
| ===Integración de controladores del brazo=== | | ===Integración de controladores del brazo=== |
− |
| |
− | ====Creación de URDF del brazo para moveIt!====
| |
− |
| |
− | Necesitamos modificar el tipo de controladores, de las articulaciones del [[Modelo para simulación brazo MYRAbot (urdf+gazebo)|brazo]], empleados en [http://wiki.ros.org/simulator_gazebo?distro=electric gazebo] para permitir que pueda tomar el control de estos [http://moveit.ros.org/ moveIt!]. También se han añadido al [[Modelo para simulación brazo MYRAbot (urdf+gazebo)|modelo del brazo]] las mallas 3D de los componentes reales. Crearemos un archivo llamado "brazo-macros_moveit.xacro" dentro del directorio "urdf" del ''package'' "brazo_fer_modelo" con el siguiente contenido:
| |
− |
| |
− | <syntaxhighlight lang="xml" enclose="div">
| |
− |
| |
− | <?xml version="1.0"?>
| |
− |
| |
− | <robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:xacro="http://ros.org/wiki/xacro">
| |
− |
| |
− | <property name="M_PI" value="3.14159"/>
| |
− | <property name="M_SCALE" value="0.001"/>
| |
− | <property name="F10_HEIGHT" value="0.004"/>
| |
− | <property name="F4_HEIGHT" value="0.0525"/>
| |
− | <property name="F3_HEIGHT" value="0.009"/>
| |
− | <property name="AX12_HEIGHT" value="0.0385"/>
| |
− | <property name="AX12_WIDTH" value="0.038"/>
| |
− | <property name="F2_HEIGHT" value="0.0265"/>
| |
− |
| |
− | <material name="white">
| |
− | <color rgba="0.87 0.90 0.87 1.0"/>
| |
− | </material>
| |
− | <material name="black">
| |
− | <color rgba="0.0 0.0 0.0 1.0"/>
| |
− | </material>
| |
− |
| |
− | <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>
| |
− |
| |
− | <xacro:macro name="bioloid_F10_fixed" params="parent name color *origin">
| |
− | <joint name="${name}_joint" type="fixed">
| |
− | <insert_block name="origin" />
| |
− | <parent link="${parent}"/>
| |
− | <child link="${name}_link" />
| |
− | </joint>
| |
− |
| |
− | <link name="${name}_link">
| |
− | <inertial>
| |
− | <mass value="0.001" />
| |
− | <origin xyz="0 0 0" />
| |
− | <default_inertia/>
| |
− | </inertial>
| |
− |
| |
− | <visual>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package:/brazo_fer_modelo/meshes/F10.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | <material name="${color}"/>
| |
− | </visual>
| |
− |
| |
− | <collision>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package://brazo_fer_modelo/meshes/F10.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | </collision>
| |
− | </link>
| |
− | </xacro:macro>
| |
− |
| |
− | <xacro:macro name="finger_fixed" params="parent name color *origin">
| |
− | <joint name="${name}_joint" type="fixed">
| |
− | <insert_block name="origin" />
| |
− | <parent link="${parent}"/>
| |
− | <child link="${name}_link" />
| |
− | </joint>
| |
− |
| |
− | <link name="${name}_link">
| |
− | <inertial>
| |
− | <mass value="0.001" />
| |
− | <origin xyz="0 0 0" />
| |
− | <default_inertia/>
| |
− | </inertial>
| |
− |
| |
− | <visual>
| |
− | <origin xyz=" 0.03075 0.0 0.001 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <box size="0.0865 0.038 0.002" />
| |
− | </geometry>
| |
− | <material name="${color}"/>
| |
− | </visual>
| |
− |
| |
− | <collision>
| |
− | <origin xyz=" 0.03075 0.0 0.001 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <box size="0.0865 0.038 0.002" />
| |
− | </geometry>
| |
− | </collision>
| |
− | </link>
| |
− | </xacro:macro>
| |
− |
| |
− | <xacro:macro name="bioloid_F3_fixed" params="parent name color *origin">
| |
− | <joint name="${name}_joint" type="fixed">
| |
− | <insert_block name="origin" />
| |
− | <parent link="${parent}"/>
| |
− | <child link="${name}_link" />
| |
− | </joint>
| |
− |
| |
− | <link name="${name}_link">
| |
− | <inertial>
| |
− | <mass value="0.001" />
| |
− | <origin xyz="0 0 0" />
| |
− | <default_inertia/>
| |
− | </inertial>
| |
− |
| |
− | <visual>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package://brazo_fer_modelo/meshes/F3.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | <material name="${color}"/>
| |
− | </visual>
| |
− |
| |
− | <collision>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package://brazo_fer_modelo/meshes/F3.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | </collision>
| |
− | </link>
| |
− | </xacro:macro>
| |
− |
| |
− | <xacro:macro name="dynamixel_AX12_fixed" params="parent name *origin">
| |
− | <joint name="${name}_joint" type="fixed">
| |
− | <insert_block name="origin" />
| |
− | <parent link="${parent}"/>
| |
− | <child link="${name}_link" />
| |
− | </joint>
| |
− |
| |
− | <link name="${name}_link">
| |
− | <inertial>
| |
− | <mass value="0.055" />
| |
− | <origin xyz="0 0 0" />
| |
− | <default_inertia_servos/>
| |
− | </inertial>
| |
− |
| |
− | <visual>
| |
− | <origin xyz="0 0 0" rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package:/brazo_fer_modelo/meshes/ax12_box.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | <material name="black"/>
| |
− | </visual>
| |
− |
| |
− | <collision>
| |
− | <origin xyz="0 0 0" rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package:/brazo_fer_modelo/meshes/ax12_box.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | </collision>
| |
− | </link>
| |
− | </xacro:macro>
| |
− |
| |
− | <xacro:macro name="bioloid_F3_revolute" params="parent name color llimit ulimit vlimit *origin">
| |
− | <joint name="${name}" type="revolute">
| |
− | <insert_block name="origin" />
| |
− | <axis xyz="0 0 -1"/>
| |
− | <limit effort="100" velocity="${vlimit}" lower="${llimit}" upper="${ulimit}" />
| |
− | <default_dynamics/>
| |
− | <parent link="${parent}"/>
| |
− | <child link="${name}_brazo_link" />
| |
− | </joint>
| |
− |
| |
− | <link name="${name}_brazo_link">
| |
− | <inertial>
| |
− | <mass value="0.001" />
| |
− | <origin xyz="0 0 0" />
| |
− | <default_inertia/>
| |
− | </inertial>
| |
− |
| |
− | <visual>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package://brazo_fer_modelo/meshes/F3.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | <material name="${color}"/>
| |
− | </visual>
| |
− |
| |
− | <collision>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package://brazo_fer_modelo/meshes/F3.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | </collision>
| |
− | </link>
| |
− | </xacro:macro>
| |
− |
| |
− | <xacro:macro name="bioloid_F2_revolute" params="parent name color llimit ulimit vlimit *origin">
| |
− | <joint name="${name}" type="revolute">
| |
− | <insert_block name="origin" />
| |
− | <axis xyz="0 1 0"/>
| |
− | <limit effort="100" velocity="${vlimit}" lower="${llimit}" upper="${ulimit}" />
| |
− | <default_dynamics/>
| |
− | <parent link="${parent}"/>
| |
− | <child link="${name}_link" />
| |
− | </joint>
| |
− |
| |
− | <link name="${name}_link">
| |
− | <inertial>
| |
− | <mass value="0.001" />
| |
− | <origin xyz="0 0 0" />
| |
− | <default_inertia/>
| |
− | </inertial>
| |
− |
| |
− | <visual>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package://brazo_fer_modelo/meshes/F2.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | <material name="${color}"/>
| |
− | </visual>
| |
− |
| |
− | <collision>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package://brazo_fer_modelo/meshes/F2.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | </collision>
| |
− | </link>
| |
− | </xacro:macro>
| |
− |
| |
− | <xacro:macro name="bioloid_F4_revolute" params="parent name color llimit ulimit vlimit *origin">
| |
− | <joint name="${name}" type="revolute">
| |
− | <insert_block name="origin" />
| |
− | <axis xyz="0 1 0"/>
| |
− | <limit effort="100" velocity="${vlimit}" lower="${llimit}" upper="${ulimit}" />
| |
− | <default_dynamics/>
| |
− | <parent link="${parent}"/>
| |
− | <child link="${name}_link" />
| |
− | </joint>
| |
− |
| |
− | <link name="${name}_link">
| |
− | <inertial>
| |
− | <mass value="0.001" />
| |
− | <origin xyz="0 0 0" />
| |
− | <default_inertia/>
| |
− | </inertial>
| |
− |
| |
− | <visual>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package://brazo_fer_modelo/meshes/F4.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | <material name="${color}"/>
| |
− | </visual>
| |
− |
| |
− | <collision>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package://brazo_fer_modelo/meshes/F4.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | </collision>
| |
− | </link>
| |
− | </xacro:macro>
| |
− |
| |
− | <xacro:macro name="gazebo_propiedades_link" params="nombre material">
| |
− | <gazebo reference="${nombre}">
| |
− | <mu1>100</mu1>
| |
− | <mu2>100</mu2>
| |
− | <kp>100000000000</kp>
| |
− | <kd>1000000000</kd>
| |
− | <material>${material}</material>
| |
− | <selfCollide>true</selfCollide>
| |
− | <turnGravityOff>false</turnGravityOff>
| |
− | </gazebo>
| |
− | </xacro:macro>
| |
− |
| |
− | <xacro:macro name="gazebo_propiedades_joint" params="nombre">
| |
− | <gazebo reference="${nombre}">
| |
− | <erp>0.1</erp>
| |
− | <stopKd value="100000000.0" />
| |
− | <stopKp value="100000000.0" />
| |
− | <fudgeFactor value="0.5" />
| |
− | </gazebo>
| |
− | </xacro:macro>
| |
− |
| |
− | <gazebo>
| |
− | <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
| |
− |
| |
− | </plugin>
| |
− | </gazebo>
| |
− |
| |
− | <transmission name="base_trans">
| |
− | <type>transmission_interface/SimpleTransmission</type>
| |
− | <joint name="base"/>
| |
− | <actuator name="base_motor">
| |
− | <hardwareInterface>EffortJointInterface</hardwareInterface>
| |
− | <mechanicalReduction>1</mechanicalReduction>
| |
− | </actuator>
| |
− | </transmission>
| |
− |
| |
− | <transmission name="arti1_trans">
| |
− | <type>transmission_interface/SimpleTransmission</type>
| |
− | <joint name="arti1"/>
| |
− | <actuator name="arti1_motor">
| |
− | <hardwareInterface>EffortJointInterface</hardwareInterface>
| |
− | <mechanicalReduction>1</mechanicalReduction>
| |
− | </actuator>
| |
− | </transmission>
| |
− |
| |
− | <transmission name="arti2_trans">
| |
− | <type>transmission_interface/SimpleTransmission</type>
| |
− | <joint name="arti2"/>
| |
− | <actuator name="arti3_motor">
| |
− | <hardwareInterface>EffortJointInterface</hardwareInterface>
| |
− | <mechanicalReduction>1</mechanicalReduction>
| |
− | </actuator>
| |
− | </transmission>
| |
− |
| |
− | <transmission name="arti3_trans">
| |
− | <type>transmission_interface/SimpleTransmission</type>
| |
− | <joint name="arti3"/>
| |
− | <actuator name="arti3_motor">
| |
− | <hardwareInterface>EffortJointInterface</hardwareInterface>
| |
− | <mechanicalReduction>1</mechanicalReduction>
| |
− | </actuator>
| |
− | </transmission>
| |
− |
| |
− | <transmission name="pinza_trans">
| |
− | <type>transmission_interface/SimpleTransmission</type>
| |
− | <joint name="pinza"/>
| |
− | <actuator name="pinza_motor">
| |
− | <hardwareInterface>EffortJointInterface</hardwareInterface>
| |
− | <mechanicalReduction>1</mechanicalReduction>
| |
− | </actuator>
| |
− | </transmission>
| |
− |
| |
− | </robot>
| |
− |
| |
− | </syntaxhighlight>
| |
− |
| |
− | Los archivos empleados, con los modelos de malla 3D ".stl", en la descripción del brazo se pueden descargar a continuación, deben guardarse en el directorio "meshes" del ''package'' "brazo_fer_modelo":
| |
− |
| |
− | * [http://www.fernando.casadogarcia.es/files/ax12_box.stl ax12_box.stl]
| |
− | * [http://www.fernando.casadogarcia.es/files/F2.stl F2.stl]
| |
− | * [http://www.fernando.casadogarcia.es/files/F3.stl F3.stl]
| |
− | * [http://www.fernando.casadogarcia.es/files/F4.stl F4.stl]
| |
− | * [http://www.fernando.casadogarcia.es/files/F10.stl F10.stl]
| |
− |
| |
− | Crearemos un archivo llamado "brazo_moveit.xacro" dentro del directorio "urdf" del ''package'' "brazo_fer_modelo" con el siguiente contenido:
| |
− |
| |
− | <syntaxhighlight lang="xml" enclose="div">
| |
− |
| |
− | <?xml version="1.0"?>
| |
− |
| |
− | <robot xmlns:xacro="http://ros.org/wiki/xacro">
| |
− |
| |
− | <xacro:include filename="$(find brazo_fer_modelo)/urdf/brazo-macros_moveit.xacro" />
| |
− |
| |
− | <xacro:macro name="brazo" params="parent *origin">
| |
− |
| |
− | <joint name="fixed" type="fixed">
| |
− | <parent link="${parent}"/>
| |
− | <child link="fixed_link"/>
| |
− | <insert_block name="origin" />
| |
− | <axis xyz="0 0 1" />
| |
− | </joint>
| |
− |
| |
− | <link name="fixed_link"/>
| |
− |
| |
− | <!-- shoulder pan joint -->
| |
− | <dynamixel_AX12_fixed parent="fixed_link" name="servo_base">
| |
− | <origin xyz="0 0 0.019" rpy="${M_PI/2} 0 ${-M_PI/2}"/>
| |
− | </dynamixel_AX12_fixed>
| |
− | <bioloid_F3_revolute parent="servo_base_link" name="base" color="white" vlimit="3" llimit="-2.62" ulimit="2.62">
| |
− | <origin xyz="0 ${AX12_WIDTH/2} 0" rpy="${-M_PI/2} ${-M_PI/2} ${-M_PI}" />
| |
− | </bioloid_F3_revolute>
| |
− |
| |
− | <!-- shoulder lift joint -->
| |
− | <dynamixel_AX12_fixed parent="base_brazo_link" name="servo_arti1">
| |
− | <origin xyz="0 0 ${-AX12_HEIGHT-F10_HEIGHT+0.001}" rpy="0 ${M_PI} 0" />
| |
− | </dynamixel_AX12_fixed>
| |
− | <bioloid_F4_revolute parent="servo_arti1_link" name="arti1" color="white" vlimit="3" llimit="-2.62" ulimit="2.62">
| |
− | <origin xyz="0 0 0" rpy="0 0 0" />
| |
− | </bioloid_F4_revolute>
| |
− | <bioloid_F10_fixed parent="arti1_link" name="arti1_F10_0" color="white">
| |
− | <origin xyz="0 0 ${F4_HEIGHT+F10_HEIGHT/2}" rpy="0 0 0" />
| |
− | </bioloid_F10_fixed>
| |
− | <bioloid_F10_fixed parent="arti1_F10_0_link" name="arti1_F10_1" color="white">
| |
− | <origin xyz="0 0 ${F10_HEIGHT}" rpy="0 0 0" />
| |
− | </bioloid_F10_fixed>
| |
− | <bioloid_F10_fixed parent="arti1_F10_1_link" name="arti1_F10_2" color="white">
| |
− | <origin xyz="0 0 ${F10_HEIGHT}" rpy="0 0 0" />
| |
− | </bioloid_F10_fixed>
| |
− | <bioloid_F3_fixed parent="arti1_F10_2_link" name="arti1_F3_0" color="white">
| |
− | <origin xyz="0 0 ${F10_HEIGHT/2}" rpy="0 ${M_PI} 0" />
| |
− | </bioloid_F3_fixed>
| |
− |
| |
− | <!-- elbow joint -->
| |
− | <dynamixel_AX12_fixed parent="arti1_F3_0_link" name="servo_arti2">
| |
− | <origin xyz="0 0 ${-AX12_HEIGHT-F10_HEIGHT+0.001}" rpy="0 ${M_PI} 0"/>
| |
− | </dynamixel_AX12_fixed>
| |
− | <bioloid_F4_revolute parent="servo_arti2_link" name="arti2" color="white" vlimit="3" llimit="-2.63" ulimit="2.63">
| |
− | <origin xyz="0 0 0" rpy="0 0 0" />
| |
− | </bioloid_F4_revolute>
| |
− | <bioloid_F10_fixed parent="arti2_link" name="arti2_F10_0" color="white">
| |
− | <origin xyz="0 0 ${F4_HEIGHT+F10_HEIGHT/2}" rpy="0 0 0" />
| |
− | </bioloid_F10_fixed>
| |
− | <bioloid_F10_fixed parent="arti2_F10_0_link" name="arti2_F10_1" color="white">
| |
− | <origin xyz="0 0 ${F10_HEIGHT}" rpy="0 0 0" />
| |
− | </bioloid_F10_fixed>
| |
− | <bioloid_F10_fixed parent="arti2_F10_1_link" name="arti2_F10_2" color="white">
| |
− | <origin xyz="0 0 ${F10_HEIGHT}" rpy="0 0 0" />
| |
− | </bioloid_F10_fixed>
| |
− | <bioloid_F3_fixed parent="arti2_F10_2_link" name="arti2_F3_0" color="white">
| |
− | <origin xyz="0 0 ${F10_HEIGHT/2}" rpy="0 ${M_PI} 0" />
| |
− | </bioloid_F3_fixed>
| |
− |
| |
− | <!-- wrist joint -->
| |
− | <dynamixel_AX12_fixed parent="arti2_F3_0_link" name="servo_arti3">
| |
− | <origin xyz="0 0 ${-AX12_HEIGHT-F10_HEIGHT+0.001}" rpy="0 ${M_PI} 0"/>
| |
− | </dynamixel_AX12_fixed>
| |
− | <bioloid_F2_revolute parent="servo_arti3_link" name="arti3" color="white" vlimit="3" llimit="-2.62" ulimit="2.62">
| |
− | <origin xyz="0 0 0" rpy="0 0 0" />
| |
− | </bioloid_F2_revolute>
| |
− | <bioloid_F3_fixed parent="arti3_link" name="arti3_F3_0" color="white">
| |
− | <origin xyz="0 0.016 ${F2_HEIGHT}" rpy="0 ${M_PI} ${-M_PI/2}" />
| |
− | </bioloid_F3_fixed>
| |
− |
| |
− | <!-- gripper joint -->
| |
− | <dynamixel_AX12_fixed parent="arti3_F3_0_link" name="servo_pinza">
| |
− | <origin xyz="-0.02275 0 ${-AX12_WIDTH/2}" rpy="${M_PI} ${M_PI/2} 0"/>
| |
− | </dynamixel_AX12_fixed>
| |
− |
| |
− | <!-- finger 1 -->
| |
− | <joint name="pinza" type="revolute">
| |
− | <origin xyz="0 0 0" rpy="0 0 0"/>
| |
− | <axis xyz="0 1 0"/>
| |
− | <limit effort="100" velocity="3" lower="-2.62" upper="2.62" />
| |
− | <default_dynamics/>
| |
− | <parent link="servo_pinza_link"/>
| |
− | <child link="pinza_movil_link" />
| |
− | </joint>
| |
− | <link name="pinza_movil_link">
| |
− | <inertial>
| |
− | <mass value="0.001" />
| |
− | <origin xyz="0 0 0" />
| |
− | <default_inertia/>
| |
− | </inertial>
| |
− | <visual>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package://brazo_fer_modelo/meshes/F2.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | <material name="white"/>
| |
− | </visual>
| |
− | <collision>
| |
− | <origin xyz=" 0 0 0 " rpy="0 0 0" />
| |
− | <geometry>
| |
− | <mesh filename="package://brazo_fer_modelo/meshes/F2.stl" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
| |
− | </geometry>
| |
− | </collision>
| |
− | </link>
| |
− | <finger_fixed parent="pinza_movil_link" name="pinza_movil_dedo" color="white">
| |
− | <origin xyz="0 0 ${F2_HEIGHT}" rpy="0 0 0" />
| |
− | </finger_fixed>
| |
− |
| |
− | <!-- finger 2 -->
| |
− | <bioloid_F3_fixed parent="servo_pinza_link" name="pinza_fija" color="white">
| |
− | <origin xyz="0 0 ${-AX12_HEIGHT-F10_HEIGHT+0.001}" rpy="0 ${M_PI} 0" />
| |
− | </bioloid_F3_fixed>
| |
− | <finger_fixed parent="pinza_fija_link" name="pinza_fija_dedo" color="white">
| |
− | <origin xyz="0 0 0" rpy="0 0 ${M_PI}" />
| |
− | </finger_fixed>
| |
− |
| |
− |
| |
− | <gazebo_propiedades_link nombre="servo_base_link" material="brazo_fer/Black" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="base_brazo_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="servo_arti1_link" material="brazo_fer/Black" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti1_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti1_F10_0_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti1_F10_1_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti1_F10_2_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti1_F3_0_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="servo_arti2_link" material="brazo_fer/Black" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti2_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti2_F10_0_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti2_F10_1_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti2_F10_2_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti2_F3_0_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="servo_arti3_link" material="brazo_fer/Black" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti3_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="arti3_F3_0_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="servo_pinza_link" material="brazo_fer/Black" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="pinza_movil_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="pinza_movil_dedo_link" material="brazo_fer/WhiteTransparent" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="pinza_fija_link" material="brazo_fer/White" />
| |
− |
| |
− | <gazebo_propiedades_link nombre="pinza_fija_dedo_link" material="brazo_fer/WhiteTransparent" />
| |
− |
| |
− |
| |
− | <gazebo_propiedades_joint nombre="base" />
| |
− |
| |
− | <gazebo_propiedades_joint nombre="arti1" />
| |
− |
| |
− | <gazebo_propiedades_joint nombre="arti2" />
| |
− |
| |
− | <gazebo_propiedades_joint nombre="arti3" />
| |
− |
| |
− | <gazebo_propiedades_joint nombre="pinza" />
| |
− |
| |
− | </xacro:macro>
| |
− |
| |
− | </robot>
| |
− |
| |
− | </syntaxhighlight>
| |
− |
| |
− | También debemos crear un archivo llamado "myrabot_moveit.urdf.xacro" dentro del directorio "urdf" del ''package'' "myrabot_fer_modelo" con el siguiente contenido, para cargar el [[Modelo para simulación MYRAbot (urdf+gazebo)|modelo del robot]] con el nuevo [[Modelo para simulación brazo MYRAbot (urdf+gazebo)|modelo del brazo]]:
| |
− |
| |
− | <syntaxhighlight lang="xml" enclose="div">
| |
− |
| |
− | <?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"
| |
− | xmlns:xacro="http://ros.org/wiki/xacro">
| |
− |
| |
− | <xacro:include filename="$(find myrabot_robot_model_b)/urdf/roomba.xacro" />
| |
− |
| |
− | <xacro:include filename="$(find myrabot_robot_model_b)/urdf/estructura-myrabot.xacro" />
| |
− |
| |
− | <xacro:include filename="$(find myrabot_robot_model_b)/urdf/kinect.xacro" />
| |
− |
| |
− | <xacro:include filename="$(find myrabot_arm_model_b)/urdf/brazo_moveit.xacro" />
| |
− |
| |
− | <xacro:include filename="$(find myrabot_robot_model_b)/urdf/webcam.xacro" />
| |
− |
| |
− | <xacro:include filename="$(find myrabot_robot_model_b)/urdf/ultrasonidos.xacro" />
| |
− |
| |
− | <roomba />
| |
− |
| |
− | <estructura_myrabot parent="base_link">
| |
− | <origin rpy="0 0 1.57" xyz="0 0 0.063"/>
| |
− | </estructura_myrabot>
| |
− |
| |
− | <kinect parent="e_base_kinect_link">
| |
− | <origin rpy="0 0 -1.57" xyz="0 -0.045 0.112"/>
| |
− | </kinect>
| |
− |
| |
− | <brazo parent="e_base_brazo_1_link">
| |
− | <origin rpy="0 0 1.57" xyz="0 -0.1015 0.075"/>
| |
− | </brazo>
| |
− |
| |
− | <webcam parent="e_monitor_link">
| |
− | <origin rpy="0 0 0" xyz="-0.135 -0.135 ${0.185/2}"/>
| |
− | </webcam>
| |
− |
| |
− | <ultrasonidos id="1" parent="e_base_2_link" d_centro="0.150">
| |
− | <origin rpy="0 0 1.57" xyz="0 0 ${0.04-0.007}"/>
| |
− | </ultrasonidos>
| |
− |
| |
− | <ultrasonidos id="2" parent="e_base_2_link" d_centro="0.150">
| |
− | <origin rpy="0 0 2.36" xyz="0 0 ${0.04-0.007}"/>
| |
− | </ultrasonidos>
| |
− |
| |
− | <ultrasonidos id="3" parent="e_base_2_link" d_centro="0.150">
| |
− | <origin rpy="0 0 3.14" xyz="0 0 ${0.04-0.007}"/>
| |
− | </ultrasonidos>
| |
− |
| |
− | <ultrasonidos id="4" parent="e_base_2_link" d_centro="0.150">
| |
− | <origin rpy="0 0 3.93" xyz="0 0 ${0.04-0.007}"/>
| |
− | </ultrasonidos>
| |
− |
| |
− | <ultrasonidos id="5" parent="e_base_2_link" d_centro="0.150">
| |
− | <origin rpy="0 0 4.71" xyz="0 0 ${0.04-0.007}"/>
| |
− | </ultrasonidos>
| |
− |
| |
− | </robot>
| |
− |
| |
− | </syntaxhighlight>
| |
| | | |
| ===Integración de sensores de percepción=== | | ===Integración de sensores de percepción=== |
| | | |
| [[Mobile manipulation | < volver a principal]] | | [[Mobile manipulation | < volver a principal]] |
Nos aparecerá la ventana que se muestra a continuación, donde podemos escoger entre crear un nuevo package de configuración (Create New MoveIt Configuration Package) o editar un package de configuración existente (Edit existing MoveIt Configuration Package):
Cuando tengamos seleccionado el modelo del robot pincharemos en "Load Files" para que el asistente de moveIt! cargue nuestro modelo. Al finalizar el proceso de carga aparecerá el modelo del robot en la parte derecha de la ventana, como se puede ver en la siguiente imagen:
Ahora seleccionaremos en el menú de la parte izquierda de la ventana "Self-Collision" y pincharemos en "Regenerate Default Collision Mtrix" para calcular la matriz de colisiones de nuestro modelo, podemos ver el resultado en la siguiente imagen:
En el menú de la izquierda seleccionaremos "Virtual Joints" y pincharemos en "Add Virtual Joint". En el campo "Virtual Joint Name" escribiremos virtual_joint, en el campo "Child_Link" seleccionaremos el link base_footprint, en el campo "Parent Frame Name" escribiremos odom y en el campo "Joint Type" seleccionaremos planar, como se muestra en la siguiente imagen:
En el menú de la izquierda seleccionaremos "Planning Groups" y pincharemos en "Add group". En el campo "Group Name" escribiremos brazo y en el campo "Kinematic Solver" seleccionaremos kdl_kinematics_plugin/KDLKinematicsPlugin, el resto de campos se dejarán como viene por defecto como se muestra en la siguiente imagen:
También debemos añadir el grupo de la pinza pinchando en "Add group". En el campo "Group Name" escribiremos pinza y en el campo "Kinematic Solver" seleccionaremos None, el resto de campos se dejarán como viene por defecto como se muestra en la siguiente imagen:
Podemos establecer posiciones predefinidas para el brazo y así poder reutilizarlas. En el menú de la izquierda seleccionaremos "Robot Poses" y pincharemos en "Add Pose". En el campo "Pose Name" escribiremos home y en el campo "Planning Group" seleccionaremos brazo. Con los cursores podemos modificar la posición de cada articulación para establecer la posición deseada, como se muestra en la siguiente imagen:
En el menú de la izquierda seleccionaremos "End Effectors" y pincharemos en "Add End Effector". En el campo "End Effector Name" escribiremos pinza_eef, en el campo "End Effector Group" seleccionaremos pinza, en el campo "Parent Link" seleccionaremos servo_arti3_link y el campo "Parent Group" lo dejaremos en blanco, como se ,muestra en la imagen:
Para finalizar seleccionamos "Configuration Files" en el menú de la izquierda y pincharemos en "Browse" para seleccionar la ubicación y nombre del package de configuración. Para generar el package simplemente pincharemos en "Generate Package", como se muestra en la imagen: