QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
QGCCameraManager.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QElapsedTimer>
4#include <QtCore/QMap>
5#include <QtCore/QObject>
6#include <QtCore/QPointer>
7#include <QtCore/QTimer>
8#include <QtCore/QVariantList>
9#include <QtQmlIntegration/QtQmlIntegration>
10
11#include "MAVLinkMessageType.h"
12#include "QmlObjectListModel.h"
13
14class Vehicle;
15
16class CameraMetaData;
17class Joystick;
19class QGCCameraManagerTest;
22
25class QGCCameraManager : public QObject
26{
27 Q_OBJECT
28 QML_ELEMENT
29 QML_UNCREATABLE("")
30 Q_MOC_INCLUDE("Joystick.h")
31 Q_MOC_INCLUDE("MavlinkCameraControlInterface.h")
32
33 Q_PROPERTY(QmlObjectListModel* cameras READ cameras NOTIFY camerasChanged)
34 Q_PROPERTY(QStringList cameraLabels READ cameraLabels NOTIFY cameraLabelsChanged)
38
39#ifdef QGC_UNITTEST_BUILD
40 friend class QGCCameraManagerTest;
41#endif
42
43public:
46
47 struct CameraStruct {
48 CameraStruct(QGCCameraManager* manager_, uint8_t compID_, Vehicle* vehicle_);
50
51 bool infoReceived = false;
52 uint8_t compID = 0;
53 int retryCount = 0;
54 QElapsedTimer lastHeartbeat;
57 QPointer<QGCCameraManager> manager;
58
59 private:
60 Q_DISABLE_COPY_MOVE(CameraStruct)
61 };
62
63 QmlObjectListModel* cameras() { return &_cameras; }
64 const QmlObjectListModel* cameras() const { return &_cameras; }
65 QStringList cameraLabels() const { return _cameraLabels; }
66 int currentCamera() const { return _currentCameraIndex; }
68 void setCurrentCamera(int sel);
71
72 const QVariantList& cameraList() const;
73
74 Vehicle* vehicle() const { return _vehicle; }
75
76 CameraStruct* findCameraStruct(uint8_t compId) const { return _cameraInfoRequest.value(QString::number(compId), nullptr); }
77
78 int currentZoomLevel() const;
79 double aspectForComp(int compId) const;
80 double currentCameraAspect();
81 Q_INVOKABLE void requestCameraFovForComp(int compId);
82
83private:
84 int _zoomValueCurrent = 0;
85
86signals:
91
93
94protected slots:
95 void _vehicleReady(bool ready);
96 void _mavlinkMessageReceived(const mavlink_message_t& message);
97 void _activeJoystickChanged(Joystick* joystick);
98 void _stepZoom(int direction);
99 void _startZoom(int direction);
100 void _stopZoom();
101 void _stepFocus(int direction);
102 void _startFocus(int direction);
103 void _stopFocus();
104 void _stepCamera(int direction);
105 void _stepStream(int direction);
107 void _triggerCamera();
109 void _stopVideoRecording();
111
112private slots:
113 void _initialConnectCompleted();
114 void _setCurrentZoomLevel(int level);
115
116private:
117 MavlinkCameraControlInterface* _findCamera(int id);
118 void _requestCameraInfo(CameraStruct* cameraInfo);
119 void _handleHeartbeat(const mavlink_message_t& message);
120 void _handleCameraInfo(const mavlink_message_t& message);
121 void _handleStorageInformation(const mavlink_message_t& message);
122 void _handleCameraSettings(const mavlink_message_t& message);
123 void _handleParamExtAck(const mavlink_message_t& message);
124 void _handleParamExtValue(const mavlink_message_t& message);
125 void _handleCameraCaptureStatus(const mavlink_message_t& message);
126 void _handleVideoStreamInformation(const mavlink_message_t& message);
127 void _handleVideoStreamStatus(const mavlink_message_t& message);
128 void _handleBatteryStatus(const mavlink_message_t& message);
129 void _handleTrackingImageStatus(const mavlink_message_t& message);
130 void _addCameraControlToLists(MavlinkCameraControlInterface* cameraControl);
131 void _handleCameraFovStatus(const mavlink_message_t& message);
132
133 Vehicle* _vehicle;
134 QPointer<SimulatedCameraControl> _simulatedCameraControl;
135 QPointer<Joystick> _activeJoystick;
136 bool _vehicleReadyState = false;
137 int _currentTask = 0;
138 QmlObjectListModel _cameras;
139 QStringList _cameraLabels;
140 int _currentCameraIndex = 0;
141 QElapsedTimer _lastZoomChange;
142 QElapsedTimer _lastFocusChange;
143 QElapsedTimer _lastCameraChange;
144 QTimer _camerasLostHeartbeatTimer;
145 QMap<QString, CameraStruct*> _cameraInfoRequest;
146 static QVariantList _cameraList;
147 bool _initialConnectComplete = false;
148
149 QHash<int, double> _aspectByCompId;
150};
struct __mavlink_message mavlink_message_t
Set of meta data which describes a camera available on the vehicle.
Abstract base class for all camera controls: real and simulated.
Camera Manager.
void currentZoomLevelChanged()
void setCurrentCamera(int sel)
void _vehicleReady(bool ready)
const QVariantList & cameraList() const
Q_INVOKABLE void requestCameraFovForComp(int compId)
QmlObjectListModel * cameras()
void cameraLabelsChanged()
MavlinkCameraControlInterface * currentCameraInstance()
QGCVideoStreamInfo * currentStreamInstance()
void _stepZoom(int direction)
void _startZoom(int direction)
double aspectForComp(int compId) const
QGCVideoStreamInfo * thermalStreamInstance()
Vehicle * vehicle() const
void _mavlinkMessageReceived(const mavlink_message_t &message)
void currentCameraChanged()
void _stepFocus(int direction)
CameraStruct * findCameraStruct(uint8_t compId) const
int currentZoomLevel() const
void _stepCamera(int direction)
void _activeJoystickChanged(Joystick *joystick)
const QmlObjectListModel * cameras() const
void _stepStream(int direction)
void _startFocus(int direction)
QStringList cameraLabels() const
int currentCamera() const
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.
Creates a simulated Camera Control which supports:
Vehicle * vehicle
Raw pointer is safe: CameraStruct is owned by QGCCameraManager which is a child of Vehicle.
QPointer< QGCCameraManager > manager