00001 00024 #ifndef PUMA_MOTOR_DRIVER_MULTI_DRIVER_NODE_H 00025 #define PUMA_MOTOR_DRIVER_MULTI_DRIVER_NODE_H 00026 00027 #include <stdint.h> 00028 #include <string> 00029 #include <vector> 00030 #include <ros/ros.h> 00031 00032 #include "puma_motor_driver/driver.h" 00033 #include "puma_motor_msgs/MultiStatus.h" 00034 #include "puma_motor_msgs/Status.h" 00035 #include "puma_motor_msgs/MultiFeedback.h" 00036 #include "puma_motor_msgs/Feedback.h" 00037 00038 namespace puma_motor_driver 00039 { 00040 class MultiDriverNode 00041 { 00042 public: 00043 MultiDriverNode(ros::NodeHandle& nh, std::vector<puma_motor_driver::Driver>& drivers); 00044 00045 void publishFeedback(); 00046 void publishStatus(); 00047 void feedbackTimerCb(const ros::TimerEvent&); 00048 void statusTimerCb(const ros::TimerEvent&); 00049 void activePublishers(bool activate); 00050 00051 private: 00052 ros::NodeHandle nh_; 00053 std::vector<puma_motor_driver::Driver>& drivers_; 00054 00055 puma_motor_msgs::MultiStatus status_msg_; 00056 puma_motor_msgs::MultiFeedback feedback_msg_; 00057 00058 ros::Publisher status_pub_; 00059 ros::Publisher feedback_pub_; 00060 00061 ros::Timer status_pub_timer_; 00062 ros::Timer feedback_pub_timer_; 00063 00064 bool active_; 00065 }; 00066 00067 } // namespace puma_motor_driver 00068 00069 #endif // PUMA_MOTOR_DRIVER_MULTI_DRIVER_NODE_H