Go to the documentation of this file.00001 #ifndef GRASP_PLANNING_GRASPIT_ROS_EIGENGRASPPLANNERCLIENT_H
00002 #define GRASP_PLANNING_GRASPIT_ROS_EIGENGRASPPLANNERCLIENT_H
00003
00004 #include <ros/ros.h>
00005 #include <grasp_planning_graspit_msgs/LoadDatabaseModel.h>
00006 #include <grasp_planning_graspit_msgs/AddToDatabase.h>
00007 #include <moveit_msgs/GraspPlanning.h>
00008 #include <geometry_msgs/Pose.h>
00009
00010 namespace grasp_planning_graspit_ros
00011 {
00012
00023 class EigenGraspPlannerClient
00024 {
00025 public:
00026 EigenGraspPlannerClient();
00027 ~EigenGraspPlannerClient();
00028
00032 bool isOK();
00033
00043 int addRobot(const std::string& modelName, const std::string filename, const std::vector<std::string>& jointNames);
00044
00054 int addObject(const std::string& modelName, const std::string filename, bool objectGraspable);
00055
00066 int loadModel(const int modelID, bool clearWorld, const geometry_msgs::Pose& modelPose);
00067
00085 int plan(const std::string robotModelName, const int objectID,
00086 const geometry_msgs::Pose * newObjectPose, const std::string& resultsOutputDirectory,
00087 std::vector<moveit_msgs::Grasp>& results);
00088
00089 private:
00090
00091 void init();
00092
00093 bool initialized;
00094 std::string addToDBService;
00095 std::string loadModelService;
00096 std::string saveWorldService;
00097 std::string egPlanningService;
00098
00099 ros::NodeHandle node;
00100 ros::ServiceClient add_to_db_client, load_model_client, eg_planner_client;
00101
00102
00103 };
00104 }
00105 #endif // GRASP_PLANNING_GRASPIT_ROS_EIGENGRASPPLANNERCLIENT_H