sr_virtual_tactile_sensor.hpp
Go to the documentation of this file.
00001 
00029 #ifndef _SR_VIRTUAL_TACTILE_SENSOR_HPP_
00030 #define _SR_VIRTUAL_TACTILE_SENSOR_HPP_
00031 
00032 #include <ros/ros.h>
00033 
00034 #include <boost/thread.hpp>
00035 
00036 #include "sr_tactile_sensors/sr_generic_tactile_sensor.hpp"
00037 
00038 #include <sr_robot_msgs/joints_data.h>
00039 #include <sr_robot_msgs/joint.h>
00040 
00041 namespace shadowrobot
00042 {
00043   class SrVirtualTactileSensor : public SrGenericTactileSensor
00044   {
00045   public:
00057     SrVirtualTactileSensor(std::string name, std::string touch_name);
00058     ~SrVirtualTactileSensor();
00059 
00065     virtual double get_touch_data();
00066 
00067   private:
00068     ros::NodeHandle nh;
00069     boost::mutex touch_mutex;
00070     double touch_value;
00071 
00075     std::vector<std::string> names_joints_linked;
00080     ros::Subscriber sub;
00089     void callback(const sr_robot_msgs::joints_dataConstPtr& msg);
00090   };
00091 
00092   class SrVirtualTactileSensorManager : public SrTactileSensorManager
00093   {
00094   public:
00095     SrVirtualTactileSensorManager();
00096     ~SrVirtualTactileSensorManager();
00097   };
00098 }
00099 
00100 /* For the emacs weenies in the crowd.
00101 Local Variables:
00102    c-basic-offset: 2
00103 End:
00104 */
00105 
00106 #endif


sr_tactile_sensors
Author(s): Ugo Cupcic
autogenerated on Mon Oct 6 2014 07:59:56