Author: Alessandro Di Fava < alessandro.difava@pal-robotics.com >
Maintainer: Sara Cooper < sara.cooper@pal-robotics.com >
Support: ari-support@pal-robotics.com
Source: https://github.com/pal-robotics/ari_tutorials.git
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Planning in cartesian space with TRAC-IK
Description: Use TRAC-IK in MoveIt! to plan a joint trajectory in order to reach a given pose in cartesian spaceKeywords: Motion planning, cartesian space, inverse kinematics, TRAC-IK
Tutorial Level: INTERMEDIATE
Contents
Purpose
This tutorial shows how to use TRAC-IK in MoveIt! in order to move the end-effector frame of ARI'S left arm to a desired pose in cartesian space.
Pre-requisites
First make sure that the tutorials are properly installed along with the ARI simulation, as shown in the Tutorials Installation Section.
Install TRAC-IK plugin
In order to execute the demo first we need to install the TRAC-IK plugin for MoveIt! in your workspace. In a console run the following command
sudo apt-get install ros-$ROS_DISTRO-trac-ik-kinematics-plugin
The command adds the trac-ik-kinematics-plugin and trac_ik_lib to your workspace.
Execution
First open two consoles and source the public simulation workspace as follows:
cd ~/ari_public_ws source ./devel/setup.bash
Launching the simulation
In the first console launch the following simulation
IK_SOLVER=trac_ik roslaunch ari_gazebo ari_gazebo.launch public_sim:=true
Gazebo will show up with ARI.
The IK_SOLVER=trac_ik environment variable is used to set TRAC_IK solver as the solver to use in MoveIt! Without this variable, the default solver is the KDL one. The configuration file ari_moveit_config/config/kinematics_trac_ik.yaml referred to TRAC_IK solver is shown:
arm_left: kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin kinematics_solver_timeout: 0.005 solve_type: Speed position_only_ik: false arm_right: kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin kinematics_solver_timeout: 0.005 solve_type: Speed position_only_ik: false
See https://bitbucket.org/traclabs/trac_ik/src/HEAD/trac_ik_kinematics_plugin for details about the parameters.
Launching the nodes
Now we are going to run the example of the previous tutorial (see http://wiki.ros.org/Robots/ARI/Tutorials/MoveIt/Planning_cartesian_space for details) that will bring ARI's left arm's end-effector frame, i.e. arm_left_4_link, to the following cartesian space configuration with respect to /base_footprint:
x: -0.2 y: 0.38 z: 1.1 Roll: -1.81 Pitch: -0.65 Yaw: -2.59
In order to safely reach such a cartesian goal the node plan_left_arm_ik included in ari_moveit_tutorial package has to be called as follows
rosrun ari_moveit_tutorial plan_left_arm_ik -0.2 0.38 1.1 -1.81 -0.65 -2.59
An example of plan executed by the node is depicted in the following sequence of images:
|
|
|
Note that the final pose of /arm_left_4_link is the same of the previous tutorial, but the joints configuration of the arm is different. It depends on MoveIt! planner but it's also due to the using of a different IK solver.