Hi Martin,<br><br>I'm glad you are making progress - we're definitely trying to make it easier for others to use arm navigation but we still have a ways to go.<br><br>To answer your question,  you don't have to supply move_arm with an ik service - that's only if you want to pass in end-effector goals and have it call the IK service.  You can call ik yourself and just pass in joint positions and everything should work.<br>

<br>If you want move_arm to invoke IK, then it boils down to whether or not you actually want to make ik aware of constraints, such as not providing solutions that are in self- or environmental collision.  If you don't care about that you can simply provide a service that take the constraint aware ik messages and then calls your non-constraint aware ik.  If you return a solution that violates constraints - for instance, that is in self-collision - then move arm will abort with an error code.  But if the solution is valid everything should work.<br>

<br>But if you are really interested in getting constraint aware ik then there's no easy way that I know about, though conceptually constraint-aware ik isn't too difficult.  What our constraint aware IK (pr2_arm_kinematics_constraint_aware) consists of is a way to check that space of potential IK solutions for a solution that obeys all constraints.  On the PR2 we only have one redundancy so we just set the redundancy according to the supplied seed, discretize the redundancy space, and then check each state for constraint satisfaction using our planning_environment.  We also do an initial check to make sure that the end effector itself isn't in collision at the desired pose - if it is there's no reason to search the space of redundancies.  We return the first valid solution we find, though we've also experimented with other versions that try to find the 'best' solution - the one furthest away from collisions, for instance.<br>
<br>I very much hope we can make things like this more generic in the future - maybe there's an openrave module that will do this for you.  But if you are interested in writing your own let us know if there's anything we can do to help.<br>
<br>Best,<br>Gil<br><br>--<br>E. Gil Jones (<a href="mailto:gjones@willowgarage.com" target="_blank">gjones@willowgarage.com</a>)<br>Research Engineer<br>Willow Garage, Inc.<br>68 Willow Road<br>Menlo Park, CA 94025<br>650.475.9772<br>

<br>
<br><br><br><div class="gmail_quote">2011/1/8 Martin Günther <span dir="ltr"><<a href="mailto:mguenthe@uos.de" target="_blank">mguenthe@uos.de</a>></span><br><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">

Hi everybody,<br>
<br>
I am currently (still) in the process of porting the arm_navigation<br>
stack to a Katana arm. I already have a replacement for almost<br>
everything in the pr2_3dnav/right_arm_navigation.launch file (mostly a<br>
big copy-and-paste orgy, followed by s/pr2/katana/g).<br>
<br>
At the moment, I use the generic arm_kinematics package from urdf_tools<br>
to provide the get_ik and get_fk services, since this seems to be the<br>
simplest package to set up. Maybe later I'm going to switch to<br>
OpenRave's ikfast module.<br>
<br>
However, move_arm expects a get_constraint_aware_ik service. Is there<br>
an easy way to get that going?<br>
<br>
Cheers,<br>
Martin<br>
<br>
--<br>
Dipl.-Inf. Martin Günther<br>
Universität Osnabrück<br>
Institut für Informatik<br>
Albrechtstr. 28  (Raum 31/503)<br>
D-49076 Osnabrück<br>
<br>
Fon: 0541 969 2434<br>
<a href="http://www.inf.uos.de/mguenthe/" target="_blank">http://www.inf.uos.de/mguenthe/</a><br>
_______________________________________________<br>
ros-users mailing list<br>
<a href="mailto:ros-users@code.ros.org" target="_blank">ros-users@code.ros.org</a><br>
<a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
</blockquote></div><br>