#include <sr_generic_tactile_sensor.hpp>

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 |
Definition at line 46 of file sr_generic_tactile_sensor.hpp.
| shadowrobot::SrGenericTactileSensor::SrGenericTactileSensor | ( | std::string | name, |
| std::string | touch_name | ||
| ) |
Definition at line 38 of file sr_generic_tactile_sensor.cpp.
|
virtual |
Definition at line 47 of file sr_generic_tactile_sensor.cpp.
|
pure virtual |
Needs to be implemented in the inheriting class
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.
|
private |
Definition at line 70 of file sr_generic_tactile_sensor.hpp.
|
private |
Definition at line 68 of file sr_generic_tactile_sensor.hpp.
|
private |
Definition at line 67 of file sr_generic_tactile_sensor.hpp.
|
private |
Definition at line 69 of file sr_generic_tactile_sensor.hpp.