-
Notifications
You must be signed in to change notification settings - Fork 30
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Grasp generation tools #44
Conversation
class GraspDirection(Enum): | ||
""" Enumerates grasp direction types. """ | ||
UNKNOWN = 0 | ||
X_POS = 1 | ||
X_NEG = 2 | ||
Y_POS = 3 | ||
Y_NEG = 4 | ||
Z_POS = 5 | ||
Z_NEG = 6 | ||
|
||
vec_from_direction = { | ||
GraspDirection.UNKNOWN: None, | ||
GraspDirection.X_POS: np.array([1.0, 0.0, 0.0]), | ||
GraspDirection.X_NEG: np.array([-1.0, 0.0, 0.0]), | ||
GraspDirection.Y_POS: np.array([0.0, 1.0, 0.0]), | ||
GraspDirection.Y_NEG: np.array([0.0, -1.0, 0.0]), | ||
GraspDirection.Z_POS: np.array([0.0, 0.0, 1.0]), | ||
GraspDirection.Z_NEG: np.array([0.0, 0.0, -1.0]), | ||
} |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Not sure how this will then morph into supporting grasps at other angles. Maybe the direction should just be a unit vector, but the enum can help look up some common directions?
Actually, the "pose" portion of the grasp should already capture this as the +Z axis should point towards the gripper from the grasp point.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Fitting a cylinder to the object would make this easier but I could imagine some objects (like a banana) where a cylinder doesn't work well...
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
In an ideal world, we'd provide the option of doing cuboid, cylinder, sphere, etc.
While implementation was tough with the cuboid, I mostly picked it because it makes the number of samples for TAMP pretty small, assuming we're just targeting the center of each face as we do in this PR.
I know the MoveIt grasps package, for example, adds more complexity to this by
- Allowing corner grasps
- Sampling offsets from the center
This PR creates a grasp generation pipeline that takes in the gripper / object dimensions, plus the robot pose relative to the object, and generates a set of feasible grasps.
For now, we'll assume all grasps will point towards the center and axis-aligned with a cuboid object.
The goal for this PR is:
In a follow-on PR, this pipeline will be linked to an example showing a next level of TAMP fidelity, where the planner can only pick up objects given feasible grasp locations sampled from this pipeline.
Here is a visualization of the grasp generation. You can run this with:
Begins addressing #45.