Public Member Functions | Private Attributes | List of all members
shadowrobot::SrGenericTactileSensor Class Referenceabstract

#include <sr_generic_tactile_sensor.hpp>

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

Public Member Functions

virtual double get_touch_data ()=0
 
void publish_current_values ()
 
 SrGenericTactileSensor (std::string name, std::string touch_name)
 
virtual ~SrGenericTactileSensor ()
 

Private Attributes

std_msgs::Float64 msg_touch
 
ros::NodeHandle n_tilde
 
ros::Publisher touch_pub
 
std::string touch_sensor_name
 

Detailed Description

Definition at line 46 of file sr_generic_tactile_sensor.hpp.

Constructor & Destructor Documentation

shadowrobot::SrGenericTactileSensor::SrGenericTactileSensor ( std::string  name,
std::string  touch_name 
)

Definition at line 38 of file sr_generic_tactile_sensor.cpp.

shadowrobot::SrGenericTactileSensor::~SrGenericTactileSensor ( )
virtual

Definition at line 47 of file sr_generic_tactile_sensor.cpp.

Member Function Documentation

virtual double shadowrobot::SrGenericTactileSensor::get_touch_data ( )
pure virtual

Needs to be implemented in the inheriting class

Returns
the pressure value

Implemented in shadowrobot::SrVirtualTactileSensor, shadowrobot::SrRealTactileSensor, and shadowrobot::SrGazeboVirtualTactileSensor.

void shadowrobot::SrGenericTactileSensor::publish_current_values ( )

publish the current values to the correct ros topics

Definition at line 51 of file sr_generic_tactile_sensor.cpp.

Member Data Documentation

std_msgs::Float64 shadowrobot::SrGenericTactileSensor::msg_touch
private

Definition at line 70 of file sr_generic_tactile_sensor.hpp.

ros::NodeHandle shadowrobot::SrGenericTactileSensor::n_tilde
private

Definition at line 68 of file sr_generic_tactile_sensor.hpp.

ros::Publisher shadowrobot::SrGenericTactileSensor::touch_pub
private

Definition at line 67 of file sr_generic_tactile_sensor.hpp.

std::string shadowrobot::SrGenericTactileSensor::touch_sensor_name
private

Definition at line 69 of file sr_generic_tactile_sensor.hpp.


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


sr_tactile_sensors
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:46