00001 00018 #ifndef PTU_MANAGER_H 00019 #define PTU_MANAGER_H 00020 00021 #ifndef Q_MOC_RUN 00022 #include <ros/ros.h> 00023 #include <ptu_controller/PTUController.h> 00024 #endif 00025 #include <QObject> 00026 00027 class PTU_Manager : public QObject 00028 { 00029 Q_OBJECT 00030 00031 public: 00032 PTU_Manager(double pan_min_angle, double pan_max_angle, double tilt_min_angle, double tilt_max_angle, int pan_step_count, int tilt_step_count); 00033 bool setStartPose(); 00034 bool nextPose(); 00035 bool setNeutralPose(); 00036 void ptu_callback(double pan, double tilt); 00037 void sendJoint(double pan, double tilt, bool wait); 00038 double getPan(); 00039 double getTilt(); 00040 signals: 00041 void ptu_moved(double pan, double tilt); 00042 protected: 00043 double pan_min_angle; 00044 double pan_max_angle; 00045 double tilt_min_angle; 00046 double tilt_max_angle; 00047 double pan_stepsize; 00048 double tilt_stepsize; 00049 int pan_step_count; 00050 int tilt_step_count; 00051 00052 double currentPan; 00053 double currentTilt; 00054 00055 int pan_step; 00056 int tilt_step; 00057 int pan_step_add; 00058 asr_flir_ptu_controller::PTUController* controller; 00059 //PTUMovementEndedCallbackPtr callbackPtr; 00060 }; 00061 00062 00063 00064 #endif // PTU_MANAGER_H