sr_gazebo_virtual_tactile_sensor.hpp
Go to the documentation of this file.
00001 
00029 #ifndef _SR_GAZEBO_VIRTUAL_TACTILE_SENSOR_HPP_
00030 #define _SR_GAZEBO_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 <gazebo_plugins/ContactsState.h>
00039 
00040 namespace shadowrobot
00041 {
00042   class SrGazeboVirtualTactileSensor : public SrGenericTactileSensor
00043   {
00044   public:
00045     SrGazeboVirtualTactileSensor(std::string name, std::string gazebo_topic);
00046     ~SrGazeboVirtualTactileSensor();
00047 
00048   protected:
00054     virtual double get_touch_data();
00055 
00056   private:
00057     ros::NodeHandle nh;
00058     boost::mutex touch_mutex;
00059     double touch_value;
00060     bool touch_freshdata;
00061 
00062     ros::Subscriber sub;
00069     void callback(const gazebo_plugins::ContactsState& msg);
00070   };
00071 
00072   class SrGazeboVirtualTactileSensorManager : public SrTactileSensorManager
00073   {
00074   public:
00075     SrGazeboVirtualTactileSensorManager();
00076     ~SrGazeboVirtualTactileSensorManager();
00077   };
00078 }
00079 
00080 /* For the emacs weenies in the crowd.
00081 Local Variables:
00082    c-basic-offset: 2
00083 End:
00084 */
00085 
00086 #endif


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