libmove3d  3.13.0
/home/slemaign/softs-local/BioMove3D-git/graspPlanning/include/gpPlacement.h
00001 #ifndef GP_PLACEMENT_H
00002 #define GP_PLACEMENT_H
00003 
00004 
00005 #include "../graspPlanning/include/graspPlanning.h"
00006 #include "../graspPlanning/include/gpContact.h"
00007 
00011 
00012 
00016 typedef enum gpTriangle_description
00017 {
00018   GP_DESCRIPTION_INDICES, 
00019   GP_DESCRIPTION_POINTS,
00020   GP_DESCRIPTION_BOTH 
00021 } gpTriangle_description;
00022 
00023 
00026 class gpTriangle
00027 {
00028   public:
00031    unsigned int i1, i2, i3;
00033    p3d_vector3 p1, p2, p3;
00034    gpTriangle_description description;
00035 
00036    gpTriangle();
00037    unsigned int operator [] (unsigned int i) const;
00038    unsigned int & operator [] (unsigned int i);
00039    gpTriangle(const gpTriangle &triangle);
00040    gpTriangle& operator=(const gpTriangle &triangle);
00041 };
00042 
00043 
00044 
00052 class gpPlacement
00053 {
00054  public:
00055   int ID;  
00056   p3d_plane plane; 
00057   p3d_vector3 center; 
00058   double stability; 
00059   double clearance; 
00061 
00062   p3d_matrix4 T;
00063 
00065   p3d_vector3 position;
00067   double theta; 
00068 
00069   p3d_polyhedre *polyhedron;  
00070   p3d_rob *object;  
00071   std::string object_name;  
00072   std::vector<gpContact> contacts; 
00073 
00074   gpPlacement();
00075   gpPlacement(const gpPlacement &placement);
00076   ~gpPlacement();
00077   gpPlacement & operator=(const gpPlacement &placement);
00078   bool operator < (const gpPlacement &placement);
00079   int computePoseMatrix(p3d_matrix4 pose); 
00080   int print();
00081   int draw(double length);
00082 };
00083 
00084 bool gpCompareStability(const gpPlacement &place1, const gpPlacement &place2); 
00085 bool gpCompareClearance(const gpPlacement &place1, const gpPlacement &place2); 
00086 
00087 extern int gpCompute_stable_placements(p3d_rob *object, std::list<gpPlacement> &placementList);
00088 
00089 extern 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);
00090 
00091 extern int gpFind_placement_from_base_configuration(p3d_rob *robot, p3d_rob *object, std::list<gpPlacement> &placementList, gpArm_type arm_type, configPt qbase, class gpGrasp &grasp, gpHand_properties &hand, double distance, configPt qpreplacement, configPt qplacement, gpPlacement &placement);
00092 
00093 extern int gpCompute_placement_clearances(p3d_rob *object, std::list<p3d_rob*> robotList, std::list<gpPlacement> &placementList);
00094 
00095 extern int gpPlacement_on_support_filter(p3d_rob *object, p3d_rob *support, std::list<gpPlacement> placementListIn, std::list<gpPlacement> &placementListOut);
00096 
00097 #endif
00098 
00099 
00100 
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Friends Defines