diff --git a/libs/mavlink/include/mavlink/v2.0 b/libs/mavlink/include/mavlink/v2.0
index 1b0dc4732864efadd72f9bfc89762bdb956c8638..37d14af47d783eb516959cc10e4cf70d66e927c0 160000
--- a/libs/mavlink/include/mavlink/v2.0
+++ b/libs/mavlink/include/mavlink/v2.0
@@ -1 +1 @@
-Subproject commit 1b0dc4732864efadd72f9bfc89762bdb956c8638
+Subproject commit 37d14af47d783eb516959cc10e4cf70d66e927c0
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 46d151e35fe2a7d0dec3a8edbcf48f5c23e8d29c..f567621e4c12527dcf58cc4492d21d988d24d505 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -568,7 +568,6 @@ HEADERS += \
src/QmlControls/AppMessages.h \
src/QmlControls/CoordinateVector.h \
src/QmlControls/EditPositionDialogController.h \
- src/QmlControls/MavlinkQmlSingleton.h \
src/QmlControls/ParameterEditorController.h \
src/QmlControls/QGCFileDialogController.h \
src/QmlControls/QGCImageProvider.h \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index ce7371c7502275d9f819ae8f4b60ad40c684843e..dd06a037add326dbed44965e70f8327fa119e17c 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -125,6 +125,7 @@
src/QmlControls/SliderSwitch.qml
src/QmlControls/SubMenuButton.qml
src/PlanView/SurveyMapVisual.qml
+ src/PlanView/TransectStyleComplexItemStats.qml
src/QmlControls/ToolStrip.qml
src/QmlControls/VehicleRotationCal.qml
src/QmlControls/VehicleSummaryRow.qml
diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
index 4fd9a8141bcb641af9265ab6402bb2872ca44c9c..db5ac58bd7d6ba6a7779c50eb0fdde18ad95b258 100644
--- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
+++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
@@ -4255,13 +4255,19 @@ default 1.5 turns per second
5
modules/mc_att_control
+
+ Multicopter air-mode
+ The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable.
+
+ modules/mc_att_control
+
Battery power level scaler
This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.
modules/mc_att_control
-
+
Cutoff frequency for the low pass filter on the D-term in the rate controller
The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to decrease the driver-level filtering, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter.
0
@@ -9524,11 +9530,6 @@ tailsitter, tiltrotor: main throttle
1
modules/vtol_att_control
-
- Optimal recovery strategy for pitch-weak tailsitters
-
- modules/vtol_att_control
-
Defines the time window during which the pusher throttle will be ramped up linearly to VT_F_TRANS_THR during a transition
to fixed wing mode. Zero or negative values will produce an instant throttle rise to VT_F_TRANS_THR
@@ -9611,6 +9612,51 @@ to fixed wing mode. Zero or negative values will produce an instant throttle ris
modules/vtol_att_control
+
+
+ Gate size for true sideslip fusion
+ Sets the number of standard deviations used by the innovation consistency test.
+ 1
+ 5
+ SD
+ modules/wind_estimator
+
+
+ Wind estimator sideslip measurement noise
+ 0
+ 1
+ rad
+ modules/wind_estimator
+
+
+ Wind estimator true airspeed scale process noise
+ 0
+ 0.1
+ modules/wind_estimator
+
+
+ Gate size for true airspeed fusion
+ Sets the number of standard deviations used by the innovation consistency test.
+ 1
+ 5
+ SD
+ modules/wind_estimator
+
+
+ Wind estimator true airspeed measurement noise
+ 0
+ 4
+ m/s
+ modules/wind_estimator
+
+
+ Wind estimator wind process noise
+ 0
+ 1
+ m/s/s
+ modules/wind_estimator
+
+
EXFW_HDNG_P
diff --git a/src/FlightMap/FlightMap.qml b/src/FlightMap/FlightMap.qml
index f478186ae1d2b8e80edf8f7b3d41f25468251825..4a7266b754b0250edfa10ce47161183e7612287c 100644
--- a/src/FlightMap/FlightMap.qml
+++ b/src/FlightMap/FlightMap.qml
@@ -19,7 +19,6 @@ import QGroundControl.FlightMap 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.MultiVehicleManager 1.0
import QGroundControl.Vehicle 1.0
-import QGroundControl.Mavlink 1.0
import QGroundControl.QGCPositionManager 1.0
Map {
diff --git a/src/MissionManager/CorridorScanComplexItem.cc b/src/MissionManager/CorridorScanComplexItem.cc
index f5bdd904410f8cd40a792ea3fda4452d73915437..a69c71b7d3df24899ace5b8759960bffc865bae2 100644
--- a/src/MissionManager/CorridorScanComplexItem.cc
+++ b/src/MissionManager/CorridorScanComplexItem.cc
@@ -305,12 +305,15 @@ void CorridorScanComplexItem::_rebuildCorridorPolygon(void)
QList secondSideVertices = _corridorPolyline.offsetPolyline(-halfWidth);
_surveyAreaPolygon.clear();
+
+ QList rgCoord;
foreach (const QGeoCoordinate& vertex, firstSideVertices) {
- _surveyAreaPolygon.appendVertex(vertex);
+ rgCoord.append(vertex);
}
for (int i=secondSideVertices.count() - 1; i >= 0; i--) {
- _surveyAreaPolygon.appendVertex(secondSideVertices[i]);
+ rgCoord.append(secondSideVertices[i]);
}
+ _surveyAreaPolygon.appendVertices(rgCoord);
}
void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
diff --git a/src/MissionManager/FWLandingPattern.FactMetaData.json b/src/MissionManager/FWLandingPattern.FactMetaData.json
index ca77c066c2ef877f4e729492601a63872e09bd9b..6d1a9a16ba32fdc7ea274189b9c82f9c8806b569 100644
--- a/src/MissionManager/FWLandingPattern.FactMetaData.json
+++ b/src/MissionManager/FWLandingPattern.FactMetaData.json
@@ -44,12 +44,12 @@
"defaultValue": 0.0
},
{
- "name": "DescentRate",
- "shortDescription": "Descent rate between landing and loiter altitude.",
+ "name": "GlideSlope",
+ "shortDescription": "The glide slope between the loiter and landing point.",
"type": "double",
- "units": "%",
+ "units": "deg",
"min": 0.1,
- "max": 100,
+ "max": 90,
"decimalPlaces": 1,
"defaultValue": 12.0
}
diff --git a/src/MissionManager/FixedWingLandingComplexItem.cc b/src/MissionManager/FixedWingLandingComplexItem.cc
index e81cb512abc96865179a319bcc15cbdc32363326..a744e86a8cf1b6f42c39b0916521fc8e19b3fe8e 100644
--- a/src/MissionManager/FixedWingLandingComplexItem.cc
+++ b/src/MissionManager/FixedWingLandingComplexItem.cc
@@ -25,15 +25,19 @@ const char* FixedWingLandingComplexItem::landingHeadingName = "LandingHead
const char* FixedWingLandingComplexItem::loiterAltitudeName = "LoiterAltitude";
const char* FixedWingLandingComplexItem::loiterRadiusName = "LoiterRadius";
const char* FixedWingLandingComplexItem::landingAltitudeName = "LandingAltitude";
-const char* FixedWingLandingComplexItem::fallRateName = "DescentRate";
+const char* FixedWingLandingComplexItem::glideSlopeName = "GlideSlope";
const char* FixedWingLandingComplexItem::_jsonLoiterCoordinateKey = "loiterCoordinate";
const char* FixedWingLandingComplexItem::_jsonLoiterRadiusKey = "loiterRadius";
const char* FixedWingLandingComplexItem::_jsonLoiterClockwiseKey = "loiterClockwise";
-const char* FixedWingLandingComplexItem::_jsonLoiterAltitudeRelativeKey = "loiterAltitudeRelative";
const char* FixedWingLandingComplexItem::_jsonLandingCoordinateKey = "landCoordinate";
-const char* FixedWingLandingComplexItem::_jsonLandingAltitudeRelativeKey = "landAltitudeRelative";
+const char* FixedWingLandingComplexItem::_jsonValueSetIsDistanceKey = "valueSetIsDistance";
+const char* FixedWingLandingComplexItem::_jsonAltitudesAreRelativeKey = "altitudesAreRelative";
+
+// Usage deprecated
const char* FixedWingLandingComplexItem::_jsonFallRateKey = "fallRate";
+const char* FixedWingLandingComplexItem::_jsonLandingAltitudeRelativeKey = "landAltitudeRelative";
+const char* FixedWingLandingComplexItem::_jsonLoiterAltitudeRelativeKey = "loiterAltitudeRelative";
FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObject* parent)
: ComplexMissionItem (vehicle, parent)
@@ -47,10 +51,10 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObje
, _loiterRadiusFact (_metaDataMap[loiterRadiusName])
, _landingHeadingFact (_metaDataMap[landingHeadingName])
, _landingAltitudeFact (_metaDataMap[landingAltitudeName])
- , _fallRateFact (_metaDataMap[fallRateName])
+ , _glideSlopeFact (_metaDataMap[glideSlopeName])
, _loiterClockwise (true)
- , _loiterAltitudeRelative (true)
- , _landingAltitudeRelative (true)
+ , _altitudesAreRelative (true)
+ , _valueSetIsDistance (true)
{
_editorQml = "qrc:/qml/FWLandingPatternEditor.qml";
@@ -66,6 +70,8 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObje
connect(this, &FixedWingLandingComplexItem::loiterCoordinateChanged, this, &FixedWingLandingComplexItem::_recalcFromCoordinateChange);
connect(this, &FixedWingLandingComplexItem::landingCoordinateChanged, this, &FixedWingLandingComplexItem::_recalcFromCoordinateChange);
+ connect(&_glideSlopeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_glideSlopeChanged);
+
connect(&_loiterAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(&_landingAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(&_landingDistanceFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_setDirty);
@@ -74,11 +80,10 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObje
connect(this, &FixedWingLandingComplexItem::loiterCoordinateChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(this, &FixedWingLandingComplexItem::landingCoordinateChanged, this, &FixedWingLandingComplexItem::_setDirty);
connect(this, &FixedWingLandingComplexItem::loiterClockwiseChanged, this, &FixedWingLandingComplexItem::_setDirty);
- connect(this, &FixedWingLandingComplexItem::loiterAltitudeRelativeChanged, this, &FixedWingLandingComplexItem::_setDirty);
- connect(this, &FixedWingLandingComplexItem::landingAltitudeRelativeChanged, this, &FixedWingLandingComplexItem::_setDirty);
+ connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::_setDirty);
- connect(this, &FixedWingLandingComplexItem::loiterAltitudeRelativeChanged, this, &FixedWingLandingComplexItem::coordinateHasRelativeAltitudeChanged);
- connect(this, &FixedWingLandingComplexItem::landingAltitudeRelativeChanged, this, &FixedWingLandingComplexItem::exitCoordinateHasRelativeAltitudeChanged);
+ connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::coordinateHasRelativeAltitudeChanged);
+ connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::exitCoordinateHasRelativeAltitudeChanged);
}
int FixedWingLandingComplexItem::lastSequenceNumber(void) const
@@ -99,7 +104,7 @@ void FixedWingLandingComplexItem::save(QJsonArray& missionItems)
{
QJsonObject saveObject;
- saveObject[JsonHelper::jsonVersionKey] = 1;
+ saveObject[JsonHelper::jsonVersionKey] = 2;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
@@ -116,10 +121,10 @@ void FixedWingLandingComplexItem::save(QJsonArray& missionItems)
JsonHelper::saveGeoCoordinate(coordinate, true /* writeAltitude */, jsonCoordinate);
saveObject[_jsonLandingCoordinateKey] = jsonCoordinate;
- saveObject[_jsonLoiterRadiusKey] = _loiterRadiusFact.rawValue().toDouble();
- saveObject[_jsonLoiterClockwiseKey] = _loiterClockwise;
- saveObject[_jsonLoiterAltitudeRelativeKey] = _loiterAltitudeRelative;
- saveObject[_jsonLandingAltitudeRelativeKey] = _landingAltitudeRelative;
+ saveObject[_jsonLoiterRadiusKey] = _loiterRadiusFact.rawValue().toDouble();
+ saveObject[_jsonLoiterClockwiseKey] = _loiterClockwise;
+ saveObject[_jsonAltitudesAreRelativeKey] = _altitudesAreRelative;
+ saveObject[_jsonValueSetIsDistanceKey] = _valueSetIsDistance;
missionItems.append(saveObject);
}
@@ -142,9 +147,7 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq
{ _jsonLoiterCoordinateKey, QJsonValue::Array, true },
{ _jsonLoiterRadiusKey, QJsonValue::Double, true },
{ _jsonLoiterClockwiseKey, QJsonValue::Bool, true },
- { _jsonLoiterAltitudeRelativeKey, QJsonValue::Bool, true },
{ _jsonLandingCoordinateKey, QJsonValue::Array, true },
- { _jsonLandingAltitudeRelativeKey, QJsonValue::Bool, true },
};
if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
return false;
@@ -161,6 +164,45 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq
_ignoreRecalcSignals = true;
+ int version = complexObject[JsonHelper::jsonVersionKey].toInt();
+ if (version == 1) {
+ QList v1KeyInfoList = {
+ { _jsonLoiterAltitudeRelativeKey, QJsonValue::Bool, true },
+ { _jsonLandingAltitudeRelativeKey, QJsonValue::Bool, true },
+ };
+ if (!JsonHelper::validateKeys(complexObject, v1KeyInfoList, errorString)) {
+ return false;
+ }
+
+ bool loiterAltitudeRelative = complexObject[_jsonLoiterAltitudeRelativeKey].toBool();
+ bool landingAltitudeRelative = complexObject[_jsonLandingAltitudeRelativeKey].toBool();
+ if (loiterAltitudeRelative != landingAltitudeRelative) {
+ qgcApp()->showMessage(tr("Fixed Wing Landing Pattern: "
+ "Setting the loiter and landing altitudes with different settings for altitude relative is no longer supported. "
+ "Both have been set to altitude relative. Be sure to adjust/check your plan prior to flight."));
+ _altitudesAreRelative = true;
+ } else {
+ _altitudesAreRelative = loiterAltitudeRelative;
+ }
+ _valueSetIsDistance = true;
+ } else if (version == 2) {
+ QList v2KeyInfoList = {
+ { _jsonAltitudesAreRelativeKey, QJsonValue::Bool, true },
+ { _jsonValueSetIsDistanceKey, QJsonValue::Bool, true },
+ };
+ if (!JsonHelper::validateKeys(complexObject, v2KeyInfoList, errorString)) {
+ _ignoreRecalcSignals = false;
+ return false;
+ }
+
+ _altitudesAreRelative = complexObject[_jsonAltitudesAreRelativeKey].toBool();
+ _valueSetIsDistance = complexObject[_jsonValueSetIsDistanceKey].toBool();
+ } else {
+ errorString = tr("%1 complex item version %2 not supported").arg(jsonComplexItemTypeValue).arg(version);
+ _ignoreRecalcSignals = false;
+ return false;
+ }
+
QGeoCoordinate coordinate;
if (!JsonHelper::loadGeoCoordinate(complexObject[_jsonLoiterCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
return false;
@@ -175,9 +217,9 @@ bool FixedWingLandingComplexItem::load(const QJsonObject& complexObject, int seq
_landingAltitudeFact.setRawValue(coordinate.altitude());
_loiterRadiusFact.setRawValue(complexObject[_jsonLoiterRadiusKey].toDouble());
- _loiterClockwise = complexObject[_jsonLoiterClockwiseKey].toBool();
- _loiterAltitudeRelative = complexObject[_jsonLoiterAltitudeRelativeKey].toBool();
- _landingAltitudeRelative = complexObject[_jsonLandingAltitudeRelativeKey].toBool();
+ _loiterClockwise = complexObject[_jsonLoiterClockwiseKey].toBool();
+
+ _calcGlideSlope();
_landingCoordSet = true;
@@ -215,7 +257,7 @@ void FixedWingLandingComplexItem::appendMissionItems(QList& items,
float loiterRadius = _loiterRadiusFact.rawValue().toDouble() * (_loiterClockwise ? 1.0 : -1.0);
item = new MissionItem(seqNum++,
MAV_CMD_NAV_LOITER_TO_ALT,
- _loiterAltitudeRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
+ _altitudesAreRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
1.0, // Heading required = true
loiterRadius, // Loiter radius
0.0, // param 3 - unused
@@ -230,7 +272,7 @@ void FixedWingLandingComplexItem::appendMissionItems(QList& items,
item = new MissionItem(seqNum++,
MAV_CMD_NAV_LAND,
- _landingAltitudeRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
+ _altitudesAreRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
0.0, 0.0, 0.0, 0.0, // param 1-4
_landingCoordinate.latitude(),
_landingCoordinate.longitude(),
@@ -261,6 +303,7 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V
missionItemLand.param1() != 0 || missionItemLand.param2() != 0 || missionItemLand.param3() != 0 || missionItemLand.param4() == 1.0) {
return false;
}
+ MAV_FRAME landPointFrame = missionItemLand.frame();
item = visualItems->value(lastItem--);
if (!item) {
@@ -268,7 +311,7 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V
}
MissionItem& missionItemLoiter = item->missionItem();
if (missionItemLoiter.command() != MAV_CMD_NAV_LOITER_TO_ALT ||
- !(missionItemLoiter.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT || missionItemLoiter.frame() == MAV_FRAME_GLOBAL) ||
+ missionItemLoiter.frame() != landPointFrame ||
missionItemLoiter.param1() != 1.0 || missionItemLoiter.param3() != 0 || missionItemLoiter.param4() != 1.0) {
return false;
}
@@ -289,18 +332,19 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, V
complexItem->_ignoreRecalcSignals = true;
- complexItem->_loiterAltitudeRelative = missionItemLoiter.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT;
+ complexItem->_altitudesAreRelative = landPointFrame == MAV_FRAME_GLOBAL_RELATIVE_ALT;
complexItem->_loiterRadiusFact.setRawValue(qAbs(missionItemLoiter.param2()));
complexItem->_loiterClockwise = missionItemLoiter.param2() > 0;
complexItem->_loiterCoordinate.setLatitude(missionItemLoiter.param5());
complexItem->_loiterCoordinate.setLongitude(missionItemLoiter.param6());
complexItem->_loiterAltitudeFact.setRawValue(missionItemLoiter.param7());
- complexItem->_landingAltitudeRelative = missionItemLand.frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT;
complexItem->_landingCoordinate.setLatitude(missionItemLand.param5());
complexItem->_landingCoordinate.setLongitude(missionItemLand.param6());
complexItem->_landingAltitudeFact.setRawValue(missionItemLand.param7());
+ complexItem->_calcGlideSlope();
+
complexItem->_landingCoordSet = true;
complexItem->_ignoreRecalcSignals = false;
@@ -418,6 +462,7 @@ void FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
// Adjusted:
// loiter
// loiter tangent
+ // glide slope
if (!_ignoreRecalcSignals && _landingCoordSet) {
// These are our known values
@@ -442,6 +487,7 @@ void FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
emit loiterTangentCoordinateChanged(_loiterTangentCoordinate);
emit loiterCoordinateChanged(_loiterCoordinate);
emit coordinateChanged(_loiterCoordinate);
+ _calcGlideSlope();
_ignoreRecalcSignals = false;
}
}
@@ -467,6 +513,7 @@ void FixedWingLandingComplexItem::_recalcFromCoordinateChange(void)
// loiter tangent
// heading
// distance
+ // glide slope
if (!_ignoreRecalcSignals && _landingCoordSet) {
// These are our known values
@@ -493,6 +540,7 @@ void FixedWingLandingComplexItem::_recalcFromCoordinateChange(void)
_landingHeadingFact.setRawValue(heading);
_landingDistanceFact.setRawValue(landToTangentDistance);
emit loiterTangentCoordinateChanged(_loiterTangentCoordinate);
+ _calcGlideSlope();
_ignoreRecalcSignals = false;
}
}
@@ -519,3 +567,20 @@ void FixedWingLandingComplexItem::applyNewAltitude(double newAltitude)
{
_loiterAltitudeFact.setRawValue(newAltitude);
}
+
+void FixedWingLandingComplexItem::_glideSlopeChanged(void)
+{
+ if (!_ignoreRecalcSignals) {
+ double landingAltDifference = _loiterAltitudeFact.rawValue().toDouble() - _landingAltitudeFact.rawValue().toDouble();
+ double glideSlope = _glideSlopeFact.rawValue().toDouble();
+ _landingDistanceFact.setRawValue(landingAltDifference / qTan(qDegreesToRadians(glideSlope)));
+ }
+}
+
+void FixedWingLandingComplexItem::_calcGlideSlope(void)
+{
+ double landingAltDifference = _loiterAltitudeFact.rawValue().toDouble() - _landingAltitudeFact.rawValue().toDouble();
+ double landingDistance = _landingDistanceFact.rawValue().toDouble();
+
+ _glideSlopeFact.setRawValue(qRadiansToDegrees(qAtan(landingAltDifference / landingDistance)));
+}
diff --git a/src/MissionManager/FixedWingLandingComplexItem.h b/src/MissionManager/FixedWingLandingComplexItem.h
index 9d04c053af843586181049b071bdd2317d2d71e8..c04d66f614253f4c6e6ebca69837e022daf0807b 100644
--- a/src/MissionManager/FixedWingLandingComplexItem.h
+++ b/src/MissionManager/FixedWingLandingComplexItem.h
@@ -24,26 +24,26 @@ class FixedWingLandingComplexItem : public ComplexMissionItem
public:
FixedWingLandingComplexItem(Vehicle* vehicle, QObject* parent = NULL);
- Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT)
- Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT)
- Q_PROPERTY(Fact* landingAltitude READ landingAltitude CONSTANT)
- Q_PROPERTY(Fact* landingDistance READ landingDistance CONSTANT)
- Q_PROPERTY(Fact* landingHeading READ landingHeading CONSTANT)
- Q_PROPERTY(Fact* fallRate READ fallRate CONSTANT)
- Q_PROPERTY(bool loiterClockwise MEMBER _loiterClockwise NOTIFY loiterClockwiseChanged)
- Q_PROPERTY(bool loiterAltitudeRelative MEMBER _loiterAltitudeRelative NOTIFY loiterAltitudeRelativeChanged)
- Q_PROPERTY(bool landingAltitudeRelative MEMBER _landingAltitudeRelative NOTIFY landingAltitudeRelativeChanged)
- Q_PROPERTY(QGeoCoordinate loiterCoordinate READ loiterCoordinate WRITE setLoiterCoordinate NOTIFY loiterCoordinateChanged)
- Q_PROPERTY(QGeoCoordinate loiterTangentCoordinate READ loiterTangentCoordinate NOTIFY loiterTangentCoordinateChanged)
- Q_PROPERTY(QGeoCoordinate landingCoordinate READ landingCoordinate WRITE setLandingCoordinate NOTIFY landingCoordinateChanged)
- Q_PROPERTY(bool landingCoordSet MEMBER _landingCoordSet NOTIFY landingCoordSetChanged)
+ Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT)
+ Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT)
+ Q_PROPERTY(Fact* landingAltitude READ landingAltitude CONSTANT)
+ Q_PROPERTY(Fact* landingHeading READ landingHeading CONSTANT)
+ Q_PROPERTY(bool valueSetIsDistance MEMBER _valueSetIsDistance NOTIFY valueSetIsDistanceChanged)
+ Q_PROPERTY(Fact* landingDistance READ landingDistance CONSTANT)
+ Q_PROPERTY(Fact* glideSlope READ glideSlope CONSTANT)
+ Q_PROPERTY(bool loiterClockwise MEMBER _loiterClockwise NOTIFY loiterClockwiseChanged)
+ Q_PROPERTY(bool altitudesAreRelative MEMBER _altitudesAreRelative NOTIFY altitudesAreRelativeChanged)
+ Q_PROPERTY(QGeoCoordinate loiterCoordinate READ loiterCoordinate WRITE setLoiterCoordinate NOTIFY loiterCoordinateChanged)
+ Q_PROPERTY(QGeoCoordinate loiterTangentCoordinate READ loiterTangentCoordinate NOTIFY loiterTangentCoordinateChanged)
+ Q_PROPERTY(QGeoCoordinate landingCoordinate READ landingCoordinate WRITE setLandingCoordinate NOTIFY landingCoordinateChanged)
+ Q_PROPERTY(bool landingCoordSet MEMBER _landingCoordSet NOTIFY landingCoordSetChanged)
Fact* loiterAltitude (void) { return &_loiterAltitudeFact; }
Fact* loiterRadius (void) { return &_loiterRadiusFact; }
Fact* landingAltitude (void) { return &_landingAltitudeFact; }
Fact* landingDistance (void) { return &_landingDistanceFact; }
Fact* landingHeading (void) { return &_landingHeadingFact; }
- Fact* fallRate (void) { return &_fallRateFact; }
+ Fact* glideSlope (void) { return &_glideSlopeFact; }
QGeoCoordinate landingCoordinate (void) const { return _landingCoordinate; }
QGeoCoordinate loiterCoordinate (void) const { return _loiterCoordinate; }
QGeoCoordinate loiterTangentCoordinate (void) const { return _loiterTangentCoordinate; }
@@ -81,8 +81,8 @@ public:
void appendMissionItems (QList& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
- bool coordinateHasRelativeAltitude (void) const final { return _loiterAltitudeRelative; }
- bool exitCoordinateHasRelativeAltitude (void) const final { return _landingAltitudeRelative; }
+ bool coordinateHasRelativeAltitude (void) const final { return _altitudesAreRelative; }
+ bool exitCoordinateHasRelativeAltitude (void) const final { return _altitudesAreRelative; }
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
@@ -97,7 +97,7 @@ public:
static const char* loiterRadiusName;
static const char* landingHeadingName;
static const char* landingAltitudeName;
- static const char* fallRateName;
+ static const char* glideSlopeName;
signals:
void loiterCoordinateChanged (QGeoCoordinate coordinate);
@@ -105,21 +105,23 @@ signals:
void landingCoordinateChanged (QGeoCoordinate coordinate);
void landingCoordSetChanged (bool landingCoordSet);
void loiterClockwiseChanged (bool loiterClockwise);
- void loiterAltitudeRelativeChanged (bool loiterAltitudeRelative);
- void landingAltitudeRelativeChanged (bool loiterAltitudeRelative);
+ void altitudesAreRelativeChanged (bool altitudesAreRelative);
+ void valueSetIsDistanceChanged (bool valueSetIsDistance);
private slots:
- void _recalcFromHeadingAndDistanceChange(void);
- void _recalcFromCoordinateChange(void);
- void _recalcFromRadiusChange(void);
- void _updateLoiterCoodinateAltitudeFromFact(void);
- void _updateLandingCoodinateAltitudeFromFact(void);
- double _mathematicAngleToHeading(double angle);
- double _headingToMathematicAngle(double heading);
- void _setDirty(void);
+ void _recalcFromHeadingAndDistanceChange (void);
+ void _recalcFromCoordinateChange (void);
+ void _recalcFromRadiusChange (void);
+ void _updateLoiterCoodinateAltitudeFromFact (void);
+ void _updateLandingCoodinateAltitudeFromFact (void);
+ double _mathematicAngleToHeading (double angle);
+ double _headingToMathematicAngle (double heading);
+ void _setDirty (void);
+ void _glideSlopeChanged (void);
private:
- QPointF _rotatePoint(const QPointF& point, const QPointF& origin, double angle);
+ QPointF _rotatePoint (const QPointF& point, const QPointF& origin, double angle);
+ void _calcGlideSlope (void);
int _sequenceNumber;
bool _dirty;
@@ -136,18 +138,22 @@ private:
Fact _loiterRadiusFact;
Fact _landingHeadingFact;
Fact _landingAltitudeFact;
- Fact _fallRateFact;
+ Fact _glideSlopeFact;
bool _loiterClockwise;
- bool _loiterAltitudeRelative;
- bool _landingAltitudeRelative;
+ bool _altitudesAreRelative;
+ bool _valueSetIsDistance;
static const char* _jsonLoiterCoordinateKey;
static const char* _jsonLoiterRadiusKey;
static const char* _jsonLoiterClockwiseKey;
- static const char* _jsonLoiterAltitudeRelativeKey;
static const char* _jsonLandingCoordinateKey;
+ static const char* _jsonValueSetIsDistanceKey;
+ static const char* _jsonAltitudesAreRelativeKey;
+
+ // Only in older file formats
static const char* _jsonLandingAltitudeRelativeKey;
+ static const char* _jsonLoiterAltitudeRelativeKey;
static const char* _jsonFallRateKey;
};
diff --git a/src/MissionManager/MissionCommandList.h b/src/MissionManager/MissionCommandList.h
index 79c6ef633dc1c29c9307269e8cfae6ef0e2e47b3..319020002311e3b50400e6eb2679326ff1cb6c96 100644
--- a/src/MissionManager/MissionCommandList.h
+++ b/src/MissionManager/MissionCommandList.h
@@ -14,7 +14,6 @@
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
-#include "MavlinkQmlSingleton.h"
#include
#include
diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc
index db5450c35ead4d4a48cfea99c4379620ee7cd297..92dacd91c9398021cca8ae40b8c14a124d5bb5e0 100644
--- a/src/MissionManager/MissionController.cc
+++ b/src/MissionManager/MissionController.cc
@@ -339,10 +339,10 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this);
newItem->setSequenceNumber(sequenceNumber);
newItem->setCoordinate(coordinate);
- newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
+ newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
_initVisualItem(newItem);
if (_visualItems->count() == 1) {
- MavlinkQmlSingleton::Qml_MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF : MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF;
+ MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)takeoffCmd)) {
newItem->setCommand(takeoffCmd);
}
@@ -369,7 +369,7 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
int sequenceNumber = _nextSequenceNumber();
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, this);
newItem->setSequenceNumber(sequenceNumber);
- newItem->setCommand((MavlinkQmlSingleton::Qml_MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ?
+ newItem->setCommand((MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ?
MAV_CMD_DO_SET_ROI_LOCATION :
MAV_CMD_DO_SET_ROI));
_initVisualItem(newItem);
@@ -845,7 +845,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
// Update sequence numbers in DO_JUMP commands to take into account added home position in index 0
for (int i=1; icount(); i++) {
SimpleMissionItem* item = qobject_cast(visualItems->get(i));
- if (item && item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
+ if (item && item->command() == MAV_CMD_DO_JUMP) {
item->missionItem().setParam1((int)item->missionItem().param1() + 1);
}
}
@@ -1302,7 +1302,7 @@ void MissionController::_recalcMissionFlightStatus()
}
// Link back to home if first item is takeoff and we have home position
- if (firstCoordinateItem && simpleItem && (simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
+ if (firstCoordinateItem && simpleItem && (simpleItem->command() == MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
if (showHomePosition) {
linkStartToHome = true;
if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
@@ -1318,19 +1318,19 @@ void MissionController::_recalcMissionFlightStatus()
// Update VTOL state
if (simpleItem && _controllerVehicle->vtol()) {
switch (simpleItem->command()) {
- case MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF:
+ case MAV_CMD_NAV_TAKEOFF:
vtolInHover = false;
break;
- case MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF:
+ case MAV_CMD_NAV_VTOL_TAKEOFF:
vtolInHover = true;
break;
- case MavlinkQmlSingleton::MAV_CMD_NAV_LAND:
+ case MAV_CMD_NAV_LAND:
vtolInHover = false;
break;
- case MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_LAND:
+ case MAV_CMD_NAV_VTOL_LAND:
vtolInHover = true;
break;
- case MavlinkQmlSingleton::MAV_CMD_DO_VTOL_TRANSITION:
+ case MAV_CMD_DO_VTOL_TRANSITION:
{
int transitionState = simpleItem->missionItem().param1();
if (transitionState == MAV_VTOL_STATE_TRANSITION_TO_MC) {
diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h
index df1d6d3aadf27c503ac8bfcee73178d22e79b9e4..a953c835e10c35c6fd85e911532abe7c5939289d 100644
--- a/src/MissionManager/MissionController.h
+++ b/src/MissionManager/MissionController.h
@@ -15,7 +15,7 @@
#include "QmlObjectListModel.h"
#include "Vehicle.h"
#include "QGCLoggingCategory.h"
-#include "MavlinkQmlSingleton.h"
+
#include "QGCGeoBoundingCube.h"
#include
diff --git a/src/MissionManager/MissionControllerTest.cc b/src/MissionManager/MissionControllerTest.cc
index c1bcdfc5c4b6c4bd7da7c8d5135ae31bd66e49c4..ef7946246d32e57f73fc99b8749798e19f3bd180 100644
--- a/src/MissionManager/MissionControllerTest.cc
+++ b/src/MissionManager/MissionControllerTest.cc
@@ -132,7 +132,7 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QVERIFY(settingsItem);
QVERIFY(simpleItem);
- QCOMPARE(simpleItem->command(), MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
+ QCOMPARE((MAV_CMD)simpleItem->command(), MAV_CMD_NAV_TAKEOFF);
QCOMPARE(simpleItem->childItems()->count(), 0);
// If the first item added specifies a coordinate, then planned home position will be set
diff --git a/src/MissionManager/MissionItem.h b/src/MissionManager/MissionItem.h
index 8202a8480535ffdd41aaef21af3edb43fadfbc16..9e2848669e64c9504a60c2ebc5552639fe4ffcd1 100644
--- a/src/MissionManager/MissionItem.h
+++ b/src/MissionManager/MissionItem.h
@@ -20,7 +20,6 @@
#include "QGCMAVLink.h"
#include "QGC.h"
-#include "MavlinkQmlSingleton.h"
#include "QmlObjectListModel.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
diff --git a/src/MissionManager/QGCMapPolygon.cc b/src/MissionManager/QGCMapPolygon.cc
index eecb5069d2f60cc5f91357f28dbd46681fd5e459..0611d5f066ec3e6d08ef4076a8151af4d42eade5 100644
--- a/src/MissionManager/QGCMapPolygon.cc
+++ b/src/MissionManager/QGCMapPolygon.cc
@@ -371,7 +371,7 @@ QGeoCoordinate QGCMapPolygon::vertexCoordinate(int vertex) const
if (vertex >= 0 && vertex < _polygonPath.count()) {
return _polygonPath[vertex].value();
} else {
- qWarning() << "QGCMapPolygon::vertexCoordinate bad vertex requested";
+ qWarning() << "QGCMapPolygon::vertexCoordinate bad vertex requested:count" << vertex << _polygonPath.count();
return QGeoCoordinate();
}
}
@@ -530,6 +530,10 @@ double QGCMapPolygon::area(void) const
{
// https://www.mathopenref.com/coordpolygonarea2.html
+ if (_polygonPath.count() < 3) {
+ return 0;
+ }
+
double coveredArea = 0.0;
QList nedVertices = nedPolygon();
for (int i=0; igetUIInfo(_vehicle, (MAV_CMD)command())->category();
}
-void SimpleMissionItem::setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command)
+void SimpleMissionItem::setCommand(int command)
{
if ((MAV_CMD)command != _missionItem.command()) {
_missionItem.setCommand((MAV_CMD)command);
diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h
index 3f1c4c44736404842570f0a8ce741153129f1fde..5d0db11406829485a658536338fd4dbc4a1e5a03 100644
--- a/src/MissionManager/SimpleMissionItem.h
+++ b/src/MissionManager/SimpleMissionItem.h
@@ -44,7 +44,7 @@ public:
Q_PROPERTY(Fact* altitude READ altitude CONSTANT) ///< Altitude as specified by altitudeMode. Not necessarily true mission item altitude
Q_PROPERTY(AltitudeMode altitudeMode READ altitudeMode WRITE setAltitudeMode NOTIFY altitudeModeChanged)
Q_PROPERTY(Fact* amslAltAboveTerrain READ amslAltAboveTerrain CONSTANT) ///< Actual AMSL altitude for item if altitudeMode == AltitudeAboveTerrain
- Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
+ Q_PROPERTY(int command READ command WRITE setCommand NOTIFY commandChanged)
/// Optional sections
Q_PROPERTY(QObject* speedSection READ speedSection NOTIFY speedSectionChanged)
@@ -65,7 +65,7 @@ public:
// Property accesors
QString category (void) const;
- MavlinkQmlSingleton::Qml_MAV_CMD command(void) const { return (MavlinkQmlSingleton::Qml_MAV_CMD)_missionItem._commandFact.cookedValue().toInt(); }
+ int command(void) const { return _missionItem._commandFact.cookedValue().toInt(); }
bool friendlyEditAllowed (void) const;
bool rawEdit (void) const;
bool specifiesAltitude (void) const;
@@ -85,7 +85,7 @@ public:
void setCommandByIndex(int index);
- void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command);
+ void setCommand(int command);
void setAltDifference (double altDifference);
void setAltPercent (double altPercent);
diff --git a/src/MissionManager/SimpleMissionItemTest.cc b/src/MissionManager/SimpleMissionItemTest.cc
index 54b15897c78de46892e3a05557b3ec3a5765a37e..6706fadcd8f6c69a67e23689d2d046575f728846 100644
--- a/src/MissionManager/SimpleMissionItemTest.cc
+++ b/src/MissionManager/SimpleMissionItemTest.cc
@@ -236,11 +236,11 @@ void SimpleMissionItemTest::_testSignals(void)
// dirtyChanged
// coordinateChanged - since altitude will be set back to default
- _simpleItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
+ _simpleItem->setCommand(MAV_CMD_NAV_WAYPOINT);
QVERIFY(_spyVisualItem->checkNoSignals());
QVERIFY(_spySimpleItem->checkNoSignals());
- _simpleItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_LOITER_TIME);
+ _simpleItem->setCommand(MAV_CMD_NAV_LOITER_TIME);
QVERIFY(_spySimpleItem->checkSignalsByMask(commandChangedMask));
QVERIFY(_spyVisualItem->checkSignalsByMask(commandNameChangedMask | dirtyChangedMask | coordinateChangedMask));
}
diff --git a/src/MissionManager/VisualMissionItem.h b/src/MissionManager/VisualMissionItem.h
index 2257e95630913628e176bc4af5c004bfafdda5cf..96cb4fc1a24c3cbd3c54a79fdba128cb71cc7a0a 100644
--- a/src/MissionManager/VisualMissionItem.h
+++ b/src/MissionManager/VisualMissionItem.h
@@ -18,7 +18,6 @@
#include "QGCMAVLink.h"
#include "QGC.h"
-#include "MavlinkQmlSingleton.h"
#include "QmlObjectListModel.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
diff --git a/src/PlanView/CorridorScanEditor.qml b/src/PlanView/CorridorScanEditor.qml
index 754086544847a17da138bf27f3d8515e6931447d..04b0c48b06ca79eef668535729a39639ff5a6590 100644
--- a/src/PlanView/CorridorScanEditor.qml
+++ b/src/PlanView/CorridorScanEditor.qml
@@ -189,16 +189,6 @@ Rectangle {
text: qsTr("Statistics")
}
- Grid {
- columns: 2
- columnSpacing: ScreenTools.defaultFontPixelWidth
- visible: statsHeader.checked
-
- QGCLabel { text: qsTr("Photo count") }
- QGCLabel { text: missionItem.cameraShots }
-
- QGCLabel { text: qsTr("Photo interval") }
- QGCLabel { text: missionItem.timeBetweenShots.toFixed(1) + " " + qsTr("secs") }
- }
+ TransectStyleComplexItemStats { }
} // Column
} // Rectangle
diff --git a/src/PlanView/FWLandingPatternEditor.qml b/src/PlanView/FWLandingPatternEditor.qml
index b703e9a63fc1cf02a1617871734e52dc7895259b..4e53bd8127522b77b6fd5baef4ebcf8947edd9d0 100644
--- a/src/PlanView/FWLandingPatternEditor.qml
+++ b/src/PlanView/FWLandingPatternEditor.qml
@@ -34,6 +34,8 @@ Rectangle {
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _spacer: ScreenTools.defaultFontPixelWidth / 2
+ ExclusiveGroup { id: distanceGlideGroup }
+
Column {
id: editorColumn
anchors.margins: _margin
@@ -58,17 +60,6 @@ Rectangle {
Item { width: 1; height: _spacer }
QGCCheckBox {
- id: loiterAltRelative
- anchors.right: parent.right
- text: qsTr("Altitude relative to home")
- checked: missionItem.loiterAltitudeRelative
- onClicked: missionItem.loiterAltitudeRelative = checked
- }
-
- Item { width: 1; height: _spacer }
-
- QGCCheckBox {
- anchors.left: loiterAltRelative.left
text: qsTr("Loiter clockwise")
checked: missionItem.loiterClockwise
onClicked: missionItem.loiterClockwise = checked
@@ -98,53 +89,33 @@ Rectangle {
}
QGCRadioButton {
- id: useLandingDistance
- text: qsTr("Landing dist")
- checked: !useFallRate.checked
- onClicked: {
- useFallRate.checked = false
- missionItem.fallRate.value = parseFloat(missionItem.loiterAltitude.value)*100/parseFloat (missionItem.landingDistance.value)
- }
- Layout.fillWidth: true
+ id: specifyLandingDistance
+ text: qsTr("Landing Dist")
+ checked: missionItem.valueSetIsDistance
+ exclusiveGroup: distanceGlideGroup
+ onClicked: missionItem.valueSetIsDistance = checked
+ Layout.fillWidth: true
}
FactTextField {
- fact: missionItem.landingDistance
- enabled: useLandingDistance.checked
- Layout.fillWidth: true
+ fact: missionItem.landingDistance
+ enabled: specifyLandingDistance.checked
+ Layout.fillWidth: true
}
QGCRadioButton {
- id: useFallRate
- text: qsTr("Descent rate")
- checked: !useLandingDistance.checked
- onClicked: {
- useLandingDistance.checked = false
- missionItem.landingDistance.value = parseFloat(missionItem.loiterAltitude.value)*100/parseFloat (missionItem.fallRate.value)
- }
- Layout.fillWidth: true
+ id: specifyGlideSlope
+ text: qsTr("Glide Slope")
+ checked: !missionItem.valueSetIsDistance
+ exclusiveGroup: distanceGlideGroup
+ onClicked: missionItem.valueSetIsDistance = !checked
+ Layout.fillWidth: true
}
FactTextField {
- fact: missionItem.fallRate
- enabled: useFallRate.checked
- Layout.fillWidth: true
- }
-
- Connections {
- target: missionItem.landingDistance
-
- onValueChanged: {
- missionItem.fallRate.value = parseFloat(missionItem.loiterAltitude.value)*100/parseFloat (missionItem.landingDistance.value)
- }
- }
-
- Connections {
- target: missionItem.fallRate
-
- onValueChanged: {
- missionItem.landingDistance.value = parseFloat(missionItem.loiterAltitude.value)*100/parseFloat (missionItem.fallRate.value)
- }
+ fact: missionItem.glideSlope
+ enabled: specifyGlideSlope.checked
+ Layout.fillWidth: true
}
}
@@ -152,9 +123,9 @@ Rectangle {
QGCCheckBox {
anchors.right: parent.right
- text: qsTr("Altitude relative to home")
- checked: missionItem.landingAltitudeRelative
- onClicked: missionItem.landingAltitudeRelative = checked
+ text: qsTr("Altitudes relative to home")
+ checked: missionItem.altitudesAreRelative
+ onClicked: missionItem.altitudesAreRelative = checked
}
}
diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml
index 419f1f2eb1e11f37b347fb05283d3fa1c4bc32e8..f26b87fcda45167f81c3d18d2c39ebd306468b42 100644
--- a/src/PlanView/PlanView.qml
+++ b/src/PlanView/PlanView.qml
@@ -23,7 +23,6 @@ import QGroundControl.Controls 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
-import QGroundControl.Mavlink 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.Airspace 1.0
import QGroundControl.Airmap 1.0
diff --git a/src/PlanView/TransectStyleComplexItemStats.qml b/src/PlanView/TransectStyleComplexItemStats.qml
new file mode 100644
index 0000000000000000000000000000000000000000..0dec0c10661552c7b9f3a846e7b6b6bdf8efbef3
--- /dev/null
+++ b/src/PlanView/TransectStyleComplexItemStats.qml
@@ -0,0 +1,30 @@
+import QtQuick 2.3
+import QtQuick.Controls 1.2
+
+import QGroundControl 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Controls 1.0
+
+// Statistics section for TransectStyleComplexItems
+Grid {
+ // The following properties must be available up the hierarchy chain
+ //property var missionItem ///< Mission Item for editor
+
+ anchors.left: parent.left
+ anchors.right: parent.right
+ columns: 2
+ columnSpacing: ScreenTools.defaultFontPixelWidth
+ visible: statsHeader.checked
+
+ QGCLabel { text: qsTr("Survey Area") }
+ QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(missionItem.coveredArea).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString }
+
+ QGCLabel { text: qsTr("Photo Count") }
+ QGCLabel { text: missionItem.cameraShots }
+
+ QGCLabel { text: qsTr("Photo Interval") }
+ QGCLabel { text: missionItem.timeBetweenShots.toFixed(1) + " " + qsTr("secs") }
+
+ QGCLabel { text: qsTr("Trigger Distance") }
+ QGCLabel { text: missionItem.cameraCalc.adjustedFootprintFrontal.valueString + " " + missionItem.cameraCalc.adjustedFootprintFrontal.units }
+}
diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc
index 9f8be2da7241953107a4b0961c3f2521b54de179..813f0dfb016660bfefde660d31c51e8031a58ad2 100644
--- a/src/QGCApplication.cc
+++ b/src/QGCApplication.cc
@@ -57,7 +57,6 @@
#include "FirmwarePluginManager.h"
#include "MultiVehicleManager.h"
#include "Vehicle.h"
-#include "MavlinkQmlSingleton.h"
#include "JoystickConfigController.h"
#include "JoystickManager.h"
#include "QmlObjectListModel.h"
@@ -130,11 +129,6 @@ static QObject* screenToolsControllerSingletonFactory(QQmlEngine*, QJSEngine*)
return screenToolsController;
}
-static QObject* mavlinkQmlSingletonFactory(QQmlEngine*, QJSEngine*)
-{
- return new MavlinkQmlSingleton;
-}
-
static QObject* qgroundcontrolQmlGlobalSingletonFactory(QQmlEngine*, QJSEngine*)
{
// We create this object as a QGCTool even though it isn't in the toolbox
@@ -406,7 +400,6 @@ void QGCApplication::_initCommon(void)
// Register Qml Singletons
qmlRegisterSingletonType ("QGroundControl", 1, 0, "QGroundControl", qgroundcontrolQmlGlobalSingletonFactory);
qmlRegisterSingletonType ("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory);
- qmlRegisterSingletonType ("QGroundControl.Mavlink", 1, 0, "Mavlink", mavlinkQmlSingletonFactory);
}
bool QGCApplication::_initForNormalAppBoot(void)
diff --git a/src/QmlControls/MavlinkQmlSingleton.h b/src/QmlControls/MavlinkQmlSingleton.h
deleted file mode 100644
index 28c625f4c2e945b62d8fd11f3b899300a554ca99..0000000000000000000000000000000000000000
--- a/src/QmlControls/MavlinkQmlSingleton.h
+++ /dev/null
@@ -1,109 +0,0 @@
-/****************************************************************************
- *
- * (c) 2009-2016 QGROUNDCONTROL PROJECT
- *
- * QGroundControl is licensed according to the terms in the file
- * COPYING.md in the root of the source code directory.
- *
- ****************************************************************************/
-
-
-#ifndef MavlinkQmlSingleton_H
-#define MavlinkQmlSingleton_H
-
-#include
-
-class MavlinkQmlSingleton : public QObject
-{
- Q_OBJECT
- Q_ENUMS(Qml_MAV_CMD)
-
-public:
- // Couldn't figure a way to get MAV_CMD enum out to Qml so I had to copy it. Sigh!
-
- typedef enum {
- MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate [ms^-1]| Desired yaw angle [rad]| Y-axis position [m]| X-axis position [m]| Z-axis / ground level position [m]| */
- MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]| Empty| Takeoff ascend rate [ms^-1]| Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position [m]| X-axis position [m]| Z-axis position [m]| */
- MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Empty| Empty| Empty| Empty| Empty| Empty| Desired altitude in meters| */
- MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Heading Required (0 = False)| Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Empty| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
- MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
- MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
- MAV_CMD_NAV_ALTITUDE_WAIT=83, /* Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. |altitude (m)| descent speed (m/s)| Wiggle Time (s)| Empty| Empty| Empty| Empty| */
- MAV_CMD_NAV_VTOL_TAKEOFF=84,
- MAV_CMD_NAV_VTOL_LAND=85,
- MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
- MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
- MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
- MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */
- MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
- MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */
- MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */
- MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
- MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */
- MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable, 2=disable_floor_only)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_MOTOR_TEST=209, /* Mission command to perform motor test |motor sequence number (a number from 1 to max number of motors on the vehicle)| throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)| throttle| timeout (in seconds)| Empty| Empty| Empty| */
- MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_GRIPPER=211, /* Mission command to operate EPM gripper |gripper number (a number from 1 to max number of grippers on the vehicle)| gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum)| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_AUTOTUNE_ENABLE=212, /* Enable/disable autotune |enable (1: enable, 0:disable)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */
- MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
- MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */
- MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
- MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. |1: Trigger actuator ID assignment and direction mapping.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
- MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */
- MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
- MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
- MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
- MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
- MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
- MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
- MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID| */
- MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.| */
- MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */
- MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence */
- MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence */
- MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved| */
- MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture */
- MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture */
- MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */
- MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| */
- MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overridden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */
- MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
- MAV_CMD_DO_START_MAG_CAL=42424, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Automatically retry on failure (0=no retry, 1=retry).| Save without user input (0=require input, 1=autosave).| Delay (seconds)| Empty| Empty| Empty| */
- MAV_CMD_DO_ACCEPT_MAG_CAL=42425, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_CANCEL_MAG_CAL=42426, /* Cancel a running magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_ENUM_END=42427, /* | */
- } Qml_MAV_CMD;
-};
-
-#endif // MavlinkQmlSingleton_H
diff --git a/src/QmlControls/ParameterEditor.qml b/src/QmlControls/ParameterEditor.qml
index c09e3546efa3aca8ea9a11f4a00057bb5a206c17..9fa0fec47affc77b0d4e8c7546d344601b264cf3 100644
--- a/src/QmlControls/ParameterEditor.qml
+++ b/src/QmlControls/ParameterEditor.qml
@@ -32,6 +32,7 @@ QGCView {
property bool _searchFilter: searchText.text.trim() != "" ///< true: showing results of search
property var _searchResults ///< List of parameter names from search results
property bool _showRCToParam: !ScreenTools.isMobile && QGroundControl.multiVehicleManager.activeVehicle.px4Firmware
+ property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
ParameterEditorController {
id: controller;
@@ -104,6 +105,7 @@ QGCView {
}
MenuItem {
text: qsTr("Reset all to defaults")
+ visible: !_activeVehicle.apmFirmware
onTriggered: showDialog(resetToDefaultConfirmComponent, qsTr("Reset All"), qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Reset)
}
MenuSeparator { }
@@ -334,7 +336,7 @@ QGCView {
QGCViewDialog {
function accept() {
- QGroundControl.multiVehicleManager.activeVehicle.rebootVehicle()
+ _activeVehicle.rebootVehicle()
hideDialog()
}
diff --git a/src/QmlControls/QGroundControl.Controls.qmldir b/src/QmlControls/QGroundControl.Controls.qmldir
index 65b86d035be9ab5cd631f4990a6c045c8b953843..6bbe56f224fca0a8747be57936d101dd2d8c8551 100644
--- a/src/QmlControls/QGroundControl.Controls.qmldir
+++ b/src/QmlControls/QGroundControl.Controls.qmldir
@@ -71,6 +71,7 @@ SimpleItemMapVisuals 1.0 SimpleItemMapVisuals.qml
SliderSwitch 1.0 SliderSwitch.qml
SubMenuButton 1.0 SubMenuButton.qml
SurveyMapVisuals 1.0 SurveyMapVisuals.qml
+TransectStyleComplexItemStats 1.0 TransectStyleComplexItemStats.qml
ToolStrip 1.0 ToolStrip.qml
VehicleRotationCal 1.0 VehicleRotationCal.qml
VehicleSummaryRow 1.0 VehicleSummaryRow.qml
diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc
index ec1a6a8ee9edb89604ad50172d3997fc8425a3c8..23a149d931308e0e6545c2e397009b45a6620669 100644
--- a/src/Terrain/TerrainQuery.cc
+++ b/src/Terrain/TerrainQuery.cc
@@ -104,7 +104,7 @@ void TerrainAirMapQuery::_requestFinished(void)
QNetworkReply* reply = qobject_cast(QObject::sender());
if (reply->error() != QNetworkReply::NoError) {
- qCDebug(TerrainQueryLog) << "_requestFinished error:" << reply->error();
+ qCDebug(TerrainQueryLog) << "_requestFinished error:data" << reply->error() << reply->readAll();
reply->deleteLater();
_requestFailed();
return;
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index 31bbf20ead0f536b662579d88781a78bcd1092cc..e8fe11d9f7f0f19d8a33cb5042f21d48feb83cd6 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -1168,7 +1168,12 @@ void Vehicle::_handleWind(mavlink_message_t& message)
mavlink_wind_t wind;
mavlink_msg_wind_decode(&message, &wind);
- _windFactGroup.direction()->setRawValue(wind.direction);
+ // We don't want negative wind angles
+ float direction = wind.direction;
+ if (direction < 0) {
+ direction += 360;
+ }
+ _windFactGroup.direction()->setRawValue(direction);
_windFactGroup.speed()->setRawValue(wind.speed);
_windFactGroup.verticalSpeed()->setRawValue(wind.speed_z);
}