Commit 0dbb19aa authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #4954 from DonLakeFlyer/WaypointFlightSpeed

Set flight speed in Waypoint items
parents 32c4d85f d60fe4ff
......@@ -469,6 +469,8 @@ HEADERS += \
src/MissionManager/RallyPointController.h \
src/MissionManager/RallyPointManager.h \
src/MissionManager/SimpleMissionItem.h \
src/MissionManager/Section.h \
src/MissionManager/SpeedSection.h \
src/MissionManager/SurveyMissionItem.h \
src/MissionManager/VisualMissionItem.h \
src/PositionManager/PositionManager.h \
......@@ -648,6 +650,7 @@ SOURCES += \
src/MissionManager/RallyPointController.cc \
src/MissionManager/RallyPointManager.cc \
src/MissionManager/SimpleMissionItem.cc \
src/MissionManager/SpeedSection.cc \
src/MissionManager/SurveyMissionItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/PositionManager/PositionManager.cpp \
......
......@@ -197,6 +197,7 @@
<file alias="FWLandingPattern.FactMetaData.json">src/MissionManager/FWLandingPattern.FactMetaData.json</file>
<file alias="USBBoardInfo.json">src/comm/USBBoardInfo.json</file>
<file alias="CameraSection.FactMetaData.json">src/MissionManager/CameraSection.FactMetaData.json</file>
<file alias="SpeedSection.FactMetaData.json">src/MissionManager/SpeedSection.FactMetaData.json</file>
<file alias="MissionSettings.FactMetaData.json">src/MissionManager/MissionSettings.FactMetaData.json</file>
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
<file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file>
......
......@@ -241,3 +241,17 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle*
}
return false;
}
void ArduCopterFirmwarePlugin::missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed)
{
QString hoverSpeedParam("WPNAV_SPEED");
// First pull settings defaults
FirmwarePlugin::missionFlightSpeedInfo(vehicle, hoverSpeed, cruiseSpeed);
cruiseSpeed = 0;
if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, hoverSpeedParam)) {
Fact* speed = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, hoverSpeedParam);
hoverSpeed = speed->rawValue().toDouble();
}
}
......@@ -76,6 +76,7 @@ public:
QString takeControlFlightMode(void) const override { return QString("Stablize"); }
bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const final;
QString autoDisarmParameter(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); }
void missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed) override;
private:
static bool _remapParamNameIntialized;
......
......@@ -11,6 +11,8 @@
#include "QGCApplication.h"
#include "Generic/GenericAutoPilotPlugin.h"
#include "CameraMetaData.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include <QDebug>
......@@ -452,3 +454,13 @@ QString FirmwarePlugin::autoDisarmParameter(Vehicle* vehicle)
Q_UNUSED(vehicle);
return QString();
}
void FirmwarePlugin::missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed)
{
Q_UNUSED(vehicle);
// Best we can do is use settings
AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
hoverSpeed = appSettings->offlineEditingHoverSpeed()->rawValue().toDouble();
cruiseSpeed = appSettings->offlineEditingCruiseSpeed()->rawValue().toDouble();
}
......@@ -282,6 +282,11 @@ public:
/// @param[out] cruiseAmps Current draw in amps during cruise
virtual void batteryConsumptionData(Vehicle* vehicle, int& mAhBattery, double& hoverAmps, double& cruiseAmps) const;
/// Returns the default mission flight speeds.
/// @param[out] hoverSpeed Flight speed for vehicle flying in multi-rotor mode. 0 for none, or not available.
/// @param[out] cruiseSpeed Flight speed for vehicle flying in fixed wing forward flight mode. 0 for none, or not available.
virtual void missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed);
// Returns the parameter which control auto-dismar. Assume == 0 means no auto disarm
virtual QString autoDisarmParameter(Vehicle* vehicle);
......
......@@ -518,9 +518,27 @@ void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_messag
bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const
{
if ( vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("MIS_YAWMODE"))) {
if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("MIS_YAWMODE"))) {
Fact* yawMode = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("MIS_YAWMODE"));
return yawMode && yawMode->rawValue().toInt() == 1;
}
return false;
}
void PX4FirmwarePlugin::missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed)
{
QString hoverSpeedParam("MPC_XY_CRUISE");
QString cruiseSpeedParam("FW_AIRSPD_TRIM");
// First pull settings defaults
FirmwarePlugin::missionFlightSpeedInfo(vehicle, hoverSpeed, cruiseSpeed);
if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, hoverSpeedParam)) {
Fact* speed = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, hoverSpeedParam);
hoverSpeed = speed->rawValue().toDouble();
}
if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, cruiseSpeedParam)) {
Fact* speed = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, cruiseSpeedParam);
cruiseSpeed = speed->rawValue().toDouble();
}
}
......@@ -68,6 +68,7 @@ public:
QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); }
bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const override;
QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("COM_DISARM_LAND"); }
void missionFlightSpeedInfo (Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed) override;
protected:
typedef struct {
......
......@@ -20,8 +20,8 @@ const char* CameraSection::_cameraPhotoIntervalTimeName = "CameraPhotoInter
QMap<QString, FactMetaData*> CameraSection::_metaDataMap;
CameraSection::CameraSection(QObject* parent)
: QObject(parent)
CameraSection::CameraSection(Vehicle* vehicle, QObject* parent)
: Section(vehicle, parent)
, _available(false)
, _settingsSpecified(false)
, _specifyGimbal(false)
......@@ -48,8 +48,8 @@ CameraSection::CameraSection(QObject* parent)
_cameraPhotoIntervalDistanceFact.setRawValue (_cameraPhotoIntervalDistanceFact.rawDefaultValue());
_cameraPhotoIntervalTimeFact.setRawValue (_cameraPhotoIntervalTimeFact.rawDefaultValue());
connect(this, &CameraSection::specifyGimbalChanged, this, &CameraSection::_setDirtyAndUpdateMissionItemCount);
connect(&_cameraActionFact, &Fact::valueChanged, this, &CameraSection::_setDirtyAndUpdateMissionItemCount);
connect(this, &CameraSection::specifyGimbalChanged, this, &CameraSection::_setDirtyAndUpdateItemCount);
connect(&_cameraActionFact, &Fact::valueChanged, this, &CameraSection::_setDirtyAndUpdateItemCount);
connect(&_gimbalPitchFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(&_gimbalYawFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
......@@ -67,7 +67,7 @@ void CameraSection::setSpecifyGimbal(bool specifyGimbal)
}
}
int CameraSection::missionItemCount(void) const
int CameraSection::itemCount(void) const
{
int itemCount = 0;
......@@ -89,9 +89,9 @@ void CameraSection::setDirty(bool dirty)
}
}
void CameraSection::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent, int nextSequenceNumber)
void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* missionItemParent, int& nextSequenceNumber)
{
// IMPORTANT NOTE: If anything changes here you must also change CameraSection::scanForMissionSettings
// IMPORTANT NOTE: If anything changes here you must also change CameraSection::scanForSection
if (_specifyGimbal) {
MissionItem* item = new MissionItem(nextSequenceNumber++,
......@@ -188,7 +188,7 @@ void CameraSection::appendMissionItems(QList<MissionItem*>& items, QObject* miss
}
}
bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int scanIndex)
bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int& scanIndex)
{
bool foundGimbal = false;
bool foundCameraAction = false;
......@@ -196,6 +196,10 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
qCDebug(CameraSectionLog) << "CameraSection::scanForCameraSection" << visualItems->count() << scanIndex;
if (!_available || scanIndex >= visualItems->count()) {
return false;
}
// Scan through the initial mission items for possible mission settings
while (!stopLooking && visualItems->count() > scanIndex) {
......@@ -214,6 +218,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case MAV_CMD_DO_MOUNT_CONTROL:
if (!foundGimbal && missionItem.param2() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == MAV_MOUNT_MODE_MAVLINK_TARGETING) {
foundGimbal = true;
scanIndex++;
setSpecifyGimbal(true);
gimbalPitch()->setRawValue(missionItem.param1());
gimbalYaw()->setRawValue(missionItem.param3());
......@@ -226,6 +231,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case MAV_CMD_IMAGE_START_CAPTURE:
if (!foundCameraAction && missionItem.param1() != 0 && missionItem.param2() == 0 && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
foundCameraAction = true;
scanIndex++;
cameraAction()->setRawValue(TakePhotosIntervalTime);
cameraPhotoIntervalTime()->setRawValue(missionItem.param1());
visualItems->removeAt(scanIndex)->deleteLater();
......@@ -245,6 +251,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
if (nextMissionItem.command() == MAV_CMD_IMAGE_STOP_CAPTURE && nextMissionItem.param1() == 0 && nextMissionItem.param2() == 0 && nextMissionItem.param3() == 0 && nextMissionItem.param4() == 0 && nextMissionItem.param5() == 0 && nextMissionItem.param6() == 0 && nextMissionItem.param7() == 0) {
// We found a stop taking photos pair
foundCameraAction = true;
scanIndex += 2;
cameraAction()->setRawValue(StopTakingPhotos);
visualItems->removeAt(scanIndex)->deleteLater();
visualItems->removeAt(scanIndex)->deleteLater();
......@@ -257,6 +264,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
// We didn't find a stop taking photos pair, check for trigger distance
if (missionItem.param1() > 0) {
foundCameraAction = true;
scanIndex++;
cameraAction()->setRawValue(TakePhotoIntervalDistance);
cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
visualItems->removeAt(scanIndex)->deleteLater();
......@@ -270,6 +278,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case MAV_CMD_VIDEO_START_CAPTURE:
if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() == -1 && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
foundCameraAction = true;
scanIndex++;
cameraAction()->setRawValue(TakeVideo);
visualItems->removeAt(scanIndex)->deleteLater();
}
......@@ -279,6 +288,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case MAV_CMD_VIDEO_STOP_CAPTURE:
if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
foundCameraAction = true;
scanIndex++;
cameraAction()->setRawValue(StopTakingVideo);
visualItems->removeAt(scanIndex)->deleteLater();
}
......@@ -304,9 +314,9 @@ void CameraSection::_setDirty(void)
setDirty(true);
}
void CameraSection::_setDirtyAndUpdateMissionItemCount(void)
void CameraSection::_setDirtyAndUpdateItemCount(void)
{
emit missionItemCountChanged(missionItemCount());
emit itemCountChanged(itemCount());
setDirty(true);
}
......
......@@ -7,21 +7,19 @@
*
****************************************************************************/
#ifndef CameraSection_H
#define CameraSection_H
#pragma once
#include "Section.h"
#include "ComplexMissionItem.h"
#include "MissionItem.h"
#include "Fact.h"
Q_DECLARE_LOGGING_CATEGORY(CameraSectionLog)
class CameraSection : public QObject
class CameraSection : public Section
{
Q_OBJECT
public:
CameraSection(QObject* parent = NULL);
CameraSection(Vehicle* vehicle, QObject* parent = NULL);
// These nume values must match the json meta data
enum CameraAction {
......@@ -34,8 +32,6 @@ public:
};
Q_ENUMS(CameraAction)
Q_PROPERTY(bool available READ available WRITE setAvailable NOTIFY availableChanged)
Q_PROPERTY(bool settingsSpecified MEMBER _settingsSpecified NOTIFY settingsSpecifiedChanged)
Q_PROPERTY(bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged)
Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT)
Q_PROPERTY(Fact* gimbalYaw READ gimbalYaw CONSTANT)
......@@ -43,8 +39,6 @@ public:
Q_PROPERTY(Fact* cameraPhotoIntervalTime READ cameraPhotoIntervalTime CONSTANT)
Q_PROPERTY(Fact* cameraPhotoIntervalDistance READ cameraPhotoIntervalDistance CONSTANT)
bool available (void) const { return _available; }
void setAvailable (bool available);
bool specifyGimbal (void) const { return _specifyGimbal; }
Fact* gimbalYaw (void) { return &_gimbalYawFact; }
Fact* gimbalPitch (void) { return &_gimbalPitchFact; }
......@@ -52,40 +46,28 @@ public:
Fact* cameraPhotoIntervalTime (void) { return &_cameraPhotoIntervalTimeFact; }
Fact* cameraPhotoIntervalDistance (void) { return &_cameraPhotoIntervalDistanceFact; }
void setSpecifyGimbal (bool specifyGimbal);
///< @return The gimbal yaw specified by this item, NaN if not specified
double specifiedGimbalYaw(void) const;
/// Scans the loaded items for the section items
/// @param visualItems Item list
/// @param scanIndex Index to start scanning from
/// @return true: camera section found
bool scanForCameraSection(QmlObjectListModel* visualItems, int scanIndex);
/// Appends the mission items associated with this section
/// @param items List to append to
/// @param missionItemParent QObject parent for created MissionItems
/// @param nextSequenceNumber Sequence number for first item
void appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent, int nextSequenceNumber);
void setSpecifyGimbal (bool specifyGimbal);
bool dirty (void) const { return _dirty; }
void setDirty (bool dirty);
/// Returns the number of mission items represented by this section.
/// Signals: missionItemCountChanged on change
int missionItemCount(void) const;
// Overrides from Section
bool available (void) const override { return _available; }
bool dirty (void) const override { return _dirty; }
void setAvailable (bool available) override;
void setDirty (bool dirty) override;
bool scanForSection (QmlObjectListModel* visualItems, int& scanIndex) override;
void appendSectionItems (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum) override;
int itemCount (void) const override;
bool settingsSpecified (void) const override {return _settingsSpecified; }
signals:
void availableChanged (bool available);
void settingsSpecifiedChanged (bool settingsSpecified);
void dirtyChanged (bool dirty);
bool specifyGimbalChanged (bool specifyGimbal);
void missionItemCountChanged (int missionItemCount);
void specifiedGimbalYawChanged (double gimbalYaw);
private slots:
void _setDirty(void);
void _setDirtyAndUpdateMissionItemCount(void);
void _setDirtyAndUpdateItemCount(void);
void _updateSpecifiedGimbalYaw(void);
private:
......@@ -107,5 +89,3 @@ private:
static const char* _cameraPhotoIntervalDistanceName;
static const char* _cameraPhotoIntervalTimeName;
};
#endif
......@@ -32,7 +32,6 @@
"specifiesCoordinate": true,
"friendlyEdit": true,
"category": "Basic",
"cameraSection": true,
"param1": {
"label": "Hold",
"units": "secs",
......
......@@ -39,7 +39,6 @@ const char* MissionCommandUIInfo::_specifiesCoordinateJsonKey = "specifiesCoor
const char* MissionCommandUIInfo::_specifiesAltitudeOnlyJsonKey = "specifiesAltitudeOnly";
const char* MissionCommandUIInfo::_unitsJsonKey = "units";
const char* MissionCommandUIInfo::_commentJsonKey = "comment";
const char* MissionCommandUIInfo::_cameraSectionJsonKey = "cameraSection";
const char* MissionCommandUIInfo::_advancedCategory = "Advanced";
MissionCmdParamInfo::MissionCmdParamInfo(QObject* parent)
......@@ -165,15 +164,6 @@ bool MissionCommandUIInfo::specifiesAltitudeOnly(void) const
}
}
bool MissionCommandUIInfo::cameraSection(void) const
{
if (_infoMap.contains(_cameraSectionJsonKey)) {
return _infoMap[_cameraSectionJsonKey].toBool();
} else {
return false;
}
}
void MissionCommandUIInfo::_overrideInfo(MissionCommandUIInfo* uiInfo)
{
// Override info values
......@@ -209,7 +199,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
QStringList allKeys;
allKeys << _idJsonKey << _rawNameJsonKey << _friendlyNameJsonKey << _descriptionJsonKey << _standaloneCoordinateJsonKey << _specifiesCoordinateJsonKey
<<_friendlyEditJsonKey << _param1JsonKey << _param2JsonKey << _param3JsonKey << _param4JsonKey << _param5JsonKey << _param6JsonKey << _param7JsonKey
<< _paramRemoveJsonKey << _categoryJsonKey << _cameraSectionJsonKey<< _specifiesAltitudeOnlyJsonKey;
<< _paramRemoveJsonKey << _categoryJsonKey << _specifiesAltitudeOnlyJsonKey;
// Look for unknown keys in top level object
foreach (const QString& key, jsonObject.keys()) {
......@@ -241,7 +231,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
QList<QJsonValue::Type> types;
types << QJsonValue::Double << QJsonValue::String << QJsonValue::String<< QJsonValue::String << QJsonValue::Bool << QJsonValue::Bool << QJsonValue::Bool
<< QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object << QJsonValue::Object
<< QJsonValue::String << QJsonValue::String << QJsonValue::Bool << QJsonValue::Bool;
<< QJsonValue::String << QJsonValue::String << QJsonValue::Bool;
if (!JsonHelper::validateKeyTypes(jsonObject, allKeys, types, internalError)) {
errorString = _loadErrorString(internalError);
return false;
......@@ -275,9 +265,6 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
if (jsonObject.contains(_friendlyEditJsonKey)) {
_infoMap[_friendlyEditJsonKey] = jsonObject.value(_friendlyEditJsonKey).toVariant();
}
if (jsonObject.contains(_cameraSectionJsonKey)) {
_infoMap[_cameraSectionJsonKey] = jsonObject.value(_cameraSectionJsonKey).toVariant();
}
if (jsonObject.contains(_paramRemoveJsonKey)) {
QStringList indexList = jsonObject.value(_paramRemoveJsonKey).toString().split(QStringLiteral(","));
foreach (const QString& indexString, indexList) {
......
......@@ -97,7 +97,6 @@ private:
/// specifiesAltitudeOnly bool false true: Command specifies an altitude only (no coordinate)
/// standaloneCoordinate bool false true: Vehicle does not fly through coordinate associated with command (exampl: ROI)
/// friendlyEdit bool false true: Command supports friendly editing dialog, false: Command supports 'Show all values" style editing only
/// cameraSection bool false true: Camera section of additional settings is added to editor
/// category string Advanced Category which this command belongs to
/// paramRemove string Used by an override to remove params, example: "1,3" will remove params 1 and 3 on the override
/// param[1-7] object MissionCommandParamInfo object
......@@ -120,7 +119,6 @@ public:
Q_PROPERTY(bool specifiesCoordinate READ specifiesCoordinate CONSTANT)
Q_PROPERTY(bool specifiesAltitudeOnly READ specifiesAltitudeOnly CONSTANT)
Q_PROPERTY(int command READ intCommand CONSTANT)
Q_PROPERTY(bool cameraSection READ cameraSection CONSTANT)
MAV_CMD command(void) const { return _command; }
int intCommand(void) const { return (int)_command; }
......@@ -133,7 +131,6 @@ public:
bool isStandaloneCoordinate (void) const;
bool specifiesCoordinate (void) const;
bool specifiesAltitudeOnly (void) const;
bool cameraSection (void) const;
/// Load the data in the object from the specified json
/// @param jsonObject Json object to load from
......@@ -192,7 +189,6 @@ private:
static const char* _specifiesAltitudeOnlyJsonKey;
static const char* _unitsJsonKey;
static const char* _commentJsonKey;
static const char* _cameraSectionJsonKey;
static const char* _advancedCategory;
friend class MissionCommandTree;
......
......@@ -1526,16 +1526,18 @@ void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualIte
qCDebug(MissionControllerLog) << "MissionController::_scanForAdditionalSettings count:scanIndex" << visualItems->count() << scanIndex;
MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
if (settingsItem && settingsItem->scanForMissionSettings(visualItems, scanIndex, vehicle)) {
if (settingsItem && settingsItem->scanForMissionSettings(visualItems, scanIndex)) {
continue;
}
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
if (simpleItem) {
simpleItem->scanForSections(visualItems, scanIndex + 1, vehicle);
scanIndex++;
simpleItem->scanForSections(visualItems, scanIndex, vehicle);
} else {
// Complex item, can't have sections
scanIndex++;
}
scanIndex++;
}
}
......
......@@ -7,14 +7,6 @@
"decimalPlaces": 1,
"defaultValue": 0
},
{
"name": "FlightSpeed",
"shortDescription": "Flight speed for mission.",
"type": "double",
"units": "m/s",
"min": 0,
"decimalPlaces": 1
},
{
"name": "MissionEndAction",
"shortDescription": "The action to take when the mission completed.",
......
This diff is collapsed.
......@@ -15,6 +15,7 @@
#include "Fact.h"
#include "QGCLoggingCategory.h"
#include "CameraSection.h"
#include "SpeedSection.h"
Q_DECLARE_LOGGING_CATEGORY(MissionSettingsComplexItemLog)
......@@ -32,22 +33,19 @@ public:
};
Q_ENUMS(MissionEndAction)
Q_PROPERTY(bool specifyMissionFlightSpeed READ specifyMissionFlightSpeed WRITE setSpecifyMissionFlightSpeed NOTIFY specifyMissionFlightSpeedChanged)
Q_PROPERTY(Fact* missionFlightSpeed READ missionFlightSpeed CONSTANT)
Q_PROPERTY(Fact* missionEndAction READ missionEndAction CONSTANT)
Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT)
Q_PROPERTY(QObject* cameraSection READ cameraSection CONSTANT)
Q_PROPERTY(QObject* speedSection READ speedSection CONSTANT)
Fact* plannedHomePositionAltitude (void) { return &_plannedHomePositionAltitudeFact; }
Fact* missionFlightSpeed (void) { return &_missionFlightSpeedFact; }
Fact* missionEndAction (void) { return &_missionEndActionFact; }
bool specifyMissionFlightSpeed (void) const { return _specifyMissionFlightSpeed; }
void setSpecifyMissionFlightSpeed(bool specifyMissionFlightSpeed);
QObject* cameraSection(void) { return &_cameraSection; }
QObject* speedSection(void) { return &_speedSection; }
/// Scans the loaded items for settings items
static bool scanForMissionSettings(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle);
static bool scanForMissionSettings(QmlObjectListModel* visualItems, int scanIndex);
/// Adds the optional mission end action to the list
/// @param items Mission items list to append to
......@@ -77,10 +75,10 @@ public:
QGeoCoordinate coordinate (void) const final { return _plannedHomePositionCoordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _plannedHomePositionCoordinate; }
int sequenceNumber (void) const final { return _sequenceNumber; }
double specifiedFlightSpeed (void) final;
double specifiedGimbalYaw (void) final;
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final { Q_UNUSED(newAltitude); /* no action */ }
double specifiedFlightSpeed (void) final;
bool coordinateHasRelativeAltitude (void) const final { return true; }
bool exitCoordinateHasRelativeAltitude (void) const final { return true; }
......@@ -99,16 +97,15 @@ signals:
private slots:
void _setDirtyAndUpdateLastSequenceNumber (void);
void _setDirty (void);
void _cameraSectionDirtyChanged (bool dirty);
void _sectionDirtyChanged (bool dirty);
void _updateAltitudeInCoordinate (QVariant value);
private:
bool _specifyMissionFlightSpeed;
QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitde
Fact _plannedHomePositionAltitudeFact;
Fact _missionFlightSpeedFact;
Fact _missionEndActionFact;
CameraSection _cameraSection;
SpeedSection _speedSection;
int _sequenceNumber;
bool _dirty;
......@@ -116,7 +113,6 @@ private:
static QMap<QString, FactMetaData*> _metaDataMap;
static const char* _plannedHomePositionAltitudeName;
static const char* _missionFlightSpeedName;
static const char* _missionEndActionName;
};
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "MissionItem.h"
#include "Vehicle.h"
#include "QmlObjectListModel.h"
Q_DECLARE_LOGGING_CATEGORY(SectionLog)
// A Section encapsulates a set of mission commands which can be associated with another simple mission item.
class Section : public QObject
{
Q_OBJECT
public:
Section(Vehicle* vehicle, QObject* parent = NULL)
: QObject(parent)
, _vehicle(vehicle)
{
}
Q_PROPERTY(bool available READ available WRITE setAvailable NOTIFY availableChanged)
Q_PROPERTY(bool settingsSpecified READ settingsSpecified NOTIFY settingsSpecifiedChanged)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY availableChanged)
virtual bool available (void) const = 0;
virtual bool settingsSpecified (void) const = 0;
virtual bool dirty (void) const = 0;
virtual void setAvailable (bool available) = 0;
virtual void setDirty (bool dirty) = 0;
/// Scans the loaded items for the section items
/// @param visualItems Item list
/// @param scanIndex[in,out] Index to start scanning from
/// @return true: section found, items added, scanIndex updated
virtual bool scanForSection(QmlObjectListModel* visualItems, int& scanIndex) = 0;
/// Appends the mission items associated with this section
/// @param items List to append to
/// @param missionItemParent QObject parent for created MissionItems
/// @param nextSequenceNumber[in,out] Sequence number for first item, updated as items are added
virtual void appendSectionItems(QList<MissionItem*>& items, QObject* missionItemParent, int& nextSequenceNumber) = 0;
/// Returns the number of mission items represented by this section.
/// Signals: itemCountChanged
virtual int itemCount(void) const = 0;
signals:
void availableChanged (bool available);
void settingsSpecifiedChanged (bool settingsSpecified);
void dirtyChanged (bool dirty);
void itemCountChanged (int itemCount);
protected:
Vehicle* _vehicle;
};
......@@ -52,6 +52,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
, _rawEdit(false)
, _dirty(false)
, _ignoreDirtyChangeSignals(false)
, _speedSection(NULL)
, _cameraSection(NULL)
, _commandTree(qgcApp()->toolbox()->missionCommandTree())
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
......@@ -72,7 +73,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
_setupMetaData();
_connectSignals();
_updateCameraSection();
_updateOptionalSections();
setDefaultsForCommand();
_rebuildFacts();
......@@ -90,6 +91,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
, _rawEdit(false)
, _dirty(false)
, _ignoreDirtyChangeSignals(false)
, _speedSection(NULL)
, _cameraSection(NULL)
, _commandTree(qgcApp()->toolbox()->missionCommandTree())
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
......@@ -110,7 +112,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
_setupMetaData();
_connectSignals();
_updateCameraSection();
_updateOptionalSections();
_syncFrameToAltitudeRelativeToHome();
_rebuildFacts();
}
......@@ -121,6 +123,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
, _rawEdit(false)
, _dirty(false)
, _ignoreDirtyChangeSignals(false)
, _speedSection(NULL)
, _cameraSection(NULL)
, _commandTree(qgcApp()->toolbox()->missionCommandTree())
, _altitudeRelativeToHomeFact (0, "Altitude is relative to home", FactMetaData::valueTypeUint32)
......@@ -136,7 +139,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
_setupMetaData();
_connectSignals();
_updateCameraSection();
_updateOptionalSections();
*this = other;
......@@ -651,7 +654,7 @@ void SimpleMissionItem::setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
if ((MAV_CMD)command != _missionItem.command()) {
_missionItem.setCommand((MAV_CMD)command);
_updateCameraSection();
_updateOptionalSections();
}
}
......@@ -674,7 +677,11 @@ void SimpleMissionItem::setSequenceNumber(int sequenceNumber)
double SimpleMissionItem::specifiedFlightSpeed(void)
{
return missionItem().specifiedFlightSpeed();
if (_speedSection->specifyFlightSpeed()) {
return _speedSection->flightSpeed()->rawValue().toDouble();
} else {
return missionItem().specifiedFlightSpeed();
}
}
double SimpleMissionItem::specifiedGimbalYaw(void)
......@@ -682,47 +689,59 @@ double SimpleMissionItem::specifiedGimbalYaw(void)
return _cameraSection->available() ? _cameraSection->specifiedGimbalYaw() : missionItem().specifiedGimbalYaw();
}
bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle)
bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int& scanIndex, Vehicle* vehicle)
{
bool sectionFound = false;
Q_UNUSED(vehicle);
if (_cameraSection->available()) {
sectionFound = _cameraSection->scanForCameraSection(visualItems, scanIndex);
sectionFound |= _cameraSection->scanForSection(visualItems, scanIndex);
}
if (_speedSection->available()) {
sectionFound |= _speedSection->scanForSection(visualItems, scanIndex);
}
return sectionFound;
}
void SimpleMissionItem::_updateCameraSection(void)
void SimpleMissionItem::_updateOptionalSections(void)
{
// Remove previous sections
if (_cameraSection) {
// Remove previous section
_cameraSection->deleteLater();
_cameraSection = NULL;
}
if (_speedSection) {
_speedSection->deleteLater();
_speedSection = NULL;
}
// Add new section
_cameraSection = new CameraSection(this);
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, (MAV_CMD)command());
if (uiInfo && uiInfo->cameraSection()) {
// Add new sections
_cameraSection = new CameraSection(_vehicle, this);
_speedSection = new SpeedSection(_vehicle, this);
if ((MAV_CMD)command() == MAV_CMD_NAV_WAYPOINT) {
_cameraSection->setAvailable(true);
_speedSection->setAvailable(true);
}
connect(_cameraSection, &CameraSection::dirtyChanged, this, &SimpleMissionItem::_cameraSectionDirtyChanged);
connect(_cameraSection, &CameraSection::availableChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
connect(_cameraSection, &CameraSection::missionItemCountChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
connect(_cameraSection, &CameraSection::dirtyChanged, this, &SimpleMissionItem::_sectionDirtyChanged);
connect(_cameraSection, &CameraSection::itemCountChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
connect(_cameraSection, &CameraSection::availableChanged, this, &SimpleMissionItem::specifiedGimbalYawChanged);
connect(_cameraSection, &CameraSection::specifyGimbalChanged, this, &SimpleMissionItem::specifiedGimbalYawChanged);
connect(_cameraSection, &CameraSection::specifiedGimbalYawChanged, this, &SimpleMissionItem::specifiedGimbalYawChanged);
connect(_speedSection, &CameraSection::dirtyChanged, this, &SimpleMissionItem::_sectionDirtyChanged);
connect(_speedSection, &CameraSection::itemCountChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
emit cameraSectionChanged(_cameraSection);
emit speedSectionChanged(_speedSection);
}
int SimpleMissionItem::lastSequenceNumber(void) const
{
return sequenceNumber() + (_cameraSection ? _cameraSection->missionItemCount() : 0);
return sequenceNumber() + (_cameraSection ? _cameraSection->itemCount() : 0) + (_speedSection ? _speedSection->itemCount() : 0);
}
void SimpleMissionItem::_updateLastSequenceNumber(void)
......@@ -730,7 +749,7 @@ void SimpleMissionItem::_updateLastSequenceNumber(void)
emit lastSequenceNumberChanged(lastSequenceNumber());
}
void SimpleMissionItem::_cameraSectionDirtyChanged(bool dirty)
void SimpleMissionItem::_sectionDirtyChanged(bool dirty)
{
if (dirty) {
setDirty(true);
......@@ -744,7 +763,8 @@ void SimpleMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject*
items.append(new MissionItem(missionItem(), missionItemParent));
seqNum++;
_cameraSection->appendMissionItems(items, missionItemParent, seqNum);
_cameraSection->appendSectionItems(items, missionItemParent, seqNum);
_speedSection->appendSectionItems(items, missionItemParent, seqNum);
}
void SimpleMissionItem::applyNewAltitude(double newAltitude)
......
......@@ -15,6 +15,7 @@
#include "MissionItem.h"
#include "MissionCommandTree.h"
#include "CameraSection.h"
#include "SpeedSection.h"
/// A SimpleMissionItem is used to represent a single MissionItem to the ui.
class SimpleMissionItem : public VisualMissionItem
......@@ -31,12 +32,13 @@ public:
const SimpleMissionItem& operator=(const SimpleMissionItem& other);
Q_PROPERTY(QString category READ category NOTIFY commandChanged)
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
Q_PROPERTY(bool friendlyEditAllowed READ friendlyEditAllowed NOTIFY friendlyEditAllowedChanged)
Q_PROPERTY(bool rawEdit READ rawEdit WRITE setRawEdit NOTIFY rawEditChanged) ///< true: raw item editing with all params
Q_PROPERTY(bool relativeAltitude READ relativeAltitude NOTIFY frameChanged)
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
/// Optional sections
Q_PROPERTY(QObject* speedSection READ speedSection NOTIFY speedSectionChanged)
Q_PROPERTY(QObject* cameraSection READ cameraSection NOTIFY cameraSectionChanged)
// These properties are used to display the editing ui
......@@ -49,8 +51,8 @@ public:
/// @param visualItems List of all visual items
/// @param scanIndex Index to start scanning from
/// @param vehicle Vehicle associated with this mission
/// @return true: section found
bool scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle);
/// @return true: section found, scanIndex updated
bool scanForSections(QmlObjectListModel* visualItems, int& scanIndex, Vehicle* vehicle);
// Property accesors
......@@ -59,6 +61,7 @@ public:
bool friendlyEditAllowed (void) const;
bool rawEdit (void) const;
CameraSection* cameraSection (void) { return _cameraSection; }
SpeedSection* speedSection (void) { return _speedSection; }
QmlObjectListModel* textFieldFacts (void) { return &_textFieldFacts; }
QmlObjectListModel* nanFacts (void) { return &_nanFacts; }
......@@ -123,10 +126,11 @@ signals:
void headingDegreesChanged (double heading);
void rawEditChanged (bool rawEdit);
void cameraSectionChanged (QObject* cameraSection);
void speedSectionChanged (QObject* cameraSection);
private slots:
void _setDirtyFromSignal (void);
void _cameraSectionDirtyChanged (bool dirty);
void _setDirtyFromSignal (void);
void _sectionDirtyChanged (bool dirty);
void _sendCommandChanged (void);
void _sendCoordinateChanged (void);
void _sendFrameChanged (void);
......@@ -139,7 +143,7 @@ private slots:
private:
void _connectSignals (void);
void _setupMetaData (void);
void _updateCameraSection (void);
void _updateOptionalSections(void);
void _rebuildTextFieldFacts (void);
void _rebuildNaNFacts (void);
void _rebuildCheckboxFacts (void);
......@@ -150,6 +154,7 @@ private:
bool _dirty;
bool _ignoreDirtyChangeSignals;
SpeedSection* _speedSection;
CameraSection* _cameraSection;
MissionCommandTree* _commandTree;
......
[
{
"name": "FlightSpeed",
"shortDescription": "Set the current flight speed",
"type": "double",
"units": "m/s",
"min": 0,
"decimalPlaces": 1,
"defaultValue": 0
}
]
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "SpeedSection.h"
#include "JsonHelper.h"
#include "FirmwarePlugin.h"
#include "SimpleMissionItem.h"
const char* SpeedSection::_flightSpeedName = "FlightSpeed";
QMap<QString, FactMetaData*> SpeedSection::_metaDataMap;
SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent)
: Section (vehicle, parent)
, _available (false)
, _dirty (false)
, _specifyFlightSpeed (false)
, _flightSpeedFact (0, _flightSpeedName, FactMetaData::valueTypeDouble)
{
if (_metaDataMap.isEmpty()) {
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/SpeedSection.FactMetaData.json"), NULL /* metaDataParent */);
}
double hoverSpeed, cruiseSpeed;
double flightSpeed = 0;
_vehicle->firmwarePlugin()->missionFlightSpeedInfo(_vehicle, hoverSpeed, cruiseSpeed);
if (_vehicle->multiRotor()) {
flightSpeed = hoverSpeed;
} else if (_vehicle->fixedWing()) {
flightSpeed = cruiseSpeed;
}
_metaDataMap[_flightSpeedName]->setRawDefaultValue(flightSpeed);
_flightSpeedFact.setMetaData(_metaDataMap[_flightSpeedName]);
_flightSpeedFact.setRawValue(flightSpeed);
connect(this, &SpeedSection::specifyFlightSpeedChanged, this, &SpeedSection::_setDirtyAndUpdateItemCount);
connect(this, &SpeedSection::specifyFlightSpeedChanged, this, &SpeedSection::settingsSpecifiedChanged);
connect(&_flightSpeedFact, &Fact::valueChanged, this, &SpeedSection::_setDirty);
}
bool SpeedSection::settingsSpecified(void) const
{
return _specifyFlightSpeed;
}
void SpeedSection::setAvailable(bool available)
{
if (available != _available) {
if (available && (_vehicle->multiRotor() || _vehicle->fixedWing())) {
_available = available;
emit availableChanged(available);
}
}
}
void SpeedSection::_setDirty(void)
{
setDirty(true);
}
void SpeedSection::_setDirtyAndUpdateItemCount(void)
{
setDirty(true);
emit itemCountChanged(itemCount());
}
void SpeedSection::setDirty(bool dirty)
{
if (_dirty != dirty) {
_dirty = dirty;
emit dirtyChanged(_dirty);
}
}
void SpeedSection::setSpecifyFlightSpeed(bool specifyFlightSpeed)
{
if (specifyFlightSpeed != _specifyFlightSpeed) {
_specifyFlightSpeed = specifyFlightSpeed;
emit specifyFlightSpeedChanged(specifyFlightSpeed);
}
}
int SpeedSection::itemCount(void) const
{
return _specifyFlightSpeed ? 1: 0;
}
void SpeedSection::appendSectionItems(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum)
{
// IMPORTANT NOTE: If anything changes here you must also change SpeedSection::scanForSettings
if (_specifyFlightSpeed) {
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_DO_CHANGE_SPEED,
MAV_FRAME_MISSION,
_vehicle->multiRotor() ? 1 /* groundspeed */ : 0 /* airspeed */, // Change airspeed or groundspeed
_flightSpeedFact.rawValue().toDouble(),
-1, // No throttle change
0, // Absolute speed change
0, 0, 0, // param 5-7 not used
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
}
bool SpeedSection::scanForSection(QmlObjectListModel* visualItems, int& scanIndex)
{
if (!_available || scanIndex >= visualItems->count()) {
return false;
}
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (!item) {
// We hit a complex item, there can't be a speed setting
return false;
}
MissionItem& missionItem = item->missionItem();
// See SpeedSection::appendMissionItems for specs on what consitutes a known speed setting
if (missionItem.command() == MAV_CMD_DO_CHANGE_SPEED && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
if (_vehicle->multiRotor() && missionItem.param1() != 1) {
return false;
} else if (_vehicle->fixedWing() && missionItem.param1() != 0) {
return false;
}
visualItems->removeAt(scanIndex)->deleteLater();
_flightSpeedFact.setRawValue(missionItem.param2());
setSpecifyFlightSpeed(true);
scanIndex++;
return true;
}
return false;
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "Section.h"
#include "FactSystem.h"
#include "QmlObjectListModel.h"
class SpeedSection : public Section
{
Q_OBJECT
public:
SpeedSection(Vehicle* vehicle, QObject* parent = NULL);
Q_PROPERTY(bool specifyFlightSpeed READ specifyFlightSpeed WRITE setSpecifyFlightSpeed NOTIFY specifyFlightSpeedChanged)
Q_PROPERTY(Fact* flightSpeed READ flightSpeed CONSTANT)
bool specifyFlightSpeed (void) const { return _specifyFlightSpeed; }
Fact* flightSpeed (void) { return &_flightSpeedFact; }
void setSpecifyFlightSpeed (bool specifyFlightSpeed);
// Overrides from Section
bool available (void) const override { return _available; }
bool dirty (void) const override { return _dirty; }
void setAvailable (bool available) override;
void setDirty (bool dirty) override;
bool scanForSection (QmlObjectListModel* visualItems, int& scanIndex) override;
void appendSectionItems (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum) override;
int itemCount (void) const override;
bool settingsSpecified (void) const override;
signals:
void specifyFlightSpeedChanged(bool specifyFlightSpeed);
private slots:
void _setDirty(void);
void _setDirtyAndUpdateItemCount(void);
private:
bool _available;
bool _dirty;
bool _specifyFlightSpeed;
Fact _flightSpeedFact;
static QMap<QString, FactMetaData*> _metaDataMap;
static const char* _flightSpeedName;
};
......@@ -31,7 +31,8 @@ Rectangle {
property bool _mobile: ScreenTools.isMobile
property var _savePath: QGroundControl.settingsManager.appSettings.missionSavePath
property var _fileExtension: QGroundControl.settingsManager.appSettings.missionFileExtension
property var _appSettings: QGroundControl.settingsManager.appSettings
property var _appSettings: QGroundControl.settingsManager.appSettings
property bool _waypointsOnlyMode: QGroundControl.corePlugin.options.missionWaypointsOnly
readonly property string _firmwareLabel: qsTr("Firmware")
readonly property string _vehicleLabel: qsTr("Vehicle")
......@@ -112,12 +113,12 @@ Rectangle {
id: flightSpeedCheckBox
text: qsTr("Flight speed")
visible: !_missionVehicle.vtol
checked: missionItem.specifyMissionFlightSpeed
onClicked: missionItem.specifyMissionFlightSpeed = checked
checked: missionItem.speedSection.specifyFlightSpeed
onClicked: missionItem.speedSection.specifyFlightSpeed = checked
}
FactTextField {
Layout.fillWidth: true
fact: missionItem.missionFlightSpeed
fact: missionItem.speedSection.flightSpeed
visible: flightSpeedCheckBox.visible
enabled: flightSpeedCheckBox.checked
}
......@@ -138,7 +139,7 @@ Rectangle {
SectionHeader {
id: vehicleInfoSectionHeader
text: qsTr("Vehicle Info")
visible: _offlineEditing
visible: _offlineEditing && !_waypointsOnlyMode
checked: false
}
......
......@@ -138,6 +138,26 @@ Rectangle {
}
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: ScreenTools.defaultFontPixelWidth
visible: missionItem.speedSection.available
QGCCheckBox {
id: flightSpeedCheckbox
text: qsTr("Flight Speed")
checked: missionItem.speedSection.specifyFlightSpeed
onClicked: missionItem.speedSection.specifyFlightSpeed = checked
}
FactTextField {
fact: missionItem.speedSection.flightSpeed
Layout.fillWidth: true
enabled: flightSpeedCheckbox.checked
}
}
Repeater {
model: missionItem.checkboxFacts
......
......@@ -74,7 +74,7 @@ Canvas {
color: "white"
opacity: 0.5
radius: _labelRadius
visible: _label.length !== 0
visible: _label.length !== 0 && !small
}
QGCLabel {
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment