Main Page
Classes
Files
File List
File Members
include
CameraUtils
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
:
32
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
);
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
;
45
double
tilt_min_angle
;
46
double
tilt_max_angle
;
47
double
pan_stepsize
;
48
double
tilt_stepsize
;
49
int
pan_step_count
;
50
int
tilt_step_count
;
51
52
double
currentPan
;
53
double
currentTilt
;
54
55
int
pan_step
;
56
int
tilt_step
;
57
int
pan_step_add
;
58
asr_flir_ptu_controller::PTUController*
controller
;
59
//PTUMovementEndedCallbackPtr callbackPtr;
60
};
61
62
63
64
#endif // PTU_MANAGER_H
PTU_Manager::getTilt
double getTilt()
Definition:
ptu_manager.cpp:104
PTU_Manager::ptu_moved
void ptu_moved(double pan, double tilt)
PTU_Manager::pan_step_count
int pan_step_count
Definition:
ptu_manager.h:49
PTU_Manager::pan_step
int pan_step
Definition:
ptu_manager.h:55
PTU_Manager::pan_min_angle
double pan_min_angle
Definition:
ptu_manager.h:43
PTU_Manager::controller
asr_flir_ptu_controller::PTUController * controller
Definition:
ptu_manager.h:58
PTU_Manager::tilt_step
int tilt_step
Definition:
ptu_manager.h:56
PTU_Manager::pan_stepsize
double pan_stepsize
Definition:
ptu_manager.h:47
PTU_Manager::sendJoint
void sendJoint(double pan, double tilt, bool wait)
Definition:
ptu_manager.cpp:86
PTU_Manager::setStartPose
bool setStartPose()
Definition:
ptu_manager.cpp:51
PTU_Manager::pan_max_angle
double pan_max_angle
Definition:
ptu_manager.h:44
PTU_Manager::nextPose
bool nextPose()
Definition:
ptu_manager.cpp:65
PTU_Manager::tilt_stepsize
double tilt_stepsize
Definition:
ptu_manager.h:48
PTU_Manager::currentPan
double currentPan
Definition:
ptu_manager.h:52
PTU_Manager::getPan
double getPan()
Definition:
ptu_manager.cpp:99
ros.h
PTU_Manager::tilt_min_angle
double tilt_min_angle
Definition:
ptu_manager.h:45
PTU_Manager::ptu_callback
void ptu_callback(double pan, double tilt)
Definition:
ptu_manager.cpp:44
PTU_Manager::tilt_step_count
int tilt_step_count
Definition:
ptu_manager.h:50
PTU_Manager
Definition:
ptu_manager.h:27
PTU_Manager::currentTilt
double currentTilt
Definition:
ptu_manager.h:53
PTU_Manager::pan_step_add
int pan_step_add
Definition:
ptu_manager.h:57
PTU_Manager::tilt_max_angle
double tilt_max_angle
Definition:
ptu_manager.h:46
PTU_Manager::setNeutralPose
bool setNeutralPose()
Definition:
ptu_manager.cpp:59
PTU_Manager::PTU_Manager
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