libmove3d  3.13.0
Classes | Modules | Typedefs | Enumerations | Functions
GraspPlanning

Classes

class  gpContact
class  gpGrasp
class  gpDoubleGrasp
class  gpHand_properties
class  gpVector3D
class  gpSphere
class  gpHTMatrix
class  gpIndex

Modules

 GraspIO
 ConvexHull
 KdTree
 StablePlacementComputation
 Workspace

Typedefs

typedef enum gpTriangle_description gpTriangle_description
typedef enum gpHand_type gpHand_type
typedef enum gpArm_type gpArm_type
typedef enum
gpGrasp_collision_state 
gpGrasp_collision_state

Enumerations

enum  gpTriangle_description { GP_DESCRIPTION_INDICES, GP_DESCRIPTION_POINTS, GP_DESCRIPTION_BOTH }
enum  gpHand_type {
  GP_GRIPPER, GP_SAHAND_RIGHT, GP_SAHAND_LEFT, GP_PR2_GRIPPER,
  GP_HAND_NONE
}
enum  gpArm_type { GP_PA10, GP_LWR, GP_ARM_NONE }
enum  gpGrasp_collision_state { NOT_TESTED, COLLIDING, COLLISION_FREE }

Functions

void logfile (const char *format,...)
int p3d_get_obj_pos (p3d_obj *o, p3d_matrix4 pose)
int p3d_print_face_neighbours (p3d_polyhedre *polyhedron, char *filename)
int p3d_save_in_OBJ_format (p3d_polyhedre *polyhedron, char *name)
p3d_polyhedre * p3d_copy_polyhedre (p3d_polyhedre *polyhedron)
int p3d_display_face (p3d_polyhedre *polyhedron, unsigned int index)
void Gb_th_matrix4 (Gb_th *th, p3d_matrix4 mat)
void Gb_matrix4_th (p3d_matrix4 mat, Gb_th *th)
int solve_trigonometric_equation (double a, double b, double c, double *x1, double *x2)
void draw_frame0 (p3d_matrix4 frame, double length)
int export_scene_to_POVRAY (char *foldername, char *filename)
void get_sample2D (int n, p3d_vector2 origin, double factor, p3d_vector2 result)
void get_sample3D (int n, p3d_vector3 origin, double factor, p3d_vector3 result)
void p3d_matrix4_to_OpenGL_format (p3d_matrix4 source, GLfloat mat[16])
int gpExport_bodies_for_coldman (p3d_rob *robot, const std::string &folderName)
int gpExport_obstacles_for_coldman ()
int gpExport_robot_for_coldman (p3d_rob *robot)
int gpPolyhedron_AABB (p3d_polyhedre *polyhedron, double &xmin, double &xmax, double &ymin, double &ymax, double &zmin, double &zmax)
int gpObj_AABB (p3d_obj *obj, double &xmin, double &xmax, double &ymin, double &ymax, double &zmin, double &zmax)
int gpPrint_robot_AABBs (p3d_rob *robot)
double gpForce_closure_2D_grasp (double(*position)[2], double(*normal)[2], double mu[], unsigned int nbContacts)
double gpForce_closure_3D_grasp (double(*position)[3], double(*normal)[3], double mu[], unsigned int nbContacts, unsigned int nbSlices)
double gpForce_closure_2D_grasp2 (double(*position)[2], double(*normal)[2], double mu[], unsigned int nbContacts)
int gpForce_closure_3D_grasp2 (double(*position)[3], double(*normal)[3], double mu[], unsigned int nbContacts, unsigned int nbSlices)
int gpLine_triangle_intersection (p3d_vector3 c1, p3d_vector3 c2, p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 p3, p3d_vector3 intersection)
int gpRay_triangle_intersection (p3d_vector3 origin, p3d_vector3 direction, p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 p3, p3d_vector3 intersection)
int gpLine_segment_plane_intersection (p3d_plane plane, p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 result)
double gpPoint_to_line_segment_distance (p3d_vector3 p, p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 closestPoint)
int gpTriangle_plane_intersection (p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 p3, p3d_plane plane, p3d_vector3 result1, p3d_vector3 result2)
int gpCheck_triangle_plane_intersection (p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 p3, p3d_plane plane)
int gpPlane_plane_intersection (p3d_plane *plane1, p3d_plane *plane2, p3d_vector3 point_on_line, p3d_vector3 line_direction)
p3d_plane gpTransform_plane_equation (p3d_matrix4 T, p3d_plane plane)
int gpLine_segment_sphere_intersection (p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 center, double radius, p3d_vector3 result1, p3d_vector3 result2)
void gpPoint_in_triangle_from_parameters (double alpha, double beta, p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 p3, p3d_vector3 result)
int gpParameters_in_triangle_from_point (p3d_vector3 p, p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 p3, double *alpha, double *beta)
void gpOrthogonal_projection_point_onto_plane (p3d_vector3 point, p3d_plane plane, p3d_vector3 result)
void gpOrthogonal_vector (p3d_vector3 v, p3d_vector3 result)
void gpOrthonormal_basis (p3d_vector3 u, p3d_vector3 v, p3d_vector3 w)
double gpPoint_to_triangle_distance (p3d_vector3 point, p3d_vector3 p0, p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 closestPoint)
void gpDraw_plane (p3d_plane plane)
void gpDraw_plane2 (p3d_plane plane, double d)
void gpDraw_plane (p3d_vector3 normal, double offset, double d)
int gpLine_line_intersection2D (double point1[2], double direction1[2], double point2[2], double direction2[2], double result[2])
int gpSegment_segment_intersection2D (double a1[2], double b1[2], double a2[2], double b2[2], double result1[2], double result2[2])
int gpIs_point_on_segment2D (double p[2], double a[2], double b[2])
double gpTriangle_area (p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 p3)
double gpPolygon_area (double(*vertices)[2], int nb_vertices)
int gpSave_polygon (char *name, double(*vertices)[2], int nb_vertices)
int gpIs_polygon_simple (double(*vertices)[2], int nb_vertices)
int gpIs_polygon_ccw (double(*vertices)[2], int nb_vertices)
int gpIs_point_in_polygon (double point[2], double(*vertices)[2], int nb_vertices)
int gpPolygon_polygon_inclusion (double(*vertices1)[2], int nb_vertices1, double(*vertices2)[2], int nb_vertices2)
double gpTetrahedron_volume (p3d_vector3 d, p3d_vector3 a, p3d_vector3 b, p3d_vector3 c)
void gpSpherical_edge_projection (p3d_vector3 x1, p3d_vector3 x2, double a, p3d_vector3 result)
int gpSample_sphere_surface (double radius, unsigned int nb_samples, std::vector< gpVector3D > &samples)
p3d_vector3 * gpSample_triangle_surface (p3d_vector3 p1, p3d_vector3 p2, p3d_vector3 p3, double step, unsigned int *nb_samples)
int gpIs_point_in_triangle (p3d_vector3 point, p3d_vector3 a, p3d_vector3 b, p3d_vector3 c)
int gpPoint_to_polyhedron_distance (p3d_vector3 point, p3d_polyhedre *polyhedron, double &distance, p3d_vector3 closestPoint)
int gpPoint_to_polyhedron_distance2 (p3d_vector3 point, p3d_polyhedre *polyhedron, double &distance, p3d_vector3 closestPoint)
int gpSample_polyhedron_AABB (p3d_polyhedre *polyhedron, double step, std::vector< gpVector3D > &samples)
int gpGrasps_from_grasp_frame_SAHand (p3d_rob *robot, p3d_rob *object, p3d_matrix4 gFrame, gpHand_properties &hand, gpKdTree &kdtree, std::list< class gpGrasp > &graspList)
int gpGrasps_from_grasp_frame_gripper (p3d_polyhedre *polyhedron, p3d_matrix4 gFrame, gpHand_properties &hand, std::list< class gpGrasp > &graspList)
int gpSample_grasp_frames (p3d_polyhedre *polyhedron, unsigned int nbPositions, unsigned int nbDirections, unsigned int nbRotations, unsigned int nbFramesMax, std::vector< gpHTMatrix > &frames)
int gpGrasp_generation (p3d_rob *robot, p3d_rob *object, gpHand_properties &handProp, unsigned int nbPositions, unsigned int nbDirections, unsigned int nbRotations, std::list< class gpGrasp > &graspList)
int gpGrasp_collision_filter (std::list< gpGrasp > &graspList, p3d_rob *robot, p3d_rob *object, gpHand_properties &hand)
int gpGrasp_context_collision_filter (std::list< gpGrasp > &graspList, p3d_rob *robot, p3d_rob *object, gpHand_properties &hand)
int gpGrasp_stability_filter (std::list< gpGrasp > &graspList)
int gpCompute_grasps_best_placement (std::list< gpGrasp > &graspList, p3d_rob *robot, p3d_rob *object, gpHand_properties &hand)
int gpInverse_geometric_model_freeflying_hand (p3d_rob *robot, p3d_matrix4 objectFrame, p3d_matrix4 graspFrame, gpHand_properties &hand, configPt q)
int gpForward_geometric_model_PA10 (p3d_rob *robot, p3d_matrix4 Tend_eff, bool display)
int gpInverse_geometric_model_PA10 (p3d_rob *robot, p3d_matrix4 Tend_eff, configPt cfg)
int gpInverse_geometric_model_and_collision_PA10 (p3d_rob *robot, p3d_matrix4 Tend_eff, configPt cfg)
int gpInverse_geometric_model_LWR (p3d_rob *robot, p3d_matrix4 Tend_eff, configPt cfg)
int gpInverse_geometric_model_and_collision_LWR (p3d_rob *robot, p3d_matrix4 Tend_eff, configPt cfg)
int gpInverse_geometric_model_arm (p3d_rob *robot, gpArm_type arm_type, p3d_matrix4 Tend_eff, configPt cfg)
int gpInverse_geometric_model_and_collision_arm (p3d_rob *robot, gpArm_type arm_type, p3d_matrix4 Tend_eff, configPt cfg)
configPt gpFind_grasp_from_base_configuration (p3d_rob *robot, p3d_rob *object, std::list< gpGrasp > &graspList, gpArm_type arm_type, configPt qbase, gpGrasp &grasp, gpHand_properties &handProp)
int gpGrasp_visibility_filter (p3d_rob *robot, p3d_rob *object, p3d_jnt *cam_jnt, double camera_fov, int imageWidth, int imageHeight, std::list< gpGrasp > &graspList, gpArm_type arm_type, configPt qbase, gpHand_properties &hand)
int gpFind_grasp_and_pregrasp_from_base_configuration (p3d_rob *robot, p3d_rob *object, std::list< gpGrasp > &graspList, gpArm_type arm_type, configPt qbase, gpGrasp &grasp, gpHand_properties &hand, double distance, configPt qpregrasp, configPt qgrasp)
int gpGet_grasp_list (const std::string &object_to_grasp, gpHand_type hand_type, std::list< gpGrasp > &graspList)
int gpGrasp_handover_filter (p3d_rob *robot1, p3d_rob *robot2, p3d_rob *object, std::list< class gpGrasp > &graspList1, const std::list< class gpGrasp > &graspList2)
int gpDouble_grasp_generation (p3d_rob *robot1, p3d_rob *robot2, p3d_rob *object, const std::list< class gpGrasp > &graspList1, const std::list< class gpGrasp > &graspList2, std::list< class gpDoubleGrasp > &doubleGraspList)
int gpReduce_grasp_list_size (const std::list< gpGrasp > &originalList, std::list< gpGrasp > &reducedList, unsigned int maxSize)
std::string gpHand_type_to_string (gpHand_type hand_type)
std::string gpHand_type_to_folder_name (gpHand_type hand_type)
std::string gpHand_suffix_from_ID (int id)
std::string gpArm_suffix_from_ID (int id)
int gpGet_arm_base_frame (p3d_rob *robot, p3d_matrix4 frame)
int gpGet_platform_frame (p3d_rob *robot, p3d_matrix4 frame)
int gpGet_wrist_frame (p3d_rob *robot, p3d_matrix4 frame)
int gpHand_frame_from_grasp_frame (p3d_matrix4 grasp_frame, p3d_matrix4 hand_frame, gpHand_properties &hand_properties)
int gpGrasp_frame_from_hand_frame (p3d_matrix4 hand_frame, p3d_matrix4 grasp_frame, gpHand_properties &hand_properties)
int gpGrasp_frame_from_end_effector_frame (p3d_matrix4 end_effector_frame, p3d_matrix4 grasp_frame, gpHand_properties &hand_properties)
void gpDraw_friction_cone (p3d_vector3 c, p3d_vector3 normal, double mu, int nb_slices, double length)
void gpDraw_friction_cone2 (p3d_vector3 c, p3d_vector3 normal, double mu, int nb_slices, double length)
configPt gpRandom_robot_base (p3d_rob *robot, double innerRadius, double outerRadius, p3d_vector3 objLoc)
int gpGet_SAHfinger_joint_angles (p3d_rob *robot, gpHand_properties &handProp, double q[4], int finger_index, int handID)
int gpSet_SAHfinger_joint_angles (p3d_rob *robot, gpHand_properties &hand, double q[4], int finger_index, int handID)
int gpSAHfinger_forward_kinematics (p3d_matrix4 Twrist, gpHand_properties &hand, double q0[4], p3d_vector3 p, p3d_vector3 fingerpad_normal, int finger_index)
int gpSAHfinger_inverse_kinematics (p3d_matrix4 Twrist, gpHand_properties &hand, p3d_vector3 p, double q[4], p3d_vector3 fingerpad_normal, int finger_index)
int gpDeactivate_object_fingertips_collisions (p3d_rob *robot, p3d_obj *object, gpHand_properties &hand, int handID)
int gpActivate_object_fingertips_collisions (p3d_rob *robot, p3d_obj *object, gpHand_properties &hand, int handID)
int gpDeactivate_object_collisions (p3d_rob *robot, p3d_obj *object, gpHand_properties &hand, int handID)
int gpActivate_object_collisions (p3d_rob *robot, p3d_obj *object, gpHand_properties &hand, int handID)
int gpOpen_hand (p3d_rob *robot, gpHand_properties &hand)
int gpClose_hand (p3d_rob *robot, gpHand_properties &hand)
int gpGet_platform_configuration (p3d_rob *robot, double &x, double &y, double &theta)
int gpSet_platform_configuration (p3d_rob *robot, double x, double y, double theta)
int gpGet_arm_configuration (p3d_rob *robot, gpArm_type arm_type, std::vector< double > &q)
int gpSet_arm_configuration (p3d_rob *robot, gpArm_type arm_type, std::vector< double > q, bool verbose)
int gpGet_hand_configuration (p3d_rob *robot, gpHand_properties &handProp, int handID, std::vector< double > &q)
int gpSet_hand_configuration (p3d_rob *robot, gpHand_properties &handProp, std::vector< double > config, bool verbose, int handID)
int gpSet_hand_configuration (p3d_rob *robot, gpHand_properties &hand, std::vector< double > config, configPt qr, int handID)
int gpSet_grasp_configuration (p3d_rob *robot, const gpGrasp &grasp, int handID)
int gpSet_grasp_open_configuration (p3d_rob *robot, const gpGrasp &grasp, int handID)
int gpSet_hand_rest_configuration (p3d_rob *robot, gpHand_properties &handProp, int handID)
int gpSet_grasp_configuration (p3d_rob *robot, const gpGrasp &grasp, configPt q, int handID)
int gpSet_grasp_open_configuration (p3d_rob *robot, const gpGrasp &grasp, configPt q, int handID)
int gpSet_hand_rest_configuration (p3d_rob *robot, gpHand_properties &handProp, configPt q, int handID)
int gpFold_arm (p3d_rob *robot, gpArm_type arm_type)
int gpDeactivate_arm_collisions (p3d_rob *robot, int armID)
int gpActivate_arm_collisions (p3d_rob *robot, int armID)
int gpDeactivate_hand_collisions (p3d_rob *robot, int handID)
int gpActivate_hand_collisions (p3d_rob *robot, int handID)
int gpDeactivate_hand_selfcollisions (p3d_rob *robot, int handID)
int gpActivate_hand_selfcollisions (p3d_rob *robot, int handID)
int gpDeactivate_finger_collisions (p3d_rob *robot, unsigned int finger_index, gpHand_properties &hand, int handID)
int gpActivate_finger_collisions (p3d_rob *robot, unsigned int finger_index, gpHand_properties &hand, int handID)
int gpGet_fingertip_bodies (p3d_rob *robot, gpHand_properties &hand, std::vector< p3d_obj * > &bodies)
int gpGet_non_fingertip_bodies (p3d_rob *robot, gpHand_properties &hand, std::vector< p3d_obj * > &bodies)
int gpSample_poly_surface (p3d_polyhedre *poly, double step, double shift, std::list< gpContact > &contactList)
int gpSample_poly_surface_random (p3d_polyhedre *poly, unsigned int nb_samples, double shift, std::list< gpContact > &contactList)
int gpSample_obj_surface (p3d_obj *object, double step, double shift, std::list< gpContact > &contactList)
int gpDraw_workspace_object_intersection (p3d_rob *object, p3d_rob *hand, gpHand_properties &handData)

