ptu_manager.h
Go to the documentation of this file.
1 
18 #ifndef PTU_MANAGER_H
19 #define PTU_MANAGER_H
20 
21 #ifndef Q_MOC_RUN
22 #include <ros/ros.h>
23 #include <ptu_controller/PTUController.h>
24 #endif
25 #include <QObject>
26 
27 class PTU_Manager : public QObject
28 {
29  Q_OBJECT
30 
31 public:
33  bool setStartPose();
34  bool nextPose();
35  bool setNeutralPose();
36  void ptu_callback(double pan, double tilt);
37  void sendJoint(double pan, double tilt, bool wait);
38  double getPan();
39  double getTilt();
40 signals:
41  void ptu_moved(double pan, double tilt);
42 protected:
43  double pan_min_angle;
44  double pan_max_angle;
47  double pan_stepsize;
48  double tilt_stepsize;
51 
52  double currentPan;
53  double currentTilt;
54 
55  int pan_step;
56  int tilt_step;
58  asr_flir_ptu_controller::PTUController* controller;
59  //PTUMovementEndedCallbackPtr callbackPtr;
60 };
61 
62 
63 
64 #endif // PTU_MANAGER_H
double getTilt()
void ptu_moved(double pan, double tilt)
int pan_step_count
Definition: ptu_manager.h:49
double pan_min_angle
Definition: ptu_manager.h:43
asr_flir_ptu_controller::PTUController * controller
Definition: ptu_manager.h:58
double pan_stepsize
Definition: ptu_manager.h:47
void sendJoint(double pan, double tilt, bool wait)
Definition: ptu_manager.cpp:86
bool setStartPose()
Definition: ptu_manager.cpp:51
double pan_max_angle
Definition: ptu_manager.h:44
bool nextPose()
Definition: ptu_manager.cpp:65
double tilt_stepsize
Definition: ptu_manager.h:48
double currentPan
Definition: ptu_manager.h:52
double getPan()
Definition: ptu_manager.cpp:99
double tilt_min_angle
Definition: ptu_manager.h:45
void ptu_callback(double pan, double tilt)
Definition: ptu_manager.cpp:44
int tilt_step_count
Definition: ptu_manager.h:50
double currentTilt
Definition: ptu_manager.h:53
int pan_step_add
Definition: ptu_manager.h:57
double tilt_max_angle
Definition: ptu_manager.h:46
bool setNeutralPose()
Definition: ptu_manager.cpp:59
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)
Definition: ptu_manager.cpp:27


asr_mild_calibration_tool
Author(s): Aumann Florian, Heller Florian, Meißner Pascal
autogenerated on Mon Dec 2 2019 03:11:43