Public Member Functions | Private Member Functions | Private Attributes | List of all members
shadowrobot::Valves Class Reference

#include <valves.h>

Public Member Functions

void publish ()
 
 Valves ()
 
 ~Valves ()
 destructor More...
 

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

shadowrobot::Valves::Valves ( )

Initializes the necessary mappings with a static list of names.

Definition at line 38 of file valves.cpp.

shadowrobot::Valves::~Valves ( )

destructor

Definition at line 74 of file valves.cpp.

Member Function Documentation

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

Definition at line 78 of file valves.cpp.

void shadowrobot::Valves::publish ( )

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

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

Member Data Documentation

ros::NodeHandle shadowrobot::Valves::n_tilde
private

Definition at line 62 of file valves.h.

ros::Rate shadowrobot::Valves::publish_rate
private

Definition at line 63 of file valves.h.

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

Definition at line 59 of file valves.h.

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

Definition at line 57 of file valves.h.

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

Definition at line 60 of file valves.h.


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


sr_hand
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:53