shadowrobot::Valves Class Reference

#include <valves.h>

List of all members.

Public Member Functions

void publish ()
 Valves ()
 ~Valves ()
 destructor

Private Member Functions

void init_subs_and_pubs (int index_joint)
void valve_command (const std_msgs::Float64ConstPtr &msg, int index_valve)

Private Attributes

ros::NodeHandle n_tilde
ros::Rate publish_rate
std::vector< ros::Publisher > valves_publishers
std::vector< struct sensor > valves_sensors
std::vector< ros::Subscriber > valves_subscribers

Detailed Description

Definition at line 39 of file valves.h.


Constructor & Destructor Documentation

shadowrobot::Valves::Valves (  ) 

Initializes the necessary mappings with a static list of names.

Definition at line 29 of file valves.cpp.

shadowrobot::Valves::~Valves (  ) 

destructor

Definition at line 66 of file valves.cpp.


Member Function Documentation

void shadowrobot::Valves::init_subs_and_pubs ( int  index_joint  )  [private]

for the old hand the phalange 4 only used the spring and the Ext only

Definition at line 70 of file valves.cpp.

void shadowrobot::Valves::publish (  ) 

Callback function for the periodic publishing: publishes the data for each valve.

Definition at line 175 of file valves.cpp.

void shadowrobot::Valves::valve_command ( const std_msgs::Float64ConstPtr &  msg,
int  index_valve 
) [private]

callback function for the valves: send a command to a given valve.

we have on subscriber per valve. The subscriber index corresponds to the index_valve. From this index_valve you can get the valve sensor from the valves_sensors vector.

Parameters:
msg the msg containing a value to send to a valve controller.
index_valve the index of the valve in the valves_sensors vector.
Returns:

Definition at line 165 of file valves.cpp.


Member Data Documentation

ros::NodeHandle shadowrobot::Valves::n_tilde [private]

Definition at line 56 of file valves.h.

ros::Rate shadowrobot::Valves::publish_rate [private]

Definition at line 57 of file valves.h.

std::vector<ros::Publisher> shadowrobot::Valves::valves_publishers [private]

Definition at line 53 of file valves.h.

std::vector<struct sensor> shadowrobot::Valves::valves_sensors [private]

Definition at line 51 of file valves.h.

std::vector<ros::Subscriber> shadowrobot::Valves::valves_subscribers [private]

Definition at line 54 of file valves.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator


sr_hand
Author(s): Ugo Cupcic / ugo@shadowrobot.com, contact@shadowrobot.com
autogenerated on Fri Jan 11 09:32:58 2013