Classes |
class | gpTriangle |
class | gpPlacement |
Functions |
int | gpCompute_stable_placements (p3d_rob *object, std::list< gpPlacement > &placementList) |
int | gpFind_placements_on_object (p3d_rob *object, p3d_rob *support, std::list< p3d_rob * > robotList, std::list< gpPlacement > placementListIn, double translationStep, unsigned int nbOrientations, double verticalOffset, std::list< gpPlacement > &placementListOut) |
int | gpCompute_placement_clearances (p3d_rob *object, std::list< p3d_rob * > robotList, std::list< gpPlacement > &placementList) |
int | gpFind_placement_from_base_configuration (p3d_rob *robot, p3d_rob *object, std::list< gpPlacement > &placementList, gpArm_type arm_type, configPt qbase, gpGrasp &grasp, gpHand_properties &hand, double distance, configPt qpreplacement, configPt qplacement, gpPlacement &placement) |
Detailed Description
This module implements some classes to compute a set of stable placements for a body.
Function Documentation
int gpCompute_placement_clearances |
( |
p3d_rob * |
object, |
|
|
std::list< p3d_rob * > |
robotList, |
|
|
std::list< gpPlacement > & |
placementList |
|
) |
| |
- Parameters:
-
object | the object to place |
robotList | a list of robots that will not be taken into account in the clearance computation |
placementList | a list of placements |
- Returns:
- GP_OK in case of success, GP_ERROR otherwise
int gpCompute_stable_placements |
( |
p3d_rob * |
object, |
|
|
std::list< gpPlacement > & |
placementList |
|
) |
| |
Computes a list of stable placements (on a plane) of the given object. The function first computes the convex hull of the object. Each face of the object's convex hull defines a support polygon. If the orthogonal projection of the object's center of mass on the plane of a face is inside the face, then this face corresponds to a stable placement.
- Parameters:
-
object | pointer to the object (a freeflyer robot whose only the first polyhedron of the first body will be considered) |
placementList | the computed placement list (sorted from best to weaker stability) |
- Returns:
- GP_OK in case of success, GP_ERROR otherwise
int gpFind_placement_from_base_configuration |
( |
p3d_rob * |
robot, |
|
|
p3d_rob * |
object, |
|
|
std::list< gpPlacement > & |
placementList, |
|
|
gpArm_type |
arm_type, |
|
|
configPt |
qbase, |
|
|
gpGrasp & |
grasp, |
|
|
gpHand_properties & |
hand, |
|
|
double |
distance, |
|
|
configPt |
qpreplacement, |
|
|
configPt |
qplacement, |
|
|
gpPlacement & |
placement |
|
) |
| |
Finds, for a given mobile base configuration of the robot, a placement from the given placement list, that is reachable by the arm and hand, and computes for the placement a configuration for the whole robot. It also computes an intermediate configuration (a configuration slightly before placing the object)
- Parameters:
-
robot | the robot |
object | the object to place |
robotList | a list of robots that will not be taken into account in the collision tests |
placementList | a list of placements |
arm_type | the robot arm type |
qbase | a configuration of the robot (only the part corresponding to the mobile base will be used) |
grasp | the grasp used to hold the object |
hand | parameters of the hand |
distance | distance between the grasp and pregrasp configurations (meters) |
qpreplacement | the preplacement configuration (must have been allocated before) |
qplacement | the placement configuration (must have been allocated before) |
placement | the found object placement |
- Returns:
- GP_OK in case of success, GP_ERROR otherwise
int gpFind_placements_on_object |
( |
p3d_rob * |
object, |
|
|
p3d_rob * |
support, |
|
|
std::list< p3d_rob * > |
robotList, |
|
|
std::list< gpPlacement > |
placementListIn, |
|
|
double |
translationStep, |
|
|
unsigned int |
nbOrientations, |
|
|
double |
verticalOffset, |
|
|
std::list< gpPlacement > & |
placementListOut |
|
) |
| |
Computes a list of stable placements of an object onto another object. The function receives an initial list of stable placements of the object on infinite planes. The almost horizontal faces of the support are sampled according to specified steps and each placement of the input list is then tested for each sample. The following collisions are checked: the object versus the environment, the object versus the other robots (including the support). It is possible to skip the collision tests between the object and some robots specified in a list given as an input.
- Parameters:
-
object | pointer to the object |
support | pointer to the object (the support) we want to place the first object on |
robotList | a list of robots that will not be taken into account in the collision tests |
placementListIn | the input placement list (NB: its size is reduced inside the function) |
translationStep | the translation step of the discretization of the horizontal faces of the support |
nbOrientations | the number of orientations (around vertical axis) that will be tested to place the object |
verticalOffset | vertical offset on the object placements (to avoid collision between object and support) |
placementListOut | the output placement list |
- Returns:
- GP_OK in case of success, GP_ERROR otherwise