Kinematics Configuration Tutorial

In this section, we will examine some of the parameters for configuring kinematics for your robot.

The kinematics.yaml file

The kinematics.yaml file generated by the MoveIt! Setup Assistant is the primary configuration file for kinematics for MoveIt!. You can see an entire example file for the PR2 robot in the moveit_pr2 github project

right_arm:
  kinematics_solver: pr2_arm_kinematics/PR2ArmKinematicsPlugin
  kinematics_solver_search_resolution: 0.001
  kinematics_solver_timeout: 0.05
  kinematics_solver_attempts: 3
right_arm_and_torso:
  kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
  kinematics_solver_search_resolution: 0.005
  kinematics_solver_timeout: 0.05

Parameters

The set of available parameters include:
  • kinematics_solver: The name of your kinematics solver plugin. Note that this must match the name that you specified in the plugin description file, e.g. example_kinematics/ExampleKinematicsPlugin
  • kinematics_solver_search_resolution: This specifies the resolution that a solver might use to search over the redundant space for inverse kinematics, e.g. using one of the joints for a 7 DOF arm specified as the redundant joint.
  • kinematics_solver_timeout: This is a default timeout specified (in seconds) for each internal iteration that the inverse kinematics solver may perform. A typical iteration (e.g. for a numerical solver) will consist of a random restart from a seed state followed by a solution cycle (for which this timeout is applicable). The solver may attempt multiple restarts - the default number of restarts is defined by the kinematics_solver_attempts parameter below.
  • kinematics_solver_attempts: The number of random restarts that will be performed on the solver. Each solution cycle after the restart will have a timeout defined by the kinematics_solver_timeout parameter above. In general, it is better to set this timeout low and fail quickly in an individual solution cycle.

The KDL Kinematics Plugin

The KDL kinematics plugin wraps around the numerical inverse kinematics solver provided by the Orocos KDL package.
  • This is the default kinematics plugin currently used by MoveIt!
  • It obeys joint limits specified in the URDF (and will use the safety limits if they are specified in the URDF).
  • The KDL kinematics plugin currently only works with serial chains.

The LMA Kinematics Plugin

The LMA (Levenberg-Marquardt) kinematics plugin also wraps around a numerical inverse kinematics solver provided by the Orocos KDL package.
  • It obeys joint limits specified in the URDF (and will use the safety limits if they are specified in the URDF).
  • The LMA kinematics plugin currently only works with serial chains.
  • Usage: kinematics_solver: lma_kinematics_plugin/LMAKinematicsPlugin

Position Only IK

Position only IK can easily be enabled (only if you are using the KDL Kinematics Plugin) by adding the following line to your kinematics.yaml file (for the particular group that you want to solve IK for):

position_only_ik: True

Open Source Feedback

See something that needs improvement? Please open a pull request on this GitHub page