#include <biotac.hpp>
Public Member Functions | |
virtual void | add_diagnostics (std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d) |
Biotac (ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state) | |
Biotac (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 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 () |
void | set_version_specific_details () |
virtual void | update (StatusType *status_data) |
Protected Attributes | |
size_t | nb_electrodes_ |
boost::shared_ptr< std::vector < BiotacData > > | tactiles_vector |
the vector containing the data for the tactiles. | |
Static Protected Attributes | |
static const size_t | nb_electrodes_v1_ = 19 |
static const size_t | nb_electrodes_v2_ = 24 |
Definition at line 43 of file biotac.hpp.
tactiles::Biotac< StatusType, CommandType >::Biotac | ( | 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 45 of file biotac.cpp.
tactiles::Biotac< StatusType, CommandType >::Biotac | ( | 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 54 of file biotac.cpp.
void tactiles::Biotac< StatusType, CommandType >::add_diagnostics | ( | std::vector< diagnostic_msgs::DiagnosticStatus > & | vec, |
diagnostic_updater::DiagnosticStatusWrapper & | d | ||
) | [virtual] |
This function adds the diagnostics for the tactiles to the multi diagnostic status published by the hand.
Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.
Definition at line 382 of file biotac.cpp.
std::vector< AllTactileData > * tactiles::Biotac< StatusType, CommandType >::get_tactile_data | ( | ) | [virtual] |
Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.
Definition at line 408 of file biotac.cpp.
void tactiles::Biotac< StatusType, CommandType >::init | ( | std::vector< generic_updater::UpdateConfig > | update_configs_vector, |
operation_mode::device_update_state::DeviceUpdateState | update_state | ||
) |
This function is called in the constructors, to initialize the necessary objects
Definition at line 72 of file biotac.cpp.
void tactiles::Biotac< StatusType, CommandType >::publish | ( | ) | [virtual] |
Publish the information to a ROS topic.
Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.
Definition at line 376 of file biotac.cpp.
void tactiles::Biotac< StatusType, CommandType >::set_version_specific_details | ( | ) |
Definition at line 419 of file biotac.cpp.
void tactiles::Biotac< StatusType, CommandType >::update | ( | StatusType * | status_data | ) | [virtual] |
This function is called each time a new etherCAT message is received in the sr06.cpp driver. It updates the tactile sensors values contained in tactiles_vector.
status_data | the received etherCAT message |
Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.
Definition at line 87 of file biotac.cpp.
size_t tactiles::Biotac< StatusType, CommandType >::nb_electrodes_ [protected] |
Definition at line 91 of file biotac.hpp.
const size_t tactiles::Biotac< StatusType, CommandType >::nb_electrodes_v1_ = 19 [static, protected] |
Definition at line 93 of file biotac.hpp.
const size_t tactiles::Biotac< StatusType, CommandType >::nb_electrodes_v2_ = 24 [static, protected] |
Definition at line 94 of file biotac.hpp.
boost::shared_ptr<std::vector<BiotacData> > tactiles::Biotac< StatusType, CommandType >::tactiles_vector [protected] |
the vector containing the data for the tactiles.
Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.
Definition at line 89 of file biotac.hpp.