grasp_server.h
Go to the documentation of this file.
00001 
00008 #ifndef grasp_server_h___
00009 #define grasp_server_h___
00010 
00011 #include "ros/ros.h"
00012 #include <boost/thread/mutex.hpp>
00013 #include <boost/shared_ptr.hpp>
00014 #include "icr_msgs/SetObject.h"
00015 #include <vector>
00016 #include <string>
00017 #include "phalange.h"
00018 #include "tf/tf.h"
00019 #include <tf/transform_listener.h>
00020 
00021 namespace ICR
00022 {
00026 class GraspServer
00027 {
00028  public:
00029 
00030   GraspServer();
00031   ~GraspServer();
00032 
00036   void spin();
00037 
00038  private:
00039 
00040   ros::NodeHandle nh_, nh_private_;
00041   ros::ServiceServer set_obj_srv_;
00042   ros::Publisher grasp_pub_;  
00043   //ros::Publisher debug_pub_;//REMOVE  
00044   boost::mutex lock_;
00045   bool ref_set_;
00046    tf::TransformListener tf_list_;
00047   tf::StampedTransform palm_pose_;
00048 
00049 
00053   std::vector<Phalange*> phalanges_;
00054 
00056   //  CALLBACKS  //
00058 
00059   bool setObject(icr_msgs::SetObject::Request  &req, icr_msgs::SetObject::Response &res);
00060 };
00061 }//end namespace
00062 #endif


icr
Author(s): Robert Krug
autogenerated on Mon Jan 6 2014 11:36:10