libmove3d
3.13.0
|
#include <gpGrasp.h>
Public Member Functions | |
gpGrasp () | |
Default constructor of the class gpGrasp. | |
gpGrasp (const gpGrasp &grasp) | |
gpGrasp (const gpHand_properties &handProp) | |
gpGrasp & | operator= (const gpGrasp &grasp) |
Copy operator of the class gpGrasp. | |
bool | operator== (const gpGrasp &grasp) |
int | print () |
Prints the content of a gpGrasp variable in the standard output. | |
int | printInFile (const char *filename) |
int | draw (double cone_length, int cone_nb_slices=10) |
int | computeStability () |
int | computeQuality () |
double | configCost () |
int | removeContactsTooCloseToEdge (double angleThreshold, double distancethreshold) |
int | contactCentroid (p3d_vector3 centroid) |
int | direction (p3d_vector3 direction) const |
double | similarity (const gpGrasp &grasp) |
int | computeOpenConfig (p3d_rob *robot, p3d_rob *object, bool environment) |
Public Attributes | |
bool | autoGen |
int | ID |
double | stability |
double | curvatureScore |
different scores that are used to compute the grasp quality: | |
double | centroidScore |
double | IKscore |
double | visibility |
double | quality |
p3d_matrix4 | frame |
std::vector< gpContact > | contacts |
int | handID |
p3d_rob * | object |
std::string | object_name |
double | finger_opening |
enum gpHand_type | hand_type |
std::vector< double > | config |
std::vector< double > | openConfig |
bool | tested |
gpPlacement | recomPlacement |
Friends | |
double | gpGraspDistance (const gpGrasp &grasp1, const gpGrasp &grasp2) |
This is the class used to describe all the characteristics of a grasp.
Computes the "open" configuration of a grasp. From the grasp configuration q, the hand is opened (in direction of the "qopen" configuration defined in gpHand_properties). If there is a contact the opening is stopped and the DOF is set to 0.5*(qstart+qopen).
robot | pointer to the robot hand (a freeflyer) |
object | pointer to the object (a freeflyer robot) |
environment | take into account the environment in the collision test or not |
int gpGrasp::computeQuality | ( | ) |
Computes the quality of the grasp. For now, the quality is a weighted sum of a "force closure quality criterion" and a score telling how close are the contact normals to the main grasping direction of the hand or gripper (i.e. the (or main) direction along which the hand can exert a force). This last point is still much too coarse. If the grasp does not verify force-closure, its global quality will be kept null.
check if the object volume properties were already computed:
int gpGrasp::computeStability | ( | ) |
Computes the stability score of the grasp. If the grasp is unstable, the score is < 0.
double gpGrasp::configCost | ( | ) |
Computes a cost for the given grasping configuration. The biggest it is, the better it is.
int gpGrasp::contactCentroid | ( | p3d_vector3 | centroid | ) |
Computes the centroid of the polyhedron defined by the contact points of the grasp.
centroid | the computed centroid of the contact polyhedron |
int gpGrasp::direction | ( | p3d_vector3 | direction | ) | const |
Gives the direction of the wrist associated to the gpGrasp.
direction | a p3d_vector3 that will be filled with the wrist direction |
int gpGrasp::draw | ( | double | length, |
int | nb_slices = 10 |
||
) |
Draws all the contacts of a grasp.
length | lenght of each friction cone to draw |
nb_slices | number of segments of each cone discretization |
int gpGrasp::printInFile | ( | const char * | filename | ) |
Prints the content of a gpGrasp variable in a file.
filename | name of the file |
int gpGrasp::removeContactsTooCloseToEdge | ( | double | angleThreshold, |
double | distancethreshold | ||
) |
Removes the contact that are too close to an sharp edge. For each contact of the grasp, the function considers the edges of the face the contact is on. If one of the edge is not too "flat", the distance from the contact to the edge is computed and if the distance is above a threshold, the contact is regarded as too close to the edge.
angleThreshold | the edge angle (in radians) above which an edge is regarded as not flat |
distancethreshold | the distance threshold |
double gpGrasp::similarity | ( | const gpGrasp & | grasp | ) |
WIP Computes a value trying to give a measure of the similarity between two grasps.
Computes the distance between two grasps. This is based on the distance between their two frames. For now, it is the euclidean distance between the two frame centers.
grasp1 | the first grasp |
grasp2 | the second grasp |
bool gpGrasp::autoGen |
tells if the grasp was generated automatically or by a user
double gpGrasp::centroidScore |
inverse of the distance from the contact centroid to object's center of mass
std::vector<double> gpGrasp::config |
configuration vector of the hand for the associated grasp
std::vector<gpContact> gpGrasp::contacts |
vector of contacts of the grasp
double gpGrasp::curvatureScore |
different scores that are used to compute the grasp quality:
score based on object's surface curvature at contact points
double gpGrasp::finger_opening |
gripper opening (distance between the jaws) corresponding to the grasp (for GP_GRIPPER hand)
p3d_matrix4 gpGrasp::frame |
grasp frame
type of the hand realizing the grasp
int gpGrasp::handID |
in case there are several hand, this stores the hand used by the grasp. If there is one hand= 0, two hands= 0 and 1
int gpGrasp::ID |
ID number
double gpGrasp::IKscore |
IK score of the grasp (optional)
the grasped object
std::string gpGrasp::object_name |
name of the grasped object
std::vector<double> gpGrasp::openConfig |
configuration vector of the hand slightly open from its grasp configuration (is used for the hand approach phase)
double gpGrasp::quality |
overall quality score of the grasp
the best way to place the object on a plane support for the current grasp: recommended placement
double gpGrasp::stability |
stability score of the grasp (unstable if < 0)
bool gpGrasp::tested |
used to mark the grasps that have been tested in some path planning function
double gpGrasp::visibility |
visibility score of the grasp (optional)