00001 #ifndef __IR_CONTROLLER_NODE_H__ 00002 #define __IR_CONTROLLER_NODE_H__ 00003 00027 #include <ros/ros.h> 00028 #include "ir_driver_interface.h" 00029 00030 // messages and services 00031 #include <ir_controller_msgs/GetTvAction.h> 00032 #include <ir_controller_msgs/TvActions.h> 00033 #include <ir_controller_msgs/SetTvAction.h> 00034 00035 class IRControllerNode { 00036 public: 00041 IRControllerNode(IrDriverInterface *ir_driver); 00042 00046 ~IRControllerNode(); 00047 00053 void init(); 00054 00060 void spin(); 00061 00063 // publishers 00065 00069 void publish(std::string command); 00070 00072 // services 00074 00081 bool send_command(ir_controller_msgs::SetTvAction::Request & req, 00082 ir_controller_msgs::SetTvAction::Response & resp); 00083 00084 private: 00085 ros::NodeHandle _nh; 00086 ros::NodeHandle _nh_private; 00087 00088 ros::Publisher _action_pub; 00089 00090 ros::ServiceServer _action_srv; 00091 00092 ros::Rate _publish_rate; 00093 00094 IrDriverInterface *_ir_driver; 00095 00096 bool _is_on; 00097 }; 00098 00099 #endif