sr_generic_tactile_sensor.hpp
Go to the documentation of this file.
00001 
00030 #ifndef _SR_GENERIC_TACTILE_SENSOR_HPP_
00031 #define _SR_GENERIC_TACTILE_SENSOR_HPP_
00032 
00033 #include <ros/ros.h>
00034 
00035 #include <boost/smart_ptr.hpp>
00036 #include <std_msgs/Float64.h>
00037 #include <XmlRpcValue.h>
00038 #include <sr_robot_msgs/is_hand_occupied.h>
00039 #include <sr_robot_msgs/which_fingers_are_touching.h>
00040 
00041 namespace shadowrobot
00042 {
00043   class SrGenericTactileSensor
00044   {
00045   public:
00046     SrGenericTactileSensor(std::string name, std::string touch_name);
00047     ~SrGenericTactileSensor();
00048 
00053     void publish_current_values();
00054 
00060     virtual double get_touch_data() = 0;
00061 
00062   private:
00063     ros::Publisher touch_pub;
00064     ros::NodeHandle n_tilde;
00065     std::string touch_sensor_name;
00066     std_msgs::Float64 msg_touch;
00067   };
00068 
00069   class SrTactileSensorManager
00070   {
00071   public:
00072     SrTactileSensorManager();
00073     ~SrTactileSensorManager();
00074 
00079     void publish_all();
00080 
00081   protected:
00082     std::vector<boost::shared_ptr<SrGenericTactileSensor> > tactile_sensors;
00083     ros::NodeHandle n_tilde;
00084     ros::Rate publish_rate;
00085 
00086     ros::ServiceServer is_hand_occupied_server;
00087     std::vector<double> is_hand_occupied_thresholds;
00100     bool is_hand_occupied_cb(sr_robot_msgs::is_hand_occupied::Request  &req,
00101                              sr_robot_msgs::is_hand_occupied::Response &res );
00102 
00103     ros::ServiceServer which_fingers_are_touching_server;
00114     bool which_fingers_are_touching_cb(sr_robot_msgs::which_fingers_are_touching::Request  &req,
00115                                        sr_robot_msgs::which_fingers_are_touching::Response &res );
00116 
00128     std::vector<std::vector<std::string> > get_all_names();
00129   };
00130 }
00131 
00132 
00133 /* For the emacs weenies in the crowd.
00134 Local Variables:
00135    c-basic-offset: 2
00136 End:
00137 */
00138 
00139 #endif


sr_tactile_sensors
Author(s): Ugo Cupcic
autogenerated on Fri Jan 3 2014 12:09:36