diff --git a/src/MissionManager/CameraSection.cc b/src/MissionManager/CameraSection.cc index 80cfc569f714164a17c5b7fcea05a4cd4458544c..131c2c18104f74963fbfa01fc1375cfd166f341d 100644 --- a/src/MissionManager/CameraSection.cc +++ b/src/MissionManager/CameraSection.cc @@ -9,6 +9,7 @@ #include "CameraSection.h" #include "SimpleMissionItem.h" +#include "FirmwarePlugin.h" QGC_LOGGING_CATEGORY(CameraSectionLog, "CameraSectionLog") @@ -402,3 +403,8 @@ void CameraSection::_cameraActionChanged(void) _setDirtyAndUpdateItemCount(); _updateSettingsSpecified(); } + +bool CameraSection::cameraModeSupported(void) const +{ + return _vehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_SET_CAMERA_MODE); +} diff --git a/src/MissionManager/CameraSection.h b/src/MissionManager/CameraSection.h index 59e2d77ace6b0373bac4fc953ced65e34c62fb0a..2e926c82e12ed689c4ca7bd6fadde08173e5ccc7 100644 --- a/src/MissionManager/CameraSection.h +++ b/src/MissionManager/CameraSection.h @@ -38,8 +38,9 @@ public: Q_PROPERTY(Fact* cameraAction READ cameraAction CONSTANT) Q_PROPERTY(Fact* cameraPhotoIntervalTime READ cameraPhotoIntervalTime CONSTANT) Q_PROPERTY(Fact* cameraPhotoIntervalDistance READ cameraPhotoIntervalDistance CONSTANT) + Q_PROPERTY(bool cameraModeSupported READ cameraModeSupported CONSTANT) ///< true: cameraMode is supported by this vehicle Q_PROPERTY(bool specifyCameraMode READ specifyCameraMode WRITE setSpecifyCameraMode NOTIFY specifyCameraModeChanged) - Q_PROPERTY(Fact* cameraMode READ cameraMode CONSTANT) + Q_PROPERTY(Fact* cameraMode READ cameraMode CONSTANT) ///< MAV_CMD_SET_CAMERA_MODE.param2 bool specifyGimbal (void) const { return _specifyGimbal; } Fact* gimbalYaw (void) { return &_gimbalYawFact; } @@ -47,6 +48,7 @@ public: Fact* cameraAction (void) { return &_cameraActionFact; } Fact* cameraPhotoIntervalTime (void) { return &_cameraPhotoIntervalTimeFact; } Fact* cameraPhotoIntervalDistance (void) { return &_cameraPhotoIntervalDistanceFact; } + bool cameraModeSupported (void) const; bool specifyCameraMode (void) const { return _specifyCameraMode; } Fact* cameraMode (void) { return &_cameraModeFact; } diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index ebb9eee50d76690c43f4d8f309c350adba252fc2..512d8a614737057abd7232cb14b98bad6f8e17a2 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -319,7 +319,7 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate MissionSettingsItem* settingsItem = _visualItems->value(0); CameraSection* cameraSection = settingsItem->cameraSection(); // Set camera to photo mode (leave alone if user already specified) - if (!cameraSection->specifyCameraMode()) { + if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) { cameraSection->setSpecifyCameraMode(true); cameraSection->cameraMode()->setRawValue(0); } @@ -382,7 +382,7 @@ void MissionController::removeMissionItem(int index) cameraSection->setSpecifyGimbal(false); } } - if (cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) { + if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) { cameraSection->setSpecifyCameraMode(false); } } diff --git a/src/PlanView/CameraSection.qml b/src/PlanView/CameraSection.qml index 64d8fee3b77dfdfb9a0c41a240468e022a49d51d..0d20c39a6ec9e08ab9a68b4e128eb4fdc6001705 100644 --- a/src/PlanView/CameraSection.qml +++ b/src/PlanView/CameraSection.qml @@ -109,6 +109,7 @@ Column { anchors.left: parent.left anchors.right: parent.right spacing: ScreenTools.defaultFontPixelWidth + visible: _camera.cameraModeSupported QGCCheckBox { id: modeCheckBox