28 #include <sr_utilities/sr_math_utils.hpp> 32 #define TACTILE_DATA_LENGTH_BYTES TACTILE_DATA_LENGTH_BYTES_v2 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>
47 std::vector<generic_updater::UpdateConfig> update_configs_vector,
50 :
GenericTactiles<StatusType, CommandType>(nh, device_id, update_configs_vector, update_state)
52 init(update_configs_vector, update_state);
54 for (
unsigned int i = 0; i < this->
nb_tactiles; i++)
56 UBI0Data tmp_pst(init_tactiles_vector->at(i));
61 template<
class StatusType,
class CommandType>
72 new std::vector<AllTactileData>(this->
nb_tactiles));
83 template<
class StatusType,
class CommandType>
86 int tactile_mask =
static_cast<int16u>(status_data->tactile_data_valid);
88 for (
unsigned int id_sensor = 0; id_sensor < this->
nb_tactiles; ++id_sensor)
91 switch (static_cast<int32u>(status_data->tactile_data_type))
95 for (
unsigned int i = 0; i <
tactiles_vector->at(id_sensor).distal.size(); ++i)
98 static_cast<int>(
static_cast<int16u>(status_data->tactile[id_sensor].word[i]));
100 for (
unsigned int i = 0; i <
tactiles_vector->at(id_sensor).middle.size(); ++i)
103 static_cast<int>(
static_cast<int16u>(status_data->tactile_mid_prox[id_sensor].named.middle[i]));
105 for (
unsigned int i = 0; i <
tactiles_vector->at(id_sensor).proximal.size(); ++i)
108 static_cast<int>(
static_cast<int16u>(status_data->tactile_mid_prox[id_sensor].named.proximal[i]));
114 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
117 static_cast<unsigned int>(
static_cast<int16u>(status_data->tactile[id_sensor].word[0]));
123 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
133 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
142 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
144 tactiles_vector->at(id_sensor).set_software_version(status_data->tactile[id_sensor].string);
149 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
161 for (
unsigned int i = 0; i <
palm_tactiles->palm.size(); ++i)
163 palm_tactiles->palm[i] =
static_cast<int>(
static_cast<int16u>(status_data->aux_spi_sensor.sensor[i]));
169 if (this->
sensor_updater->initialization_configs_vector.size() == 0)
176 template<
class StatusType,
class CommandType>
193 template<
class StatusType,
class CommandType>
197 for (
unsigned int id_tact = 0; id_tact < this->
nb_tactiles; ++id_tact)
199 std::stringstream ss;
202 ss << prefix <<
"Tactile " << id_tact + 1;
204 d.name = ss.str().c_str();
212 d.
addf(
"Software Version",
"%s",
tactiles_vector->at(id_tact).get_software_version().c_str());
219 template<
class StatusType,
class CommandType>
TACTILE_SENSOR_TYPE_SOFTWARE_VERSION
void summary(unsigned char lvl, const std::string s)
TACTILE_SENSOR_TYPE_MANUFACTURER
UBI0(ros::NodeHandle nh, std::string device_id, 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 update(StatusType *status_data)
static const unsigned int nb_tactiles
Number of tactile sensors (TODO: should probably be defined in the protocol)
#define TACTILE_DATA_LENGTH_BYTES
TACTILE_SENSOR_TYPE_UBI0_TACTILE
void addf(const std::string &key, const char *format,...)
boost::shared_ptr< generic_updater::SensorUpdater< CommandType > > sensor_updater
void init(std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
boost::shared_ptr< UBI0PalmData > palm_tactiles
the object containing the data from the palm sensors
TACTILE_SENSOR_TYPE_SERIAL_NUMBER
boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::AuxSpiData > > aux_spi_publisher
boost::shared_ptr< std::vector< UBI0Data > > tactiles_vector
the vector containing the data for the tactiles.
TACTILE_SENSOR_TYPE_PCB_VERSION
void process_received_data_type(int32u 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)
virtual void add_diagnostics(std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
ros::NodeHandle nodehandle_