Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Protected Attributes
tactiles::GenericTactiles Class Reference

#include <generic_tactiles.hpp>

Inheritance diagram for tactiles::GenericTactiles:
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 (ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *status_data)
 ~GenericTactiles ()

Public Attributes

boost::shared_ptr
< generic_updater::SensorUpdater
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

Definition at line 53 of file generic_tactiles.hpp.


Constructor & Destructor Documentation

Definition at line 36 of file generic_tactiles.cpp.

Definition at line 57 of file generic_tactiles.hpp.


Member Function Documentation

void tactiles::GenericTactiles::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::Biotac, and tactiles::ShadowPSTs.

Definition at line 149 of file generic_tactiles.cpp.

Reimplemented in tactiles::Biotac, and tactiles::ShadowPSTs.

Definition at line 193 of file generic_tactiles.cpp.

Definition at line 133 of file generic_tactiles.cpp.

Publish the information to a ROS topic.

Reimplemented in tactiles::Biotac, and tactiles::ShadowPSTs.

Definition at line 144 of file generic_tactiles.cpp.

bool tactiles::GenericTactiles::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 163 of file generic_tactiles.cpp.

std::string tactiles::GenericTactiles::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 172 of file generic_tactiles.cpp.

void tactiles::GenericTactiles::update ( ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *  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::Biotac, and tactiles::ShadowPSTs.

Definition at line 56 of file generic_tactiles.cpp.


Member Data Documentation

Definition at line 124 of file generic_tactiles.hpp.

Contains the received data types.

Definition at line 110 of file generic_tactiles.hpp.

const unsigned int tactiles::GenericTactiles::nb_tactiles = 5 [static]

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

Definition at line 93 of file generic_tactiles.hpp.

Definition at line 105 of file generic_tactiles.hpp.

Definition at line 107 of file generic_tactiles.hpp.

Definition at line 95 of file generic_tactiles.hpp.

the vector containing the data for the tactiles.

Reimplemented in tactiles::Biotac, and tactiles::ShadowPSTs.

Definition at line 97 of file generic_tactiles.hpp.


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


sr_robot_lib
Author(s): Ugo Cupcic / ugo@shadowrobot.com , software@shadowrobot.com
autogenerated on Thu Jan 2 2014 12:02:17