#include <shadow_PSTs.hpp>
Public Member Functions | |
virtual void | add_diagnostics (std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d) |
virtual std::vector< AllTactileData > * | get_tactile_data () |
void | init (std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state) |
virtual void | publish () |
ShadowPSTs (ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state) | |
ShadowPSTs (ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state, boost::shared_ptr< std::vector< GenericTactileData > > init_tactiles_vector) | |
virtual void | update (StatusType *status_data) |
Public Member Functions inherited from tactiles::GenericTactiles< StatusType, CommandType > | |
GenericTactiles (ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state) | |
bool | reset (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response) |
virtual | ~GenericTactiles () |
Public Attributes | |
boost::shared_ptr< std::vector< PST3Data > > | tactiles_vector |
the vector containing the data for the tactiles. More... | |
Public Attributes inherited from tactiles::GenericTactiles< StatusType, CommandType > | |
boost::shared_ptr< generic_updater::SensorUpdater< CommandType > > | sensor_updater |
boost::shared_ptr< std::vector< GenericTactileData > > | tactiles_vector |
the vector containing the data for the tactiles. More... | |
Additional Inherited Members | |
Static Public Attributes inherited from tactiles::GenericTactiles< StatusType, CommandType > | |
static const unsigned int | nb_tactiles = 5 |
Number of tactile sensors (TODO: should probably be defined in the protocol) More... | |
Protected Member Functions inherited from tactiles::GenericTactiles< StatusType, CommandType > | |
void | process_received_data_type (int32u data) |
std::string | sanitise_string (const char *raw_string, const unsigned int str_size) |
Protected Attributes inherited from tactiles::GenericTactiles< StatusType, CommandType > | |
boost::shared_ptr< std::vector< AllTactileData > > | all_tactile_data |
std::string | device_id_ |
std::vector< int32u > | initialization_received_data_vector |
ros::NodeHandle | nodehandle_ |
ros::ServiceServer | reset_service_client_ |
Definition at line 42 of file shadow_PSTs.hpp.
tactiles::ShadowPSTs< StatusType, CommandType >::ShadowPSTs | ( | ros::NodeHandle | nh, |
std::string | device_id, | ||
std::vector< generic_updater::UpdateConfig > | update_configs_vector, | ||
operation_mode::device_update_state::DeviceUpdateState | update_state | ||
) |
Definition at line 37 of file shadow_PSTs.cpp.
tactiles::ShadowPSTs< StatusType, CommandType >::ShadowPSTs | ( | ros::NodeHandle | nh, |
std::string | device_id, | ||
std::vector< generic_updater::UpdateConfig > | update_configs_vector, | ||
operation_mode::device_update_state::DeviceUpdateState | update_state, | ||
boost::shared_ptr< std::vector< GenericTactileData > > | init_tactiles_vector | ||
) |
Definition at line 47 of file shadow_PSTs.cpp.
|
virtual |
Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.
Definition at line 185 of file shadow_PSTs.cpp.
|
virtual |
Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.
Definition at line 214 of file shadow_PSTs.cpp.
void tactiles::ShadowPSTs< StatusType, CommandType >::init | ( | std::vector< generic_updater::UpdateConfig > | update_configs_vector, |
operation_mode::device_update_state::DeviceUpdateState | update_state | ||
) |
Definition at line 63 of file shadow_PSTs.cpp.
|
virtual |
Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.
Definition at line 179 of file shadow_PSTs.cpp.
|
virtual |
Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.
Definition at line 78 of file shadow_PSTs.cpp.
boost::shared_ptr<std::vector<PST3Data> > tactiles::ShadowPSTs< StatusType, CommandType >::tactiles_vector |
the vector containing the data for the tactiles.
Definition at line 81 of file shadow_PSTs.hpp.