27 #ifndef _SHADOW_PSTS_HPP_ 28 #define _SHADOW_PSTS_HPP_ 32 #include <sr_robot_msgs/ShadowPST.h> 35 #include <sr_hardware_interface/tactile_sensors.hpp> 41 template<
class StatusType,
class CommandType>
47 std::vector<generic_updater::UpdateConfig> update_configs_vector,
51 std::vector<generic_updater::UpdateConfig> update_configs_vector,
55 void init(std::vector<generic_updater::UpdateConfig> update_configs_vector,
65 virtual void update(StatusType *status_data);
77 virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
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)
boost::shared_ptr< std::vector< PST3Data > > tactiles_vector
the vector containing the data for the tactiles.
ShadowPSTs(ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
virtual void update(StatusType *status_data)