00001 #ifndef __EYELIDS_NODE_H__ 00002 #define __EYELIDS_NODE_H__ 00003 00027 #include <termios.h> 00028 #include <ros/ros.h> 00029 #include "eyelids_data.h" 00030 #include "serial_communication_interface.h" 00031 00032 // messages and services 00033 #include <eyelids_msgs/EyelidPositions.h> 00034 #include <eyelids_msgs/MoveStrPos.h> 00035 #include <motor_controller_msgs/MoveAbsPos.h> 00036 00037 class EyelidsNode { 00038 public: 00043 EyelidsNode(SerialCommunicationInterface *serial_comm); 00044 00048 ~EyelidsNode(); 00049 00055 void init(); 00056 00062 void spin(); 00063 00065 // services 00067 00074 bool move_abs_pos(motor_controller_msgs::MoveAbsPos::Request & req, motor_controller_msgs::MoveAbsPos::Response & resp); 00075 00082 bool move_str_pos(eyelids_msgs::MoveStrPos::Request & req, eyelids_msgs::MoveStrPos::Response & resp); 00083 00085 // methods 00087 00093 int move(int position); 00094 00095 private: 00096 // nodes 00097 ros::NodeHandle _nh; 00098 ros::NodeHandle _nh_private; 00099 00100 // publishers 00101 ros::Publisher _get_position_msg; 00102 00103 // services 00104 ros::ServiceServer _move_abs_pos_srv; 00105 ros::ServiceServer _move_str_pos_srv; 00106 00107 // spin rate 00108 ros::Rate _publish_rate; 00109 00110 // serial communication 00111 SerialCommunicationInterface *_serial_comm; 00112 struct termios _oldtio; 00113 00114 // left or right eye 00115 std::string _side; 00116 }; 00117 00118 #endif