Public Member Functions | Private Attributes
RotatingHand Class Reference

Calculate collision-free grasp hypotheses that fit a point neighborhood. More...

#include <rotating_hand.h>

List of all members.

Public Member Functions

std::vector< GraspHypothesisevaluateHand (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

Detailed Description

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.


Constructor & Destructor Documentation

Default constructor.

Definition at line 62 of file rotating_hand.h.

RotatingHand::RotatingHand ( bool  tolerant_antipodal,
int  cam_source 
) [inline]

Constructor.

Parameters:
tolerant_antipodalwhether the antipodal quality estimation uses "tolerant" thresholds
thecamera 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.

Parameters:
camera_origin_leftthe position of the left camera
camera_origin_rightthe position of the right camera
finger_handthe FingerHand object to be used
tolerant_antipodalwhether the antipodal quality estimation uses "tolerant" thresholds
thecamera source of the sample for which the point neighborhood was found

Definition at line 4 of file rotating_hand.cpp.


Member Function Documentation

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.

Parameters:
init_bitethe minimum object height
samplethe sample for which the point neighborhood was found
use_antipodalwhether 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.

Returns:
the 3x2 matrix containing the positions of the cameras

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.

Returns:
the camera source of the sample

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.

Returns:
the 1xn matrix containing 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.

Parameters:
pointsthe set of points to be transformed
normalthe normal, used as one axis in the hand frame
axisthe axis, used as another axis in the hand frame
normalsthe set of normals for the set of points
points_cam_sourcethe set of camera sources for the set of points
hand_heightthe hand height, the hand extends plus/minus this value along the hand axis

Definition at line 19 of file rotating_hand.cpp.


Member Data Documentation

Eigen::VectorXd RotatingHand::angles_ [private]

the hand orientations that are evaluated

Definition at line 137 of file rotating_hand.h.

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.

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.

whether the antipodal testing uses "tolerant" thresholds

parameters

Definition at line 146 of file rotating_hand.h.


The documentation for this class was generated from the following files:


agile_grasp
Author(s):
autogenerated on Thu Aug 27 2015 12:01:28