Difference between revisions of "Integration of MYRAbot in moveIt! (gazebo+moveIt!)"
(→New URDF of the arm) |
(→New URDF of the arm) |
||
Line 13: | Line 13: | ||
====New URDF of the arm==== | ====New URDF of the arm==== | ||
− | We need to modify the type of the [http://wiki.ros.org/simulator_gazebo?distro=electric gazebo] controllers of the [[MYRAbot's arm model for simulation (urdf+gazebo)|arm]]'s joints in order to allow to [http://moveit.ros.org/ moveIt!] to take the control of these. | + | We need to modify the type of the [http://wiki.ros.org/simulator_gazebo?distro=electric gazebo] controllers of the [[MYRAbot's arm model for simulation (urdf+gazebo)|arm]]'s joints in order to allow to [http://moveit.ros.org/ moveIt!] to take the control of these. Also we have added the 3D meshes of the real components of the arm. We will create a file named "brazo-macros_moveit.xacro" within the folder "urdf" of the ''package'' "brazo_fer_modelo" with the content that is shown below: |
− | |||
− | |||
− | |||
− | |||
<syntaxhighlight lang="xml" enclose="div"> | <syntaxhighlight lang="xml" enclose="div"> | ||
Line 355: | Line 351: | ||
</syntaxhighlight> | </syntaxhighlight> | ||
− | + | We will add the next files within the folder "meshes" of the ''package'' "brazo_fer_modelo": | |
* [http://www.fernando.casadogarcia.es/files/ax12_box.stl ax12_box.stl] | * [http://www.fernando.casadogarcia.es/files/ax12_box.stl ax12_box.stl] | ||
Line 363: | Line 359: | ||
* [http://www.fernando.casadogarcia.es/files/F10.stl F10.stl] | * [http://www.fernando.casadogarcia.es/files/F10.stl F10.stl] | ||
− | + | We will create a file named "brazo_moveit.xacro" within the folder "urdf" of the ''package'' "brazo_fer_modelo" with the content that is shown below: | |
<syntaxhighlight lang="xml" enclose="div"> | <syntaxhighlight lang="xml" enclose="div"> | ||
Line 384: | Line 380: | ||
<link name="fixed_link"/> | <link name="fixed_link"/> | ||
− | shoulder pan joint | + | <!-- shoulder pan joint --> |
<dynamixel_AX12_fixed parent="fixed_link" name="servo_base"> | <dynamixel_AX12_fixed parent="fixed_link" name="servo_base"> | ||
<origin xyz="0 0 0.019" rpy="${M_PI/2} 0 ${-M_PI/2}"/> | <origin xyz="0 0 0.019" rpy="${M_PI/2} 0 ${-M_PI/2}"/> | ||
Line 392: | Line 388: | ||
</bioloid_F3_revolute> | </bioloid_F3_revolute> | ||
− | shoulder lift joint | + | <!-- shoulder lift joint --> |
<dynamixel_AX12_fixed parent="base_brazo_link" name="servo_arti1"> | <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" /> | <origin xyz="0 0 ${-AX12_HEIGHT-F10_HEIGHT+0.001}" rpy="0 ${M_PI} 0" /> | ||
Line 412: | Line 408: | ||
</bioloid_F3_fixed> | </bioloid_F3_fixed> | ||
− | elbow joint | + | <!-- elbow joint --> |
<dynamixel_AX12_fixed parent="arti1_F3_0_link" name="servo_arti2"> | <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"/> | <origin xyz="0 0 ${-AX12_HEIGHT-F10_HEIGHT+0.001}" rpy="0 ${M_PI} 0"/> | ||
Line 432: | Line 428: | ||
</bioloid_F3_fixed> | </bioloid_F3_fixed> | ||
− | wrist joint | + | <!-- wrist joint --> |
<dynamixel_AX12_fixed parent="arti2_F3_0_link" name="servo_arti3"> | <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"/> | <origin xyz="0 0 ${-AX12_HEIGHT-F10_HEIGHT+0.001}" rpy="0 ${M_PI} 0"/> | ||
Line 443: | Line 439: | ||
</bioloid_F3_fixed> | </bioloid_F3_fixed> | ||
− | + | <!-- gripper joint --> | |
<dynamixel_AX12_fixed parent="arti3_F3_0_link" name="servo_pinza"> | <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"/> | <origin xyz="-0.02275 0 ${-AX12_WIDTH/2}" rpy="${M_PI} ${M_PI/2} 0"/> | ||
</dynamixel_AX12_fixed> | </dynamixel_AX12_fixed> | ||
− | + | <!-- finger 1 --> | |
<joint name="pinza" type="revolute"> | <joint name="pinza" type="revolute"> | ||
<origin xyz="0 0 0" rpy="0 0 0"/> | <origin xyz="0 0 0" rpy="0 0 0"/> | ||
Line 481: | Line 477: | ||
</finger_fixed> | </finger_fixed> | ||
− | + | <!-- finger 2 --> | |
<bioloid_F3_fixed parent="servo_pinza_link" name="pinza_fija" color="white"> | <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" /> | <origin xyz="0 0 ${-AX12_HEIGHT-F10_HEIGHT+0.001}" rpy="0 ${M_PI} 0" /> | ||
Line 551: | Line 547: | ||
</syntaxhighlight> | </syntaxhighlight> | ||
− | ==== | + | ====Controllers for arm simulation==== |
− | + | We will create a file named "controller_moveit.yaml" within the folder "config" of the ''package'' "brazo_fer_modelo" with the content that is shown below: | |
<syntaxhighlight> | <syntaxhighlight> | ||
Line 583: | Line 579: | ||
</syntaxhighlight> | </syntaxhighlight> | ||
+ | |||
+ | |||
+ | |||
+ | <!-- | ||
====Nuevo URDF soporte y cámara xtion==== | ====Nuevo URDF soporte y cámara xtion==== |
Revision as of 20:04, 10 March 2014
Contents
Previous steps
Installation of moveIt!
MoveIt! is a package that provides a software tool for all types of manipulation tasks both industrial level and domestic level. It is available for the ROS distributions groovy and hydro, for this reason we must have installed some of these. We will execute the next command in a terminal in order to install moveIt!, where "ROS_DISTRIBUCION" is our installed distribution:
sudo apt-get install ros-ROS_DISTRIBUCION-moveit-full
Modification of MYRAbot model for moveIt!
New URDF of the arm
We need to modify the type of the gazebo controllers of the arm's joints in order to allow to moveIt! to take the control of these. Also we have added the 3D meshes of the real components of the arm. We will create a file named "brazo-macros_moveit.xacro" within the folder "urdf" of the package "brazo_fer_modelo" with the content that is shown below:
<?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>
We will add the next files within the folder "meshes" of the package "brazo_fer_modelo":
We will create a file named "brazo_moveit.xacro" within the folder "urdf" of the package "brazo_fer_modelo" with the content that is shown below:
<?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>
Controllers for arm simulation
We will create a file named "controller_moveit.yaml" within the folder "config" of the package "brazo_fer_modelo" with the content that is shown below:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
# Position Controllers ---------------------------------------
pinza_pos_controller:
type: effort_controllers/JointPositionController
joint: pinza
pid: {p: 0.8, i: 0.6, d: 0.3, i_clamp: 1}
brazo_controller:
type: effort_controllers/JointTrajectoryController
joints:
- arti1
- arti2
- arti3
- base
gains: # Required because we're controlling an effort interface
arti1: {p: 1.0, i: 0.6, d: 0.3, i_clamp: 10}
arti2: {p: 1.0, i: 0.6, d: 0.3, i_clamp: 10}
arti3: {p: 1.0, i: 0.6, d: 0.3, i_clamp: 10}
base: {p: 1.0, i: 0.6, d: 0.3, i_clamp: 10}