Detailed Description

This file describes some classes used by the module graspPlanning, dedicated to automatic computation of grasp configurations. It also contains numerous symbolic names of joints or bodies. The names contained in .p3d or .macro files must be adapted according to those defined in graspPlanning.h or modify the '#define's in graspPlanning.h. In case the robot has several parts of the same kinds (e.g. two hands, each one having a joints with the symbolic name defined in GP_FOREFINGERJOINT1 i.e. fingerJointForeBase), the names must be suffixed with the number of the part (e.g. there will be fingerJointForeBase_1 and fingerJointForeBase_2). The grasp planning module is dedicated to automatic computation of grasp configurations. It can compute a grasp list for a given object (represented by a freeflyer robot with a single body) for a given hand type (among the defined ones).


Typedef Documentation

typedef enum gpArm_type gpArm_type

The different arm types:

This is used to store the result of a collision state for a grasp. Depending on the context, this result can change and a rejected grasp may become valid.

typedef enum gpHand_type gpHand_type

The different hand types:

The following enum is used by the gpTriangle class to know how it is described.


Enumeration Type Documentation

enum gpArm_type

The different arm types:

This is used to store the result of a collision state for a grasp. Depending on the context, this result can change and a rejected grasp may become valid.

The different hand types:

The following enum is used by the gpTriangle class to know how it is described.

Enumerator:
GP_DESCRIPTION_INDICES 

the triangle is described by the indices of its vertices in a vertex array

GP_DESCRIPTION_POINTS 

the triangle is described by the coordinates of its vertices

GP_DESCRIPTION_BOTH 

the triangle is described by both data types


Function Documentation

void draw_frame0 ( p3d_matrix4  frame,
double  length 
)

Fonction d'affichage d'un repere (matrice 4x4). Les axes sont dessines sur une longueur "length". A utiliser dans une fonction d'affichage OpenGL.

int export_scene_to_POVRAY ( char *  foldername,
char *  filename 
)

Exports the current scene to a .pov file (for POVRAY ray tracer). Still experimental.

Parameters:
foldernamename of the folder where all the created include files (.inc) will be written
filenamename of the created .pov file
void Gb_matrix4_th ( p3d_matrix4  mat,
Gb_th *  th 
)

Fonction pour passer d'une matrice 4x4 du format de move3D a celui de la librairie "GB" .

void Gb_th_matrix4 ( Gb_th *  th,
p3d_matrix4  mat 
)

Fonction pour passer d'une matrice 4x4 du format de la librairie "GB" a celui de move3D.

void get_sample2D ( int  n,
p3d_vector2  origin,
double  factor,
p3d_vector2  result 
)

Fonction de calcul d'une suite de points realisant un echantillonnage de la surface du carre ([origin[0];origin[0]+factor],[origin[1];origin[1]+factor]). L'echantillon calcule (copie dans 'result') est le n-ieme de la suite. Computes the n-th sample of an incremental lattice sampling the surface of a square. The method is from "Incremental low-discrepancy lattice methods for motion planning" by S. R. Lindemann and S. M. LaValle In Proc. IEEE International Conference on Robotics and Automation, 2003

Parameters:
nindex of the sample in the sequence
originthe sampled square is ([origin[0];origin[0]+factor],[origin[1];origin[1]+factor])
factorthe sampled square is ([origin[0];origin[0]+factor],[origin[1];origin[1]+factor])
resultthe computed sample
void get_sample3D ( int  n,
p3d_vector3  origin,
double  factor,
p3d_vector3  result 
)

