Integration of MYRAbot in moveIt! (gazebo+moveIt!)
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
<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>
<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>
<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>
<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>
<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>
<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>
<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>
Controladores para simulación brazo
Crearemos un archivo llamado "controller_moveit.yaml" dentro del directorio "config" del package "brazo_fer_modelo" con el siguiente contenido:
# 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}
Nuevo URDF soporte y cámara xtion
Se ha colocado una estructra de soporte para situar la nueva cámara asus Xtion PRO LIVE para poder realizar tareas de manipulación y reconocimiento de objetos, en sustitución de la anterior cámara web. Para la estructura de soporte añadiremos las siguientes líneas de código al archivo "estructura-myrabot.xacro" situado en el directotio "urdf" del package "myrabot_fer_modelo":
...
<joint name="soporte_3" type="fixed">
<parent link="e_soporte_1_link"/>
<child link="e_soporte_3_link"/>
<origin xyz="0 0.065 0.61" rpy="0.12 0 0" />
</joint>
<link name="e_soporte_3_link">
<inertial>
<mass value="0.01"/>
<origin rpy="0 0 0" xyz="0.0 -0.065 ${0.06/2}"/>
<default_inertia_e />
</inertial>
<visual>
<origin rpy="0 0 0" xyz="-0.135 -0.2 -0.03"/>
<geometry>
<mesh filename="package://myrabot_fer_modelo/meshes/e_soporte_3.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="wood" />
</visual>
<collision>
<origin rpy="0 0 0" xyz="-0.135 -0.2 -0.03"/>
<geometry>
<mesh filename="package://myrabot_fer_modelo/meshes/e_soporte_3.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
...
<gazebo_propiedades nombre="e_soporte_3_link" material="myrabot_fer/LightWood" />
...
Crearemos un archivo llamado "xtion.xacro" dentro del directorio "urdf" del package "myrabot_fer_modelo" con el siguiente contenido para el modelo del sensor 3D:
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Xacro properties -->
<xacro:property name="M_SCALE" value="0.001"/>
<xacro:property name="asus_xtion_pro_depth_rel_rgb_py" value="0.0270" />
<xacro:property name="asus_xtion_pro_cam_rel_rgb_py" value="-0.0220" />
<property name="M_PI" value="3.14159"/>
<!-- Parameterised in part by the values in turtlebot_properties.urdf.xacro -->
<xacro:macro name="xtion" params="parent *origin">
<joint name="camera_rgb_joint_xtion" type="fixed">
<insert_block name="origin" />
<parent link="${parent}"/>
<child link="camera_rgb_frame_xtion" />
</joint>
<link name="camera_rgb_frame_xtion">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" />
<inertia ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0"
izz="0.0001" />
</inertial>
</link>
<joint name="camera_rgb_optical_joint_xtion" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_rgb_frame_xtion" />
<child link="camera_rgb_optical_frame_xtion" />
</joint>
<link name="camera_rgb_optical_frame_xtion">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" />
<inertia ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0"
izz="0.0001" />
</inertial>
</link>
<joint name="camera_joint_xtion" type="fixed">
<origin xyz="0.0175 ${asus_xtion_pro_cam_rel_rgb_py} 0.021"
rpy="0 0 0"/>
<parent link="camera_rgb_frame_xtion"/>
<child link="camera_link_xtion"/>
</joint>
<link name="camera_link_xtion">
<visual>
<origin xyz="-0.01 0 0" rpy="${-M_PI/2} -${M_PI} ${-M_PI/2}"/>
<geometry>
<mesh filename="package://myrabot_fer_modelo/meshes/asus_xtion_pro_live.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
</geometry>
</visual>
<collision>
<origin xyz="-0.01 0 0" rpy="${-M_PI/2} -${M_PI} ${-M_PI/2}"/>
<geometry>
<mesh filename="package://myrabot_fer_modelo/meshes/asus_xtion_pro_live.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
</geometry>
</collision>
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
</link>
<joint name="camera_depth_joint_xtion" type="fixed">
<origin xyz="0.0175 ${asus_xtion_pro_depth_rel_rgb_py} 0.021" rpy="0 0 0" />
<parent link="camera_rgb_frame_xtion" />
<child link="camera_depth_frame_xtion" />
</joint>
<link name="camera_depth_frame_xtion">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
</link>
<joint name="camera_depth_optical_joint_xtion" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_depth_frame_xtion" />
<child link="camera_depth_optical_frame_xtion" />
</joint>
<link name="camera_depth_optical_frame_xtion">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" />
<inertia ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0"
izz="0.0001" />
</inertial>
</link>
<gazebo reference="camera_link_xtion">
<sensor type="depth" name="xtion">
<always_on>true</always_on>
<update_rate>20.0</update_rate>
<camera>
<horizontal_fov>${60.0*M_PI/180.0}</horizontal_fov>
<image>
<format>R8G8B8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.05</near>
<far>8.0</far>
</clip>
</camera>
<plugin name="xtion_camera_controller" filename="libgazebo_ros_openni_kinect.so">
<cameraName>xtion</cameraName>
<alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<imageTopicName>rgb/image_raw</imageTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<frameName>camera_depth_optical_frame_xtion</frameName>
<baseline>0.1</baseline>
<distortion_k1>0.0</distortion_k1>
<distortion_k2>0.0</distortion_k2>
<distortion_k3>0.0</distortion_k3>
<distortion_t1>0.0</distortion_t1>
<distortion_t2>0.0</distortion_t2>
<pointCloudCutoff>0.4</pointCloudCutoff>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
Los archivos empleados, con los modelos de malla 3D ".stl" y ".dae", en la descrición de la estructura soporte y de la cámara se pueden descargar a continuación, deben guardarse en el directorio "meshes" de nuestro package:
Nuevo URDF de MYRAbot
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 del robot con el nuevo modelo del brazo:
<?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_fer_modelo)/urdf/roomba.xacro" />
<xacro:include filename="$(find myrabot_fer_modelo)/urdf/estructura-myrabot.xacro" />
<xacro:include filename="$(find myrabot_fer_modelo)/urdf/kinect.xacro" />
<xacro:include filename="$(find brazo_fer_modelo)/urdf/brazo_moveit.xacro" />
<xacro:include filename="$(find myrabot_fer_modelo)/urdf/xtion.xacro" />
<xacro:include filename="$(find myrabot_fer_modelo)/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>
<xtion parent="e_soporte_3_link">
<origin rpy="0 0.65 -1.57" xyz="0.021 -0.03 0.175"/>
</xtion>
<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>
Crearemos un archivo llamado "myrabot_gazebo_moveit.launcher" dentro del directorio "launch" del package "myrabot_fer_modelo" con el siguiente contenido, para cargar en gazebo el nuevo modelo del robot adaptado a moveIt!:
<launch>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="paused" value="true"/>
<arg name="use_sim_time" value="true"/>
<arg name="debug" value="false"/>
<arg name="world_name" value="$(find turtlebot_gazebo)/worlds/empty.world"/>
</include>
<param name="robot_description" command="$(find xacro)/xacro.py '$(find brazo_fer_modelo)/urdf/myrabot_moveit.urdf.xacro'" />
<node name="spawn_myrabot" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model MYRAbot" respawn="false" output="screen" />
<rosparam file="$(find brazo_fer_modelo)/config/controller_moveit.yaml" command="load"/>
<node name="controller_spawner" pkg="controller_manager" type="spawner" args="pinza_pos_controller brazo_controller joint_state_controller" respawn="false" output="screen" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />
<node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf">
<param name="freq" value="30.0"/>
<param name="sensor_timeout" value="1.0"/>
<param name="publish_tf" value="true"/>
<param name="odom_used" value="true"/>
<param name="imu_used" value="false"/>
<param name="vo_used" value="false"/>
<param name="output_frame" value="odom"/>
</node>
<node pkg="nodelet" type="nodelet" name="pointcloud_throttle" args="load pointcloud_to_laserscan/CloudThrottle openni_manager" respawn="true">
<param name="max_rate" value="20.0"/>
<remap from="cloud_in" to="/camera/depth/points"/>
<remap from="cloud_out" to="cloud_throttled"/>
</node>
<node pkg="nodelet" type="nodelet" name="kinect_laser" args="load pointcloud_to_laserscan/CloudToScan openni_manager" respawn="true">
<param name="output_frame_id" value="/camera_depth_frame"/>
<!-- heights are in the (optical?) frame of the kinect -->
<param name="min_height" value="-0.15"/>
<param name="max_height" value="0.15"/>
<remap from="cloud" to="/cloud_throttled"/>
</node>
<node pkg="nodelet" type="nodelet" name="kinect_laser_narrow" args="load pointcloud_to_laserscan/CloudToScan openni_manager" respawn="true">
<param name="output_frame_id" value="/camera_depth_frame"/>
<!-- heights are in the (optical?) frame of the kinect -->
<param name="min_height" value="-0.025"/>
<param name="max_height" value="0.025"/>
<remap from="cloud" to="/cloud_throttled"/>
<remap from="scan" to="/narrow_scan"/>
</node>
</launch>
Configuración de MYRAbot en moveIt!
Asistente de configuración
Una vez instalado moveIt! ejecutaremos el siguiente comando en un terminal para iniciar el asistente de configuración de este package:
roslaunch moveit_setup_assistant setup_assistant.launch
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):
Seleccionamos el archivo URDF del modelo de MYRAbot pinchando en "Browse" > |
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:
Seleccionamos de la lista las articulaciones del brazo (base, arti1, arti2, arti3) > |
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:
Seleccionamos de la lista las partes de la pinza > |
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 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:
Integración de controladores del brazo
Crearemos un archivo llamado "controllers.yaml" dentro del directorio "config" del package de configuración de moveIt! creado con el siguiente contenido:
controller_list:
- name: brazo_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- arti1
- arti2
- arti3
- base
Editaremos el archivo "MYRAbot_moveit_controller_manager.launch.xml" situado en el directorio "launch" del package de configuración de moveIt! creado para que su contenido sea el siguiente:
<launch>
<!-- Set the param that trajectory_execution_manager needs to find the controller plugin -->
<arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager" />
<param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/>
<!-- load controller_list -->
<rosparam file="$(find myrabot_moveit_generated)/config/controllers.yaml"/>
</launch>
Integración de sensores de percepción
Dentro de estos sensores tenemos la asus xtion pro live y la kinect, con las cuales puede estar equipado MYRAbot y las cuales se configuran de igual modo. Crearemos un archivo llamado "xtion.yaml" dentro del directorio "config" del package de configuración de moveIt! creado con el siguiente contenido:
sensors:
- sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
point_cloud_topic: /xtion/depth/points
max_range: 5.0
point_subsample: 1
padding_offset: 0.1
padding_scale: 1.0
filtered_cloud_topic: filtered_cloud
Editaremos el archivo "MYRAbot_moveit_sensor_manager.launch.xml" situado en el directorio "launch" del package de configuración de moveIt! creado para que su contenido sea el siguiente:
<launch>
<rosparam command="load" file="$(find myrabot_moveit_generated)/config/xtion.yaml" />
<param name="octomap_frame" type="string" value="odom" />
<param name="octomap_resolution" type="double" value="0.05" />
<param name="max_range" type="double" value="5.0" />
</launch>
Tenemos que añadir el valor move_group/MoveGroupGetPlanningSceneService al parámetro "capabilities" en el archivo "move_group.launch" que se encuantra dentro del directorio "launch" del package de configuración de moveIt! creado, quedando como se muestra a continuación:
...
<!-- MoveGroup capabilities to load -->
<param name="capabilities" value="move_group/MoveGroupCartesianPathService
move_group/MoveGroupExecuteService
move_group/MoveGroupKinematicsService
move_group/MoveGroupMoveAction
move_group/MoveGroupPickPlaceAction
move_group/MoveGroupPlanService
move_group/MoveGroupQueryPlannersService
move_group/MoveGroupStateValidationService
move_group/MoveGroupGetPlanningSceneService
" />
...
Modificación del archivo .srdf generado
Tenemos que modificar el archivo "MYRAbot.srdf" generado por el asistente para remplazar las comas por puntos en los valores de las posiciones de las articulaciones guardados, como se muestra a continuación:
<group_state name="home" group="brazo">
<joint name="arti1" value="1,3836" />
<joint name="arti2" value="-2,2458" />
<joint name="arti3" value="-0,7065" />
<joint name="base" value="0" />
</group_state>
por
<group_state name="home" group="brazo">
<joint name="arti1" value="1.3836" />
<joint name="arti2" value="-2.2458" />
<joint name="arti3" value="-0.7065" />
<joint name="base" value="0" />
</group_state>
Ejecución
Planificación simple
Para probar que MYRAbot funciona correctamente en moveIt! podemos iniciar el launcher "demo.launch" contenido en el directorio "launch" del package generado, ejecutando en un terminal el siguiente comando:
roslaunch myrabot_moveit_generated demo.launch
Se cargará el modelo de MYRAbot en rviz con el "Motion Planning Interface" de moveIt!, como se muestra en la siguiente imagen:
Podemos ver, si esta seleccionado el modo "interact", unos interactive markers en torno a la pinza mediante los cuales podremos interactuar con la representación de los estados inicial y final del brazo. Si desplegamos la opción Planning Request dentro de MotionPlanning, podemos activa o desactivar la representación del estado inicial Query Start State (representado en verde) o la representación del estado final Query Goal State (representado en naranja). Cuando alguna de las partes del brazo entre en contacto con otra u otro objeto, estas cambiarán a color rojo.
En el siguiente vídeo podemos ver un proceso de planificación simple, sin obstáculos, que desplaza el brazo desde una posición inicio, en este caso la pose guardada "home", hasta una posición de destino, marcada desplazando el brazo usando los interantive markers:
Planificación con escena modelada
Ejecutaremos el siguiente comando en un terminal para iniciar rviz con el modelo del robot y el "MotionPlanning" de moveIt!:
roslaunch myrabot_moveit_generated demo.launch
Se ha creado una escena con figuras geométricas básicas que representan una mesa y una lata sobre esta. No se han empleado mallas 3D, meshes, aunque es una opción disponible, ya que hay problemas de intercambio aleatorio entre las representaciones visuales de los objetos. Crearemos un archivo llamado "mesa_lata.scene" dentro de nuestra carpeta personal con el siguiente contenido:
Mesa_Lata
* mesa_pata_izquierda_delantera
1
cylinder
0.015 0.71
0.20 0.97 0.355
0 0 0 1
0 0 0 1
* mesa_pata_derecha_delantera
1
cylinder
0.015 0.71
0.20 -0.97 0.355
0 0 0 1
0 0 0 1
* mesa_pata_derecha_trasera
1
cylinder
0.015 0.71
0.89 -0.97 0.355
0 0 0 1
0 0 0 1
* mesa_pata_izquierda_trasera
1
cylinder
0.015 0.71
0.89 0.97 0.355
0 0 0 1
0 0 0 1
* mesa_tablero
1
box
0.75 2 0.03
0.545 0 0.725
0 0 0 1
0.71372549 0.494117647 0.301960784 1
* lata
1
cylinder
0.03 0.12
0.28 0 0.8
0 0 0 1
1 0 0 1
.
Este archivo lo cargaremos en el menú Scene Objects de MotionPlanning pinchando en Import From Text. En el siguiente vídeo podemos ver el proceso de carga de la escena y la planificación de la trayectoria para evitar la lata, representada por un cilindro de color rojo, situada sobre la masa, desplazando el brazo desde un punto de partida a otro de destino entre los cuales se encuentra situada la lata:
Planificación con robot en gazebo
Crearemos un archivo llamado "myrabot_gazebo_moveit_mesa+latas.launch" dentro del directorio "launch" del package "myrabot_fer_modelo" con el siguiente contenido, para cargar los modelos de los objetos (mesa y latas):
<launch>
<include file="$(find myrabot_fer_modelo)/launch/myrabot_gazebo_moveit.launch" />
<!-- Load models table and cans -->
<node name="spawn_mesa" pkg="gazebo_ros" type="spawn_model" args="-file $(find myrabot_objects_models_b)/urdf/mesa.urdf -urdf -x 0.545 -y 0 -z 0 -Y -1.57 -model mesa" respawn="false" output="screen" />
<!--node name="spawn_lata_coca_cola" pkg="gazebo_ros" type="spawn_model" args="-file $(find myrabot_objects_models_b)/urdf/lata_coca_cola.urdf -urdf -x 0.32 -y -0.18 -z 0.74 -Y -1.57 -model lata_Coca_Cola" respawn="false" output="screen" /-->
<node name="spawn_lata_amstel" pkg="gazebo_ros" type="spawn_model" args="-file $(find myrabot_objects_models_b)/urdf/lata_amstel.urdf -urdf -x 0.32 -y 0.0 -z 0.74 -Y -1.57 -model lata_Amstel" respawn="false" output="screen" />
</launch>
Crearemos otro archivo llamado "moveit_planning_execution.launch" dentro del directorio "launch" del package de configuración de moveIt! con el siguiente contenido, para iniciar el interfaz de planificación de movimientos:
<launch>
# The planning and execution components of MoveIt! configured to
# publish the current configuration of the robot (simulated or real)
# and the current state of the world as seen by the planner
<include file="$(find myrabot_moveit_generated)/launch/move_group.launch">
<arg name="publish_monitored_planning_scene" value="true" />
</include>
# The visualization component of MoveIt!
<include file="$(find myrabot_moveit_generated)/launch/moveit_rviz.launch"/>
</launch>
Ejecutaremos el siguiente comando en un terminal para iniciar gazebo con los modelos del robot y los objetos:
roslaunch myrabot_robot_model myrabot_gazebo_moveit_mesa+latas.launch
En otro terminal ejecutaremos el siguiente comando para iniciar rviz con el "Motion Planning Interface" de moveIt!:
roslaunch myrabot_moveit_generated moveit_planning_execution.launch
En el siguiente vídeo podemos ver el proceso de planificación y ejecución de la trayectoria para evitar la lata que se encuentra en medio de la trayectoria de las posiciones de inicio y destino, se planifica dos veces ya que la primera vez se detecta una colisión entre el brazo y la lata. La escena representada corresponde con la captada por el sensor de percepción situado por encima de la pantalla, donde se muestra el espacio ocupado mediante cubos con una tolerancia que permita evitar colisiones.
-->