Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
shadowrobot::SrGazeboVirtualTactileSensor Class Reference

#include <sr_gazebo_virtual_tactile_sensor.hpp>

Inheritance diagram for shadowrobot::SrGazeboVirtualTactileSensor:
Inheritance graph
[legend]

Public Member Functions

 SrGazeboVirtualTactileSensor (std::string name, std::string gazebo_topic)
 
virtual ~SrGazeboVirtualTactileSensor ()
 
- Public Member Functions inherited from shadowrobot::SrGenericTactileSensor
void publish_current_values ()
 
 SrGenericTactileSensor (std::string name, std::string touch_name)
 
virtual ~SrGenericTactileSensor ()
 

Protected Member Functions

virtual double get_touch_data ()
 

Private Member Functions

void callback (const gazebo_msgs::ContactsState &msg)
 

Private Attributes

ros::NodeHandle nh
 
ros::Subscriber sub
 
bool touch_freshdata
 
boost::mutex touch_mutex
 
double touch_value
 

Detailed Description

Definition at line 43 of file sr_gazebo_virtual_tactile_sensor.hpp.

Constructor & Destructor Documentation

◆ SrGazeboVirtualTactileSensor()

shadowrobot::SrGazeboVirtualTactileSensor::SrGazeboVirtualTactileSensor ( std::string  name,
std::string  gazebo_topic 
)

Definition at line 39 of file sr_gazebo_virtual_tactile_sensor.cpp.

◆ ~SrGazeboVirtualTactileSensor()

shadowrobot::SrGazeboVirtualTactileSensor::~SrGazeboVirtualTactileSensor ( )
virtual

Definition at line 48 of file sr_gazebo_virtual_tactile_sensor.cpp.

Member Function Documentation

◆ callback()

void shadowrobot::SrGazeboVirtualTactileSensor::callback ( const gazebo_msgs::ContactsState &  msg)
private

Callback function called when a msg is received on the gazebo bumper topic.

Parameters
msgthe message containing the contact data

Definition at line 52 of file sr_gazebo_virtual_tactile_sensor.cpp.

◆ get_touch_data()

double shadowrobot::SrGazeboVirtualTactileSensor::get_touch_data ( )
protectedvirtual

Generates a value for the sensor

Returns
the pressure value

Implements shadowrobot::SrGenericTactileSensor.

Definition at line 85 of file sr_gazebo_virtual_tactile_sensor.cpp.

Member Data Documentation

◆ nh

ros::NodeHandle shadowrobot::SrGazeboVirtualTactileSensor::nh
private

Definition at line 60 of file sr_gazebo_virtual_tactile_sensor.hpp.

◆ sub

ros::Subscriber shadowrobot::SrGazeboVirtualTactileSensor::sub
private

Definition at line 65 of file sr_gazebo_virtual_tactile_sensor.hpp.

◆ touch_freshdata

bool shadowrobot::SrGazeboVirtualTactileSensor::touch_freshdata
private

Definition at line 63 of file sr_gazebo_virtual_tactile_sensor.hpp.

◆ touch_mutex

boost::mutex shadowrobot::SrGazeboVirtualTactileSensor::touch_mutex
private

Definition at line 61 of file sr_gazebo_virtual_tactile_sensor.hpp.

◆ touch_value

double shadowrobot::SrGazeboVirtualTactileSensor::touch_value
private

Definition at line 62 of file sr_gazebo_virtual_tactile_sensor.hpp.


The documentation for this class was generated from the following files:


sr_tactile_sensors
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:14