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

Problem with the reference frame of grasps in the household_objects_database

asked 2012-03-01 02:07:09 -0500

toniOliver gravatar image

I'm using the manipulation stack in ROS electric, in a simulated environment in Gazebo. I have a simulated robot arm and hand, a simulated table and a coke can, and a simulated kinect.

Object recognition is working well with the coke can, from the model in the household_objects_database (using the image from the simulated kinect).

But the problem is that when I want to use the object_manipulator, the grasps for that object are read from the database and represented in a weird and unexpected way.

The grasps (and pregrasps) for the coke can are in the grasp table of the DB with different positions but all of them have the identity quaternion (0,0,0,1) for orientation, so no rotation should be applied. But when trying to pickup the object with object_manipulator, the grasps are read from the database and the markers representing the grasps are more or less (but not exactly) in the expected position, but they have a completely unexpected orientation, as it can be seen in the following two images.

I thought that the parent frame of the grasps would be the frame of the recognised object (/object_frame in this case), but the orientation of the represented grasps is different from that.

Can anyone tell me what's the reference frame of the grasps, or what can I be doing wrong?

Screenshot of the grasps with no rotation

Screenshot of the grasps with no rotation. Top view

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2012-03-01 10:06:57 -0500

Matei Ciocarlie gravatar image

The pose of the grasps in the database should be saved in the reference frame of the object - that is, relative to the origin of the 3D model (the mesh) of the object.

At run-time however, the manipulation pipeline does not know if the reference frame of the object is actually available in TF. It seems like it is in your system, but htat is not generally the case. Therefore, when you query the objects database node and ask for grasps for the object, it will also look where the object is in relation to a TF frame (this information is contained in the GraspableObject you are passing to the GetGrasps callback). It will then give you back the grasps transformed to the same reference frame that the object is in.

For example: let's say that object recognition gives you the object at location T1 w.r.t. the "base_link" frame. Let's say that in the database you have a grasp stored at location G1 relative to the object. When you get the grasps from the database, the objects_database_node will give you back a grasp expressed in the "base_link" frame, and its pose will be T1 * G1.

There are a few ways in which you can get the desired behavior. Since there seems to be some node in your system publishing an "object_frame" to TF, you could simply ask for grasps for a GraspableObject with a DatabaseModel with an identity pose relative to the "object_frame".

edit flag offensive delete link more

Comments

Thanks for your answer, Matei. I've finally found what was happening.

toniOliver gravatar image toniOliver  ( 2012-03-05 23:59:51 -0500 )edit
0

answered 2012-03-06 00:34:56 -0500

toniOliver gravatar image

As far as I can tell, my problem had two causes:

  • Reference frame

The grasps in the database are not relative to the frame named /object_frame. They are relative to the potential model frame, which is different, but located more or less in the same position.

The /object_frame is generated and published by the find_object_frame_and_bounding_box() function (in cluster_bounding_box_finder.py), which basically takes the z axis of the frame we want to use (/world in our case), and finds some convenient x and y axis so that the bounding box contains the point cluster.

Therefore we can't expect these axes to be oriented like those in the potential model frame.

  • DB format of the grasps

The grasps I had created manually were expressed in a wrong format. The orientation was expressed as a quaternion qX,qY,qZ,qW. So the grasp pose was {X,Y,Z,qX,qY,qZ,qW}.

But in the household objects database they must be {X,Y,Z,qW,qX,qY,qZ}.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2012-03-01 02:07:09 -0500

Seen: 412 times

Last updated: Mar 06 '12