Note: This tutorial assumes that you have completed the previous tutorials: Setting up the prerequisites.
(!) 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.

Configuring kinematics for your arm

Description: Configuring kinematics for your arm and launching the kinematics node.

Tutorial Level: BEGINNER

In the previous tutorial, you learned how to setup and launch a set of prerequisites to do constraint aware kinematics for the arm. In this tutorial, you will learn how to configure the actual kinematics node for your arm. You will need to follow two configuration steps:

  1. Configure the arm kinematics solvers
  2. Configure the planning environment

Configuring the arm kinematics solvers

Setup the arm parameters

Note that in all the tutorials we have been following for this section, we have so far been planning for the group named right_arm. We will continue with this example. To configure the inverse kinematics plugin for your arm, you need to know the names of two links/frame:

  1. The tip name: This is the end-effector link that you would like to plan for. Note that the name of this link should match the name of the tip link defined in the group definition (see the Robot planning description section in this tutorial for more details on group configuration). For the PR2 arm, the r_wrist_roll_link is the name of the end-effector link for the right arm.

  2. The root name: This is the name of the root link to which your group is attached to. For example, the base or first link of the PR2 arm is the r_shoulder_pan_link whose parent link is the torso_lift_link (through the r_shoulder_pan_joint). So the root name for the right_arm of the PR2 robot is the torso_lift_link.

In a file named example_kinematics.yaml, add the following text (replacing the link names with the appropriate names for your robot):

right_arm:
  tip_name: r_wrist_roll_link
  root_name: torso_lift_link

Configuring the kinematics plugin

Configuring the kinematics plugin requires only one parameter: the name of the plugin that you would like to use. In this case, we are using the generic plugin from the arm_kinematics_constraint_aware package which has the name arm_kinematics_constraint_aware/KDLArmKinematicsPlugin. Thus, the complete configuration is:

right_arm:
  tip_name: r_wrist_roll_link
  root_name: torso_lift_link
  kinematics_solver: arm_kinematics_constraint_aware/KDLArmKinematicsPlugin

Note that a custom plugin can also be used here, if you have one (see the documentation for the kinematics_base package for information on how to write your own plugin). For example, the pr2_arm_kinematics package provides a custom implementation of kinematics for the PR2 arm which can be configured for this node using the following configuration parameters:

right_arm:
  tip_name: r_wrist_roll_link
  root_name: torso_lift_link
  kinematics_solver: pr2_arm_kinematics/PR2ArmKinematicsPlugin

Configure the environment

You are now almost ready to start the kinematics node. A few additional parameters first have to be specified fully configure the planning environment, i.e. the representation of the robot and the environment that the node will use. You can choose to use the default parameters specified below (depending on the particular case you are solving for).

Dealing only with self-collisions

If you are handling only self-collisions, i.e. you have no sensors on your robot that can give you a representation of the environment as a collision map or you just want to ignore such sensor information, here's a pre-configured set of parameters:

use_collision_map: false
collision_map_safety_timeout: 10000.0
joint_states_safety_timeout: 1.0
tf_safety_timeout: 10.0
default_robot_padding: 0.02
link_padding:
  - link: right_arm 
    padding: .02

The link padding is essentially a list of links for which you can specify a padding or clearance parameter. This is important since you want the robot to stay away from obstacles.

You should put this set of parameters in your example_kinematics.yaml file.

Dealing with self-collisions and a collision map

If you want to deal with self-collisions and a collision map generated by your robot's sensors (e.g. a tilting laser scanner, a RGB-D sensor or a stereo camera, etc.), here's a pre-configured set of parameters:

use_collision_map: true
default_robot_padding: 0.02
link_padding:
  - link: right_arm 
    padding: .02

The link padding is essentially a list of links for which you can specify a padding or clearance parameter. This is important since you want the robot to stay away from obstacles.

You should put this set of parameters in your example_kinematics.yaml file. Also make sure that you have a source that publishes a collision map on the collision_map topic. See the CollisionMap message description for more details on the format expected. You can also look at the collision_map package for more information on how collision maps are generated from the PR2 sensors.

Launch the node

You need to include the configuration file you generated in a launch file. Here's an example launch file that you can use (save it as example_kinematics.launch in your example_kinematics package):

<launch>
 <node pkg="arm_kinematics_constraint_aware" type="arm_kinematics_constrain
t_aware" name="example_right_arm_kinematics" output="screen">
 <rosparam command="load" file="$(find example_kinematics)/example_kinematics.yaml" />
 </node>
</launch>

Now, launch this file to get your node up and running.

roslaunch example_kinematics example_kinematics.launch

More details (Optional)

This section is for more advanced users that would like to play around with the configuration a little more. Listed here are the minimal set of parameters that you need to be aware of and configure for more advanced behaviors.

~robot_description (string, default: "robot_description")

  • The name of the ROS parameter that contains the string representation of the URDF for the robot.
~allow_valid_collisions (bool, default: false)
  • If true and allowable contact regions exist, collisions inside the allowed contact regions will be ignored.
~collision_map_safety_timeout (double, default: 0.0)
  • If > 0.0 seconds, the node will expect the collision map to be published regularly within this interval of time. If the node has not received a collision map within the interval it will declare all states and trajectories unsafe.
~joint_states_safety_timeout (double, default: 0.0 (seconds))
  • If > 0.0 seconds, the node will expect the joint states to be published more frequently than this safety timeout. If the node has not received joint states within the interval it will declare all states and trajectories unsafe.
~global_frame (string, default: "")
  • If the global frame is specified to be the empty string, the root frame in which all monitoring will take place is the root link of the robot ("base_link" for the robot). Otherwise, this parameter can be set to a fixed frame in the world (e.g. "odom_combined", "map")
~tf_safety_timeout (double, default: 0.0 (seconds))
  • The expected interval between TF updates. If global_frame is set to a valid fixed frame (and not to its default of an empty string), THEN if the node has not received TF updates within this interval it will declare all states and trajectories unsafe.
~use_collision_map (bool, default: true)
  • If true, collision map information is expected and used in the collision space. If the robot has no sensors to create a representation of the environment or if you do not want to take 3D sensor data into account while planning, set this to false.
<robot_description_name>_collision/default_robot_padding (double, default: .01)
  • The value for a padding to add around the collision bodies associated with all links in the collision space. Note that <robot_description_name> will be replaced with either robot_description or whatever value has been remapped for robot_description.

Wiki: arm_kinematics_constraint_aware/Tutorials/Configuring kinematics for your arm (last edited 2011-05-24 04:34:19 by SachinChitta)