Fonction de calcul d'une suite de points realisant un echantillonnage du volume du cube ([origin[0];origin[0]+factor],[origin[1];origin[1]+factor],[origin[2];origin[2]+factor]). L'echantillon calcule (copie dans 'result') est le n-ieme de la suite. Computes the n-th sample of an incremental lattice sampling the volume of a cube. The method is from "Incremental low-discrepancy lattice methods for motion planning" by S. R. Lindemann and S. M. LaValle In Proc. IEEE International Conference on Robotics and Automation, 2003

Parameters:
nindex of the sample in the sequence
originthe sampled cube is ([origin[0];origin[0]+factor],[origin[1];origin[1]+factor],[origin[2];origin[2]+factor])
factorhe sampled cube is ([origin[0];origin[0]+factor],[origin[1];origin[1]+factor],[origin[2];origin[2]+factor])
resultthe computed sample
int gpActivate_arm_collisions ( p3d_rob robot,
int  armID 
)

Activates all the collision tests for the arm bodies of the specified robot.

Parameters:
robotthe robot (its arm bodies must have specific names, defined in graspPlanning.h)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpActivate_finger_collisions ( p3d_rob robot,
unsigned int  finger_index,
gpHand_properties hand,
int  handID 
)

Activates all the collision tests for the specified finger of the specified robot.

Parameters:
robotthe robot (its finger bodies must have specific names, defined in graspPlanning.h)
finger_indexthe number of the finger ( 1 <= finger_index <= hand number of fingers)
handa gpHand_properties variable filled with information concerning the chosen hand characteristics
handIDthe id of the hand (if the robot has n hands, the ids are 0,1,...n-1)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpActivate_hand_collisions ( p3d_rob robot,
int  handID 
)

Activates all the collision tests for the hand bodies of the specified robot.

Parameters:
robotthe robot (its hand bodies must have specific names, defined in graspPlanning.h)
handIDthe id of the hand (if the robot has n hands, the ids are 0,1,...n-1)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpActivate_hand_selfcollisions ( p3d_rob robot,
int  handID 
)

Activates all the selfcollision tests for the hand bodies of the specified robot.

Parameters:
robotthe robot (its hand bodies must have specific names, defined in graspPlanning.h)
handIDthe id of the hand (if the robot has n hands, the ids are 0,1,...n-1)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpActivate_object_collisions ( p3d_rob robot,
p3d_obj object,
gpHand_properties hand,
int  handID 
)

Activates the collision tests between an object and the hand of a robot (that has some).

Parameters:
robotthe robot (its fingertip bodies must have specific names, defined in graspPlanning.h)
objectthe object
handstructure containing information about the hand geometry
handIDthe id of the hand (if the robot has n hands, the ids are 0,1,...n-1)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpActivate_object_fingertips_collisions ( p3d_rob robot,
p3d_obj object,
gpHand_properties hand,
int  handID 
)

Activates the collision tests between an object and the fingertips of a robot (that has some).

Parameters:
robotthe robot (its fingertip bodies must have specific names, defined in graspPlanning.h)
objectthe object
handstructure containing information about the hand geometry
handIDthe id of the hand (if the robot has n hands, the ids are 0,1,...n-1)
Returns:
GP_OK in case of success, GP_ERROR otherwise
std::string gpArm_suffix_from_ID ( int  id)

From an arm ID, returns the string that must be used in a .p3d file as a suffix to the name of a part of the arm.

int gpCheck_triangle_plane_intersection ( p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  p3,
p3d_plane  plane 
)

Cette fonction retourne 1 si le plan coupe le triangle (p1p2p3), 0 sinon.

int gpClose_hand ( p3d_rob robot,
gpHand_properties hand 
)

Closes the gripper or hand at its maximum.

Parameters:
robotthe robot (its joints must have specific names, defined in graspPlanning.h)
handstructure containing information about the hand geometry
Returns:
GP_OK in case of success, GP_ERROR otherwise

warning: in the following the SAHand joint values should not be their minimal bounds:

int gpCompute_grasps_best_placement ( std::list< gpGrasp > &  graspList,
p3d_rob robot,
p3d_rob object,
gpHand_properties hand 
)

For each grasp of a list, computes the best way to place the grasped object with this grasp.

Parameters:
graspListthe grasp list
robotthe hand robot (a freeflying robot only composed of the hand/gripper bodies)
objectthe grasped object
handstructure containing information about the hand geometry
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpDeactivate_arm_collisions ( p3d_rob robot,
int  armID 
)

Deactivates all the collision tests for the arm bodies of the specified robot.

Parameters:
robotthe robot (its arm bodies must have specific names, defined in graspPlanning.h)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpDeactivate_finger_collisions ( p3d_rob robot,
unsigned int  finger_index,
gpHand_properties hand,
int  handID 
)

Deactivates all the collision tests for the specified finger of the specified robot.

Parameters:
robotthe robot (its finger bodies must have specific names, defined in graspPlanning.h)
finger_indexthe number of the finger ( 1 <= finger_index <= hand number of fingers)
handa gpHand_properties variable filled with information concerning the chosen hand characteristics
handIDthe id of the hand (if the robot has n hands, the ids are 0,1,...n-1)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpDeactivate_hand_collisions ( p3d_rob robot,
int  handID 
)

Deactivates all the collision tests for the hand bodies of the specified robot.

Parameters:
robotthe robot (its hand bodies must have specific names, defined in graspPlanning.h)
handIDthe id of the hand (if the robot has n hands, the ids are 0,1,...n-1)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpDeactivate_hand_selfcollisions ( p3d_rob robot,
int  handID 
)

Deactivates all the selfcollision tests for the hand bodies of the specified robot.

Parameters:
robotthe robot (its hand bodies must have specific names, defined in graspPlanning.h)
handIDthe id of the hand (if the robot has n hands, the ids are 0,1,...n-1)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpDeactivate_object_collisions ( p3d_rob robot,
p3d_obj object,
gpHand_properties hand,
int  handID 
)

Deactivates the collision tests between an object and the hand of a robot (that has some).

Parameters:
robotthe robot (its fingertip bodies must have specific names, defined in graspPlanning.h)
objectthe object
handstructure containing information about the hand geometry
handIDthe id of the hand (if the robot has n hands, the ids are 0,1,...n-1)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpDeactivate_object_fingertips_collisions ( p3d_rob robot,
p3d_obj object,
gpHand_properties hand,
int  handID 
)

Deactivates the collision tests between an object and the fingertips of a robot (that has some).

Parameters:
robotthe robot (its fingertip bodies must have specific names, defined in graspPlanning.h)
objectthe object
handstructure containing information about the hand geometry
handIDthe id of the hand (if the robot has n hands, the ids are 0,1,...n-1)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpDouble_grasp_generation ( p3d_rob robot1,
p3d_rob robot2,
p3d_rob object,
const std::list< class gpGrasp > &  graspList1,
const std::list< class gpGrasp > &  graspList2,
std::list< class gpDoubleGrasp > &  doubleGraspList 
)

Generates a list of double grasps from two lists of simple grasps.

Parameters:
robot1pointer to the first robot hand
robot2pointer to the second robot hand
graspList1previously computed grasp list for the first robot hand
graspList2previously computed grasp list for the second robot hand
doubleGraspListthe double grasp list that will be computed
Returns:
GP_OK in case of success, GP_ERROR otherwise
void gpDraw_friction_cone ( p3d_vector3  c,
p3d_vector3  normal,
double  mu,
int  nb_slices,
double  length 
)

Draws a wireframe friction cone with OpenGL functions.

