[ros-users] reverse kinematics using robot_state_publisher ?

Ruben Smits ruben.smits at mech.kuleuven.be
Fri Apr 9 07:12:14 UTC 2010


On Thursday 08 April 2010 18:50:59 Ugo Cupcic wrote:
> Dear Ruben,
> 
> Are you using KDL::TreeIkSolverPos_NR_JL for the inverse position
> kinematics ? If it is the case, would you have an example? I can't find
> any on the web :S

This solver was developed in cooperation with a student at EPFL who
used it to control the arms and the torso of the iCub robot. This is
AFAIK the only case in which the solver was used. I don't know if
she still has the user-code, I'll dive in my mail archive to see if there
is still some trace of it.

Ruben
 
> Cheers,
> 
> Ugo
> 
> On 07/04/10 12:08, Ruben Smits wrote:
> > On Wednesday 07 April 2010 12:48:23 Sachin Chitta wrote:
> >> Hi Ugo,
> >> 
> >> You can use KDL to do inverse kinematics using one of the inverse
> >> kinematics solvers in the package. These are numerical solvers that
> >> operate on a KDL chain. First use the kdl_parser package to create a KDL
> >> chain and then initialize an inverse kinematics solver for the chain.
> >> The solution tends to be dependent on the initial state you pass into
> >> the solver and can sometimes get stuck in local minima. Also, I am not
> >> sure about how well the solvers handle joint limits. I believe more
> >> advanced solvers are in the works but I will let the orocos folks
> >> comment on that.
> > 
> > If you need inverse velocity kinematics, which is commonly the case in
> > a control application, KDL contains various implementations including
> > the use of (task and/or robot space weighted)pseudo-inverses of the
> > jacobian and (damped) least squares solutions of the inverse velocity
> > problem.  More advanced (constraint-based) solvers are currently being
> > developed, but these are still at the velocity level.
> > 
> > 
> > If you need inverse position kinematics, KDL does currently not have a
> > perfect solution, at the moment we only have an implementation of a
> > Newton-Raphson integration on top of one of the inverse velocity
> > kinematic solvers.
> > 
> > Ruben
> > 
> >> Have a look at the api page here
> >> http://orocos.org/kdl/UserManual/kinematic_solvers for more examples.
> > 
> > This page (sadly) does not cover all the existing solvers :(
> > 
> >> The other option is to write your own solver (we have one for the PR2
> >> that takes in a hint for one of the joint angles and then computes the
> >> other 6 analytically -
> >> www.ros.org/wiki/pr2_arm_kinematics<http://www.ros.org/wiki/pr2_arm_kine
> >> ma tics>)
> >> 
> >> Sachin
> >> 
> >> On Wed, Apr 7, 2010 at 3:28 AM, Ugo Cupcic
> >> <ugo at shadowrobot.com<mailto:ugo at shadowrobot.com>>  wrote: Hi all,
> >> 
> >> Is it possible to use robot_state_publisher or some other ROS stack to
> >> do reverse kinematic on my urdf model?
> >> Or do I need to implement my own using the "Coding a realtime Cartesian
> >> controller with KDL" tutorial ?
> >> 
> >> Cheers,
> >> 
> >> Ugo
> >> 
> >> 
> >> --
> >> Ugo Cupcic         |  Shadow Robot Company |
> >> ugo at shadowrobot.com<mailto:ugo at shadowrobot.com>  Software Engineer     
> >> 251 Liverpool Road
> >> need a Hand?           London  N1 1LX       | +44 20 7700 2487
> >> http://www.shadowrobot.com/hand/              @shadowrobot
> >> 
> >> _______________________________________________
> >> ros-users mailing list
> >> ros-users at code.ros.org<mailto:ros-users at code.ros.org>
> >> https://code.ros.org/mailman/listinfo/ros-users
> >> 
> >> 
> >> 
> >> --
> >> Sachin Chitta
> >> Research Scientist
> >> Willow Garage
> > 
> > _______________________________________________
> > ros-users mailing list
> > ros-users at code.ros.org
> > https://code.ros.org/mailman/listinfo/ros-users



More information about the ros-users mailing list