28 #include <sr_utilities/sr_math_utils.hpp> 32 #define TACTILE_DATA_LENGTH_BYTES TACTILE_DATA_LENGTH_BYTES_v1 36 template<
class StatusType,
class CommandType>
38 std::vector<generic_updater::UpdateConfig> update_configs_vector,
40 :
GenericTactiles<StatusType, CommandType>(nh, device_id, update_configs_vector, update_state)
42 init(update_configs_vector, update_state);
45 template<
class StatusType,
class CommandType>
48 std::vector<generic_updater::UpdateConfig> update_configs_vector,
51 :
GenericTactiles<StatusType, CommandType>(nh, device_id, update_configs_vector, update_state)
53 init(update_configs_vector, update_state);
55 for (
unsigned int i = 0; i < this->
nb_tactiles; i++)
57 PST3Data tmp_pst(init_tactiles_vector->at(i));
62 template<
class StatusType,
class CommandType>
69 new std::vector<AllTactileData>(this->
nb_tactiles));
77 template<
class StatusType,
class CommandType>
80 int tactile_mask =
static_cast<int16u>(status_data->tactile_data_valid);
82 for (
unsigned int id_sensor = 0; id_sensor < this->
nb_tactiles; ++id_sensor)
84 switch (static_cast<int32u>(status_data->tactile_data_type))
88 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
91 static_cast<unsigned int>(
static_cast<int16u>(status_data->tactile[id_sensor].word[0]));
93 static_cast<unsigned int>(
static_cast<int16u>(status_data->tactile[id_sensor].word[1]));
95 static_cast<unsigned int>(
static_cast<int16u>(status_data->tactile[id_sensor].word[2]));
97 static_cast<unsigned int>(
static_cast<int16u>(status_data->tactile[id_sensor].word[3]));
102 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
105 static_cast<unsigned int>(
static_cast<int16u>(status_data->tactile[id_sensor].word[0]));
107 static_cast<unsigned int>(
static_cast<int16u>(status_data->tactile[id_sensor].word[1]));
112 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
115 static_cast<unsigned int>(
static_cast<int16u>(status_data->tactile[id_sensor].word[0]));
121 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
124 static_cast<unsigned int>(
static_cast<int16u>(status_data->tactile[id_sensor].word[0]));
130 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
140 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
149 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
151 tactiles_vector->at(id_sensor).set_software_version(status_data->tactile[id_sensor].string);
156 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
171 if (this->
sensor_updater->initialization_configs_vector.size() == 0)
178 template<
class StatusType,
class CommandType>
184 template <
class StatusType,
class CommandType>
188 for (
unsigned int id_tact = 0; id_tact < this->
nb_tactiles; ++id_tact)
190 std::stringstream ss;
192 ss << prefix <<
"Tactile " << id_tact + 1;
194 d.name = ss.str().c_str();
202 d.
addf(
"Software Version",
"%s",
tactiles_vector->at(id_tact).get_software_version().c_str());
213 template<
class StatusType,
class CommandType>
TACTILE_SENSOR_TYPE_PST3_PRESSURE_TEMPERATURE
TACTILE_SENSOR_TYPE_SOFTWARE_VERSION
void summary(unsigned char lvl, const std::string s)
TACTILE_SENSOR_TYPE_MANUFACTURER
virtual void add_diagnostics(std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
TACTILE_SENSOR_TYPE_PST3_DAC_VALUE
static const unsigned int nb_tactiles
Number of tactile sensors (TODO: should probably be defined in the protocol)
void addf(const std::string &key, const char *format,...)
boost::shared_ptr< generic_updater::SensorUpdater< CommandType > > sensor_updater
virtual std::vector< AllTactileData > * get_tactile_data()
TACTILE_SENSOR_TYPE_SERIAL_NUMBER
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)
TACTILE_SENSOR_TYPE_PST3_PRESSURE_RAW_ZERO_TRACKING
TACTILE_SENSOR_TYPE_PCB_VERSION
void process_received_data_type(int32u data)
virtual void update(StatusType *status_data)
TACTILE_SENSOR_TYPE_SAMPLE_FREQUENCY_HZ
boost::shared_ptr< std::vector< AllTactileData > > all_tactile_data
std::string sanitise_string(const char *raw_string, const unsigned int str_size)
#define TACTILE_DATA_LENGTH_BYTES