Public Member Functions | Private Member Functions | Private Attributes
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::Publishervalves_publishers
std::vector< struct sensor > valves_sensors
std::vector< ros::Subscribervalves_subscribers

Detailed Description

Definition at line 41 of file valves.h.


Constructor & Destructor Documentation

Initializes the necessary mappings with a static list of names.

Definition at line 36 of file valves.cpp.

destructor

Definition at line 73 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 77 of file valves.cpp.

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

Definition at line 182 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:
msgthe msg containing a value to send to a valve controller.
index_valvethe index of the valve in the valves_sensors vector.
Returns:

Definition at line 172 of file valves.cpp.


Member Data Documentation

Definition at line 61 of file valves.h.

Definition at line 62 of file valves.h.

Definition at line 58 of file valves.h.

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

Definition at line 56 of file valves.h.

Definition at line 59 of file valves.h.


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


sr_hand
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:24:55