Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 #ifndef GRASP_GENERATOR_H
00036 #define GRASP_GENERATOR_H
00037 
00038 #include <boost/shared_ptr.hpp>
00039 
00040 #include <ros/ros.h>
00041 
00042 #include <object_manipulation_msgs/GraspableObject.h>
00043 #include <object_manipulation_msgs/Grasp.h>
00044 #include <household_objects_database_msgs/DatabaseModelPose.h>
00045 #include <household_objects_database/objects_database.h>
00046 #include "household_objects_database/database_grasp.h"
00047 #include "household_objects_database/database_perturbation.h"
00048 #include "bayesian_grasp_planner/bayesian_grasp_planner_tools.h"
00049 
00050 namespace bayesian_grasp_planner {
00051 
00052 class GraspGenerator
00053 {
00054 protected:
00055   std::vector<GraspWM> grasps_;
00056  
00057 public:
00058   virtual void generateGrasps() = 0;
00059 
00060   const std::vector<GraspWM> & getGrasps() {return grasps_;}
00061 
00062   void getGrasps(std::vector<GraspWM> &grasps)
00063   {
00064     grasps.insert( grasps.end(), grasps_.begin(), grasps_.end());
00065   }
00066 
00067 };
00068 
00069 class GraspGeneratorServiceCaller : public GraspGenerator
00070 {
00071 private:
00072   ros::ServiceClient service_;
00073   const object_manipulation_msgs::GraspableObject object_;
00074   const std::string arm_name_;
00075   const std::string service_name_;
00076 
00077   void appendMetadataToGrasps(std::vector<object_manipulation_msgs::Grasp> &grasp_msgs,
00078                               std::vector<GraspWM> &grasps);
00079 
00080 public:
00081   GraspGeneratorServiceCaller(ros::NodeHandle &nh, const std::string service_name, 
00082                               const object_manipulation_msgs::GraspableObject &graspable_object,
00083                               const std::string arm_name);
00084 
00085   void generateGrasps();
00086 };
00087 
00088 class GraspGeneratorDatabaseRetriever : public GraspGenerator
00089 {
00090 private:
00091   boost::shared_ptr<household_objects_database::ObjectsDatabase> database_;
00092   household_objects_database_msgs::DatabaseModelPose model_;
00093   const std::string arm_name_;
00094 
00095   void appendMetadataToGrasps(const std::vector<household_objects_database::DatabaseGraspPtr> &db_grasps,
00096                        std::vector<GraspWM> &grasps);
00097 
00098   bool cluster_reps_;
00099 
00100 public:
00101   GraspGeneratorDatabaseRetriever(boost::shared_ptr<household_objects_database::ObjectsDatabase> database,
00102                                   household_objects_database_msgs::DatabaseModelPose model, const std::string arm_name,
00103                                   bool cluster_reps);
00104 
00105   void generateGrasps();
00106 };
00107 
00108 
00109 }
00110 
00111 
00112 #endif