Skip to content

Commit

Permalink
Added Trac-IK tutorial (moveit#41)
Browse files Browse the repository at this point in the history
  • Loading branch information
davetcoleman authored and v4hn committed Oct 31, 2016
1 parent 969ce78 commit aa6a6e9
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 2 deletions.
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

This repo is automatically built by the ROS build farm and its output is hosted here: http://docs.ros.org/kinetic/api/moveit_tutorials/html/

The tutorials use the [reStructuredText](http://www.sphinx-doc.org/en/stable/rest.html) format commonly used in the Sphinx "Python Documentation Generator". This unfortuantly differs from the common Markdown format.

## Travis Continuous Integration

[![Build Status](https://travis-ci.org/ros-planning/moveit_tutorials.svg?branch=master)](https://travis-ci.org/ros-planning/moveit_tutorials)
Expand Down
26 changes: 24 additions & 2 deletions doc/trac_ik_tutorial.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,28 @@
Trac-IK Kinematics Solver
=========================

**Note:** *This is a stub tutorial, to be expanded upon in the future*
`Trac-IK <https://bitbucket.org/traclabs/trac_ik>` is an inverse kinematics solver developed by Traclabs that combines two IK implementations via threading to achieve more reliable solutions than common available open source IK solvers. From their documentation:

For now see `Trac-IK <https://bitbucket.org/traclabs/trac_ik/src/HEAD/trac_ik_kinematics_plugin/>`_
(Trac-IK) provides an alternative Inverse Kinematics solver to the popular inverse Jacobian methods in KDL. Specifically, KDL's convergence algorithms are based on Newton's method, which does not work well in the presence of joint limits --- common for many robotic platforms. TRAC-IK concurrently runs two IK implementations. One is a simple extension to KDL's Newton-based convergence algorithm that detects and mitigates local minima due to joint limits by random jumps. The second is an SQP (Sequential Quadratic Programming) nonlinear optimization approach which uses quasi-Newton methods that better handle joint limits. By default, the IK search returns immediately when either of these algorithms converges to an answer. Secondary constraints of distance and manipulability are also provided in order to receive back the "best" IK solution.

The package `trac_ik_kinematics_plugin <https://bitbucket.org/traclabs/trac_ik/src/HEAD/trac_ik_kinematics_plugin/>` provides a KinematicsBase MoveIt! interface that can replace the default KDL solver. Currently mimic joints are *not* supported.

Install
-------

As of v1.4.3, **trac_ik** is part of the ROS Indigo/Jade binaries::

sudo apt-get install ros-jade-trac-ik-kinematics-plugin

Usage
-----

- Install **trac_ik_kinematics_plugin** and **trac_ik_lib package** or add to your catkin workspace.
- Find the MoveIt! `kinematics.yaml <http://docs.ros.org/kinetic/api/moveit_tutorials/html/doc/pr2_tutorials/kinematics/src/doc/kinematics_configuration.html>` file created for your robot.
- Replace ``kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin`` (or similar) with ``kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin``
- Set parameters as desired:
- **kinematics\_solver\_timeout** (timeout in seconds, e.g., 0.005) and **position\_only\_ik** **ARE** supported.
- **solve\_type** can be Speed, Distance, Manipulation1, Manipulation2 (see trac\_ik\_lib documentation for details). Default is Speed.
- **kinematics\_solver\_attempts** parameter is unneeded: unlike KDL, TRAC-IK solver already restarts when it gets stuck
- **kinematics\_solver\_search\_resolution** is not applicable here.
- Note: The Cartesian error distance used to determine a valid solution is **1e-5**, as that is what is hard-coded into MoveIt's KDL plugin.

0 comments on commit aa6a6e9

Please sign in to comment.