#include <sr_gazebo_virtual_tactile_sensor.hpp>
Public Member Functions | |
SrGazeboVirtualTactileSensor (std::string name, std::string gazebo_topic) | |
~SrGazeboVirtualTactileSensor () | |
Protected Member Functions | |
virtual double | get_touch_data () |
Private Member Functions | |
void | callback (const gazebo_plugins::ContactsState &msg) |
Private Attributes | |
ros::NodeHandle | nh |
ros::Subscriber | sub |
bool | touch_freshdata |
boost::mutex | touch_mutex |
double | touch_value |
Definition at line 42 of file sr_gazebo_virtual_tactile_sensor.hpp.
shadowrobot::SrGazeboVirtualTactileSensor::SrGazeboVirtualTactileSensor | ( | std::string | name, |
std::string | gazebo_topic | ||
) |
Definition at line 38 of file sr_gazebo_virtual_tactile_sensor.cpp.
Definition at line 47 of file sr_gazebo_virtual_tactile_sensor.cpp.
void shadowrobot::SrGazeboVirtualTactileSensor::callback | ( | const gazebo_plugins::ContactsState & | msg | ) | [private] |
Callback function called when a msg is received on the gazebo bumper topic.
msg | the message containing the contact data |
Definition at line 50 of file sr_gazebo_virtual_tactile_sensor.cpp.
double shadowrobot::SrGazeboVirtualTactileSensor::get_touch_data | ( | ) | [protected, virtual] |
Generates a value for the sensor
Implements shadowrobot::SrGenericTactileSensor.
Definition at line 83 of file sr_gazebo_virtual_tactile_sensor.cpp.
Definition at line 57 of file sr_gazebo_virtual_tactile_sensor.hpp.
Definition at line 62 of file sr_gazebo_virtual_tactile_sensor.hpp.
bool shadowrobot::SrGazeboVirtualTactileSensor::touch_freshdata [private] |
Definition at line 60 of file sr_gazebo_virtual_tactile_sensor.hpp.
boost::mutex shadowrobot::SrGazeboVirtualTactileSensor::touch_mutex [private] |
Definition at line 58 of file sr_gazebo_virtual_tactile_sensor.hpp.
double shadowrobot::SrGazeboVirtualTactileSensor::touch_value [private] |
Definition at line 59 of file sr_gazebo_virtual_tactile_sensor.hpp.