[ros-users] replicating pr2_arm_kinematics for 6-DOF arm

Rosen Diankov rosen.diankov at gmail.com
Sun Jul 18 00:46:59 UTC 2010


I am in the process of writing better documentation, but if you have
your robot in COLLADA or OpenRAVE XML format, then you can use the
ikfast program to generate the analytical inverse kinematics:

http://openrave.programmingvision.com/index.php?title=Component:Ikfast

http://openrave.programmingvision.com/index.php/Databases:InverseKinematics

from all the timings i've done, these ikfast solvers can generate all
possible solutions for you in ~6 microseconds.


rosen,

2010/7/17 Morgan Quigley <mquigley at cs.stanford.edu>:
> Hi Dave,
>
> The Orocos KDL library is great. I just switched to it last week; my
> code is pretty ugly, but it's using the KDL::ChainIkSolverPos_NR_JL
> class, which has joint limits:
>
> http://stanford-ros-pkg.googlecode.com/svn/trunk/openarms/control/goto_cart.cpp
>
> The ik_tool() function is what you're after. You set the joint limits
> when you construct the ChainIkSolverPos_NR_JL object; search for
> "ik_solver_pos" in that .cpp file to see the exact syntax.
>
> (sorry about all the commented code... it's a work in progress)
>
> HTH,
> Morgan
>
>
> On Sat, Jul 17, 2010 at 10:43 AM, David Feil-Seifer
> <david.feilseifer at gmail.com> wrote:
>> I am trying to replicate the IK-functionality of pr2_arm_navigation
>> for our humanoid robot, Bandit. I have attached a xacro file for it's
>> arm. I have it rendering correctly, and am able to have it mimic the
>> movements of a real Bandit with joint_states_publisher and a
>> /joint_states message. I seem to have correctly ported
>> pr2_arm_ik_solver and pr2_arm_kinematics by simply changing all 7's to
>> 6's and changing the names of the root and tip links
>> (bandit_torso_link and left/right_hand_link). However, I'm having
>> trouble with pr2_arm_ik.cpp. Clearly, the math here was meant for a
>> 7-DOF arm, and I don't really know what algorithm is being used here,
>> so I'm having trouble translating that to a 6-DOF arm. I have figured
>> out that in the init function, that I needed to change the
>> link_offsets for the shoulder_upperarm_offset, elbow_wrist offset, and
>> upperarm_elbow_offset values. Those are now correct. I am just having
>> trouble making computeIKShoulderPan and computeIKShoulderRoll to a 6
>> joint arm. Can anyone give me some guidance on how to proceed?
>>
>> I did look at the KDL examples on their website, but they were pretty
>> vague about creating an IK solver with joint limits.
>>
>> Thanks for your help.
>> -Dave
>>
>> _______________________________________________
>> ros-users mailing list
>> ros-users at code.ros.org
>> https://code.ros.org/mailman/listinfo/ros-users
>>
>>
> _______________________________________________
> 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