Hi Ugo, I'm not sure exactly which stack/code you are using, but those markers look like they're coming from the interpolated IK motion planner. The interpolated IK motion planner can search for a consistent/feasible path starting from either end--if the start_from_end parameter is true, then the planner finds IK solutions for the end pose first, then works its way backwards towards the start pose, using the last set of found arm angles as the starting point. Typically when you're planning from pregrasp to grasp, you want to enter pregrasp as start and grasp as end so the trajectory times are correct, but you want to ask it to start searching from the grasp (end) pose and work its way backwards. That's because you typically can't compromise on the final grasp pose, but you might not mind if the Cartesian path backwards towards the pregrasp gets almost but not all the way there. That's what the error codes tell you--how far it got. (You can also set the steps_before_abort param to 0 if you just want it to abort if it finds any infeasible/inconsistent poses at all.) If you get an incomplete path back, you can decide whether you're willing to just motion plan to a slightly closer pregrasp pose, or if you want to abort. If the markers don't make it all the way to the pregrasp, it means that the path is incomplete--the next step towards the pregrasp either had no collision-free IK solution, or else had no solution consistent with the last step (within consistent_angle for all joint angles from the last step). I'm not sure what you're running to get to the pregrasp, but you probably want to use move_arm or some such to move to the start of the (completed portion of the) trajectory returned by the interpolated IK motion planner, then use a normal joint trajectory movement to get through the rest of the trajectory. (Or you can just use a Cartesian controller, assured that there actually is a feasible/consistent path to actually reach the grasp pose from that set of joint angles.) Hope that helps. -Kaijen On Thu, Feb 3, 2011 at 8:25 AM, Ugo Cupcic wrote: > Hi all, > > I'm still trying to get the manipulation stack to work with our arm and hand > and I ran into some problem: > > As you can see here, A path from pregrasp to grasp is found: > http://img267.imageshack.us/img267/199/rviz013.png > > But: >  > the path seems to be the wrong way around: the first markers are at the > bottom, instead of at the top. >  > when moving the arm, the arm moves maybe 5cm below the markers (on the > screenshot, it's at position 0 which should be pregrasp). > > The values I put in the database are: > grasp_pregrasp_position = > "{0,0,0.281533,0.707106781186548,0.707106781186548,0,0}" > grasp_grasp_position = > "{0,0,0.213018,0.707106781186548,0.707106781186548,0,0}" > > Any help greatly appreciated. > > Cheers, > > Ugo > > -- > Ugo Cupcic | Shadow Robot Company | ugo@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@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users > >