Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Protected Attributes
tactiles::GenericTactiles< StatusType, CommandType > Class Template Reference

#include <generic_tactiles.hpp>

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

List of all members.

Public Member Functions

virtual void add_diagnostics (std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
 GenericTactiles (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 publish ()
bool reset (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
virtual void update (StatusType *status_data)
virtual ~GenericTactiles ()

Public Attributes

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.

Static Public Attributes

static const unsigned int nb_tactiles = 5
 Number of tactile sensors (TODO: should probably be defined in the protocol)

Protected Member Functions

void process_received_data_type (int32u data)
std::string sanitise_string (const char *raw_string, const unsigned int str_size)

Protected Attributes

boost::shared_ptr< std::vector
< AllTactileData > > 
all_tactile_data
std::vector< int32uinitialization_received_data_vector
 Contains the received data types.
ros::NodeHandle nodehandle_
ros::ServiceServer reset_service_client_

Detailed Description

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

Definition at line 56 of file generic_tactiles.hpp.


Constructor & Destructor Documentation

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

Definition at line 43 of file generic_tactiles.cpp.

template<class StatusType, class CommandType>
virtual tactiles::GenericTactiles< StatusType, CommandType >::~GenericTactiles ( ) [inline, virtual]

Definition at line 60 of file generic_tactiles.hpp.


Member Function Documentation

template<class StatusType , class CommandType >
void tactiles::GenericTactiles< 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 in tactiles::UBI0< StatusType, CommandType >, tactiles::Biotac< StatusType, CommandType >, and tactiles::ShadowPSTs< StatusType, CommandType >.

Definition at line 159 of file generic_tactiles.cpp.

template<class StatusType , class CommandType >
std::vector< AllTactileData > * tactiles::GenericTactiles< StatusType, CommandType >::get_tactile_data ( ) [virtual]
template<class StatusType , class CommandType >
void tactiles::GenericTactiles< StatusType, CommandType >::process_received_data_type ( int32u  data) [protected]

Definition at line 141 of file generic_tactiles.cpp.

template<class StatusType , class CommandType >
void tactiles::GenericTactiles< StatusType, CommandType >::publish ( ) [virtual]
template<class StatusType , class CommandType >
bool tactiles::GenericTactiles< StatusType, CommandType >::reset ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)

Reset the tactile sensors.

Parameters:
requestempty
responseempty
Returns:
true if success

Definition at line 174 of file generic_tactiles.cpp.

template<class StatusType , class CommandType >
std::string tactiles::GenericTactiles< StatusType, CommandType >::sanitise_string ( const char *  raw_string,
const unsigned int  str_size 
) [protected]

Sanitise a string coming from the palm. Make sure we're not outputting garbage in the diagnostics topic. The acceptable range for the char is [0x20 .. 0x7E]

Parameters:
raw_stringThe incoming raw string
str_sizeThe max size of the string
Returns:
The sanitised string.

Definition at line 183 of file generic_tactiles.cpp.

template<class StatusType, class CommandType >
void tactiles::GenericTactiles< 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.

Parameters:
status_datathe received etherCAT message

Reimplemented in tactiles::UBI0< StatusType, CommandType >, tactiles::Biotac< StatusType, CommandType >, and tactiles::ShadowPSTs< StatusType, CommandType >.

Definition at line 63 of file generic_tactiles.cpp.


Member Data Documentation

template<class StatusType, class CommandType>
boost::shared_ptr<std::vector<AllTactileData> > tactiles::GenericTactiles< StatusType, CommandType >::all_tactile_data [protected]

Definition at line 127 of file generic_tactiles.hpp.

template<class StatusType, class CommandType>
std::vector<int32u> tactiles::GenericTactiles< StatusType, CommandType >::initialization_received_data_vector [protected]

Contains the received data types.

Definition at line 113 of file generic_tactiles.hpp.

template<class StatusType, class CommandType>
const unsigned int tactiles::GenericTactiles< StatusType, CommandType >::nb_tactiles = 5 [static]

Number of tactile sensors (TODO: should probably be defined in the protocol)

Definition at line 96 of file generic_tactiles.hpp.

template<class StatusType, class CommandType>
ros::NodeHandle tactiles::GenericTactiles< StatusType, CommandType >::nodehandle_ [protected]

Definition at line 108 of file generic_tactiles.hpp.

template<class StatusType, class CommandType>
ros::ServiceServer tactiles::GenericTactiles< StatusType, CommandType >::reset_service_client_ [protected]

Definition at line 110 of file generic_tactiles.hpp.

template<class StatusType, class CommandType>
boost::shared_ptr<generic_updater::SensorUpdater<CommandType> > tactiles::GenericTactiles< StatusType, CommandType >::sensor_updater

Definition at line 98 of file generic_tactiles.hpp.

template<class StatusType, class CommandType>
boost::shared_ptr< std::vector<GenericTactileData> > tactiles::GenericTactiles< StatusType, CommandType >::tactiles_vector

the vector containing the data for the tactiles.

Reimplemented in tactiles::UBI0< StatusType, CommandType >, tactiles::Biotac< StatusType, CommandType >, and tactiles::ShadowPSTs< StatusType, CommandType >.

Definition at line 100 of file generic_tactiles.hpp.


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


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Thu Aug 27 2015 15:16:37