QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
CameraSection.cc
Go to the documentation of this file.
1#include "CameraSection.h"
2#include "SimpleMissionItem.h"
3#include "FirmwarePlugin.h"
5#include "MissionItem.h"
6#include "Vehicle.h"
8
9QGC_LOGGING_CATEGORY(CameraSectionLog, "Plan.CameraSection")
10
11QMap<QString, FactMetaData*> CameraSection::_metaDataMap;
12
13CameraSection::CameraSection(PlanMasterController* masterController, QObject* parent)
14 : Section (masterController, parent)
15 , _available (false)
16 , _settingsSpecified (false)
17 , _specifyGimbal (false)
18 , _specifyCameraMode (false)
19 , _gimbalYawFact (0, _gimbalYawName, FactMetaData::valueTypeDouble)
20 , _gimbalPitchFact (0, _gimbalPitchName, FactMetaData::valueTypeDouble)
21 , _cameraActionFact (0, _cameraActionName, FactMetaData::valueTypeDouble)
22 , _cameraPhotoIntervalDistanceFact (0, _cameraPhotoIntervalDistanceName, FactMetaData::valueTypeDouble)
23 , _cameraPhotoIntervalTimeFact (0, _cameraPhotoIntervalTimeName, FactMetaData::valueTypeUint32)
24 , _cameraModeFact (0, _cameraModeName, FactMetaData::valueTypeUint32)
25 , _takePhotoSequence (0)
26 , _dirty (false)
27{
28 if (_metaDataMap.isEmpty()) {
29 _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CameraSection.FactMetaData.json"), Q_NULLPTR /* metaDataParent */);
30 }
31
32 _gimbalPitchFact.setMetaData (_metaDataMap[_gimbalPitchName]);
33 _gimbalYawFact.setMetaData (_metaDataMap[_gimbalYawName]);
34 _cameraActionFact.setMetaData (_metaDataMap[_cameraActionName]);
35 _cameraPhotoIntervalDistanceFact.setMetaData (_metaDataMap[_cameraPhotoIntervalDistanceName]);
36 _cameraPhotoIntervalTimeFact.setMetaData (_metaDataMap[_cameraPhotoIntervalTimeName]);
37 _cameraModeFact.setMetaData (_metaDataMap[_cameraModeName]);
38
39 _gimbalPitchFact.setRawValue (_gimbalPitchFact.rawDefaultValue());
40 _gimbalYawFact.setRawValue (_gimbalYawFact.rawDefaultValue());
41 _cameraActionFact.setRawValue (_cameraActionFact.rawDefaultValue());
42 _cameraPhotoIntervalDistanceFact.setRawValue (_cameraPhotoIntervalDistanceFact.rawDefaultValue());
43 _cameraPhotoIntervalTimeFact.setRawValue (_cameraPhotoIntervalTimeFact.rawDefaultValue());
44 _cameraModeFact.setRawValue (_cameraModeFact.rawDefaultValue());
45
46 connect(this, &CameraSection::specifyGimbalChanged, this, &CameraSection::_specifyChanged);
47 connect(this, &CameraSection::specifyCameraModeChanged, this, &CameraSection::_specifyChanged);
48
49 connect(&_cameraActionFact, &Fact::valueChanged, this, &CameraSection::_cameraActionChanged);
50
51 connect(&_gimbalPitchFact, &Fact::valueChanged, this, &CameraSection::_dirtyIfSpecified);
52 connect(&_gimbalYawFact, &Fact::valueChanged, this, &CameraSection::_dirtyIfSpecified);
53 connect(&_cameraPhotoIntervalDistanceFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
54 connect(&_cameraPhotoIntervalTimeFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
55 connect(&_cameraModeFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
56 connect(this, &CameraSection::specifyGimbalChanged, this, &CameraSection::_setDirty);
57 connect(this, &CameraSection::specifyCameraModeChanged, this, &CameraSection::_setDirty);
58
59 connect(&_gimbalYawFact, &Fact::valueChanged, this, &CameraSection::_updateSpecifiedGimbalYaw);
60 connect(&_gimbalPitchFact, &Fact::valueChanged, this, &CameraSection::_updateSpecifiedGimbalPitch);
61}
62
63void CameraSection::setSpecifyGimbal(bool specifyGimbal)
64{
65 if (specifyGimbal != _specifyGimbal) {
66 _specifyGimbal = specifyGimbal;
67 emit specifyGimbalChanged(specifyGimbal);
70 }
71}
72
73void CameraSection::setSpecifyCameraMode(bool specifyCameraMode)
74{
75 if (specifyCameraMode != _specifyCameraMode) {
76 _specifyCameraMode = specifyCameraMode;
78 }
79}
80
82{
83 int itemCount = 0;
84
85 if (_specifyGimbal) {
86 itemCount++;
87 }
88 if (_specifyCameraMode) {
89 itemCount++;
90 }
91 if (_cameraActionFact.rawValue().toInt() != CameraActionNone) {
92 itemCount++;
93 }
94
95 return itemCount;
96}
97
99{
100 if (_dirty != dirty) {
101 _dirty = dirty;
102 emit dirtyChanged(_dirty);
103 }
104}
105
106void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* missionItemParent, int& nextSequenceNumber)
107{
108 // IMPORTANT NOTE: If anything changes here you must also change CameraSection::scanForSection
109
110 if (_specifyCameraMode) {
111 MissionItem* item = new MissionItem(nextSequenceNumber++,
112 MAV_CMD_SET_CAMERA_MODE,
113 MAV_FRAME_MISSION,
114 0, // Reserved (Set to 0)
115 _cameraModeFact.rawValue().toDouble(),
116 qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), // reserved
117 true, // autoContinue
118 false, // isCurrentItem
119 missionItemParent);
120 items.append(item);
121 }
122
123 if (_specifyGimbal) {
124 MissionItem* item = new MissionItem(nextSequenceNumber++,
125 MAV_CMD_DO_MOUNT_CONTROL,
126 MAV_FRAME_MISSION,
127 _gimbalPitchFact.rawValue().toDouble(),
128 0, // Gimbal roll
129 _gimbalYawFact.rawValue().toDouble(),
130 0, 0, 0, // param 4-6 not used
131 MAV_MOUNT_MODE_MAVLINK_TARGETING,
132 true, // autoContinue
133 false, // isCurrentItem
134 missionItemParent);
135 items.append(item);
136 }
137
138 if (_cameraActionFact.rawValue().toInt() != CameraActionNone) {
139 MissionItem* item = nullptr;
140
141 switch (_cameraActionFact.rawValue().toInt()) {
143 item = new MissionItem(nextSequenceNumber++,
144 MAV_CMD_IMAGE_START_CAPTURE,
145 MAV_FRAME_MISSION,
146 0, // Reserved (Set to 0)
147 _cameraPhotoIntervalTimeFact.rawValue().toInt(), // Interval
148 0, // Unlimited photo count
149 qQNaN(), qQNaN(), qQNaN(), qQNaN(), // reserved
150 true, // autoContinue
151 false, // isCurrentItem
152 missionItemParent);
153 break;
154
156 item = new MissionItem(nextSequenceNumber++,
157 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
158 MAV_FRAME_MISSION,
159 _cameraPhotoIntervalDistanceFact.rawValue().toDouble(), // Trigger distance
160 0, // No shutter integartion
161 1, // Trigger immediately
162 0, 0, 0, 0, // param 4-7 not used
163 true, // autoContinue
164 false, // isCurrentItem
165 missionItemParent);
166 break;
167
168 case TakeVideo:
169 item = new MissionItem(nextSequenceNumber++,
170 MAV_CMD_VIDEO_START_CAPTURE,
171 MAV_FRAME_MISSION,
172 0, // Reserved (Set to 0)
173 VIDEO_CAPTURE_STATUS_INTERVAL, // CAMERA_CAPTURE_STATUS (default to every 5 seconds)
174 qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), // reserved
175 true, // autoContinue
176 false, // isCurrentItem
177 missionItemParent);
178 break;
179
180 case StopTakingVideo:
181 appendStopTakingVideo(items, nextSequenceNumber, missionItemParent);
182 break;
183
184 case StopTakingPhotos:
185 appendStopTakingPhotos(items, nextSequenceNumber, missionItemParent);
186 break;
187
188 case TakePhoto:
189 item = new MissionItem(nextSequenceNumber++,
190 MAV_CMD_IMAGE_START_CAPTURE,
191 MAV_FRAME_MISSION,
192 0, // Reserved (Set to 0)
193 0, // Interval (none)
194 1, // Take 1 photo
195 _takePhotoSequence++, // Increasing sequence number
196 qQNaN(), qQNaN(), qQNaN(), // reserved
197 true, // autoContinue
198 false, // isCurrentItem
199 missionItemParent);
200 break;
201 }
202 if (item) {
203 items.append(item);
204 }
205 }
206}
207
208void CameraSection::appendStopTakingPhotos(QList<MissionItem*>& items, int& seqNum, QObject* missionItemParent)
209{
210 MissionItem* item = new MissionItem(seqNum++,
211 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
212 MAV_FRAME_MISSION,
213 0, // Trigger distance = 0 means stop
214 0, 0, 0, 0, 0, 0, // param 2-7 not used
215 true, // autoContinue
216 false, // isCurrentItem
217 missionItemParent);
218 items.append(item);
219 item = new MissionItem(seqNum++,
220 MAV_CMD_IMAGE_STOP_CAPTURE,
221 MAV_FRAME_MISSION,
222 0, // Reserved (Set to 0)
223 qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), // reserved
224 true, // autoContinue
225 false, // isCurrentItem
226 missionItemParent);
227 items.append(item);
228}
229
230void CameraSection::appendStopTakingVideo(QList<MissionItem*>& items, int& seqNum, QObject* missionItemParent)
231{
232 MissionItem* item = new MissionItem(seqNum++,
233 MAV_CMD_VIDEO_STOP_CAPTURE,
234 MAV_FRAME_MISSION,
235 0, // Reserved (Set to 0)
236 qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), // reserved
237 true, // autoContinue
238 false, // isCurrentItem
239 missionItemParent);
240 items.append(item);
241}
242
243bool CameraSection::_scanGimbal(QmlObjectListModel* visualItems, int scanIndex)
244{
245 if (scanIndex > visualItems->count() -1) {
246 return false;
247 }
248 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
249 if (item) {
250 MissionItem& missionItem = item->missionItem();
251 if ((MAV_CMD)item->command() == MAV_CMD_DO_MOUNT_CONTROL) {
252 if (missionItem.param2() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == static_cast<double>(MAV_MOUNT_MODE_MAVLINK_TARGETING)) {
253 setSpecifyGimbal(true);
254 gimbalPitch()->setRawValue(missionItem.param1());
255 gimbalYaw()->setRawValue(missionItem.param3());
256 visualItems->removeAt(scanIndex)->deleteLater();
257 return true;
258 }
259 }
260 }
261
262 return false;
263}
264
265bool CameraSection::_scanTakePhoto(QmlObjectListModel* visualItems, int scanIndex)
266{
267 if (scanIndex > visualItems->count() -1) {
268 return false;
269 }
270 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
271 if (item) {
272 MissionItem& missionItem = item->missionItem();
273 if ((MAV_CMD)item->command() == MAV_CMD_IMAGE_START_CAPTURE) {
274 if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 1) {
275 cameraAction()->setRawValue(TakePhoto);
276 visualItems->removeAt(scanIndex)->deleteLater();
277 return true;
278 }
279 }
280 }
281
282 return false;
283}
284
285bool CameraSection::_scanTakePhotosIntervalTime(QmlObjectListModel* visualItems, int scanIndex)
286{
287 if (scanIndex > visualItems->count() -1) {
288 return false;
289 }
290 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
291 if (item) {
292 MissionItem& missionItem = item->missionItem();
293 if ((MAV_CMD)item->command() == MAV_CMD_IMAGE_START_CAPTURE) {
294 if (missionItem.param1() == 0 && missionItem.param2() >= 1 && missionItem.param3() == 0) {
295 cameraAction()->setRawValue(TakePhotosIntervalTime);
296 cameraPhotoIntervalTime()->setRawValue(missionItem.param2());
297 visualItems->removeAt(scanIndex)->deleteLater();
298 return true;
299 }
300 }
301 }
302
303 return false;
304}
305
306bool CameraSection::scanStopTakingPhotos(QmlObjectListModel* visualItems, int scanIndex, bool removeScannedItems)
307{
308 if (scanIndex < 0 || scanIndex > visualItems->count() -1) {
309 return false;
310 }
311 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
312 if (item) {
313 MissionItem& missionItem = item->missionItem();
314 if ((MAV_CMD)item->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) {
315 if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
316 if (scanIndex < visualItems->count() - 1) {
317 SimpleMissionItem* nextItem = visualItems->value<SimpleMissionItem*>(scanIndex + 1);
318 if (nextItem) {
319 MissionItem& nextMissionItem = nextItem->missionItem();
320 if (nextMissionItem.command() == MAV_CMD_IMAGE_STOP_CAPTURE && nextMissionItem.param1() == 0) {
321 if (removeScannedItems) {
322 visualItems->removeAt(scanIndex)->deleteLater();
323 visualItems->removeAt(scanIndex)->deleteLater();
324 }
325 return true;
326 }
327 }
328 }
329 }
330 }
331 }
332
333 return false;
334}
335
336bool CameraSection::_scanTriggerStartDistance(QmlObjectListModel* visualItems, int scanIndex)
337{
338 if (scanIndex < 0 || scanIndex > visualItems->count() -1) {
339 return false;
340 }
341 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
342 if (item) {
343 MissionItem& missionItem = item->missionItem();
344 if ((MAV_CMD)item->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) {
345 if (missionItem.param1() > 0 && missionItem.param2() == 0 && missionItem.param3() == 1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
347 cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
348 visualItems->removeAt(scanIndex)->deleteLater();
349 return true;
350 }
351 }
352 }
353
354 return false;
355}
356
357bool CameraSection::_scanTriggerStopDistance(QmlObjectListModel* visualItems, int scanIndex)
358{
359 if (scanIndex < 0 || scanIndex > visualItems->count() -1) {
360 return false;
361 }
362 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
363 if (item) {
364 MissionItem& missionItem = item->missionItem();
365 if ((MAV_CMD)item->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) {
366 if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
368 cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
369 visualItems->removeAt(scanIndex)->deleteLater();
370 return true;
371 }
372 }
373 }
374
375 return false;
376}
377
378bool CameraSection::_scanTakeVideo(QmlObjectListModel* visualItems, int scanIndex)
379{
380 if (scanIndex > visualItems->count() -1) {
381 return false;
382 }
383 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
384 if (item) {
385 MissionItem& missionItem = item->missionItem();
386 if ((MAV_CMD)item->command() == MAV_CMD_VIDEO_START_CAPTURE) {
387 if (missionItem.param1() == 0 && missionItem.param2() == VIDEO_CAPTURE_STATUS_INTERVAL) {
388 cameraAction()->setRawValue(TakeVideo);
389 visualItems->removeAt(scanIndex)->deleteLater();
390 return true;
391 }
392 }
393 }
394
395 return false;
396}
397
398bool CameraSection::scanStopTakingVideo(QmlObjectListModel* visualItems, int scanIndex, bool removeScannedItems)
399{
400 if (scanIndex < 0 || scanIndex > visualItems->count() -1) {
401 return false;
402 }
403 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
404 if (item) {
405 MissionItem& missionItem = item->missionItem();
406 if ((MAV_CMD)item->command() == MAV_CMD_VIDEO_STOP_CAPTURE) {
407 if (missionItem.param1() == 0) {
408 if (removeScannedItems) {
409 visualItems->removeAt(scanIndex)->deleteLater();
410 }
411 return true;
412 }
413 }
414 }
415
416 return false;
417}
418
419bool CameraSection::_scanSetCameraMode(QmlObjectListModel* visualItems, int scanIndex)
420{
421 if (scanIndex < 0 || scanIndex > visualItems->count() -1) {
422 return false;
423 }
424 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
425 if (item) {
426 MissionItem& missionItem = item->missionItem();
427 if ((MAV_CMD)item->command() == MAV_CMD_SET_CAMERA_MODE) {
428 // We specifically don't test param 5/6/7 since we don't have NaN persistence for those fields
429 if (missionItem.param1() == 0 && (missionItem.param2() == static_cast<double>(CAMERA_MODE_IMAGE) || missionItem.param2() == static_cast<double>(CAMERA_MODE_VIDEO) || missionItem.param2() == static_cast<double>(CAMERA_MODE_IMAGE_SURVEY)) && qIsNaN(missionItem.param3())) {
431 cameraMode()->setRawValue(missionItem.param2());
432 visualItems->removeAt(scanIndex)->deleteLater();
433 return true;
434 }
435 }
436 }
437
438 return false;
439}
440
441bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex)
442{
443 bool foundGimbal = false;
444 bool foundCameraAction = false;
445 bool foundCameraMode = false;
446
447 qCDebug(CameraSectionLog) << "CameraSection::scanForCameraSection visualItems->count():scanIndex;" << visualItems->count() << scanIndex;
448
449 if (!_available || scanIndex >= visualItems->count()) {
450 return false;
451 }
452
453 // Scan through the initial mission items for possible mission settings
454
455 while (visualItems->count() > scanIndex) {
456 if (!foundGimbal && _scanGimbal(visualItems, scanIndex)) {
457 foundGimbal = true;
458 continue;
459 }
460 if (!foundCameraAction && _scanTakePhoto(visualItems, scanIndex)) {
461 foundCameraAction = true;
462 continue;
463 }
464 if (!foundCameraAction && _scanTakePhotosIntervalTime(visualItems, scanIndex)) {
465 foundCameraAction = true;
466 continue;
467 }
468 if (!foundCameraAction && scanStopTakingPhotos(visualItems, scanIndex, true /* removeScannedItems */)) {
469 cameraAction()->setRawValue(StopTakingPhotos);
470 foundCameraAction = true;
471 continue;
472 }
473 if (!foundCameraAction && _scanTriggerStartDistance(visualItems, scanIndex)) {
474 foundCameraAction = true;
475 continue;
476 }
477 if (!foundCameraAction && _scanTriggerStopDistance(visualItems, scanIndex)) {
478 foundCameraAction = true;
479 continue;
480 }
481 if (!foundCameraAction && _scanTakeVideo(visualItems, scanIndex)) {
482 foundCameraAction = true;
483 continue;
484 }
485 if (!foundCameraAction && scanStopTakingVideo(visualItems, scanIndex, true /* removeScannedItems */)) {
486 cameraAction()->setRawValue(StopTakingVideo);
487 foundCameraAction = true;
488 continue;
489 }
490 if (!foundCameraMode && _scanSetCameraMode(visualItems, scanIndex)) {
491 foundCameraMode = true;
492 continue;
493 }
494 break;
495 }
496
497 qCDebug(CameraSectionLog) << "CameraSection::scanForCameraSection foundGimbal:foundCameraAction:foundCameraMode;" << foundGimbal << foundCameraAction << foundCameraMode;
498
499 _settingsSpecified = foundGimbal || foundCameraAction || foundCameraMode;
500 emit settingsSpecifiedChanged(_settingsSpecified);
501
502 return _settingsSpecified;
503}
504
505void CameraSection::_setDirty(void)
506{
507 setDirty(true);
508}
509
510void CameraSection::_setDirtyAndUpdateItemCount(void)
511{
513 setDirty(true);
514}
515
516void CameraSection::setAvailable(bool available)
517{
518 if (_available != available) {
519 _available = available;
521 }
522}
523
525{
526 return _specifyGimbal ? _gimbalYawFact.rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
527}
528
530{
531 return _specifyGimbal ? _gimbalPitchFact.rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
532}
533
534void CameraSection::_updateSpecifiedGimbalYaw(void)
535{
536 if (_specifyGimbal) {
538 }
539}
540
541void CameraSection::_updateSpecifiedGimbalPitch(void)
542{
543 if (_specifyGimbal) {
545 }
546}
547
548void CameraSection::_updateSettingsSpecified(void)
549{
550 bool newSettingsSpecified = _specifyGimbal || _specifyCameraMode || _cameraActionFact.rawValue().toInt() != CameraActionNone;
551 if (newSettingsSpecified != _settingsSpecified) {
552 _settingsSpecified = newSettingsSpecified;
553 emit settingsSpecifiedChanged(newSettingsSpecified);
554 }
555}
556
557void CameraSection::_specifyChanged(void)
558{
559 _setDirtyAndUpdateItemCount();
560 _updateSettingsSpecified();
561}
562
563void CameraSection::_cameraActionChanged(void)
564{
565 _setDirtyAndUpdateItemCount();
566 _updateSettingsSpecified();
567}
568
570{
571 return _specifyCameraMode || _masterController->controllerVehicle()->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_SET_CAMERA_MODE);
572}
573
574void CameraSection::_dirtyIfSpecified(void)
575{
576 // We only set the dirty bit if specify gimbal it set. This allows us to change defaults without affecting dirty.
577 if (_specifyGimbal) {
578 setDirty(true);
579 }
580}
#define VIDEO_CAPTURE_STATUS_INTERVAL
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void setSpecifyCameraMode(bool specifyCameraMode)
bool scanForSection(QmlObjectListModel *visualItems, int scanIndex) override
double specifiedGimbalPitch(void) const
void setSpecifyGimbal(bool specifyGimbal)
void appendSectionItems(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum) override
bool specifyCameraMode(void) const
void specifiedGimbalYawChanged(double gimbalYaw)
bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged(Fact *gimbalPitch READ gimbalPitch CONSTANT) 1(Fact *gimbalYaw READ gimbalYaw CONSTANT) 1(Fact *cameraAction READ cameraAction CONSTANT) 1(Fact *cameraPhotoIntervalTime READ cameraPhotoIntervalTime CONSTANT) 1(Fact *cameraPhotoIntervalDistance READ cameraPhotoIntervalDistance CONSTANT) 1(bool cameraModeSupported READ cameraModeSupported CONSTANT) 1(bool specifyCameraMode READ specifyCameraMode WRITE setSpecifyCameraMode NOTIFY specifyCameraModeChanged) 1(Fact *cameraMode READ cameraMode CONSTANT) bool specifyGimbal(void) const
< true: cameraMode is supported by this vehicle
double specifiedGimbalYaw(void) const
Fact * gimbalPitch(void)
static void appendStopTakingVideo(QList< MissionItem * > &items, int &seqNum, QObject *missionItemParent)
Fact * cameraPhotoIntervalTime(void)
Fact * cameraMode(void)
bool cameraModeSupported(void) const
Fact * gimbalYaw(void)
void specifiedGimbalPitchChanged(double gimbalPitch)
static void appendStopTakingPhotos(QList< MissionItem * > &items, int &seqNum, QObject *missionItemParent)
static bool scanStopTakingVideo(QmlObjectListModel *visualItems, int scanIndex, bool removeScannedItems)
static bool scanStopTakingPhotos(QmlObjectListModel *visualItems, int scanIndex, bool removeScannedItems)
Fact * cameraPhotoIntervalDistance(void)
bool dirty(void) const override
bool available(void) const override
bool specifyCameraModeChanged(bool specifyCameraMode)
int itemCount(void) const override
Fact * cameraAction(void)
void setDirty(bool dirty) override
void setAvailable(bool available) override
static QMap< QString, FactMetaData * > createMapFromJsonFile(const QString &jsonFilename, QObject *metaDataParent)
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
virtual QList< MAV_CMD > supportedMissionCommands(QGCMAVLink::VehicleClass_t) const
List of supported mission commands. Empty list for all commands supported.
MAV_CMD command(void) const
Definition MissionItem.h:49
double param5(void) const
Definition MissionItem.h:58
double param7(void) const
Definition MissionItem.h:60
double param3(void) const
Definition MissionItem.h:56
double param6(void) const
Definition MissionItem.h:59
double param1(void) const
Definition MissionItem.h:54
double param4(void) const
Definition MissionItem.h:57
double param2(void) const
Definition MissionItem.h:55
Master controller for mission, fence, rally.
Vehicle * controllerVehicle(void)
T value(int index) const
QObject * removeAt(int index)
int count() const override final
void dirtyChanged(bool dirty)
PlanMasterController * _masterController
Definition Section.h:59
void itemCountChanged(int itemCount)
bool available READ available WRITE setAvailable NOTIFY availableChanged(bool settingsSpecified READ settingsSpecified NOTIFY settingsSpecifiedChanged) 1(bool dirty READ dirty WRITE setDirty NOTIFY availableChanged) virtual bool available(void) const =0
void settingsSpecifiedChanged(bool settingsSpecified)
A SimpleMissionItem is used to represent a single MissionItem to the ui.
int command(void) const
MissionItem & missionItem(void)
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:444