$search
#include <valves.h>
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 |
Definition at line 41 of file valves.h.
shadowrobot::Valves::Valves | ( | ) |
Initializes the necessary mappings with a static list of names.
Definition at line 36 of file valves.cpp.
shadowrobot::Valves::~Valves | ( | ) |
destructor
Definition at line 73 of file valves.cpp.
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.
void shadowrobot::Valves::publish | ( | ) |
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.
msg | the msg containing a value to send to a valve controller. | |
index_valve | the index of the valve in the valves_sensors vector. |
Definition at line 172 of file valves.cpp.
ros::NodeHandle shadowrobot::Valves::n_tilde [private] |
ros::Rate shadowrobot::Valves::publish_rate [private] |
std::vector<ros::Publisher> shadowrobot::Valves::valves_publishers [private] |
std::vector<struct sensor> shadowrobot::Valves::valves_sensors [private] |
std::vector<ros::Subscriber> shadowrobot::Valves::valves_subscribers [private] |