#include <generic_tactiles.hpp>
Public Member Functions | |
virtual void | add_diagnostics (std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d) |
GenericTactiles (std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state) | |
virtual std::vector < AllTactileData > * | get_tactile_data () |
virtual void | publish () |
bool | reset (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response) |
virtual void | update (ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *status_data) |
~GenericTactiles () | |
Public Attributes | |
boost::shared_ptr < generic_updater::SensorUpdater > | sensor_updater |
boost::shared_ptr< std::vector < GenericTactileData > > | tactiles_vector |
the vector containing the data for the tactiles. | |
Static Public Attributes | |
static const unsigned int | nb_tactiles = 5 |
Number of tactile sensors (TODO: should probably be defined in the protocol) | |
Protected Member Functions | |
void | process_received_data_type (int32u data) |
std::string | sanitise_string (const char *raw_string, const unsigned int str_size) |
Protected Attributes | |
boost::shared_ptr< std::vector < AllTactileData > > | all_tactile_data |
std::vector< int32u > | initialization_received_data_vector |
Contains the received data types. | |
ros::NodeHandle | nodehandle_ |
ros::ServiceServer | reset_service_client_ |
Definition at line 53 of file generic_tactiles.hpp.
tactiles::GenericTactiles::GenericTactiles | ( | std::vector< generic_updater::UpdateConfig > | update_configs_vector, |
operation_mode::device_update_state::DeviceUpdateState | update_state | ||
) |
Definition at line 36 of file generic_tactiles.cpp.
tactiles::GenericTactiles::~GenericTactiles | ( | ) | [inline] |
Definition at line 57 of file generic_tactiles.hpp.
void tactiles::GenericTactiles::add_diagnostics | ( | std::vector< diagnostic_msgs::DiagnosticStatus > & | vec, |
diagnostic_updater::DiagnosticStatusWrapper & | d | ||
) | [virtual] |
This function adds the diagnostics for the tactiles to the multi diagnostic status published by the hand.
Reimplemented in tactiles::Biotac, and tactiles::ShadowPSTs.
Definition at line 149 of file generic_tactiles.cpp.
std::vector< AllTactileData > * tactiles::GenericTactiles::get_tactile_data | ( | ) | [virtual] |
Reimplemented in tactiles::Biotac, and tactiles::ShadowPSTs.
Definition at line 193 of file generic_tactiles.cpp.
void tactiles::GenericTactiles::process_received_data_type | ( | int32u | data | ) | [protected] |
Definition at line 133 of file generic_tactiles.cpp.
void tactiles::GenericTactiles::publish | ( | ) | [virtual] |
Publish the information to a ROS topic.
Reimplemented in tactiles::Biotac, and tactiles::ShadowPSTs.
Definition at line 144 of file generic_tactiles.cpp.
bool tactiles::GenericTactiles::reset | ( | std_srvs::Empty::Request & | request, |
std_srvs::Empty::Response & | response | ||
) |
Reset the tactile sensors.
request | empty |
response | empty |
Definition at line 163 of file generic_tactiles.cpp.
std::string tactiles::GenericTactiles::sanitise_string | ( | const char * | raw_string, |
const unsigned int | str_size | ||
) | [protected] |
Sanitise a string coming from the palm. Make sure we're not outputting garbage in the diagnostics topic. The acceptable range for the char is [0x20 .. 0x7E]
raw_string | The incoming raw string |
str_size | The max size of the string |
Definition at line 172 of file generic_tactiles.cpp.
void tactiles::GenericTactiles::update | ( | ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS * | status_data | ) | [virtual] |
This function is called each time a new etherCAT message is received in the sr06.cpp driver. It updates the tactile sensors values contained in tactiles_vector.
status_data | the received etherCAT message |
Reimplemented in tactiles::Biotac, and tactiles::ShadowPSTs.
Definition at line 56 of file generic_tactiles.cpp.
boost::shared_ptr<std::vector<AllTactileData> > tactiles::GenericTactiles::all_tactile_data [protected] |
Definition at line 124 of file generic_tactiles.hpp.
Contains the received data types.
Definition at line 110 of file generic_tactiles.hpp.
const unsigned int tactiles::GenericTactiles::nb_tactiles = 5 [static] |
Number of tactile sensors (TODO: should probably be defined in the protocol)
Definition at line 93 of file generic_tactiles.hpp.
Definition at line 105 of file generic_tactiles.hpp.
Definition at line 107 of file generic_tactiles.hpp.
boost::shared_ptr<generic_updater::SensorUpdater> tactiles::GenericTactiles::sensor_updater |
Definition at line 95 of file generic_tactiles.hpp.
boost::shared_ptr< std::vector<GenericTactileData> > tactiles::GenericTactiles::tactiles_vector |
the vector containing the data for the tactiles.
Reimplemented in tactiles::Biotac, and tactiles::ShadowPSTs.
Definition at line 97 of file generic_tactiles.hpp.