valves.h
Go to the documentation of this file.
1 
27 #ifndef SR_HAND_HAND_VALVES_H
28 #define SR_HAND_HAND_VALVES_H
29 
30 #include <robot/config.h>
31 #include <robot/robot.h>
32 #include <robot/hand.h>
33 #include <robot/hand_protocol.h>
34 #include <ros/ros.h>
35 #include <vector>
36 
37 #include <std_msgs/Float64.h>
38 
39 namespace shadowrobot
40 {
41 class Valves
42 {
43 public:
47  Valves();
48 
50  ~Valves();
51 
52  void publish();
53 
54 private:
55  void valve_command(const std_msgs::Float64ConstPtr &msg, int index_valve);
56 
57  std::vector<struct sensor> valves_sensors;
58 
59  std::vector <ros::Publisher> valves_publishers;
60  std::vector <ros::Subscriber> valves_subscribers;
61 
64 
65  void init_subs_and_pubs(int index_joint);
66 };
67 
68 } // namespace shadowrobot
69 
70 #endif // SR_HAND_HAND_VALVES_H
71 
72 /* For the emacs weenies in the crowd.
73 Local Variables:
74  c-basic-offset: 2
75 End:
76 */
77 
msg
ros::Rate publish_rate
Definition: valves.h:63
~Valves()
destructor
Definition: valves.cpp:74
std::vector< ros::Subscriber > valves_subscribers
Definition: valves.h:60
void valve_command(const std_msgs::Float64ConstPtr &msg, int index_valve)
Definition: valves.cpp:182
std::vector< struct sensor > valves_sensors
Definition: valves.h:57
ros::NodeHandle n_tilde
Definition: valves.h:62
std::vector< ros::Publisher > valves_publishers
Definition: valves.h:59
void init_subs_and_pubs(int index_joint)
Definition: valves.cpp:78


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