valves.h
Go to the documentation of this file.
00001 
00027 #ifndef VALVES_H_
00028 #define VALVES_H_
00029 
00030 #include <robot/config.h>
00031 #include <robot/robot.h>
00032 #include <robot/hand.h>
00033 #include <robot/hand_protocol.h>
00034 #include <ros/ros.h>
00035 
00036 #include <std_msgs/Float64.h>
00037 
00038 namespace shadowrobot
00039 {
00040 
00041   class Valves
00042   {
00043   public:
00047     Valves();
00049     ~Valves();
00050 
00051     void publish();
00052 
00053   private:
00054     void valve_command(const std_msgs::Float64ConstPtr& msg, int index_valve);
00055 
00056     std::vector<struct sensor> valves_sensors;
00057 
00058     std::vector<ros::Publisher> valves_publishers;
00059     std::vector<ros::Subscriber> valves_subscribers;
00060 
00061     ros::NodeHandle n_tilde;
00062     ros::Rate publish_rate;
00063 
00064     void init_subs_and_pubs(int index_joint);
00065   };
00066 
00067 }//end namespace
00068 
00069 #endif /* VALVES_H_ */
00070 
00071 /* For the emacs weenies in the crowd.
00072 Local Variables:
00073    c-basic-offset: 2
00074 End:
00075 */
00076 


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