Calculate collision-free grasp hypotheses that fit a point neighborhood. More...
#include <rotating_hand.h>
Public Member Functions | |
| std::vector< GraspHypothesis > | evaluateHand (double init_bite, const Eigen::Vector3d &sample, bool use_antipodal) |
| Evaluate which hand orientations and which finger placements lead to a valid grasp. | |
| const Eigen::Matrix< double, 3, 2 > & | getCams () const |
| Return the camera positions. | |
| int | getCamSource () const |
| Return the camera source of the sample for which the point neighborhood was calculated. | |
| const Eigen::VectorXi & | getPointsCamSource () const |
| Return the camera source for each point in the point neighborhood. | |
| RotatingHand () | |
| Default constructor. | |
| RotatingHand (bool tolerant_antipodal, int cam_source) | |
| Constructor. | |
| RotatingHand (const Eigen::VectorXd &camera_origin_left, const Eigen::VectorXd &camera_origin_right, const FingerHand &finger_hand, bool tolerant_antipodal, int cam_source) | |
| Constructor. | |
| void | transformPoints (const Eigen::Matrix3Xd &points, const Eigen::Vector3d &normal, const Eigen::Vector3d &axis, const Eigen::Matrix3Xd &normals, const Eigen::VectorXi &points_cam_source, double hand_height) |
| Transforms a set of points into the hand frame, defined by normal and axis. | |
Private Attributes | |
| Eigen::VectorXd | angles_ |
| the hand orientations that are evaluated | |
| int | cam_source_ |
| the camera source of the sample | |
| Eigen::Matrix< double, 3, 2 > | cams_ |
| the camera positions | |
| FingerHand | finger_hand_ |
| the finger hand object | |
| Eigen::Matrix3d | frame_ |
| the robot hand frame for the point neighborhood | |
| Eigen::Vector3d | hand_axis_ |
| the robot hand axis for the point neighborhood | |
| Eigen::Matrix3Xd | normals_ |
| the normals for each point in the point neighborhood | |
| Eigen::Matrix3Xd | points_ |
| the points in the point neighborhood | |
| Eigen::VectorXi | points_cam_source_ |
| the camera source for each point in the point neighborhood | |
| bool | tolerant_antipodal_ |
| whether the antipodal testing uses "tolerant" thresholds | |
Calculate collision-free grasp hypotheses that fit a point neighborhood.
RotatingHand class
This class calculates a set of collision-free grasp hypotheses that fit a point neighborhood. The point neighborhood is first transformed into the robot hand frame, then rotated into one of the evaluated hand orientations, and finally tested for finger placements. A grasp hypothesis can also be tested for being antipodal with this class.
Definition at line 55 of file rotating_hand.h.
| RotatingHand::RotatingHand | ( | ) | [inline] |
Default constructor.
Definition at line 62 of file rotating_hand.h.
| RotatingHand::RotatingHand | ( | bool | tolerant_antipodal, |
| int | cam_source | ||
| ) | [inline] |
Constructor.
| tolerant_antipodal | whether the antipodal quality estimation uses "tolerant" thresholds |
| the | camera source of the sample for which the point neighborhood was found |
Definition at line 69 of file rotating_hand.h.
| RotatingHand::RotatingHand | ( | const Eigen::VectorXd & | camera_origin_left, |
| const Eigen::VectorXd & | camera_origin_right, | ||
| const FingerHand & | finger_hand, | ||
| bool | tolerant_antipodal, | ||
| int | cam_source | ||
| ) |
Constructor.
| camera_origin_left | the position of the left camera |
| camera_origin_right | the position of the right camera |
| finger_hand | the FingerHand object to be used |
| tolerant_antipodal | whether the antipodal quality estimation uses "tolerant" thresholds |
| the | camera source of the sample for which the point neighborhood was found |
Definition at line 4 of file rotating_hand.cpp.
| std::vector< GraspHypothesis > RotatingHand::evaluateHand | ( | double | init_bite, |
| const Eigen::Vector3d & | sample, | ||
| bool | use_antipodal | ||
| ) |
Evaluate which hand orientations and which finger placements lead to a valid grasp.
| init_bite | the minimum object height |
| sample | the sample for which the point neighborhood was found |
| use_antipodal | whether the hand orientations are checked for antipodal grasps |
Definition at line 78 of file rotating_hand.cpp.
| const Eigen::Matrix<double, 3, 2>& RotatingHand::getCams | ( | ) | const [inline] |
Return the camera positions.
Definition at line 109 of file rotating_hand.h.
| int RotatingHand::getCamSource | ( | ) | const [inline] |
Return the camera source of the sample for which the point neighborhood was calculated.
Definition at line 127 of file rotating_hand.h.
| const Eigen::VectorXi& RotatingHand::getPointsCamSource | ( | ) | const [inline] |
Return the camera source for each point in the point neighborhood.
Definition at line 118 of file rotating_hand.h.
| void RotatingHand::transformPoints | ( | const Eigen::Matrix3Xd & | points, |
| const Eigen::Vector3d & | normal, | ||
| const Eigen::Vector3d & | axis, | ||
| const Eigen::Matrix3Xd & | normals, | ||
| const Eigen::VectorXi & | points_cam_source, | ||
| double | hand_height | ||
| ) |
Transforms a set of points into the hand frame, defined by normal and axis.
| points | the set of points to be transformed |
| normal | the normal, used as one axis in the hand frame |
| axis | the axis, used as another axis in the hand frame |
| normals | the set of normals for the set of points |
| points_cam_source | the set of camera sources for the set of points |
| hand_height | the hand height, the hand extends plus/minus this value along the hand axis |
Definition at line 19 of file rotating_hand.cpp.
Eigen::VectorXd RotatingHand::angles_ [private] |
the hand orientations that are evaluated
Definition at line 137 of file rotating_hand.h.
int RotatingHand::cam_source_ [private] |
the camera source of the sample
Definition at line 135 of file rotating_hand.h.
Eigen::Matrix<double, 3, 2> RotatingHand::cams_ [private] |
the camera positions
Definition at line 136 of file rotating_hand.h.
FingerHand RotatingHand::finger_hand_ [private] |
the finger hand object
Definition at line 143 of file rotating_hand.h.
Eigen::Matrix3d RotatingHand::frame_ [private] |
the robot hand frame for the point neighborhood
Definition at line 140 of file rotating_hand.h.
Eigen::Vector3d RotatingHand::hand_axis_ [private] |
the robot hand axis for the point neighborhood
Definition at line 139 of file rotating_hand.h.
Eigen::Matrix3Xd RotatingHand::normals_ [private] |
the normals for each point in the point neighborhood
Definition at line 141 of file rotating_hand.h.
Eigen::Matrix3Xd RotatingHand::points_ [private] |
the points in the point neighborhood
Definition at line 138 of file rotating_hand.h.
Eigen::VectorXi RotatingHand::points_cam_source_ [private] |
the camera source for each point in the point neighborhood
Definition at line 142 of file rotating_hand.h.
bool RotatingHand::tolerant_antipodal_ [private] |
whether the antipodal testing uses "tolerant" thresholds
parameters
Definition at line 146 of file rotating_hand.h.