14 :
Section (masterController, parent)
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)
28 if (_metaDataMap.isEmpty()) {
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]);
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());
49 connect(&_cameraActionFact, &
Fact::valueChanged,
this, &CameraSection::_cameraActionChanged);
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);
59 connect(&_gimbalYawFact, &
Fact::valueChanged,
this, &CameraSection::_updateSpecifiedGimbalYaw);
60 connect(&_gimbalPitchFact, &
Fact::valueChanged,
this, &CameraSection::_updateSpecifiedGimbalPitch);
65 if (specifyGimbal != _specifyGimbal) {
66 _specifyGimbal = specifyGimbal;
88 if (_specifyCameraMode) {
100 if (_dirty !=
dirty) {
110 if (_specifyCameraMode) {
112 MAV_CMD_SET_CAMERA_MODE,
115 _cameraModeFact.rawValue().toDouble(),
116 qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(),
123 if (_specifyGimbal) {
125 MAV_CMD_DO_MOUNT_CONTROL,
127 _gimbalPitchFact.rawValue().toDouble(),
129 _gimbalYawFact.rawValue().toDouble(),
131 MAV_MOUNT_MODE_MAVLINK_TARGETING,
141 switch (_cameraActionFact.rawValue().toInt()) {
144 MAV_CMD_IMAGE_START_CAPTURE,
147 _cameraPhotoIntervalTimeFact.rawValue().toInt(),
149 qQNaN(), qQNaN(), qQNaN(), qQNaN(),
157 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
159 _cameraPhotoIntervalDistanceFact.rawValue().toDouble(),
170 MAV_CMD_VIDEO_START_CAPTURE,
174 qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(),
190 MAV_CMD_IMAGE_START_CAPTURE,
195 _takePhotoSequence++,
196 qQNaN(), qQNaN(), qQNaN(),
211 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
220 MAV_CMD_IMAGE_STOP_CAPTURE,
223 qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(),
233 MAV_CMD_VIDEO_STOP_CAPTURE,
236 qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(), qQNaN(),
245 if (scanIndex > visualItems->
count() -1) {
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)) {
256 visualItems->
removeAt(scanIndex)->deleteLater();
267 if (scanIndex > visualItems->
count() -1) {
273 if ((MAV_CMD)item->
command() == MAV_CMD_IMAGE_START_CAPTURE) {
274 if (missionItem.
param1() == 0 && missionItem.
param2() == 0 && missionItem.
param3() == 1) {
276 visualItems->
removeAt(scanIndex)->deleteLater();
285bool CameraSection::_scanTakePhotosIntervalTime(
QmlObjectListModel* visualItems,
int scanIndex)
287 if (scanIndex > visualItems->
count() -1) {
293 if ((MAV_CMD)item->
command() == MAV_CMD_IMAGE_START_CAPTURE) {
294 if (missionItem.
param1() == 0 && missionItem.
param2() >= 1 && missionItem.
param3() == 0) {
297 visualItems->
removeAt(scanIndex)->deleteLater();
308 if (scanIndex < 0 || scanIndex > visualItems->
count() -1) {
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) {
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();
336bool CameraSection::_scanTriggerStartDistance(
QmlObjectListModel* visualItems,
int scanIndex)
338 if (scanIndex < 0 || scanIndex > visualItems->
count() -1) {
344 if ((MAV_CMD)item->
command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) {
348 visualItems->
removeAt(scanIndex)->deleteLater();
357bool CameraSection::_scanTriggerStopDistance(
QmlObjectListModel* visualItems,
int scanIndex)
359 if (scanIndex < 0 || scanIndex > visualItems->
count() -1) {
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) {
369 visualItems->
removeAt(scanIndex)->deleteLater();
380 if (scanIndex > visualItems->
count() -1) {
386 if ((MAV_CMD)item->
command() == MAV_CMD_VIDEO_START_CAPTURE) {
389 visualItems->
removeAt(scanIndex)->deleteLater();
400 if (scanIndex < 0 || scanIndex > visualItems->
count() -1) {
406 if ((MAV_CMD)item->
command() == MAV_CMD_VIDEO_STOP_CAPTURE) {
407 if (missionItem.
param1() == 0) {
408 if (removeScannedItems) {
409 visualItems->
removeAt(scanIndex)->deleteLater();
421 if (scanIndex < 0 || scanIndex > visualItems->
count() -1) {
427 if ((MAV_CMD)item->
command() == MAV_CMD_SET_CAMERA_MODE) {
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())) {
432 visualItems->
removeAt(scanIndex)->deleteLater();
443 bool foundGimbal =
false;
444 bool foundCameraAction =
false;
445 bool foundCameraMode =
false;
447 qCDebug(CameraSectionLog) <<
"CameraSection::scanForCameraSection visualItems->count():scanIndex;" << visualItems->
count() << scanIndex;
449 if (!_available || scanIndex >= visualItems->
count()) {
455 while (visualItems->
count() > scanIndex) {
456 if (!foundGimbal && _scanGimbal(visualItems, scanIndex)) {
460 if (!foundCameraAction && _scanTakePhoto(visualItems, scanIndex)) {
461 foundCameraAction =
true;
464 if (!foundCameraAction && _scanTakePhotosIntervalTime(visualItems, scanIndex)) {
465 foundCameraAction =
true;
470 foundCameraAction =
true;
473 if (!foundCameraAction && _scanTriggerStartDistance(visualItems, scanIndex)) {
474 foundCameraAction =
true;
477 if (!foundCameraAction && _scanTriggerStopDistance(visualItems, scanIndex)) {
478 foundCameraAction =
true;
481 if (!foundCameraAction && _scanTakeVideo(visualItems, scanIndex)) {
482 foundCameraAction =
true;
487 foundCameraAction =
true;
490 if (!foundCameraMode && _scanSetCameraMode(visualItems, scanIndex)) {
491 foundCameraMode =
true;
497 qCDebug(CameraSectionLog) <<
"CameraSection::scanForCameraSection foundGimbal:foundCameraAction:foundCameraMode;" << foundGimbal << foundCameraAction << foundCameraMode;
499 _settingsSpecified = foundGimbal || foundCameraAction || foundCameraMode;
502 return _settingsSpecified;
505void CameraSection::_setDirty(
void)
510void CameraSection::_setDirtyAndUpdateItemCount(
void)
526 return _specifyGimbal ? _gimbalYawFact.rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
531 return _specifyGimbal ? _gimbalPitchFact.rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
534void CameraSection::_updateSpecifiedGimbalYaw(
void)
536 if (_specifyGimbal) {
541void CameraSection::_updateSpecifiedGimbalPitch(
void)
543 if (_specifyGimbal) {
548void CameraSection::_updateSettingsSpecified(
void)
550 bool newSettingsSpecified = _specifyGimbal || _specifyCameraMode || _cameraActionFact.rawValue().toInt() !=
CameraActionNone;
551 if (newSettingsSpecified != _settingsSpecified) {
552 _settingsSpecified = newSettingsSpecified;
557void CameraSection::_specifyChanged(
void)
559 _setDirtyAndUpdateItemCount();
560 _updateSettingsSpecified();
563void CameraSection::_cameraActionChanged(
void)
565 _setDirtyAndUpdateItemCount();
566 _updateSettingsSpecified();
574void CameraSection::_dirtyIfSpecified(
void)
577 if (_specifyGimbal) {
#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
@ TakePhotoIntervalDistance
static void appendStopTakingVideo(QList< MissionItem * > &items, int &seqNum, QObject *missionItemParent)
Fact * cameraPhotoIntervalTime(void)
bool cameraModeSupported(void) const
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
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
double param5(void) const
double param7(void) const
double param3(void) const
double param6(void) const
double param1(void) const
double param4(void) const
double param2(void) const
Master controller for mission, fence, rally.
Vehicle * controllerVehicle(void)
static constexpr const VehicleClass_t VehicleClassGeneric
QObject * removeAt(int index)
int count() const override final
void dirtyChanged(bool dirty)
PlanMasterController * _masterController
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.
MissionItem & missionItem(void)
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.