Parameters:
ccone vertex
normalcone normal (directed from the vertex to the cone's inside)
mufriction coefficient
nb_slicesnumber of segments of the cone discretization
lengthlength of the cone
void gpDraw_friction_cone2 ( p3d_vector3  c,
p3d_vector3  normal,
double  mu,
int  nb_slices,
double  length 
)

A different version, that also works.

void gpDraw_plane ( p3d_plane  plane)

Displays a plane (structure p3d_plane). a*x + b*y + c*z + d = 0 To use in an OpenGL display function.

void gpDraw_plane ( p3d_vector3  normal,
double  offset,
double  d 
)

Displays a plane as a grid (squares of length d) normal_x*x + normal_y*y + normal_z*z + offset = 0, sous forme de grille (squares of length d).

Parameters:
normalplane's normal
offsetplane's offset
dsize of the grid's squares Use in an OpenGL context.
void gpDraw_plane2 ( p3d_plane  plane,
double  d 
)

Displays a plane (structure p3d_plane) a*x + b*y + c*z + d = 0, as a grid (squares of length d). To use in an OpenGL display function.

int gpDraw_workspace_object_intersection ( p3d_rob object,
p3d_rob hand,
gpHand_properties handData 
)

Draws the intersection of the kdtree of the object surface sample points and the hand workspace sphere approximation.

Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpExport_bodies_for_coldman ( p3d_rob robot,
const std::string &  folderName 
)

Exports the bodies to make them usable by coldman. Each body is in a .obj file and its vertices are transformed so that their reference frame is the joint's frame.

Parameters:
robotpointer to the robot
folderNamename of the folder wherein to save the body files
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpExport_obstacles_for_coldman ( )

Exports the different environment obstacles as separate .obj files with associated .mtl file containing the same colors as the ones defined in the p3d models.

Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpExport_robot_for_coldman ( p3d_rob robot)

Exports the description of a robot into a xml file with the format required by coldman. Everything is exported but the constraints.

Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpFind_grasp_and_pregrasp_from_base_configuration ( p3d_rob robot,
p3d_rob object,
std::list< gpGrasp > &  graspList,
gpArm_type  arm_type,
configPt  qbase,
gpGrasp grasp,
gpHand_properties hand,
double  distance,
configPt  qpregrasp,
configPt  qgrasp 
)

Finds, for a given mobile base configuration of the robot, a grasp from the given grasp list, that is reachable by the arm and hand, and computes for the grasp a grasping configuration for the whole robot. It also computes an intermediate configuration (a configuration slightly before grasping the object)

Parameters:
robotthe robot
objectthe object to grasp
graspLista list of grasps
arm_typethe robot arm type
qbasea configuration of the robot (only the part corresponding to the mobile base will be used)
graspa copy of the grasp that has been found, in case of success
handparameters of the hand
distancedistance between the grasp and pregrasp configurations (meters)
qpregraspthe pregrasp configuration (must have been allocated before)
qgraspthe grasp configuration (must have been allocated before)
Returns:
GP_OK in case of success, GP_ERROR otherwise NB: The quality score of the grasps is modified inside the function.
configPt gpFind_grasp_from_base_configuration ( p3d_rob robot,
p3d_rob object,
std::list< gpGrasp > &  graspList,
gpArm_type  arm_type,
configPt  qbase,
gpGrasp grasp,
gpHand_properties handProp 
)

Finds, for a given mobile base configuration of the robot, a grasp from the given grasp list, that is reachable by the arm and hand, and computes for the grasp a grasping configuration for the whole arm.

Parameters:
robotthe robot
objectthe object to grasp (a freeflyer robot)
graspLista list of grasps
arm_typethe robot arm type
qbasea configuration of the robot (only the part corresponding to the mobile base will be used)
graspa copy of the grasp that has been found, in case of success
handparameters of the hand
Returns:
a pointer to the computed grasping configuration of the whole robot in case of success, NULL otherwise
int gpFold_arm ( p3d_rob robot,
gpArm_type  arm_type 
)

Sets the robot's arm to a "folded" configuration so that it takes the less room (when the base is moving for instance).

Parameters:
robotpointer to the robot
arm_typearm type (for now, only PA10 is supported)
Returns:
GP_OK in case of success, GP_ERROR otherwise
double gpForce_closure_2D_grasp ( double(*)  position[2],
double(*)  normal[2],
double  mu[],
unsigned int  nbContacts 
)

Computes the quality of a 2D grasp. The algorithm comes from an article by Belkacem Bounab: "Central Axis Approach for Computing n-Finger Force-closure Grasps", proceedings of ICRA 2008, May 2008.

( contact[0][0] contact[1][0] contact[2][0] ... ) = ( C1x C2x C3x ... ) ( contact[0][1] contact[1][1] contact[2][1] ... ) ( C2y C2y C3y ... )

( normal[0][0] normal[1][0] normal[2][0] ... ) = ( N1x N2x N3x ... ) ( normal[0][1] normal[1][1] normal[2][1] ... ) ( N1y N2y N3y ... )

Les frontières des cônes sont (V11, V12), (V21, V22), ..., (Vn1, Vn2)

Le problème se ramène au problème d'optimisation linéaire suivant:

minimize a11 + a12 + a21 + a22 + ... + an1 + an2 - delta a

subject to a11*V11 + a12*V12 + ... + an1*Vn1 + an2*Vn2 + delta*N1 = 0 (C2 - C1)x(a21*V21 + a22*V22) + (C3 - C1)x(a31*V31 + a32*V32) + ... = 0

avec a= ( a11, a12, a21, a22, ... ,an1, an2, delta ) et N la normale au premier point de contact. The problem is solved with the GLPK (GNU Linear Programming Kit) library (http://www.gnu.org/software/glpk/)

Parameters:
positionan array of dimensions [nbContacts][2] containing the contact positions (wrt the object's center of mass)
normalan array of dimensions [nbContacts][2] containing the contact normals
muan array of dimensions [nbContacts] containing the contact friction coefficients
nbContactsthe number of contacts of the grasp
Returns:
the quality of the grasp (>0) if it is stable, 0 otherwise
double gpForce_closure_2D_grasp2 ( double(*)  position[2],
double(*)  normal[2],
double  mu[],
unsigned int  nbContacts 
)

Tests the force closure property of a 2D grasp.

Parameters:
positionan array of dimensions [nbContacts][2] containing the contact positions (wrt the object's center of mass)
normalan array of dimensions [nbContacts][2] containing the contact normals
muan array of dimensions [nbContacts] containing the contact friction coefficients
nbContactsthe number of contacts of the grasp
Returns:
the quality of the grasp (>0) if it is stable, 0 otherwise
double gpForce_closure_3D_grasp ( double(*)  position[3],
double(*)  normal[3],
double  mu[],
unsigned int  nbContacts,
unsigned int  nbSlices 
)

Computes the quality of a 3D grasp. The algorithm comes from an article by Belkacem Bounab: "Central Axis Approach for Computing n-Finger Force-closure Grasps", proceedings of ICRA 2008, May 2008.

( contact[0][0] contact[1][0] contact[2][0] ... ) ( C1x C2x C3x ... ) ( contact[0][1] contact[1][1] contact[2][0] ... ) = ( C2y C2y C3y ... ) ( contact[0][2] contact[1][2] contact[2][0] ... ) ( C2z C2z C3z ... )

( normal[0][0] normal[1][0] normal[2][0] ... ) ( N1x N2x N3x ... ) ( normal[0][1] normal[1][1] normal[2][0] ... ) = ( N1y N2y N3y ... ) ( normal[0][2] normal[1][2] normal[2][0] ... ) ( N1z N2z N3z ... )

Les arêtes des cônes de frottement discrétisés en m segments chacun sont ( V11x, V12x, ..., V1mx, V21x, V22x, ..., V2mx, ..., Vn1x, Vn2x, ..., Vnmx ) ( V11y, V12y, ..., V1my, V21y, V22y, ..., V2my, ..., Vn1y, Vn2y, ..., Vnmy ) ( V11z, V12z, ..., V1mz, V21z, V22z, ..., V2mz, ..., Vn1z, Vn2z, ..., Vnmz )

Le problème se ramène au problème d'optimisation linéaire suivant:

minimize a11 + a12 + a21 + a22 + ... + am1 + am2 - delta a

subject to sum(j=1..m)(a1j*V1j) + sum(j=1..m)(a2j*V2j) + ... + sum(j=1..m)(anj*Vnj) + delta*N1 = 0

sum(j=1..m)(C2 - C1)x(a2j*V2j) + sum(j=1..m)(C3 - C1)x(a3j*V3j) + ...+ sum(j=1..m)(Cn - C1)x(anj*Vnj) = 0

avec a= ( a11, a12,..., a1m, a21, a22,..., a2m, ... ,anm, delta ) The problem is solved with the GLPK (GNU Linear Programming Kit) library (http://www.gnu.org/software/glpk/)

Parameters:
positionan array of dimensions [nbContacts][3] containing the contact positions (wrt the object's center of mass)
normalan array of dimensions [nbContacts][3] containing the contact normals
muan array of dimensions [nbContacts] containing the contact friction coefficients
nbContactsthe number of contacts of the grasp
nbSlicesnumber of segments of the linearized friction cones
Returns:
the quality of the grasp (>0) if it is stable, 0 otherwise
int gpForce_closure_3D_grasp2 ( double(*)  position[3],
double(*)  normal[3],
double  mu[],
unsigned int  nbContacts,
unsigned int  nbSlices 
)

Tests the force closure property of a 3D grasp.

Parameters:
positionan array of dimensions [nbContacts][3] containing the contact positions (wrt the object's center of mass)
normalan array of dimensions [nbContacts][3] containing the contact normals
muan array of dimensions [nbContacts] containing the contact friction coefficients
nbContactsthe number of contacts of the grasp
nbSlicesnumber of segments of the linearized friction cones
Returns:
1 if the grasp verifies the force closure property, 0 otherwise
int gpForward_geometric_model_PA10 ( p3d_rob robot,
p3d_matrix4  Tend_eff,
bool  display 
)

Computes the forward kinematics model of the PA-10 arm for the robot's current configuration.

Parameters:
robotthe robot (that must have joints with specific names (see graspPlanning.h))
Tend_effthe computed end effector pose matrix (in the world frame)
displayif true, the frame of each body will be displayed
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGet_arm_base_frame ( p3d_rob robot,
p3d_matrix4  frame 
)

Gets the arm base frame of a robot as a 4x4 matrix. The frame is the one of the (fixed) joint that links the arm base body to the mobile base main body. The function finds the joint by its name, that must be the one defined by GP_ARMBASEJOINT (see graspPlanning.h).

Parameters:
robotpointer to the robot
framethe ouput matrix
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGet_arm_configuration ( p3d_rob robot,
gpArm_type  arm_type,
std::vector< double > &  q 
)

Gets the robot's arm configuration (in radians).

Parameters:
robotpointer to the robot
arm_typearm type
qvector of the joint angles
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGet_fingertip_bodies ( p3d_rob robot,
gpHand_properties hand,
std::vector< p3d_obj * > &  bodies 
)

Gets all the bodies corresponding of the fingertips.

Parameters:
robotthe robot (its finger bodies must have specific names, defined in graspPlanning.h)
handa gpHand_properties variable filled with information concerning the chosen hand characteristics
bodiesa vector of pointers to the bodies
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGet_grasp_list ( const std::string &  object_to_grasp,
gpHand_type  hand_type,
std::list< gpGrasp > &  graspList 
)

Computes (or loads if it has been previously computed) a grasp list for a given object with the given hand type The computed list will be saved in a file. NB: The world needs to have a robot corresponding to the chosen hand (see graspPlanning.h). The grasps are tested for "internal" collisions (hand self collisions and hand vs object collisions ) and stability. Collision against environment depends on the context and must be tested separately. The grasp list file is searched for in a directory graspPlanning/graspList/"hand name" inside the directory $HOME_MOVE3D. If it does not exist, it will be created by the function.

Parameters:
object_to_graspthe name of the object to grasp (a freeflyer robot)
hand_typetype of the hand (defined in graspPlanning.h)
graspListthe computed grasp list
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGet_hand_configuration ( p3d_rob robot,
gpHand_properties handProp,
int  handID,
std::vector< double > &  q 
)

Gets the hand/gripper's configuration of a robot and copies it in a std::vector.

Parameters:
robotpointer to the robot
handPropgeometric information about the hand
handIDID of the hand in case the robot has several hand (see graspPlanning.h)
qa std::vector that will be filled with the current joint parameters of the hand
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGet_non_fingertip_bodies ( p3d_rob robot,
gpHand_properties hand,
std::vector< p3d_obj * > &  bodies 
)

Gets all the bodies of the hand except for the fingertip bodies.

Parameters:
robotthe robot (its finger bodies must have specific names, defined in graspPlanning.h)
handa gpHand_properties variable filled with information concerning the chosen hand characteristics
bodiesa vector of pointers to the bodies
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGet_platform_configuration ( p3d_rob robot,
double &  x,
double &  y,
double &  theta 
)

Gets the robot's platform configuration (x,y,theta). The robot must have a joint of type P3D_FREEFLYER or P3D_PLAN with the name defined in GP_PLATFORMJOINT (see graspPlanning.h).

Parameters:
robotpointer to the robot
xwhere to copy the current x position
ywhere to copy the current y position
thetawhere to copy the current theta position
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGet_platform_frame ( p3d_rob robot,
p3d_matrix4  frame 
)

Gets the platform frame of a robot as a 4x4 matrix. This frame is chosen to be the same as the frame of the joint linking the mobile platform to the environment. This joint is found by its name defined by GP_PLATFORMJOINT (see graspPlanning.h).

Parameters:
robotpointer to the robot
framethe ouput matrix
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGet_SAHfinger_joint_angles ( p3d_rob robot,
gpHand_properties handProp,
double  q[4],
int  finger_index,
int  handID 
)

Gets the joint angles of the SAHand fingers in its current configuration.

Parameters:
robotthe robot (that must have joint with the appropriate names (see graspPlanning.h))
handPropstructure containing information about the hand geometry
qarray that will be filled with the finger joint parameters (angles in radians). Except for the thumb, only the three last elements are used.
finger_indexindex of the chosen finger (1= thumb, 2= forefinger, 3= middlefinger, 4= ringfinger)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGet_wrist_frame ( p3d_rob robot,
p3d_matrix4  frame 
)

Gets the wrist frame of a robot as a 4x4 matrix. This frame is chosen to be the same as the frame of the robot's wrist joint. This joint is found by its name defined by GP_WRISTJOINT (see graspPlanning.h).

Parameters:
robotpointer to the robot
framethe ouput matrix
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGrasp_collision_filter ( std::list< gpGrasp > &  graspList,
p3d_rob robot,
p3d_rob object,
gpHand_properties hand 
)

Context independent collision test: removes from a grasp list all the grasps causing a collision between the robot hand and the grasped object.

Parameters:
graspListthe original grasp list
robotthe hand robot (a freeflying robot only composed of the hand/gripper bodies)
objectthe grasped object
handstructure containing information about the hand geometry
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGrasp_context_collision_filter ( std::list< gpGrasp > &  graspList,
p3d_rob robot,
p3d_rob object,
gpHand_properties hand 
)

Context dependent collision test: removes from a grasp list all the grasps causing a collision between the robot hand and the environment.

Parameters:
graspListthe grasp list
robotthe hand robot (a freeflying robot only composed of the hand/gripper bodies)
objectthe grasped object
handstructure containing information about the hand geometry
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGrasp_frame_from_end_effector_frame ( p3d_matrix4  end_effector_frame,
p3d_matrix4  grasp_frame,
gpHand_properties hand_properties 
)

Gets the grasp frame that must be associated to a given robot's end effector pose.

Parameters:
end_effector_framedesired end effector frame
grasp_framecomputed grasp frame
hand_propertiesparameters of the hand
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGrasp_frame_from_hand_frame ( p3d_matrix4  hand_frame,
p3d_matrix4  grasp_frame,
gpHand_properties hand_properties 
)

Gets the grasp frame that must be associated to a given hand pose (robot hand pose).

Parameters:
hand_framedesired hand frame
grasp_framecomputed grasp frame
hand_propertiesparameters of the hand
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGrasp_generation ( p3d_rob robot,
p3d_rob object,
gpHand_properties handProp,
unsigned int  nbPositions,
unsigned int  nbDirections,
unsigned int  nbRotations,
std::list< class gpGrasp > &  graspList 
)

Generates a list of grasp for the given robot hand and object.

Parameters:
robotthe hand robot (a freeflying robot composed of the hand/gripper bodies only)
objectthe object to be grasped
handPropstructure containing information about the hand geometry
translationSteptranslation discretization step for hand/object pose sampling
nbDirectionsnumber of sampled directions for hand/object pose sampling
rotationSteprotation discretization step around each sampled direction for hand/object pose sampling
graspListthe computed grasp list
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGrasp_handover_filter ( p3d_rob robot1,
p3d_rob robot2,
p3d_rob object,
std::list< class gpGrasp > &  graspList1,
const std::list< class gpGrasp > &  graspList2 
)

Handover filter: removes from a grasp list L1, computed for a hand H1 and an object O all the grasps that makes impossible to grasp O with one of the grasps of the list L2, computed for a hand H2.

Parameters:
robot1pointer to the first robot hand (H1)
robot2pointer to the second robot hand (H2)
graspList1previously computed grasp list for the first robot hand (L1) (will be modified)
graspList2previously computed grasp list for the second robot hand (L2)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGrasp_stability_filter ( std::list< gpGrasp > &  graspList)

Eliminates all the unstable grasps from a list.

Parameters:
graspLista list of grasps
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGrasp_visibility_filter ( p3d_rob robot,
p3d_rob object,
p3d_jnt cam_jnt,
double  camera_fov,
int  imageWidth,
int  imageHeight,
std::list< gpGrasp > &  graspList,
gpArm_type  arm_type,
configPt  qbase,
gpHand_properties hand 
)

Computes the visibility of the grasps from a list for a given base configuration of the robot. For each grasp, the function tests the inverse kinematics of the arm; if the grasp is reachable, the function then computes how much the object is visible from the view point given by the frame of the robot's joint defined as the camera joint.

Parameters:
robotthe robot
objectthe object to grasp (a freeflyer robot)
cam_jntthe joint of the robot that is supposed to have the same pose than the camera from which we will compute the object visibility
camera_fovthe field of view angle of the robot's camera (in degrees)
imageWidthwidth of the synthetized images
imageHeightheight of the synthetized images
graspLista list of grasps
arm_typethe robot arm type
qbasea configuration of the robot (only the part corresponding to the mobile base will be used)
handparameters of the hand
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpGrasps_from_grasp_frame_gripper ( p3d_polyhedre *  polyhedron,
p3d_matrix4  gFrame,
gpHand_properties hand,
std::list< class gpGrasp > &  graspList 
)

Cette fonction calcule, pour la pince à 3 doigts, les trois positions des doigts obtenus à partir d'un repere de prise ainsi qu'un repere lié aux points de contact. La fonction retourne 0 au cas où il n'y a pas de solution, 1 sinon. L'argument 'part' sert à sélectionner une partie de l'objet (ensemble de facettes) dans le cas où il a été segmenté par ailleurs. Par défaut, on la laisse à 0 et toutes les facettes seront considérées. Principe général (plus de détails et des figures dans la thèse d'Efrain Lopez Damian: "Grasp planning for object manipulation by an autonomous robot"): On part de la donnée d'un repere de prise (Oxyz). On définit le plan de prise par (Oxy). Le premier point de contact (p1) est donné par l'intersection de l'axe Ox avec la surface de l'objet (intersection entre une demi-droite et un des triangles du polyèdre). Ce point est décalé dans la direction de la normale à la surface d'une distance égale au rayon Rf des doigts (les doigts sont hémisphériques) pour donner p1', la position du centre du doigt 1. Pour le second point (p2), on cherche d'abord l'intersection entre le plan de prise et les facettes déplacées d'une distance R dans la direction de la normale à la surface. Les segments obtenus doivent intersecter un cercle de centre p1 et de rayon R où R est le rayon entre les deux doigts du même côté de la paume (ceux des contacts 1 et 2). Le point d'intersection est p2'. Comme il y a deux possibilités, on prend p2' tel que p1'p2' soit dans le même sens que l'axe (Oy). On prend alors p1'p2' comme nouvel axe Oy du repere de prise (après normalisation). Le nouvel axe Z est la normale au plan formé par les point (O, p1',p2'). p3 est alors l'intersection entre le rayon partant du milieu de p1'p2' et de direction égale à celle de l'axe Ox du nouveau repere. p3' est obtenu en décalant p3 de Rf dans la direction de la normale à la surface. On choisit alors une nouvelle origine pour le nouveau repere de prise: le milieu du segment formé par le milieu de p1'p2' et p3'. NOTE: le plan défini par les trois points de contact n'est pas forcément le plan de prise initiale. Il va dépendre des normales des faces intersectées par le plan de prise initial. Plusieurs prises peuvent être obtenue à partir d'un même repere de prise. Compute a set of grasps for a given grasp frame for the gripper.

Parameters:
polyhedronthe polyhedral mesh of the object surface
partif the object has been previously segmented, "part" is used to select a part of the object (a set of triangles). Set to 0 to select all the triangles.
gFramethe grasp frame (a 4x4 homogeneous transform matrix)
handstructure containing information about the hand geometry
graspLista grasp list the computed set of grasps will be added to
Returns:
1 if grasps were found and added to the list, 0 otherwise
int gpGrasps_from_grasp_frame_SAHand ( p3d_rob robot,
p3d_rob object,
p3d_matrix4  gFrame,
gpHand_properties hand,
gpKdTree kdtree,
std::list< class gpGrasp > &  graspList 
)

Computes a set of grasps from a grasp frame for the SAHand.

Parameters:
robotthe hand robot (a freeflying robot composed of hand bodies only)
objectthe object to grasp
gframethe grasp frame (a 4x4 homogeneous transform matrix)
handvariable containing information about the hand geometry
kdtreeKdTree of the object's mesh
graspLista grasp list the computed set of grasps will be added to
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpHand_frame_from_grasp_frame ( p3d_matrix4  grasp_frame,
p3d_matrix4  hand_frame,
gpHand_properties hand_properties 
)

Gets the hand frame that is associated to a grasp frame for the given hand.

Parameters:
grasp_framedesired grasp frame
hand_framecomputed hand frame
hand_propertiesparameters of the hand
Returns:
GP_OK in case of success, GP_ERROR otherwise
std::string gpHand_suffix_from_ID ( int  id)

From an hand ID (as used in class gpGrasp), returns the string that must be used in a .p3d file as a suffix to the name of a part of the hand.

std::string gpHand_type_to_folder_name ( gpHand_type  hand_type)

Converts a gpHand_type to a std::string.

std::string gpHand_type_to_string ( gpHand_type  hand_type)

Converts a gpHand_type to a std::string.

int gpInverse_geometric_model_and_collision_arm ( p3d_rob robot,
gpArm_type  arm_type,
p3d_matrix4  Tend_eff,
configPt  cfg 
)

Computes a collision-free inverse kinematics solution of robot's arm (PA-10 or LWR).

Parameters:
robotthe robot (that must have joints with specific names (see graspPlanning.h))
arm_typethe chosen arm type (see gpArm_type in graspPlanning.h)
Tend_effthe desired end effector pose matrix (given in the arm base frame)
qthe solution joint parameter vector (that must be allocated before calling the function)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpInverse_geometric_model_and_collision_LWR ( p3d_rob robot,
p3d_matrix4  Tend_eff,
configPt  cfg 
)

Computes the inverse kinematics of the LWR arm. Checks all the different solution class until it finds a valid one with no collision.

Parameters:
robotthe robot (that must have joints with specific names (see graspPlanning.h))
Tend_effthe desired end effector pose matrix (given in the arm base frame)
qthe solution joint parameter vector (that must be allocated before calling the function)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpInverse_geometric_model_and_collision_PA10 ( p3d_rob robot,
p3d_matrix4  Tend_eff,
configPt  cfg 
)

Computes a collision-free inverse kinematics of the PA-10 arm. Tests all the possible solutions until a valid and collision-free one is found.

Parameters:
robotthe robot (that must have joints with specific names (see graspPlanning.h))
Tend_effthe desired end effector pose matrix (given in the arm base frame)
valid
qthe solution joint parameter vector (that must be allocated before calling the function)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpInverse_geometric_model_arm ( p3d_rob robot,
gpArm_type  arm_type,
p3d_matrix4  Tend_eff,
configPt  cfg 
)

Computes the inverse kinematics of robot's arm (PA-10 or LWR).

Parameters:
robotthe robot (that must have joints with specific names (see graspPlanning.h))
arm_typethe chosen arm type (see gpArm_type in graspPlanning.h)
Tend_effthe desired end effector pose matrix (given in the arm base frame)
qthe solution joint parameter vector (that must be allocated before calling the function)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpInverse_geometric_model_freeflying_hand ( p3d_rob robot,
p3d_matrix4  objectFrame,
p3d_matrix4  graspFrame,
gpHand_properties hand,
configPt  q 
)

Computes the hand (wrist) pose corresponding to a given grasp frame.

Parameters:
robotpointer to the hand robot (its first joint must be a P3D_FREEFLYER)
objectFrameframe representing the object pose (in world frame)
graspFramegrasp frame (in object frame)
handstructure containing information about the hand geometry
qthe computed hand configuration (must have been allocated before calling the function). Only the part corresponding to the hand pose is modified. The finger configurations are not modified.
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpInverse_geometric_model_LWR ( p3d_rob robot,
p3d_matrix4  Tend_eff,
configPt  cfg 
)

Computes the inverse kinematics of the LWR arm. Checks all the different solution class until it finds a valid one.

Parameters:
robotthe robot (that must have joints with specific names (see graspPlanning.h))
Tend_effthe desired end effector pose matrix (given in the arm base frame)
qthe solution joint parameter vector (that must be allocated before calling the function)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpInverse_geometric_model_PA10 ( p3d_rob robot,
p3d_matrix4  Tend_eff,
configPt  cfg 
)

Computes the inverse kinematics of the PA-10 arm. Checks all the different solution class until it finds a valid one.

Parameters:
robotthe robot (that must have joints with specific names (see graspPlanning.h))
Tend_effthe desired end effector pose matrix (given in the arm base frame)
qthe solution joint parameter vector (that must be allocated before calling the function)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpIs_point_in_polygon ( double  point[2],
double(*)  vertices[2],
int  nb_vertices 
)

Fonction testant l'inclusion d'un point dans un polygone. Les coordonnees des points du polygone sont rangees dans le tableau vertices comme suit: ( vertices[0][0] vertices[1][0] ... vertices[nb_vertices-1][0] ) = ( x1 x2 ... xn ) ( vertices[0][1] vertices[1][1] ... vertices[nb_vertices-1][1] ) = ( y1 y2 ... yn ) Code original de W Randolph Franklin du Rensselaer Polytechnic Institute. NOTE: Remarque importante de l'auteur: "My code uses the fact that, in the C language, when executing the code a&&b, if a is false, then b must not be evaluated. If your compiler doesn't do this, then it's not implementing C, and you will get a divide-by-zero, i.a., when the test point is vertically in line with a vertical edge. When translating this code to another language with different semantics, then you must implement this test explicitly".

int gpIs_point_in_triangle ( p3d_vector3  point,
p3d_vector3  a,
p3d_vector3  b,
p3d_vector3  c 
)

Tests if a 3D point is at the vertical of a 3D triangle (if the point is inside the infinite prism whose section is the triangle).

Parameters:
pthe coordinates of the point
athe coordinates of the triangle's first vertex
bthe coordinates of the triangle's second vertex
cthe coordinates of the triangle's third vertex
Returns:
1 if the point is inside the triangle, 0 otherwise
int gpIs_point_on_segment2D ( double  p[2],
double  a[2],
double  b[2] 
)

Cette fonction teste si le point p est sur le segment[ab]. Elle retourne 1 si c'est le cas, 0 sinon.

int gpIs_polygon_ccw ( double(*)  vertices[2],
int  nb_vertices 
) [inline]

Cette fonction teste si l'orientation d'un polygone est CCW (counterclockwise=sens direct) ou non et retourne respectivement 1 ou 0. Les sommets sont ranges comme suit: ( vertices[0][0] vertices[1][0] ... vertices[nb_vertices-1][0] ) = ( x1 x2 ... xn ) ( vertices[0][1] vertices[1][1] ... vertices[nb_vertices-1][1] ) = ( y1 y2 ... yn )

int gpIs_polygon_simple ( double(*)  vertices[2],
int  nb_vertices 
)

Cette fonction verifie si un polygone est simple ou non (un polygone est simple si les seuls points d'intersection de ses arêtes sont ses sommets). Les sommets sont ranges comme suit: ( vertices[0][0] vertices[1][0] ... vertices[nb_vertices-1][0] ) = ( x1 x2 ... xn ) ( vertices[0][1] vertices[1][1] ... vertices[nb_vertices-1][1] ) = ( y1 y2 ... yn ) La fonction retourne 1 si le polygone est simple, 0 sinon.

int gpLine_line_intersection2D ( double  point1[2],
double  direction1[2],
double  point2[2],
double  direction2[2],
double  result[2] 
)

Cette fonction calcule l'intersection entre deux droites dans le plan. Ces droites sont caracterisees par un de leur point et leur direction. Retourne le nombre d'intersections (0 ou 1).

int gpLine_segment_plane_intersection ( p3d_plane  plane,
p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  result 
)

Cette fonction calcule l'intersection entre un plan et un segment donne par deux points. Il peut y avoir 0, 1 ou 2 points d'intersection (le segment est dans le plan). S'il n'y en a qu'un, le point d'intersection est recopie en sortie. S'il y en a deux, les points d'intersection sont directement les points du segment. La fonction retourne le nombre de points d'intersection.

int gpLine_segment_sphere_intersection ( p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  center,
double  radius,
p3d_vector3  result1,
p3d_vector3  result2 
)

Cette fonction calcule l'intersection entre un segment de droite et une sphere. Le segment est donne par les points p1 et p2 et la sphere par son centre "center" et son rayon "radius". Il peut y avoir 0, 1 ou 2 points d'intersection. Ce nombre est retourne par la fonction. S'ils existent, les points d'intersection sont recopies dans result1 et result2. S'il n'y en a qu'un, il est recopie dans result1.

int gpLine_triangle_intersection ( p3d_vector3  c1,
p3d_vector3  c2,
p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  p3,
p3d_vector3  intersection 
)

Cette fonction calcule l'intersection entre la droite (c1c2) et le triangle (p1p2p3). Retourne 1 ou 0 selon qu'il y a intersection ou pas et recopie l'intersection si elle existe dans "intersection". L'intersection pint avec le plan du triangle (a*x + b*y + c*z + d = 0 ) doit verifier pint.n + d = 0 et pint= c1 + alpha*c1c2 avec n= (a,b,c) et alpha un reel. c1.n + alpha*(c1c2.n) + d = 0 alpha= -(c1.n + d)/(c1c2.n) La fonction teste ensuite si l'intersection est bien dans le triangle. Computes the intersection between a triangle and a line.

Parameters:
c1first point used to define the line
c2second point used to define the line
p1first point of the triangle
p2second point of the triangle
p3third point of the triangle
Returns:
1 if there is an intersection, 0 otherwise
int gpObj_AABB ( p3d_obj obj,
double &  xmin,
double &  xmax,
double &  ymin,
double &  ymax,
double &  zmin,
double &  zmax 
)

Computes the axis-aligned bounding box of a p3d_obj.

Parameters:
objpointer to the p3d_obj
xminminimal coordinate along X-axis
xmaxmaximal coordinate along X-axis
yminminimal coordinate along Y-axis
ymaxmaximal coordinate along Y-axis
zminminimal coordinate along Z-axis
zmaxmaximal coordinate along Z-axis
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpOpen_hand ( p3d_rob robot,
gpHand_properties hand 
)

Opens the gripper or hand at its maximum.

Parameters:
robotthe robot (its joints must have specific names, defined in graspPlanning.h)
handstructure containing information about the hand geometry
Returns:
GP_OK in case of success, GP_ERROR otherwise

warning: in the following the SAHand joint values should not be their maximal bounds:

void gpOrthogonal_projection_point_onto_plane ( p3d_vector3  point,
p3d_plane  plane,
p3d_vector3  result 
)

Cette fonction calcule la projection orthogonale d'un point sur un plan d'equation (ax + by + cz + d = 0) dont les parametres sont dans une structure p3d_plane.

void gpOrthogonal_vector ( p3d_vector3  v,
p3d_vector3  result 
)

Cette fonction calcule un vecteur orthogonal (quelconque) au vecteur v et le normalise. Elle retourne un choix parmi l'infinite possible.

void gpOrthonormal_basis ( p3d_vector3  u,
p3d_vector3  v,
p3d_vector3  w 
)

Cette fonction calcule les vecteurs v et w tels que (u,v,w) soit une base orthonormal directe. Elle retourne un choix parmi l'infinite possible.

int gpParameters_in_triangle_from_point ( p3d_vector3  p,
p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  p3,
double *  alpha,
double *  beta 
)

Cette fonction reçoit le point p dont on sait qu'il appartient au triangle (p1p2p3). Elle retourne sa parametrisation (alpha,beta) sur la surface du triangle.

int gpPlane_plane_intersection ( p3d_plane *  plane1,
p3d_plane *  plane2,
p3d_vector3  point_on_line,
p3d_vector3  line_direction 
)

Cette fonction calcule l'intersection entre deux plans d'equation plane1 et plane2. Le resultat est une droite passant par "point_on_line" de vecteur directeur "line_direction". La fonction retourne 0 si les plans sont paralleles, 1 sinon. NOTE: not tested.

void gpPoint_in_triangle_from_parameters ( double  alpha,
double  beta,
p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  p3,
p3d_vector3  result 
)

Cette fonction calcule les coordonnees 3D d'un point a l'interieur du triangle (p1p2p3) a partir de deux coordonnees (alpha,beta) comprises entre 0.0 et 1.0. Les coordonnees calculees sont retournees dans result.

double gpPoint_to_line_segment_distance ( p3d_vector3  p,
p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  closestPoint 
)

Computes the closest point of a point to a segment line.

Parameters:
pthe point
p1the first point of the segment line
p2the second point of the segment line
closestPointthe point on the segment that is the closest to p
Returns:
the minimimal distance between the segment and the point
int gpPoint_to_polyhedron_distance ( p3d_vector3  point,
p3d_polyhedre *  polyhedron,
double &  distance,
p3d_vector3  closestPoint 
)

WIP

double gpPoint_to_triangle_distance ( p3d_vector3  point,
p3d_vector3  p0,
p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  closestPoint 
)

Fonction calculant la distance entre un point "point" et le point C du triangle (p0p1p2) tel que la distance de "point" a C soit minimale. La fonction retourne cette distance et recopie les coordonnees de C dans "closestPoint". Cette fonction est une adaptation (passage de C++ a C) de la fonction "DistVector3Triangle3" de la bibliotheque "Wild Magic Library" (WM3), http://www.geometrictools.com de David Eberly.

double gpPolygon_area ( double(*)  vertices[2],
int  nb_vertices 
)

Cette fonction calcule l'aire d'un polygone dont les sommets sont ranges comme suit: ( vertices[0][0] vertices[1][0] ... vertices[nb_vertices-1][0] ) = ( x1 x2 ... xn ) ( vertices[0][1] vertices[1][1] ... vertices[nb_vertices-1][1] ) = ( y1 y2 ... yn ) L'aire A du polygone est donnee par la formule A= 0.5 * (x1*y2 - y1*x2 + x2*y3 - y2*x3 + ... + xn*y1 - yn*x1 ) Elle est positive si les points sont donnes dans le sens trigonometrique, negative sinon. Weisstein, Eric W. "Polygon Area." From MathWorld--A Wolfram Web Resource. http://mathworld.wolfram.com/PolygonArea.html

int gpPolygon_polygon_inclusion ( double(*)  vertices1[2],
int  nb_vertices1,
double(*)  vertices2[2],
int  nb_vertices2 
)

Retourne 1 si le polygone dont les sommets sont donnes a la suite dans vertices1 est inclus dans le polygone dont les sommets sont donnes a la suite dans vertices2, 0 sinon.

int gpPolyhedron_AABB ( p3d_polyhedre *  polyhedron,
double &  xmin,
double &  xmax,
double &  ymin,
double &  ymax,
double &  zmin,
double &  zmax 
)

Computes the axis-aligned bounding box of a polyhedron.

Parameters:
polyhedronpointer to the polyhedron
xminminimal coordinate along X-axis
xmaxmaximal coordinate along X-axis
yminminimal coordinate along Y-axis
ymaxmaximal coordinate along Y-axis
zminminimal coordinate along Z-axis
zmaxmaximal coordinate along Z-axis
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpPrint_robot_AABBs ( p3d_rob robot)

Prints the AABBs of each body of a robot. It is meant to be used to automatically compute P3D_GHOST volumes for the robot.

Parameters:
robotpointer to the robot
Returns:
GP_OK in case of success, GP_ERROR otherwise
configPt gpRandom_robot_base ( p3d_rob robot,
double  innerRadius,
double  outerRadius,
p3d_vector3  objLoc 
)

Finds a collision-free configuration for the mobile base of a robot in a ring centered on a specified position. The collisions are avoided for the base only. Some of the robot's joints or bodies must have specific names (see graspPlanning.h). NB: modification: the random base configurations are now tested with the arm in folded configuration

Parameters:
robotpointer to the robot
innerRadiusinner radius of the ring
outerRadiusouter radius of the ring
objLocdesired center of the ring (world coordinates)
arm_typetype of the robot's arm
Returns:
a pointer to the computed robot configuration
int gpRay_triangle_intersection ( p3d_vector3  origin,
p3d_vector3  direction,
p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  p3,
p3d_vector3  intersection 
)

Cette fonction calcule l'intersection entre le rayon (demi-droite) partant de "origin" dans la direction "direction" et le triangle (p1p2p3). Le rayon est une DEMI-droite. Retourne 1 ou 0 selon qu'il y a intersection ou pas et recopie l'intersection si elle existe dans intersection. L'intersection pint avec le plan du triangle (a*x + b*y + c*z + d = 0 ) doit verifier pint.n + d = 0 et pint= origin + alpha*direction avec n= (a,b,c) et alpha un reel >= 0. origin.n + alpha*(direction.n) + d = 0 alpha= -(origin.n + d)/(direction.n) La fonction teste ensuite si l'intersection est bien dans le triangle.

int gpReduce_grasp_list_size ( const std::list< gpGrasp > &  originalList,
std::list< gpGrasp > &  reducedList,
unsigned int  maxSize 
)

Reduces the number of elements of a grasp list. The criterion used to choose which grasps to remove is the distance between the grasp frame (see gpGrasp::gpGraspDistance()). If there are too many elements, they are first remove at random.

Parameters:
originalListthe original grasp list
reducedListthe reduced grasp list
maxSizethe desired maximum number of elements in the grasp list
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSAHfinger_forward_kinematics ( p3d_matrix4  Twrist,
gpHand_properties hand,
double  q0[4],
p3d_vector3  p,
p3d_vector3  fingerpad_normal,
int  finger_index 
)

Computes the forward kinematics of the SAHand fingers.

Parameters:
Twristhand pose (frame of the wrist center)
handstructure containing information about the hand geometry
qthe finger joint parameters (angles in radians). Except for the thumb, only the three last elements are used.
pthe computed position of the fingertip center wrt to the wrist frame
fingerpad_normala vector giving the direction of the fingertip contact surface (orthogonal to the medial axis of the distal phalanx and directed towards the inside of the hand). It is computed for the given finger configuration.
finger_indexindex of the chosen finger (1= thumb, 2= forefinger, 3= middlefinger, 4= ringfinger)
Returns:
GP_OK in case of success, GP_ERROR otherwise NB: the first joint of the thumb is not taken into account: it is supposed to be at its maximum value (90 degrees) in opposition to the other fingers.
int gpSAHfinger_inverse_kinematics ( p3d_matrix4  Twrist,
gpHand_properties hand,
p3d_vector3  p,
double  q[4],
p3d_vector3  fingerpad_normal,
int  finger_index 
)

Computes the inverse kinematics of the SAHand fingers.

Parameters:
Twristhand pose (frame of the wrist center) in the world frame
handstructure containing information about the hand geometry
pthe desired position of the fingertip in the world frame
qthe computed finger joint parameters (angles in radians). Except for the thumb, only the three last elements are used.
fingerpad_normala vector giving the direction of the fingertip contact surface (orthogonal to the medial axis of the distal phalanx and directed towards the inside of the hand (outside of the fingertip surface)). It is computed for the computed finger joint angles (if a solution of the inverse kinematics problem exists) and given in the world frame
finger_indexindex of the chosen finger (1= thumb, 2= forefinger, 3= middlefinger, 4= ringfinger)
Returns:
GP_OK in case of success, GP_ERROR otherwise NB: the first joint of the thumb is not taken into account: it is supposed to be at its maximum value (90 degrees) in opposition to the other fingers.
int gpSample_grasp_frames ( p3d_polyhedre *  polyhedron,
unsigned int  nbPositions,
unsigned int  nbDirections,
unsigned int  nbRotations,
unsigned int  nbFramesMax,
std::vector< gpHTMatrix > &  frames 
)

Computes a set of grasp frames by building a grid. The number of computed frames depends on the given discretization steps and on a threshold on the maximal number of frames. The positions are computed in a grid with given resolution.and are then filtered to remove all the points that are outside the convex hull of the polyhedron's points. NB: if nbSamples is too big (in regard of a realistic memory allocation), the function returns NULL and set nbSamples to a value !=0 whereas if their is a memory allocation error, it returns NULL and sets nbSamples to 0.

Parameters:
polyhedronpointer to the p3d_polyhedre to sample point inside its convex hull
translationSteptranslation discretization step for hand/object pose sampling
nbDirectionsnumber of sampled directions for hand/object pose sampling
rotationSteprotation discretization step around each sampled direction for hand/object pose sampling
nbFramesMaxmaximal number of frames (the resolution will be adapted to reduce the number of frames under this threshold)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSample_obj_surface ( p3d_obj object,
double  step,
double  shift,
std::list< gpContact > &  contactList 
)

Computes a set of contact points on the surface of an object mesh.

Parameters:
objectthe object
stepthe discretization step of the sampling (if it is bigger than the triangle dimensions, there will be only one sample generated, positioned at the triangle center)
shiftthe point will be shifted in the direction of the surface normal of a distance 'shift'
contactLista contactList list the computed set of contacts will be added to
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSample_poly_surface ( p3d_polyhedre *  poly,
double  step,
double  shift,
std::list< gpContact > &  contactList 
)

Computes a set of contact points on the surface of a mesh.

Parameters:
polythe p3d_polyhedre
stepthe discretization step of the sampling (if it is bigger than the triangle dimensions, there will be only one sample generated, positioned at the triangle center)
shiftthe point will be shifted in the direction of the surface normal of a distance 'shift'
contactLista contactList list the computed set of contacts will be added to
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSample_poly_surface_random ( p3d_polyhedre *  poly,
unsigned int  nb_samples,
double  shift,
std::list< gpContact > &  contactList 
)

Computes a set of contact points on the surface of a mesh.

Parameters:
polythe p3d_polyhedre
nb_samplesthe desired number of samples
shiftthe point will be shifted in the direction of the surface normal of a distance 'shift'
contactLista contactList list the computed set of contacts will be added to
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSample_polyhedron_AABB ( p3d_polyhedre *  polyhedron,
double  step,
std::vector< gpVector3D > &  samples 
)

Builds a point grid inside the axis-aligned bounding box of a p3d_polyhedre.

Parameters:
polyhedronpointer to the polyhedron
stepgrid resolution
samplesa vector to store the grid points
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSample_sphere_surface ( double  radius,
unsigned int  nb_samples,
std::vector< gpVector3D > &  samples 
)

Computes a sample set of the surface of a sphere. The surface is sampled with a multiresolution grid (cf Deterministic Sampling Methods for Spheres and SO(3), A. Yershova, S. Lavalle, ICRA 2004).

Parameters:
radiusradius of the sphere
nb_samplesthe desired number of samples
samplesthe computed samples
Returns:
GP_OK in case of success, GP_ERROR otherwise
p3d_vector3* gpSample_triangle_surface ( p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  p3,
double  step,
unsigned int *  nb_samples 
)

Computes a set of sample points on a triangle surface. The idea is to sample a minimal area rectangle that bounds the triangle, with a regular grid, and to only keep the points that are inside the triangle.

Parameters:
p1first point of the triangle
p2second point of the triangle
p3third point of the triangle
stepthe discretization step of the sampling (if it is bigger than the triangle dimensions, there will be only one sample generated, positioned at the triangle center)
nb_samplespointer to an integer that will be filled with the number of computed samples
Returns:
a 3D point array of size "nb_samples"
int gpSegment_segment_intersection2D ( double  a1[2],
double  b1[2],
double  a2[2],
double  b2[2],
double  result1[2],
double  result2[2] 
)

Cette fonction calcule l'intersection entre deux segments [a1b1] et [a2b2] dans le plan. Retourne le nombre d'intersections (0, 1 ou 2). Le cas 2 a lieu quand les deux segments sont paralleles et se recoupent partiellement. Dans ce cas, les deux extremites de l'intersection sont recopies dans result1 et result2.

int gpSet_arm_configuration ( p3d_rob robot,
gpArm_type  arm_type,
std::vector< double >  q,
bool  verbose 
)

Sets the robot's arm configuration with the given values (in radians). NB: The respect of joint limits is verified.

Parameters:
robotpointer to the robot
arm_typearm type
qvector of the joint angles
verboseenable/disable error message display
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSet_grasp_configuration ( p3d_rob robot,
const gpGrasp grasp,
int  handID 
)

Sets the hand/gripper configuration of a robot with the grasping configuration contained in a gpGrasp variable. It only modifies the parameters of the hand. NB: The finger joints require to have specific names (see graspPlanning.h).

Parameters:
robotpointer to the robot
graspthe grasp to set
handIDthe hand to set (in case there are several): 0 by default
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSet_grasp_configuration ( p3d_rob robot,
const gpGrasp grasp,
configPt  q,
int  handID 
)

Sets the hand/gripper configuration of a robot with the grasping configuration contained in a gpGrasp variable. The rest of the robot configuration is set from a configPt. NB: The finger joints require to have specific names (see graspPlanning.h).

Parameters:
robotpointer to the robot
graspthe grasp to set
qdesired complete configuration vector of the robot (only the non-hand part will be used)
handIDthe hand to set (in case there are several): 0 by default
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSet_grasp_open_configuration ( p3d_rob robot,
const gpGrasp grasp,
int  handID 
)

Sets the hand/gripper configuration of a robot with the open configuration contained in a gpGrasp variable. It only modifies the parameters of the hand. NB: The finger joints require to have specific names (see graspPlanning.h).

Parameters:
robotpointer to the robot
graspthe grasp to set
handIDthe hand to set (in case there are several): 0 by default
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSet_grasp_open_configuration ( p3d_rob robot,
const gpGrasp grasp,
configPt  q,
int  handID 
)

Sets the hand/gripper configuration of a robot with the open configuration contained in a gpGrasp variable. The rest of the robot configuration is set from a configPt. NB: The finger joints require to have specific names (see graspPlanning.h).

Parameters:
robotpointer to the robot
graspthe grasp to set
qdesired complete configuration vector of the robot (only the non-hand part will be used)
handIDthe hand to set (in case there are several): 0 by default
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSet_hand_configuration ( p3d_rob robot,
gpHand_properties handProp,
std::vector< double >  config,
bool  verbose,
int  handID 
)

Sets the hand/gripper's configuration of a robot with the configuration contained in a std::vector. It only modifies the parameters of the hand.

Parameters:
robotpointer to the robot
handPropgeometric information about the hand
configa std::vector containing the finger joint parameters associated to the grasp
verboseflag to print information in case of error or not
handIDID of the hand used by the grasp (see gpHand_suffix_from_ID)
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSet_hand_configuration ( p3d_rob robot,
gpHand_properties hand,
std::vector< double >  config,
configPt  qr,
int  handID 
)

Sets the hand/gripper's configuration of a robot with the configuration contained in a std::vector. The rest of the robot configuration is set from a configPt.

Parameters:
robotpointer to the robot
handPropgeometric information about the hand
configa std::vector containing the finger joint parameters associated to the grasp
qrdesired complete configuration vector of the robot (only the non-hand part will be used)
handIDID of the hand used by the grasp
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSet_hand_rest_configuration ( p3d_rob robot,
gpHand_properties handProp,
int  handID 
)

Sets the hand/gripper configuration of a robot to a "rest" configuration. It only modifies the parameters of the hand. NB: The finger joints require to have specific names (see graspPlanning.h).

Parameters:
robotpointer to the robot
handinformation concerning the hand
handIDthe hand to set (in case there are several): 0 by default
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSet_hand_rest_configuration ( p3d_rob robot,
gpHand_properties handProp,
configPt  q,
int  handID 
)

Sets the hand/gripper configuration of a robot to a "rest" configuration. The rest of the robot configuration is set from a configPt. NB: The finger joints require to have specific names (see graspPlanning.h).

Parameters:
robotpointer to the robot
handinformation concerning the hand
qdesired complete configuration vector of the robot (only the non-hand part will be used)
handIDthe hand to set (in case there are several): 0 by default
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSet_platform_configuration ( p3d_rob robot,
double  x,
double  y,
double  theta 
)

Sets the robot's platform configuration to the given values. The robot must have a joint of type P3D_FREEFLYER or P3D_PLAN with the name defined in GP_PLATFORMJOINT (see graspPlanning.h).

Parameters:
robotpointer to the robot
xdesired X position
ydesired Y position
thetadesired orientation around Z-axis
Returns:
GP_OK in case of success, GP_ERROR otherwise
int gpSet_SAHfinger_joint_angles ( p3d_rob robot,
gpHand_properties hand,
double  q[4],
int  finger_index,
int  handID 
)

Sets the joint angles of the SAHand fingers and update its current configuration.

Parameters:
robotthe robot (that must have joint with the appropriate names (see graspPlanning.h))
handstructure containing information about the hand geometry
qarray containing the finger joint parameters (angles in radians). Except for the thumb, only the three last elements are used.
finger_indexindex of the chosen finger (1= thumb, 2= forefinger, 3= middlefinger, 4= ringfinger)
Returns:
GP_OK in case of success, GP_ERROR otherwise
double gpTetrahedron_volume ( p3d_vector3  d,
p3d_vector3  a,
p3d_vector3  b,
p3d_vector3  c 
)

Calcule le volume d'un tetraedre dont les sommets sont les points a, b, c, d. On a les formules suivantes: volume= (1/6)*| det(a-b,b-c,c-d) | et volume= (1/6)*| (a-b).((b-c)x(c-d)) | Computes the signed volume of the tetrahedron defined by the points d, a, b and c. The formula is | xa-xd ya-yd za-zd | volume= (1/6)*| xb-xd yb-yd zb-zd | | xc-xd yc-yd zc-zd |

p3d_plane gpTransform_plane_equation ( p3d_matrix4  T,
p3d_plane  plane 
)

A partir de l'equation d'un plan "plane", definie pour des coordonnees exprimees dans le repere de matrice de transformation T, retourne l'equation du plan dans le repere global.

double gpTriangle_area ( p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  p3 
)

Cette fonction calcule et retourne l'aire du triangle (p1p2p3). Elle utilise la formule de Heron d'Alexandrie.

int gpTriangle_plane_intersection ( p3d_vector3  p1,
p3d_vector3  p2,
p3d_vector3  p3,
p3d_plane  plane,
p3d_vector3  result1,
p3d_vector3  result2 
)

Cette fonction calcule l'intersection entre le triangle p1p2p3 et un plan. Elle retourne le nombre d'intersections (0, 1, 2 ou 3 (triangle dans le plan)). NB: le cas d'une seule intersection correspond a la situation où seul un des sommets du triangle appartient au plan. Si on a 3 intersections, les intersections sont les points d'origine du triangle. Computes the intersection between a triangle and a plane.

Parameters:
p1first point of the triangle
p2second point of the triangle
p3third point of the triangle
planethe plane's equation
result1the first intersection (if it exists)
result2the second intersection (if it exists)
Returns:
the number of intersections (0, 1, 2 or 3 (the triangle is in the plane))
void logfile ( const char *  format,
  ... 
)

Cette fonction s'utilise comme un printf mais ecrit dans le fichier logfile. La premiere fois qu'elle est appelee, elle ecrase le contenu precedent du fichier. This function is used like a printf but writes in a file named "logfile". The first time it is called, the previous content of the file is erased.

p3d_polyhedre* p3d_copy_polyhedre ( p3d_polyhedre *  polyhedron)

Cree un p3d_polyhedre identique a celui donne en parametre.

int p3d_display_face ( p3d_polyhedre *  polyhedron,
unsigned int  index 
)

Affiche la face d'indice "index" du polyedre. L'indice doit être compris entre 0 et nb_faces-1 A utiliser dans une fonction d'affichage OpenGL.

int p3d_get_obj_pos ( p3d_obj o,
p3d_matrix4  pose 
)

This function just gets the pose of the given object.

void p3d_matrix4_to_OpenGL_format ( p3d_matrix4  source,
GLfloat  mat[16] 
)

Writes the content of the p3d_matrix4 in a float array with the format used by OpenGL (when calling a function like glLoadMatrix or glMultMatrix).

int p3d_print_face_neighbours ( p3d_polyhedre *  polyhedron,
char *  filename 
)

Ecrit dans un fichier les indices des triangles voisins de chaque face du polyedre.

int p3d_save_in_OBJ_format ( p3d_polyhedre *  polyhedron,
char *  name 
)

Enregistre au format .obj (format wavefront), une structure p3d_polyhedre.

int solve_trigonometric_equation ( double  a,
double  b,
double  c,
double *  x1,
double *  x2 
)

Solves the trigonometric equation a*cos(x) + b*sin(x)= c where a,b and c are given and x is the unknown.

Parameters:
afirst parameter of the equation to solve
bsecond parameter of the equation to solve
cthird parameter of the equation to solve
x1pointer to where the first solution (if it exists) will be copied
x2pointer to where the second solution (if it exists) will be copied
Returns:
the number of solutions of the equation (0, 1 or 2)
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines