27 #ifndef GENERIC_TACTILES_HPP_ 28 #define GENERIC_TACTILES_HPP_ 30 #include <boost/smart_ptr.hpp> 44 #include <std_srvs/Empty.h> 46 #include <diagnostic_msgs/DiagnosticStatus.h> 49 #include <sr_hardware_interface/tactile_sensors.hpp> 55 template<
class StatusType,
class CommandType>
60 std::vector<generic_updater::UpdateConfig> update_configs_vector,
74 virtual void update(StatusType *status_data);
86 virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
97 bool reset(std_srvs::Empty::Request &request,
98 std_srvs::Empty::Response &response);
130 std::string
sanitise_string(
const char *raw_string,
const unsigned int str_size);
bool reset(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
static const unsigned int nb_tactiles
Number of tactile sensors (TODO: should probably be defined in the protocol)
virtual void update(StatusType *status_data)
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.
std::vector< int32u > initialization_received_data_vector
virtual std::vector< AllTactileData > * get_tactile_data()
virtual ~GenericTactiles()
GenericTactiles(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
void process_received_data_type(int32u data)
virtual void add_diagnostics(std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
boost::shared_ptr< std::vector< AllTactileData > > all_tactile_data
std::string sanitise_string(const char *raw_string, const unsigned int str_size)
ros::ServiceServer reset_service_client_
ros::NodeHandle nodehandle_