Calculate collision-free fingers. More...
#include <finger_hand.h>
Public Member Functions | |
void | deepenHand (double init_deepness, double max_deepness) |
Select center hand and try to extend it into the object as deeply as possible. | |
void | evaluateFingers (double bite) |
Find collision-free finger placements. | |
void | evaluateGraspParameters (double bite) |
Set the grasp parameters. | |
void | evaluateHand () |
Find robot hand configurations that fit the cloud. | |
FingerHand () | |
Default constructor. | |
FingerHand (double finger_width, double hand_outer_diameter, double hand_depth) | |
Constructor. | |
double | getBackOfHand () const |
Return where the back of the hand is. | |
const Eigen::Array< bool, 1, Eigen::Dynamic > & | getFingers () const |
Return the finger placement evaluations. | |
const Eigen::Vector2d & | getGraspBottom () const |
Return the grasp position between the end of the finger tips. | |
const Eigen::Vector2d & | getGraspSurface () const |
Return the grasp position between the end of the finger tips projected onto the back of the hand. | |
double | getGraspWidth () const |
Return the width of the object contained in the grasp. | |
const Eigen::Array< bool, 1, Eigen::Dynamic > & | getHand () const |
Return the hand configuration evaluations. | |
double | getHandDepth () const |
Return the depth of the hand. | |
void | setPoints (const Eigen::MatrixXd &points) |
Set the points. | |
Private Attributes | |
double | back_of_hand_ |
where the back of the hand is (distance from back to position between finger tip ends) | |
Eigen::VectorXd | finger_spacing_ |
the possible finger placements | |
double | finger_width_ |
the width of the robot hand fingers | |
Eigen::Array< bool, 1, Eigen::Dynamic > | fingers_ |
indicates which finger placements are collision-free | |
Eigen::Vector2d | grasp_bottom |
the grasp position between the end of the finger tips | |
Eigen::Vector2d | grasp_surface |
the position between the end of the finger tips projected to the back of the hand | |
double | grasp_width_ |
the width of the object contained in the grasp | |
Eigen::Array< bool, 1, Eigen::Dynamic > | hand_ |
indicates which hand configurations fit the point cloud | |
double | hand_depth_ |
the hand depth (finger length) | |
double | hand_outer_diameter_ |
the maximum aperture of the robot hand | |
Eigen::MatrixXd | points_ |
the points in the point neighborhood (see FingerHand::setPoints) |
Calculate collision-free fingers.
FingerHand class
This class calculates a set of collision-free finger placements. The parameters are the dimensions of the robot hand and the desired "bite" that the grasp must have. The bite is how far the hand can be moved into the object.
Definition at line 48 of file finger_hand.h.
FingerHand::FingerHand | ( | ) | [inline] |
Default constructor.
Definition at line 55 of file finger_hand.h.
FingerHand::FingerHand | ( | double | finger_width, |
double | hand_outer_diameter, | ||
double | hand_depth | ||
) |
Constructor.
finger_width | the width of the fingers |
hand_outer_diameter | the maximum aperture of the robot hand |
hand_depth | the length of the fingers |
Definition at line 3 of file finger_hand.cpp.
void FingerHand::deepenHand | ( | double | init_deepness, |
double | max_deepness | ||
) |
Select center hand and try to extend it into the object as deeply as possible.
init_deepness | the initial deepness (usually the minimum object height) |
max_deepness | the maximum allowed deepness (usually the finger length) |
Definition at line 173 of file finger_hand.cpp.
void FingerHand::evaluateFingers | ( | double | bite | ) |
Find collision-free finger placements.
bite | the minimum object height |
Definition at line 20 of file finger_hand.cpp.
void FingerHand::evaluateGraspParameters | ( | double | bite | ) |
Set the grasp parameters.
The parameter bite
is used to calculate the grasp width by only evaluating the width of the points below bite
.
bite | the minimum object height |
Definition at line 117 of file finger_hand.cpp.
void FingerHand::evaluateHand | ( | ) |
Find robot hand configurations that fit the cloud.
Definition at line 100 of file finger_hand.cpp.
double FingerHand::getBackOfHand | ( | ) | const [inline] |
Return where the back of the hand is.
Definition at line 166 of file finger_hand.h.
const Eigen::Array<bool, 1, Eigen::Dynamic>& FingerHand::getFingers | ( | ) | const [inline] |
Return the finger placement evaluations.
Definition at line 130 of file finger_hand.h.
const Eigen::Vector2d& FingerHand::getGraspBottom | ( | ) | const [inline] |
Return the grasp position between the end of the finger tips.
Definition at line 139 of file finger_hand.h.
const Eigen::Vector2d& FingerHand::getGraspSurface | ( | ) | const [inline] |
Return the grasp position between the end of the finger tips projected onto the back of the hand.
Definition at line 148 of file finger_hand.h.
double FingerHand::getGraspWidth | ( | ) | const [inline] |
Return the width of the object contained in the grasp.
Definition at line 157 of file finger_hand.h.
const Eigen::Array<bool, 1, Eigen::Dynamic>& FingerHand::getHand | ( | ) | const [inline] |
Return the hand configuration evaluations.
Definition at line 121 of file finger_hand.h.
double FingerHand::getHandDepth | ( | ) | const [inline] |
void FingerHand::setPoints | ( | const Eigen::MatrixXd & | points | ) | [inline] |
Set the points.
The points contained in the matrix points
are assumed to be already rotated into the robot hand frame and offset to a point within the local neighborhood.
points | the points to be set |
Definition at line 103 of file finger_hand.h.
double FingerHand::back_of_hand_ [private] |
where the back of the hand is (distance from back to position between finger tip ends)
Definition at line 177 of file finger_hand.h.
Eigen::VectorXd FingerHand::finger_spacing_ [private] |
the possible finger placements
Definition at line 181 of file finger_hand.h.
double FingerHand::finger_width_ [private] |
the width of the robot hand fingers
Definition at line 173 of file finger_hand.h.
Eigen::Array<bool, 1, Eigen::Dynamic> FingerHand::fingers_ [private] |
indicates which finger placements are collision-free
Definition at line 182 of file finger_hand.h.
Eigen::Vector2d FingerHand::grasp_bottom [private] |
the grasp position between the end of the finger tips
Definition at line 185 of file finger_hand.h.
Eigen::Vector2d FingerHand::grasp_surface [private] |
the position between the end of the finger tips projected to the back of the hand
Definition at line 186 of file finger_hand.h.
double FingerHand::grasp_width_ [private] |
the width of the object contained in the grasp
Definition at line 179 of file finger_hand.h.
Eigen::Array<bool, 1, Eigen::Dynamic> FingerHand::hand_ [private] |
indicates which hand configurations fit the point cloud
Definition at line 183 of file finger_hand.h.
double FingerHand::hand_depth_ [private] |
the hand depth (finger length)
Definition at line 175 of file finger_hand.h.
double FingerHand::hand_outer_diameter_ [private] |
the maximum aperture of the robot hand
Definition at line 174 of file finger_hand.h.
Eigen::MatrixXd FingerHand::points_ [private] |
the points in the point neighborhood (see FingerHand::setPoints)
Definition at line 184 of file finger_hand.h.