shadowrobot::SrGenericTactileSensor Class Reference

#include <sr_generic_tactile_sensor.hpp>

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

List of all members.

Public Member Functions

void publish_current_values ()
 SrGenericTactileSensor (std::string name, std::string touch_name)
 ~SrGenericTactileSensor ()

Protected Member Functions

virtual double get_touch_data ()=0

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 40 of file sr_generic_tactile_sensor.hpp.


Constructor & Destructor Documentation

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

Definition at line 35 of file sr_generic_tactile_sensor.cpp.

shadowrobot::SrGenericTactileSensor::~SrGenericTactileSensor (  ) 

Definition at line 44 of file sr_generic_tactile_sensor.cpp.


Member Function Documentation

virtual double shadowrobot::SrGenericTactileSensor::get_touch_data (  )  [protected, pure virtual]

Needs to be implemented in the inheriting class

Returns:
the pressure value

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

void shadowrobot::SrGenericTactileSensor::publish_current_values (  ) 

publish the current values to the correct ros topics

Definition at line 47 of file sr_generic_tactile_sensor.cpp.


Member Data Documentation

Definition at line 64 of file sr_generic_tactile_sensor.hpp.

Definition at line 62 of file sr_generic_tactile_sensor.hpp.

Definition at line 61 of file sr_generic_tactile_sensor.hpp.

Definition at line 63 of file sr_generic_tactile_sensor.hpp.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables


sr_tactile_sensors
Author(s): Ugo Cupcic
autogenerated on Fri Jan 11 09:41:20 2013