## page was renamed from Robots/TIAGo/Tutorials/Planning_cartesian_space_TRAC-IK ## page was renamed from Robots/TIAGo/Tutorials/Planning in cartesian space with TRAC-IK ## page was renamed from Robots/TIAGo/Tutorials/Planning in cartesian space with Trac-IK ## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0= ## descriptive title for the tutorial ## title = Planning in cartesian space with TRAC-IK ## multi-line description to be displayed in search ## description = Use [[https://bitbucket.org/traclabs/trac_ik/overview|TRAC-IK]] in [[http://moveit.ros.org|MoveIt!]] to plan a joint trajectory in order to reach a given pose in cartesian space ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link=[[Robots/TIAGo/Tutorials/MoveIt/Planning_Octomap|Planning with Octomap]] ## next.1.link= ## what level user is this tutorial for ## level= IntermediateCategory ## keywords = Motion planning, cartesian space, inverse kinematics, TRAC-IK #################################### Author: Alessandro Di Fava < alessandro.difava@pal-robotics.com > Maintainer: Jordi Pages < jordi.pages@pal-robotics.com >, Alessandro Di Fava < alessandro.difava@pal-robotics.com > Support: tiago-support@pal-robotics.com Source: https://github.com/pal-robotics/tiago_tutorials.git <> {{attachment:tiago_trac_ik_4.png||align="right", width="200"}} <> == Purpose == This tutorial shows how to use [[https://bitbucket.org/traclabs/trac_ik/overview|TRAC-IK]] in [[http://moveit.ros.org|MoveIt!]] in order to move the end-effector frame of TIAGo to a desired pose in cartesian space. == Pre-requisites == First make sure that the tutorials are properly installed along with the TIAGo simulation, as shown in the [[Robots/TIAGo/Tutorials/Installation/TiagoSimulation|Tutorials Installation]] Section. == Install TRAC-IK plugin == In order to execute the demo first we need to install the [[https://bitbucket.org/traclabs/trac_ik/src/HEAD/trac_ik_kinematics_plugin/|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 /tiago_public_ws/ source ./devel/setup.bash }}} == Launching the simulation == In the first console launch the following simulation {{{ IK_SOLVER=trac_ik roslaunch tiago_gazebo tiago_gazebo.launch public_sim:=true end_effector:=pal-gripper }}} Gazebo will show up with TIAGo. {{attachment:tiago_steel_planning_ik_gazebo.jpg||align="center", width="600"}} Wait until TIAGo has tucked its arm. Then you may proceed with the next steps. 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 '''tiago_moveit_config/config/kinematics_trac_ik.yaml''' referred to TRAC_IK solver is shown: {{{ arm_torso: kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin kinematics_solver_timeout: 0.005 solve_type: Speed position_only_ik: false arm: 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/TIAGo/Tutorials/MoveIt/Planning_cartesian_space for details) that will bring TIAGo's end-effector frame, i.e. arm_tool_link, to the following cartesian space configuration with respect to /base_footprint: {{{ x: 0.4 y: -0.3 z: 0.26 Roll: -0.011 Pitch: 1.57 Yaw: 0.037 }}} In order to safely reach such a cartesian goal the node '''plan_arm_torso_ik''' included in '''tiago_moveit_tutorial''' package has to be called as follows {{{ rosrun tiago_moveit_tutorial plan_arm_torso_ik 0.4 -0.3 0.26 -0.011, 1.57, 0.037 }}} An example of plan executed by the node is depicted in the following sequence of images: || {{attachment:tiago_trac_ik_1.png||width="350"}} || {{attachment:tiago_trac_ik_2.png||width="350"}} || || {{attachment:tiago_trac_ik_3.png||width="350"}} || {{attachment:tiago_trac_ik_4.png||width="350"}} || Note that the final pose of /arm_tool_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. ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE