ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Moveit pick too complicated?

asked 2016-09-30 18:07:56 -0600

greenghost gravatar image

updated 2016-09-30 18:12:24 -0600

I am using a turtlebot with an attached arm. In moveit I can move the arm nicely.

I am currently writing a python script (which is similar to the pick_and_place.py demo.

Placing a table and a box object in the world is very easy. Picking it up isn't.. Calling self.arm.pick(self.box_id) is only resulting in [ WARN] [1475274220.198944028]: Fail: ABORTED: No motion plan found. No execution attempted. The pick and place demo is calling the method by passing a grasp list (even though the parameter is optional). The way the grasp list is generated seems to be extremely complicated and unreadable.

Why do I need to pass a grasp list? So far what I could see from moveit is that it is able to move the arm very nicely & precise, why isn't it able to move the arm to the object? I understand that there are multiple possibilities for picking up the object. Simply a valid solution would be enough for me (no collision). The behavior for moving the arm itself is just the same: there are multiple possibilities, moveit is just taking one; why isn't it working like that for picking an object?

Thank you in advance

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
6

answered 2016-09-30 19:43:12 -0600

v4hn gravatar image

why isn't it able to move the arm to the object?

It surely is able to do that, but that's not what you want. You don't just want to move the arm to where the object is, but instead, you want to grasp the object, meaning you would like to stably fixate it in the end effector, maybe touching the object at specific regions such as a handle, and allow the arm to move around with the object grasped. Probably you like to include a safe approach motion of the arm. You might want to be able to specify how to grasp the object with the end-effector (e.g. how much force). You might even have an end-effector that is no simple one-dimensional gripper and can even grasp in multiple ways. And you might also want to lift the object off the table (which direction is that?) for a certain distance (how far?) after closing the gripper to demostrate that it's actually grasped stably and isolate the object from its support surface to simplify later motions.

Grasping an object is not an easy thing to do. There have been major international research programs on the topic, and in my opinion we are still far from having it "solved" even in theory. The MoveIt pick_and_place pipeline tries to make this more accessible by boiling the problematic points down to the Grasp message that should be provided by the user (or some intelligent scripts they implement) and imho the original author(s) did quite a decent job there.

The pick-place-capability...

  • provides an integrated pipeline to reason about the whole grasp process and decomposes it into a number of executable trajectories for multiple low-level controller.
  • does forward projection such that you will not start executing a grasp to only then find out that because of some obstacle or the kinematics of your arm you can't lift the object off the table after closing the endeffector.
  • manages attaching and detaching of the grasped object so that collision checking when moving the arm with an object attached will also check for collisions of the object in the environment (even in the forward projection).
  • supports parallel checking of multiple candidate grasps for all the different trajectory-parts of the grasp
  • it provides a visualization of evaluated grasps during the process in RViz

... along with all the usual capabilities of MoveIt. This is quite a lot.

In practice, most of the time you will have to provide a valid Grasp message yourself for a successful grasp (and as I pointed out already, this is not necessarily easy and also highly depends on your setup). If you call the pick(std::string) method, the pick_place pipeline will try to request candidate grasps to test from an external service instead (you have to provide that ROS-service yourself) and adds a somewhat meaningful "default" grasp. The code for that part is here: https://github.com/ros-planning/movei...

That being said, there are quite a number of ... (more)

edit flag offensive delete link more

Comments

Moveit provides a lot that is for sure. But I still don't understand why it can't provide any valid grasps. In RVIZ I can just move the arm to the object. I can actually do the same in Moveit (by moving the arm to the object pose) but there seems to be no way to publish a pose without orientation

greenghost gravatar image greenghost  ( 2016-10-04 17:45:04 -0600 )edit

well, you could use the position IK service of the move_group and look for an IK for your object position. That gives you a valid orientation to use with the pick request.

v4hn gravatar image v4hn  ( 2016-11-15 08:20:25 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2016-09-30 18:07:56 -0600

Seen: 2,085 times

Last updated: Sep 30 '16