00001 00013 #ifndef RAIL_PICK_AND_PLACE_GRASP_MODEL_RETRIEVER_H_ 00014 #define RAIL_PICK_AND_PLACE_GRASP_MODEL_RETRIEVER_H_ 00015 00016 // ROS 00017 #include <actionlib/server/simple_action_server.h> 00018 #include <graspdb/graspdb.h> 00019 #include <rail_pick_and_place_msgs/RetrieveGraspModelAction.h> 00020 #include <ros/ros.h> 00021 00022 namespace rail 00023 { 00024 namespace pick_and_place 00025 { 00026 00035 class GraspModelRetriever 00036 { 00037 public: 00043 GraspModelRetriever(); 00044 00050 virtual ~GraspModelRetriever(); 00051 00059 bool okay() const; 00060 00061 private: 00069 void retrieveGraspModel(const rail_pick_and_place_msgs::RetrieveGraspModelGoalConstPtr &goal); 00070 00072 bool okay_; 00074 graspdb::Client *graspdb_; 00075 00077 ros::NodeHandle node_, private_node_; 00079 actionlib::SimpleActionServer<rail_pick_and_place_msgs::RetrieveGraspModelAction> as_; 00081 ros::Publisher point_cloud_pub_, poses_pub_; 00082 }; 00083 00084 } 00085 } 00086 00087 #endif