QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
SimulatedCameraControl.cc
Go to the documentation of this file.
2#include "FlyViewSettings.h"
3#include "AppMessages.h"
5#include "SettingsManager.h"
6#include "Vehicle.h"
7#include "VideoManager.h"
8
9QGC_LOGGING_CATEGORY(SimulatedCameraControlLog, "Camera.SimulatedCameraControl")
10
12 : MavlinkCameraControlInterface(vehicle, parent)
13{
14 qCDebug(SimulatedCameraControlLog) << this;
15
16 auto videoManager = VideoManager::instance();
17 (void) connect(videoManager, &VideoManager::recordingChanged, this, [this](bool recording) {
18 _videoCaptureStatusValue = recording ? VIDEO_CAPTURE_STATUS_RUNNING : VIDEO_CAPTURE_STATUS_STOPPED;
19 emit videoCaptureStatusChanged();
20 });
21
22 (void) connect(videoManager, &VideoManager::hasVideoChanged, this, &SimulatedCameraControl::infoChanged);
23 (void) connect(videoManager, &VideoManager::decodingChanged, this, &SimulatedCameraControl::infoChanged);
24
27
34
35 (void) connect(SettingsManager::instance()->flyViewSettings()->showSimpleCameraControl(), &Fact::rawValueChanged, this, &SimulatedCameraControl::infoChanged);
36
37 if (capturesVideo()) {
38 _cameraMode = CAM_MODE_VIDEO;
39 } else if (capturesPhotos()) {
40 _cameraMode = CAM_MODE_PHOTO;
41 } else {
42 _cameraMode = CAM_MODE_UNDEFINED;
43 }
44
45 _videoRecordTimeUpdateTimer.setInterval(1000);
46 (void) connect(&_videoRecordTimeUpdateTimer, &QTimer::timeout, this, &SimulatedCameraControl::recordTimeChanged);
47}
48
50{
51 qCDebug(SimulatedCameraControlLog) << this;
52}
53
55{
56 return QTime(0, 0).addMSecs(static_cast<int>(recordTime())).toString("hh:mm:ss");
57}
58
60{
61 qCDebug(SimulatedCameraControlLog) << cameraModeToStr(cameraMode);
62
63 if (!hasModes()) {
64 qCWarning(SimulatedCameraControlLog) << "Set camera mode denied - camera does not support modes";
65 return;
66 }
67
68 switch (cameraMode) {
69 case CAM_MODE_VIDEO:
70 _setCameraMode(CAM_MODE_VIDEO);
71 break;
72 case CAM_MODE_PHOTO:
73 _setCameraMode(CAM_MODE_PHOTO);
74 break;
75 default:
76 qCWarning(SimulatedCameraControlLog) << "Invalid mode" << cameraMode;
77 break;
78 }
79}
80
81void SimulatedCameraControl::_setCameraMode(CameraMode mode)
82{
83 if (_cameraMode != mode) {
85 emit cameraModeChanged();
86 }
87}
88
90{
91 if (!hasModes()) {
92 qCWarning(SimulatedCameraControlLog) << "Toggle camera mode denied - camera does not support modes";
93 return;
94 }
97 } else if(_cameraMode == CAM_MODE_VIDEO) {
99 }
100}
101
106
108{
109 if (!hasModes()) {
110 qCWarning(SimulatedCameraControlLog) << "Camera does not support modes";
111 return;
112 }
113
114 _setCameraMode(CAM_MODE_VIDEO);
115}
116
118{
119 if (!hasModes()) {
120 qCWarning(SimulatedCameraControlLog) << "Camera does not support modes";
121 return;
122 }
123
124 _setCameraMode(CAM_MODE_PHOTO);
125}
126
128{
129 if (!capturesPhotos()) {
130 qCWarning(SimulatedCameraControlLog) << "Camera does not handle image capture";
131 return false;
132 }
133
135 qCWarning(SimulatedCameraControlLog) << "Camera not idle";
136 return false;
137 }
138
140 qCWarning(SimulatedCameraControlLog) << "Camera not in correct mode:" << cameraModeToStr(_cameraMode);
141 return false;
142 }
143
144 switch (photoCaptureMode()) {
149 QTimer::singleShot(500, this, [this]() { _photoCaptureStatusValue = PHOTO_CAPTURE_IDLE; emit photoCaptureStatusChanged(); });
150 return true;
152 QGC::showAppMessage(tr("Time lapse capture not supported by this camera"));
153 default:
154 break;
155 }
156
157 return false;
158}
159
161{
162 if (!capturesVideo()) {
163 qCWarning(SimulatedCameraControlLog) << "Camera does not handle video capture";
164 return false;
165 }
167 qCWarning(SimulatedCameraControlLog) << "Camera does not take video in photo mode";
168 return false;
169 }
171 qCWarning(SimulatedCameraControlLog) << "Camera already recording";
172 return false;
173 }
174
176 _videoRecordTimeElapsedTimer.start();
178 return true;
179}
180
182{
184 qCWarning(SimulatedCameraControlLog) << "Camera not recording";
185 return false;
186 }
187
190 return true;
191}
192
194{
195 return (_videoRecordTimeUpdateTimer.isActive() ? _videoRecordTimeElapsedTimer.elapsed() : 0);
196}
197
202
204{
205 return SettingsManager::instance()->flyViewSettings()->showSimpleCameraControl()->rawValue().toBool();
206}
207
208
210{
211 return (capturesPhotos() && capturesVideo());
212}
213
218
232
243
245{
247 qCWarning(SimulatedCameraControlLog) << "Time lapse capture not supported by simulated camera";
248 return;
249 }
253 }
254}
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void rawValueChanged(const QVariant &value)
Abstract base class for all camera controls: real and simulated.
PhotoCaptureStatus _photoCaptureStatus() const
virtual PhotoCaptureMode photoCaptureMode() const
VideoCaptureStatus _videoCaptureStatus() const
static SettingsManager * instance()
FlyViewSettings * flyViewSettings() const
Creates a simulated Camera Control which supports:
CapturePhotosState capturePhotosState() const override
void setCameraMode(CameraMode cameraMode) override
bool capturesPhotos() const override
CaptureVideoState captureVideoState() const override
void setPhotoCaptureMode(PhotoCaptureMode mode) override
QString recordTimeStr() const override
bool hasVideoStream() const override
quint32 recordTime() const override
bool capturesVideo() const override
bool hasModes() const override
Q_INVOKABLE void triggerSimpleCamera(void)
Trigger camera using MAV_CMD_DO_DIGICAM_CONTROL command.
Definition Vehicle.cc:3128
void decodingChanged()
Q_INVOKABLE void stopRecording()
void hasVideoChanged()
Q_INVOKABLE void startRecording(const QString &videoFile=QString())
static VideoManager * instance()
bool decoding() const
bool hasVideo() const
void recordingChanged(bool recording)
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Definition AppMessages.cc:9