Public Member Functions | Protected Attributes | List of all members
tactiles::UBI0< StatusType, CommandType > Class Template Reference

#include <UBI0.hpp>

Inheritance diagram for tactiles::UBI0< StatusType, CommandType >:
Inheritance graph
[legend]

Public Member Functions

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)
 
virtual void publish ()
 
 UBI0 (ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
 
 UBI0 (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 void update (StatusType *status_data)
 
- Public Member Functions inherited from tactiles::GenericTactiles< StatusType, CommandType >
 GenericTactiles (ros::NodeHandle nh, std::string device_id, std::vector< generic_updater::UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
 
bool reset (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 
virtual ~GenericTactiles ()
 

Protected Attributes

boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::AuxSpiData > > aux_spi_publisher
 
boost::shared_ptr< UBI0PalmData > palm_tactiles
 the object containing the data from the palm sensors More...
 
boost::shared_ptr< std::vector< UBI0Data > > tactiles_vector
 the vector containing the data for the tactiles. More...
 
- Protected Attributes inherited from tactiles::GenericTactiles< StatusType, CommandType >
boost::shared_ptr< std::vector< AllTactileData > > all_tactile_data
 
std::string device_id_
 
std::vector< int32uinitialization_received_data_vector
 
ros::NodeHandle nodehandle_
 
ros::ServiceServer reset_service_client_
 

Additional Inherited Members

- Public Attributes inherited from tactiles::GenericTactiles< StatusType, CommandType >
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. More...
 
- Static Public Attributes inherited from tactiles::GenericTactiles< StatusType, CommandType >
static const unsigned int nb_tactiles = 5
 Number of tactile sensors (TODO: should probably be defined in the protocol) More...
 
- Protected Member Functions inherited from tactiles::GenericTactiles< StatusType, CommandType >
void process_received_data_type (int32u data)
 
std::string sanitise_string (const char *raw_string, const unsigned int str_size)
 

Detailed Description

template<class StatusType, class CommandType>
class tactiles::UBI0< StatusType, CommandType >

Definition at line 45 of file UBI0.hpp.

Constructor & Destructor Documentation

template<class StatusType , class CommandType >
tactiles::UBI0< StatusType, CommandType >::UBI0 ( 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 37 of file UBI0.cpp.

template<class StatusType , class CommandType >
tactiles::UBI0< StatusType, CommandType >::UBI0 ( 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 46 of file UBI0.cpp.

Member Function Documentation

template<class StatusType , class CommandType >
void tactiles::UBI0< StatusType, CommandType >::add_diagnostics ( std::vector< diagnostic_msgs::DiagnosticStatus > &  vec,
diagnostic_updater::DiagnosticStatusWrapper d 
)
virtual

Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.

Definition at line 194 of file UBI0.cpp.

template<class StatusType , class CommandType >
std::vector< AllTactileData > * tactiles::UBI0< StatusType, CommandType >::get_tactile_data ( )
virtual

Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.

Definition at line 220 of file UBI0.cpp.

template<class StatusType , class CommandType >
void tactiles::UBI0< StatusType, CommandType >::init ( std::vector< generic_updater::UpdateConfig update_configs_vector,
operation_mode::device_update_state::DeviceUpdateState  update_state 
)

Definition at line 62 of file UBI0.cpp.

template<class StatusType , class CommandType >
void tactiles::UBI0< StatusType, CommandType >::publish ( )
virtual

Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.

Definition at line 177 of file UBI0.cpp.

template<class StatusType , class CommandType >
void tactiles::UBI0< StatusType, CommandType >::update ( StatusType *  status_data)
virtual

Reimplemented from tactiles::GenericTactiles< StatusType, CommandType >.

Definition at line 84 of file UBI0.cpp.

Member Data Documentation

template<class StatusType , class CommandType >
boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::AuxSpiData> > tactiles::UBI0< StatusType, CommandType >::aux_spi_publisher
protected

Definition at line 95 of file UBI0.hpp.

template<class StatusType , class CommandType >
boost::shared_ptr<UBI0PalmData> tactiles::UBI0< StatusType, CommandType >::palm_tactiles
protected

the object containing the data from the palm sensors

Definition at line 92 of file UBI0.hpp.

template<class StatusType , class CommandType >
boost::shared_ptr<std::vector<UBI0Data> > tactiles::UBI0< StatusType, CommandType >::tactiles_vector
protected

the vector containing the data for the tactiles.

Definition at line 89 of file UBI0.hpp.


The documentation for this class was generated from the following files:


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Tue Oct 13 2020 04:01:58