diff --git a/ChangeLog.md b/ChangeLog.md
new file mode 100644
index 0000000000000000000000000000000000000000..df99792ec298717246f80bbecc194003ccdebf4b
--- /dev/null
+++ b/ChangeLog.md
@@ -0,0 +1,14 @@
+# QGroundControl Change Log
+
+Note: This file only contains high level features or important fixes.
+
+## 3.5
+
+### 3.5.0 - Not yet released
+* Add ESTIMATOR_STATUS values to new estimatorStatus Vehicle FactGroup. These are now available to display in instrument panel.
+
+## 3.4
+
+### 3.4.1 - Not yet released
+* Fix crash when Survery with terrain follow is moved quickly
+* Fix terrain follow climb/descent rate fields swapped in ui
diff --git a/deploy/qgroundcontrol_installer.nsi b/deploy/qgroundcontrol_installer.nsi
index e3064b681af7269891ed8f49f819aa58d568ac84..e1ede489b32e6a4541f19abd2e742741bc6b1d57 100644
--- a/deploy/qgroundcontrol_installer.nsi
+++ b/deploy/qgroundcontrol_installer.nsi
@@ -2,6 +2,7 @@
!include LogicLib.nsh
!include Win\COM.nsh
!include Win\Propkey.nsh
+!include "FileFunc.nsh"
!macro DemoteShortCut target
!insertmacro ComHlpr_CreateInProcInstance ${CLSID_ShellLink} ${IID_IShellLink} r0 ""
@@ -61,7 +62,7 @@ Section
ReadRegStr $R0 HKLM "Software\Microsoft\Windows\CurrentVersion\Uninstall\${APPNAME}" "UninstallString"
StrCmp $R0 "" doinstall
- ExecWait "$R0 /S _?=$INSTDIR"
+ ExecWait "$R0 /S _?=$INSTDIR -LEAVE_DATA=1"
IntCmp $0 0 doinstall
MessageBox MB_OK|MB_ICONEXCLAMATION \
@@ -104,12 +105,16 @@ done:
SectionEnd
Section "Uninstall"
+ ${GetParameters} $R0
+ ${GetOptions} $R0 "-LEAVE_DATA=" $R1
!insertmacro MUI_STARTMENU_GETFOLDER Application $StartMenuFolder
SetShellVarContext all
RMDir /r /REBOOTOK $INSTDIR
RMDir /r /REBOOTOK "$SMPROGRAMS\$StartMenuFolder\"
SetShellVarContext current
- RMDir /r /REBOOTOK "$APPDATA\${ORGNAME}\"
+ ${If} $R1 != 1
+ RMDir /r /REBOOTOK "$APPDATA\${ORGNAME}\"
+ ${Endif}
DeleteRegKey HKLM "SOFTWARE\Microsoft\Windows\CurrentVersion\Uninstall\${APPNAME}"
DeleteRegKey HKLM "SOFTWARE\Microsoft\Windows\Windows Error Reporting\LocalDumps\${EXENAME}.exe"
SectionEnd
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 3e4c367dfb1a9098bbd0e1556563870c289e2c5e..0f8c82c81c6ceeefdbdd68b8a83c8a2d5147f4b9 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -44,29 +44,6 @@ MacBuild {
}
}
-iOSBuild {
- LIBS += -framework AVFoundation
- #-- Info.plist (need an "official" one for the App Store)
- ForAppStore {
- message(App Store Build)
- #-- Create official, versioned Info.plist
- APP_STORE = $$system(cd $${BASEDIR} && $${BASEDIR}/tools/update_ios_version.sh $${BASEDIR}/ios/iOSForAppStore-Info-Source.plist $${BASEDIR}/ios/iOSForAppStore-Info.plist)
- APP_ERROR = $$find(APP_STORE, "Error")
- count(APP_ERROR, 1) {
- error("Error building .plist file. 'ForAppStore' builds are only possible through the official build system.")
- }
- QT += qml-private
- QMAKE_INFO_PLIST = $${BASEDIR}/ios/iOSForAppStore-Info.plist
- OTHER_FILES += $${BASEDIR}/ios/iOSForAppStore-Info.plist
- } else {
- QMAKE_INFO_PLIST = $${BASEDIR}/ios/iOS-Info.plist
- OTHER_FILES += $${BASEDIR}/ios/iOS-Info.plist
- }
- QMAKE_ASSET_CATALOGS += ios/Images.xcassets
- BUNDLE.files = ios/QGCLaunchScreen.xib $$QMAKE_INFO_PLIST
- QMAKE_BUNDLE_DATA += BUNDLE
-}
-
LinuxBuild {
CONFIG += qesp_linux_udev
}
@@ -132,6 +109,36 @@ WindowsBuild {
QMAKE_TARGET_PRODUCT = "$${QGC_APP_NAME}"
}
+#-------------------------------------------------------------------------------------
+# iOS
+
+iOSBuild {
+ contains (CONFIG, DISABLE_BUILTIN_IOS) {
+ message("Skipping builtin support for iOS")
+ } else {
+ LIBS += -framework AVFoundation
+ #-- Info.plist (need an "official" one for the App Store)
+ ForAppStore {
+ message(App Store Build)
+ #-- Create official, versioned Info.plist
+ APP_STORE = $$system(cd $${BASEDIR} && $${BASEDIR}/tools/update_ios_version.sh $${BASEDIR}/ios/iOSForAppStore-Info-Source.plist $${BASEDIR}/ios/iOSForAppStore-Info.plist)
+ APP_ERROR = $$find(APP_STORE, "Error")
+ count(APP_ERROR, 1) {
+ error("Error building .plist file. 'ForAppStore' builds are only possible through the official build system.")
+ }
+ QT += qml-private
+ QMAKE_INFO_PLIST = $${BASEDIR}/ios/iOSForAppStore-Info.plist
+ OTHER_FILES += $${BASEDIR}/ios/iOSForAppStore-Info.plist
+ } else {
+ QMAKE_INFO_PLIST = $${BASEDIR}/ios/iOS-Info.plist
+ OTHER_FILES += $${BASEDIR}/ios/iOS-Info.plist
+ }
+ QMAKE_ASSET_CATALOGS += ios/Images.xcassets
+ BUNDLE.files = ios/QGCLaunchScreen.xib $$QMAKE_INFO_PLIST
+ QMAKE_BUNDLE_DATA += BUNDLE
+ }
+}
+
#
# Plugin configuration
#
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 786860205bddaa69740aa13509d1b2de6b178114..ab82893d4ad6b5fdfbaa9e88123a8656b7413055 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -237,6 +237,7 @@
src/Vehicle/BatteryFact.json
src/Vehicle/ClockFact.json
src/Vehicle/DistanceSensorFact.json
+ src/Vehicle/EstimatorStatusFactGroup.json
src/Vehicle/GPSFact.json
src/Vehicle/GPSRTKFact.json
src/Vehicle/SetpointFact.json
diff --git a/src/AnalyzeView/ExifParser.cc b/src/AnalyzeView/ExifParser.cc
index b82d4f1fdce306abb7dd682ded8b16ba197f9fd5..1a3bcee99755731bb21f81592220f8e015c85ea2 100644
--- a/src/AnalyzeView/ExifParser.cc
+++ b/src/AnalyzeView/ExifParser.cc
@@ -159,8 +159,8 @@ bool ExifParser::write(QByteArray& buf, GeoTagWorker::cameraFeedbackPacket& geot
gpsData.readable.fields.gpsLon.content = gpsDataExtInd + 6 * 4;
gpsData.readable.fields.gpsAltRef.tagID = 5;
- gpsData.readable.fields.gpsAltRef.type = 2;
- gpsData.readable.fields.gpsAltRef.size = 2;
+ gpsData.readable.fields.gpsAltRef.type = 1;
+ gpsData.readable.fields.gpsAltRef.size = 1;
gpsData.readable.fields.gpsAltRef.content = 0x00;
gpsData.readable.fields.gpsAlt.tagID = 6;
diff --git a/src/AutoPilotPlugins/PX4/SensorsSetup.qml b/src/AutoPilotPlugins/PX4/SensorsSetup.qml
index 6bbb20ddc5758d471d3644e3fc59c88fb5910b9c..d6c4902728e0abae9291d774ef6e4c1bdd079732 100644
--- a/src/AutoPilotPlugins/PX4/SensorsSetup.qml
+++ b/src/AutoPilotPlugins/PX4/SensorsSetup.qml
@@ -132,10 +132,8 @@ Item {
onResetStatusTextArea: statusLog.text = statusTextAreaDefaultText
onMagCalComplete: {
- //if (!_sensorsHaveFixedOrientation && (showCompass0Rot || showCompass1Rot || showCompass2Rot)) {
- setOrientationsDialogShowBoardOrientation = false
- showDialog(setOrientationsDialogComponent, qsTr("Compass Calibration Complete"), qgcView.showDialogDefaultWidth, StandardButton.Ok)
- //}
+ setOrientationsDialogShowBoardOrientation = false
+ showDialog(setOrientationsDialogComponent, qsTr("Compass Calibration Complete"), qgcView.showDialogDefaultWidth, StandardButton.Ok)
}
onWaitingForCancelChanged: {
@@ -255,7 +253,9 @@ Item {
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
- text: qsTr("Set your compass orientations below and the make sure to reboot the vehicle prior to flight.")
+ text: _sensorsHaveFixedOrientation ?
+ qsTr("Make sure to reboot the vehicle prior to flight.") :
+ qsTr("Set your compass orientations below and the make sure to reboot the vehicle prior to flight.")
}
QGCButton {
@@ -270,6 +270,7 @@ Item {
width: parent.width
wrapMode: Text.WordWrap
text: boardRotationText
+ visible: !_sensorsHaveFixedOrientation
}
Column {
@@ -287,8 +288,10 @@ Item {
}
}
+ // Compass 0 rotation
Column {
- // Compass 0 rotation
+ visible: !_sensorsHaveFixedOrientation
+
Component {
id: compass0ComponentLabel2
@@ -312,8 +315,10 @@ Item {
Loader { sourceComponent: showCompass0Rot ? compass0ComponentCombo2 : null }
}
+ // Compass 1 rotation
Column {
- // Compass 1 rotation
+ visible: !_sensorsHaveFixedOrientation
+
Component {
id: compass1ComponentLabel2
@@ -337,10 +342,11 @@ Item {
Loader { sourceComponent: showCompass1Rot ? compass1ComponentCombo2 : null }
}
+ // Compass 2 rotation
Column {
+ visible: !_sensorsHaveFixedOrientation
spacing: ScreenTools.defaultFontPixelWidth
- // Compass 2 rotation
Component {
id: compass2ComponentLabel2
diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc
index 9becee8db6465011915301551e6d2fadff67d57f..565fe3b921ac5b8468f490420fa72295d07b25e7 100644
--- a/src/FactSystem/Fact.cc
+++ b/src/FactSystem/Fact.cc
@@ -310,6 +310,9 @@ QString Fact::_variantToString(const QVariant& variant, int decimalPlaces) const
}
}
break;
+ case FactMetaData::valueTypeBool:
+ valueString = variant.toBool() ? tr("true") : tr("false");
+ break;
case FactMetaData::valueTypeElapsedTimeInSeconds:
{
double dValue = variant.toDouble();
diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc
index 238708479bc8b3efb997454ebf2c143f6e66a4e0..4a9c5aa407909d0d273d288d603a127ebeaac9c4 100644
--- a/src/FactSystem/FactMetaData.cc
+++ b/src/FactSystem/FactMetaData.cc
@@ -1207,7 +1207,7 @@ QMap FactMetaData::createMapFromJsonFile(const QString&
QJsonParseError jsonParseError;
QJsonDocument doc = QJsonDocument::fromJson(bytes, &jsonParseError);
if (jsonParseError.error != QJsonParseError::NoError) {
- qWarning() << "Unable to parse json document" << jsonFilename << jsonParseError.errorString();
+ qWarning() << "Unable to parse json document filename:error:offset" << jsonFilename << jsonParseError.errorString() << jsonParseError.offset;
return metaDataMap;
}
diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
index 188da227fb950f3f941e53d6446d2d89dea4c747..ea1f2d7a6945577542d8152aa48c12fe7195e85e 100644
--- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
@@ -285,7 +285,7 @@ QList PX4FirmwarePlugin::supportedMissionCommands(void)
list << MAV_CMD_NAV_WAYPOINT
<< MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TIME << MAV_CMD_NAV_LOITER_TO_ALT
- << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF
+ << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF << MAV_CMD_NAV_RETURN_TO_LAUNCH
<< MAV_CMD_DO_JUMP
<< MAV_CMD_DO_VTOL_TRANSITION << MAV_CMD_NAV_VTOL_TAKEOFF << MAV_CMD_NAV_VTOL_LAND
<< MAV_CMD_DO_DIGICAM_CONTROL
diff --git a/src/FlightDisplay/FlightDisplayViewWidgets.qml b/src/FlightDisplay/FlightDisplayViewWidgets.qml
index a904a52893494a0ff498ff62039a228334d1b0b9..2999626702caea607352ca935ddd1d8a8cc21bad 100644
--- a/src/FlightDisplay/FlightDisplayViewWidgets.qml
+++ b/src/FlightDisplay/FlightDisplayViewWidgets.qml
@@ -43,12 +43,10 @@ Item {
QGCPalette { id: qgcPal }
function getPreferredInstrumentWidth() {
- if(ScreenTools.isMobile) {
- return mainWindow.width * 0.25
- } else if(ScreenTools.isHugeScreen) {
- return mainWindow.width * 0.11
- }
- return ScreenTools.defaultFontPixelWidth * 30
+ // Don't allow instrument panel to chew more than 1/4 of full window
+ var defaultWidth = ScreenTools.defaultFontPixelWidth * 30
+ var maxWidth = mainWindow.width * 0.25
+ return Math.min(maxWidth, defaultWidth)
}
function _setInstrumentWidget() {
diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc
index 4e2f8694a684f760b9c108fd473d40b425993fee..61891902e772bd59b3cf6f24d7b5f202c7ed7ea1 100644
--- a/src/MissionManager/MissionController.cc
+++ b/src/MissionManager/MissionController.cc
@@ -58,8 +58,8 @@ const int MissionController::_missionFileVersion = 2;
MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
: PlanElementController (masterController, parent)
, _missionManager (_managerVehicle->missionManager())
- , _visualItems (NULL)
- , _settingsItem (NULL)
+ , _visualItems (nullptr)
+ , _settingsItem (nullptr)
, _firstItemsFromVehicle (false)
, _itemsRequested (false)
, _inRecalcSequence (false)
@@ -70,7 +70,7 @@ MissionController::MissionController(PlanMasterController* masterController, QOb
, _appSettings (qgcApp()->toolbox()->settingsManager()->appSettings())
, _progressPct (0)
, _currentPlanViewIndex (-1)
- , _currentPlanViewItem (NULL)
+ , _currentPlanViewItem (nullptr)
{
_resetMissionFlightStatus();
managerVehicleChanged(_managerVehicle);
@@ -113,7 +113,7 @@ void MissionController::_resetMissionFlightStatus(void)
_controllerVehicle->firmwarePlugin()->batteryConsumptionData(_controllerVehicle, _missionFlightStatus.mAhBattery, _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
if (_missionFlightStatus.mAhBattery != 0) {
double batteryPercentRemainingAnnounce = qgcApp()->toolbox()->settingsManager()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
- _missionFlightStatus.ampMinutesAvailable = (double)_missionFlightStatus.mAhBattery / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
+ _missionFlightStatus.ampMinutesAvailable = static_cast(_missionFlightStatus.mAhBattery) / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
}
emit missionDistanceChanged(_missionFlightStatus.totalDistance);
@@ -186,8 +186,8 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
_deinitAllVisualItems();
_visualItems->deleteLater();
- _settingsItem = NULL;
- _visualItems = NULL;
+ _settingsItem = nullptr;
+ _visualItems = nullptr;
_updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
_visualItems = newControllerMissionItems;
@@ -353,20 +353,19 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
newItem->setCoordinate(coordinate);
newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
_initVisualItem(newItem);
- if (_visualItems->count() == 1) {
+ if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
- if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)takeoffCmd)) {
+ if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
newItem->setCommand(takeoffCmd);
}
}
- newItem->setDefaultsForCommand();
if (newItem->specifiesAltitude()) {
double prevAltitude;
int prevAltitudeMode;
if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
newItem->altitude()->setRawValue(prevAltitude);
- newItem->setAltitudeMode((SimpleMissionItem::AltitudeMode)prevAltitudeMode);
+ newItem->setAltitudeMode(static_cast(prevAltitudeMode));
}
}
newItem->setMissionFlightStatus(_missionFlightStatus);
@@ -381,11 +380,10 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
int sequenceNumber = _nextSequenceNumber();
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
newItem->setSequenceNumber(sequenceNumber);
- newItem->setCommand((MAV_CMD)(_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains((MAV_CMD)MAV_CMD_DO_SET_ROI_LOCATION) ?
+ newItem->setCommand((_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_DO_SET_ROI_LOCATION) ?
MAV_CMD_DO_SET_ROI_LOCATION :
MAV_CMD_DO_SET_ROI));
_initVisualItem(newItem);
- newItem->setDefaultsForCommand();
newItem->setCoordinate(coordinate);
double prevAltitude;
@@ -393,7 +391,7 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
newItem->altitude()->setRawValue(prevAltitude);
- newItem->setAltitudeMode((SimpleMissionItem::AltitudeMode)prevAltitudeMode);
+ newItem->setAltitudeMode(static_cast(prevAltitudeMode));
}
_visualItems->insert(i, newItem);
@@ -542,7 +540,7 @@ void MissionController::removeAll(void)
_deinitAllVisualItems();
_visualItems->clearAndDeleteContents();
_visualItems->deleteLater();
- _settingsItem = NULL;
+ _settingsItem = nullptr;
_visualItems = new QmlObjectListModel(this);
_addMissionSettings(_visualItems, false /* addToCenter */);
_initAllVisualItems();
@@ -670,9 +668,9 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if (_masterController->offline()) {
// We only update if offline since if we are online we use the online vehicle settings
- appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType((MAV_AUTOPILOT)json[_jsonFirmwareTypeKey].toInt()));
+ appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast(json[_jsonFirmwareTypeKey].toInt())));
if (json.contains(_jsonVehicleTypeKey)) {
- appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType((MAV_TYPE)json[_jsonVehicleTypeKey].toInt()));
+ appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast(json[_jsonVehicleTypeKey].toInt())));
}
}
if (json.contains(_jsonCruiseSpeedKey)) {
@@ -790,9 +788,9 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
for (int i=0; icount(); i++) {
if (visualItems->value(i)->isSimpleItem()) {
SimpleMissionItem* doJumpItem = visualItems->value(i);
- if ((MAV_CMD)doJumpItem->command() == MAV_CMD_DO_JUMP) {
+ if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
bool found = false;
- int findDoJumpId = doJumpItem->missionItem().param1();
+ int findDoJumpId = static_cast(doJumpItem->missionItem().param1());
for (int j=0; jcount(); j++) {
if (visualItems->value(j)->isSimpleItem()) {
SimpleMissionItem* targetItem = visualItems->value(j);
@@ -887,7 +885,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
for (int i=1; icount(); i++) {
SimpleMissionItem* item = qobject_cast(visualItems->get(i));
if (item && item->command() == MAV_CMD_DO_JUMP) {
- item->missionItem().setParam1((int)item->missionItem().param1() + 1);
+ item->missionItem().setParam1(static_cast(item->missionItem().param1()) + 1);
}
}
}
@@ -900,7 +898,7 @@ void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualI
if (_visualItems) {
_deinitAllVisualItems();
_visualItems->deleteLater();
- _settingsItem = NULL;
+ _settingsItem = nullptr;
}
_visualItems = loadedVisualItems;
@@ -996,11 +994,11 @@ void MissionController::save(QJsonObject& json)
}
QJsonValue coordinateValue;
JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
- json[_jsonPlannedHomePositionKey] = coordinateValue;
- json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
- json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
- json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
- json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
+ json[_jsonPlannedHomePositionKey] = coordinateValue;
+ json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
+ json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
+ json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
+ json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
// Save the visual items
diff --git a/src/MissionManager/PlanMasterController.cc b/src/MissionManager/PlanMasterController.cc
index c2137565eba82d6d2408d73dff84cee6e293a510..f42d5e433805a8de74cf5d7b1edf5c286f9373fe 100644
--- a/src/MissionManager/PlanMasterController.cc
+++ b/src/MissionManager/PlanMasterController.cc
@@ -9,6 +9,7 @@
#include "PlanMasterController.h"
#include "QGCApplication.h"
+#include "QGCCorePlugin.h"
#include "MultiVehicleManager.h"
#include "SettingsManager.h"
#include "AppSettings.h"
@@ -25,16 +26,19 @@
QGC_LOGGING_CATEGORY(PlanMasterControllerLog, "PlanMasterControllerLog")
-const int PlanMasterController::_planFileVersion = 1;
-const char* PlanMasterController::_planFileType = "Plan";
-const char* PlanMasterController::_jsonMissionObjectKey = "mission";
-const char* PlanMasterController::_jsonGeoFenceObjectKey = "geoFence";
-const char* PlanMasterController::_jsonRallyPointsObjectKey = "rallyPoints";
+const int PlanMasterController::kPlanFileVersion = 1;
+const char* PlanMasterController::kPlanFileType = "Plan";
+const char* PlanMasterController::kJsonMissionObjectKey = "mission";
+const char* PlanMasterController::kJsonGeoFenceObjectKey = "geoFence";
+const char* PlanMasterController::kJsonRallyPointsObjectKey = "rallyPoints";
PlanMasterController::PlanMasterController(QObject* parent)
: QObject (parent)
, _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager())
- , _controllerVehicle (new Vehicle((MAV_AUTOPILOT)qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->rawValue().toInt(), (MAV_TYPE)qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingVehicleType()->rawValue().toInt(), qgcApp()->toolbox()->firmwarePluginManager()))
+ , _controllerVehicle (new Vehicle(
+ static_cast(qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->rawValue().toInt()),
+ static_cast(qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingVehicleType()->rawValue().toInt()),
+ qgcApp()->toolbox()->firmwarePluginManager()))
, _managerVehicle (_controllerVehicle)
, _flyView (true)
, _offline (true)
@@ -111,7 +115,7 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
}
bool newOffline = false;
- if (activeVehicle == NULL) {
+ if (activeVehicle == nullptr) {
// Since there is no longer an active vehicle we use the offline controller vehicle as the manager vehicle
_managerVehicle = _controllerVehicle;
newOffline = true;
@@ -309,28 +313,33 @@ void PlanMasterController::loadFromFile(const QString& filename)
return;
}
- int version;
QJsonObject json = jsonDoc.object();
- if (!JsonHelper::validateQGCJsonFile(json, _planFileType, _planFileVersion, _planFileVersion, version, errorString)) {
+ //-- Allow plugins to pre process the load
+ qgcApp()->toolbox()->corePlugin()->preLoadFromJson(this, json);
+
+ int version;
+ if (!JsonHelper::validateQGCJsonFile(json, kPlanFileType, kPlanFileVersion, kPlanFileVersion, version, errorString)) {
qgcApp()->showMessage(errorMessage.arg(errorString));
return;
}
QList rgKeyInfo = {
- { _jsonMissionObjectKey, QJsonValue::Object, true },
- { _jsonGeoFenceObjectKey, QJsonValue::Object, true },
- { _jsonRallyPointsObjectKey, QJsonValue::Object, true },
+ { kJsonMissionObjectKey, QJsonValue::Object, true },
+ { kJsonGeoFenceObjectKey, QJsonValue::Object, true },
+ { kJsonRallyPointsObjectKey, QJsonValue::Object, true },
};
if (!JsonHelper::validateKeys(json, rgKeyInfo, errorString)) {
qgcApp()->showMessage(errorMessage.arg(errorString));
return;
}
- if (!_missionController.load(json[_jsonMissionObjectKey].toObject(), errorString) ||
- !_geoFenceController.load(json[_jsonGeoFenceObjectKey].toObject(), errorString) ||
- !_rallyPointController.load(json[_jsonRallyPointsObjectKey].toObject(), errorString)) {
+ if (!_missionController.load(json[kJsonMissionObjectKey].toObject(), errorString) ||
+ !_geoFenceController.load(json[kJsonGeoFenceObjectKey].toObject(), errorString) ||
+ !_rallyPointController.load(json[kJsonRallyPointsObjectKey].toObject(), errorString)) {
qgcApp()->showMessage(errorMessage.arg(errorString));
} else {
+ //-- Allow plugins to post process the load
+ qgcApp()->toolbox()->corePlugin()->postLoadFromJson(this, json);
success = true;
}
} else if (fileInfo.suffix() == AppSettings::missionFileExtension) {
@@ -364,16 +373,22 @@ void PlanMasterController::loadFromFile(const QString& filename)
QJsonDocument PlanMasterController::saveToJson()
{
QJsonObject planJson;
+ qgcApp()->toolbox()->corePlugin()->preSaveToJson(this, planJson);
QJsonObject missionJson;
QJsonObject fenceJson;
QJsonObject rallyJson;
- JsonHelper::saveQGCJsonFileHeader(planJson, _planFileType, _planFileVersion);
+ JsonHelper::saveQGCJsonFileHeader(planJson, kPlanFileType, kPlanFileVersion);
+ //-- Allow plugin to preemptly add its own keys to mission
+ qgcApp()->toolbox()->corePlugin()->preSaveToMissionJson(this, missionJson);
_missionController.save(missionJson);
+ //-- Allow plugin to add its own keys to mission
+ qgcApp()->toolbox()->corePlugin()->postSaveToMissionJson(this, missionJson);
_geoFenceController.save(fenceJson);
_rallyPointController.save(rallyJson);
- planJson[_jsonMissionObjectKey] = missionJson;
- planJson[_jsonGeoFenceObjectKey] = fenceJson;
- planJson[_jsonRallyPointsObjectKey] = rallyJson;
+ planJson[kJsonMissionObjectKey] = missionJson;
+ planJson[kJsonGeoFenceObjectKey] = fenceJson;
+ planJson[kJsonRallyPointsObjectKey] = rallyJson;
+ qgcApp()->toolbox()->corePlugin()->postSaveToJson(this, planJson);
return QJsonDocument(planJson);
}
diff --git a/src/MissionManager/PlanMasterController.h b/src/MissionManager/PlanMasterController.h
index 0878b2f202b50a004a9fd63b3fe741a657927b08..6c355e68e8f1d36b9d0397857016d86a1fa97936 100644
--- a/src/MissionManager/PlanMasterController.h
+++ b/src/MissionManager/PlanMasterController.h
@@ -91,6 +91,12 @@ public:
Vehicle* controllerVehicle(void) { return _controllerVehicle; }
Vehicle* managerVehicle(void) { return _managerVehicle; }
+ static const int kPlanFileVersion;
+ static const char* kPlanFileType;
+ static const char* kJsonMissionObjectKey;
+ static const char* kJsonGeoFenceObjectKey;
+ static const char* kJsonRallyPointsObjectKey;
+
signals:
void containsItemsChanged (bool containsItems);
void syncInProgressChanged (void);
@@ -124,9 +130,4 @@ private:
bool _sendRallyPoints;
QString _currentPlanFile;
- static const int _planFileVersion;
- static const char* _planFileType;
- static const char* _jsonMissionObjectKey;
- static const char* _jsonGeoFenceObjectKey;
- static const char* _jsonRallyPointsObjectKey;
};
diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc
index 6c1583b6c5b3ee105e5b3d7786c89ac2749b2683..e96c9256b95b088775155a2234957bb536388af1 100644
--- a/src/MissionManager/SimpleMissionItem.cc
+++ b/src/MissionManager/SimpleMissionItem.cc
@@ -78,7 +78,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* pa
_connectSignals();
_updateOptionalSections();
- setDefaultsForCommand();
+ _setDefaultsForCommand();
_rebuildFacts();
setDirty(false);
@@ -213,7 +213,7 @@ void SimpleMissionItem::_connectSignals(void)
connect(&_missionItem._frameFact, &Fact::valueChanged, this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
// A command change triggers a number of other changes as well.
- connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::setDefaultsForCommand);
+ connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::_setDefaultsForCommand);
connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandNameChanged);
connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandDescriptionChanged);
connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::abbreviationChanged);
@@ -729,15 +729,32 @@ bool SimpleMissionItem::readyForSave(void) const
return !specifiesAltitude() || !qIsNaN(_missionItem._param7Fact.rawValue().toDouble());
}
-void SimpleMissionItem::setDefaultsForCommand(void)
+void SimpleMissionItem::_setDefaultsForCommand(void)
{
- // We set these global defaults first, then if there are param defaults they will get reset
+ // First reset params 1-4 to 0, we leave 5-7 alone to preserve any previous location information on command change
+ _missionItem._param1Fact.setRawValue(0);
+ _missionItem._param2Fact.setRawValue(0);
+ _missionItem._param3Fact.setRawValue(0);
+ _missionItem._param4Fact.setRawValue(0);
+
+ if (!specifiesCoordinate() && !isStandaloneCoordinate()) {
+ // No need to carry across previous lat/lon
+ _missionItem._param5Fact.setRawValue(0);
+ _missionItem._param6Fact.setRawValue(0);
+ }
+
+ // Set global defaults first, then if there are param defaults they will get reset
_altitudeMode = AltitudeRelative;
emit altitudeModeChanged();
- double defaultAlt = qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble();
- _altitudeFact.setRawValue(defaultAlt);
- _missionItem._param7Fact.setRawValue(defaultAlt);
_amslAltAboveTerrainFact.setRawValue(qQNaN());
+ if (specifiesCoordinate() || isStandaloneCoordinate() || specifiesAltitudeOnly()) {
+ double defaultAlt = qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble();
+ _altitudeFact.setRawValue(defaultAlt);
+ _missionItem._param7Fact.setRawValue(defaultAlt);
+ } else {
+ _altitudeFact.setRawValue(0);
+ _missionItem._param7Fact.setRawValue(0);
+ }
MAV_CMD command = (MAV_CMD)this->command();
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_vehicle, command);
diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h
index 886d6f4cdc812ca9e67eed78d375be5216d7bd32..c8a85ca4a2d729f8bd205ee8cffd4521ed26dcc0 100644
--- a/src/MissionManager/SimpleMissionItem.h
+++ b/src/MissionManager/SimpleMissionItem.h
@@ -134,9 +134,6 @@ public:
int lastSequenceNumber (void) const final;
void save (QJsonArray& missionItems) final;
-public slots:
- void setDefaultsForCommand(void);
-
signals:
void commandChanged (int command);
void friendlyEditAllowedChanged (bool friendlyEditAllowed);
@@ -160,6 +157,7 @@ private slots:
void _rebuildFacts (void);
void _rebuildTextFieldFacts (void);
void _possibleAdditionalTimeDelayChanged(void);
+ void _setDefaultsForCommand (void);
private:
void _connectSignals (void);
diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc
index 56d8d704d2c25b531ae5165cf116b8db46eb5dcb..22126e744a033c0503f846ea29917225835f3bb5 100644
--- a/src/MissionManager/TransectStyleComplexItem.cc
+++ b/src/MissionManager/TransectStyleComplexItem.cc
@@ -412,11 +412,6 @@ void TransectStyleComplexItem::_setBoundingCube(QGCGeoBoundingCube bc)
void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void)
{
_transectsPathHeightInfo.clear();
- if (_terrainPolyPathQuery) {
- // Toss previous query
- _terrainPolyPathQuery->deleteLater();
- _terrainPolyPathQuery = NULL;
- }
if (_transects.count()) {
// We don't actually send the query until this timer times out. This way we only send
@@ -427,6 +422,20 @@ void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void)
void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)
{
+ // Clear any previous query
+ if (_terrainPolyPathQuery) {
+ // FIXME: We should really be blowing away any previous query here. But internally that is difficult to implement so instead we let
+ // it complete and drop the results.
+#if 0
+ // Toss previous query
+ _terrainPolyPathQuery->deleteLater();
+#else
+ // Let the signal fall on the floor
+ disconnect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainDataReceived, this, &TransectStyleComplexItem::_polyPathTerrainData);
+#endif
+ _terrainPolyPathQuery = NULL;
+ }
+
// Append all transects into a single PolyPath query
QList transectPoints;
@@ -463,6 +472,12 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList 300)
- return 2
+ if(QGroundControl.corePlugin.options.devicePixelDensity != 0) {
+ return QGroundControl.corePlugin.options.devicePixelDensity
+ }
+ //-- Android is rather unreliable
+ if(isAndroid) {
+ // Lets assume it's unlikely you have a tablet over 300mm wide
+ if((Screen.width / Screen.pixelDensity) > 300) {
+ return Screen.pixelDensity * 2
+ }
}
- //-- Use whatever the system tells us
- return Screen.devicePixelRatio
+ //-- Let's use what the system tells us
+ return Screen.pixelDensity
}
property bool isAndroid: ScreenToolsController.isAndroid
@@ -74,9 +74,10 @@ Item {
property bool isMobile: ScreenToolsController.isMobile
property bool isWindows: ScreenToolsController.isWindows
property bool isDebug: ScreenToolsController.isDebug
+ property bool isMac: ScreenToolsController.isMacOS
property bool isTinyScreen: (Screen.width / realPixelDensity) < 120 // 120mm
property bool isShortScreen: ScreenToolsController.isMobile && ((Screen.height / Screen.width) < 0.6) // Nexus 7 for example
- property bool isHugeScreen: Screen.width >= 1920*2
+ property bool isHugeScreen: (Screen.width / realPixelDensity) >= (23.5 * 25.4) // 27" monitor
readonly property real minTouchMillimeters: 10 ///< Minimum touch size in millimeters
property real minTouchPixels: 0 ///< Minimum touch size in pixels
@@ -111,10 +112,6 @@ Item {
_setBasePointSize(defaultFontPointSize)
}
- onRealPixelRatioChanged: {
- _setBasePointSize(defaultFontPointSize)
- }
-
function printScreenStats() {
console.log('ScreenTools: Screen.width: ' + Screen.width + ' Screen.height: ' + Screen.height + ' Screen.pixelDensity: ' + Screen.pixelDensity)
}
@@ -138,7 +135,7 @@ Item {
smallFontPointSize = defaultFontPointSize * _screenTools.smallFontPointRatio
mediumFontPointSize = defaultFontPointSize * _screenTools.mediumFontPointRatio
largeFontPointSize = defaultFontPointSize * _screenTools.largeFontPointRatio
- minTouchPixels = Math.round(minTouchMillimeters * realPixelDensity * realPixelRatio)
+ minTouchPixels = Math.round(minTouchMillimeters * realPixelDensity)
if (minTouchPixels / Screen.height > 0.15) {
// If using physical sizing takes up too much of the vertical real estate fall back to font based sizing
minTouchPixels = defaultFontPixelHeight * 3
diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc
index 81dcd45dc5a4162db6f48fde5186040c267ad52a..77074762ecf3ea2ccd219825379d7a0de6b30e91 100644
--- a/src/Terrain/TerrainQuery.cc
+++ b/src/Terrain/TerrainQuery.cc
@@ -416,7 +416,7 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList
error = true;
qCWarning(TerrainQueryLog) << "TerrainTileManager::_getAltitudesForCoordinates Internal Error: negative elevation in tile cache";
} else {
- qCWarning(TerrainQueryLog) << "TerrainTileManager::_getAltitudesForCoordinates returning elevation from tile cache" << elevation;
+ qCDebug(TerrainQueryLog) << "TerrainTileManager::_getAltitudesForCoordinates returning elevation from tile cache" << elevation;
}
altitudes.push_back(elevation);
} else {
diff --git a/src/Vehicle/EstimatorStatusFactGroup.json b/src/Vehicle/EstimatorStatusFactGroup.json
new file mode 100644
index 0000000000000000000000000000000000000000..6a1d3cea067d1dd3e0d60aeded756b1e37edf4c6
--- /dev/null
+++ b/src/Vehicle/EstimatorStatusFactGroup.json
@@ -0,0 +1,130 @@
+[
+{
+ "name": "goodAttitudeEsimate",
+ "shortDescription": "Good Attitude Esimate",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "goodHorizVelEstimate",
+ "shortDescription": "Good Horiz Vel Estimate",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "goodVertVelEstimate",
+ "shortDescription": "Good Vert Vel Estimate",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "goodHorizPosRelEstimate",
+ "shortDescription": "Good Horiz Pos Rel Estimate",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "goodHorizPosAbsEstimate",
+ "shortDescription": "Good Horiz Pos Abs Estimate",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "goodVertPosAbsEstimate",
+ "shortDescription": "Good Vert Pos Abs Estimate",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "goodVertPosAGLEstimate",
+ "shortDescription": "Good Vert Pos AGL Estimate",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "goodConstPosModeEstimate",
+ "shortDescription": "Good Const Pos Mode Estimate",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "goodPredHorizPosRelEstimate",
+ "shortDescription": "Good Pred Horiz Pos Rel Estimate",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "goodPredHorizPosAbsEstimate",
+ "shortDescription": "Good Pred Horiz Pos Abs Estimate",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "gpsGlitch",
+ "shortDescription": "Gps Glitch",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "accelError",
+ "shortDescription": "Accel Error",
+ "type": "bool",
+ "default": false
+},
+{
+ "name": "velRatio",
+ "shortDescription": "Vel Ratio",
+ "type": "float",
+ "decimalPlaces": 2,
+ "default": null
+},
+{
+ "name": "horizPosRatio",
+ "shortDescription": "Horiz Pos Ratio",
+ "type": "float",
+ "decimalPlaces": 2,
+ "default": null
+},
+{
+ "name": "vertPosRatio",
+ "shortDescription": "Vert Pos Ratio",
+ "type": "float",
+ "decimalPlaces": 2,
+ "default": null
+},
+{
+ "name": "magRatio",
+ "shortDescription": "Mag Ratio",
+ "type": "float",
+ "decimalPlaces": 2,
+ "default": null
+},
+{
+ "name": "haglRatio",
+ "shortDescription": "HAGL Ratio",
+ "type": "float",
+ "decimalPlaces": 2,
+ "default": null
+},
+{
+ "name": "tasRatio",
+ "shortDescription": "TAS Ratio",
+ "type": "float",
+ "decimalPlaces": 2,
+ "default": null
+},
+{
+ "name": "horizPosAccuracy",
+ "shortDescription": "Horiz Pos Accuracy",
+ "type": "float",
+ "decimalPlaces": 2,
+ "default": null
+},
+{
+ "name": "vertPosAccuracy",
+ "shortDescription": "Vert Pos Accuracy",
+ "type": "float",
+ "decimalPlaces": 2,
+ "default": null
+}
+]
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index 3228a1e827104606db6768bfb4142619fb6a8266..ebec3e5529450a52dd4b953650b98387ca16eda2 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -71,14 +71,15 @@ const char* Vehicle::_flightTimeFactName = "flightTime";
const char* Vehicle::_distanceToHomeFactName = "distanceToHome";
const char* Vehicle::_hobbsFactName = "hobbs";
-const char* Vehicle::_gpsFactGroupName = "gps";
-const char* Vehicle::_battery1FactGroupName = "battery";
-const char* Vehicle::_battery2FactGroupName = "battery2";
-const char* Vehicle::_windFactGroupName = "wind";
-const char* Vehicle::_vibrationFactGroupName = "vibration";
-const char* Vehicle::_temperatureFactGroupName = "temperature";
-const char* Vehicle::_clockFactGroupName = "clock";
-const char* Vehicle::_distanceSensorFactGroupName = "distanceSensor";
+const char* Vehicle::_gpsFactGroupName = "gps";
+const char* Vehicle::_battery1FactGroupName = "battery";
+const char* Vehicle::_battery2FactGroupName = "battery2";
+const char* Vehicle::_windFactGroupName = "wind";
+const char* Vehicle::_vibrationFactGroupName = "vibration";
+const char* Vehicle::_temperatureFactGroupName = "temperature";
+const char* Vehicle::_clockFactGroupName = "clock";
+const char* Vehicle::_distanceSensorFactGroupName = "distanceSensor";
+const char* Vehicle::_estimatorStatusFactGroupName = "estimatorStatus";
Vehicle::Vehicle(LinkInterface* link,
int vehicleId,
@@ -94,17 +95,17 @@ Vehicle::Vehicle(LinkInterface* link,
, _offlineEditingVehicle(false)
, _firmwareType(firmwareType)
, _vehicleType(vehicleType)
- , _firmwarePlugin(NULL)
- , _firmwarePluginInstanceData(NULL)
- , _autopilotPlugin(NULL)
- , _mavlink(NULL)
+ , _firmwarePlugin(nullptr)
+ , _firmwarePluginInstanceData(nullptr)
+ , _autopilotPlugin(nullptr)
+ , _mavlink(nullptr)
, _soloFirmware(false)
, _toolbox(qgcApp()->toolbox())
, _settingsManager(_toolbox->settingsManager())
, _joystickMode(JoystickModeRC)
, _joystickEnabled(false)
- , _uas(NULL)
- , _mav(NULL)
+ , _uas(nullptr)
+ , _mav(nullptr)
, _currentMessageCount(0)
, _messageCount(0)
, _currentErrorCount(0)
@@ -138,19 +139,19 @@ Vehicle::Vehicle(LinkInterface* link,
, _capabilityBits(0)
, _highLatencyLink(false)
, _receivingAttitudeQuaternion(false)
- , _cameras(NULL)
+ , _cameras(nullptr)
, _connectionLost(false)
, _connectionLostEnabled(true)
, _initialPlanRequestComplete(false)
- , _missionManager(NULL)
+ , _missionManager(nullptr)
, _missionManagerInitialRequestSent(false)
- , _geoFenceManager(NULL)
+ , _geoFenceManager(nullptr)
, _geoFenceManagerInitialRequestSent(false)
- , _rallyPointManager(NULL)
+ , _rallyPointManager(nullptr)
, _rallyPointManagerInitialRequestSent(false)
- , _parameterManager(NULL)
+ , _parameterManager(nullptr)
#if defined(QGC_AIRMAP_ENABLED)
- , _airspaceVehicleManager(NULL)
+ , _airspaceVehicleManager(nullptr)
#endif
, _armed(false)
, _base_mode(0)
@@ -200,6 +201,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _temperatureFactGroup(this)
, _clockFactGroup(this)
, _distanceSensorFactGroup(this)
+ , _estimatorStatusFactGroup(this)
{
connect(_joystickManager, &JoystickManager::activeJoystickChanged, this, &Vehicle::_loadSettings);
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleAvailableChanged, this, &Vehicle::_loadSettings);
@@ -294,17 +296,17 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _offlineEditingVehicle(true)
, _firmwareType(firmwareType)
, _vehicleType(vehicleType)
- , _firmwarePlugin(NULL)
- , _firmwarePluginInstanceData(NULL)
- , _autopilotPlugin(NULL)
- , _mavlink(NULL)
+ , _firmwarePlugin(nullptr)
+ , _firmwarePluginInstanceData(nullptr)
+ , _autopilotPlugin(nullptr)
+ , _mavlink(nullptr)
, _soloFirmware(false)
, _toolbox(qgcApp()->toolbox())
, _settingsManager(_toolbox->settingsManager())
, _joystickMode(JoystickModeRC)
, _joystickEnabled(false)
- , _uas(NULL)
- , _mav(NULL)
+ , _uas(nullptr)
+ , _mav(nullptr)
, _currentMessageCount(0)
, _messageCount(0)
, _currentErrorCount(0)
@@ -330,26 +332,26 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _capabilityBits(_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY)
, _highLatencyLink(false)
, _receivingAttitudeQuaternion(false)
- , _cameras(NULL)
+ , _cameras(nullptr)
, _connectionLost(false)
, _connectionLostEnabled(true)
, _initialPlanRequestComplete(false)
- , _missionManager(NULL)
+ , _missionManager(nullptr)
, _missionManagerInitialRequestSent(false)
- , _geoFenceManager(NULL)
+ , _geoFenceManager(nullptr)
, _geoFenceManagerInitialRequestSent(false)
- , _rallyPointManager(NULL)
+ , _rallyPointManager(nullptr)
, _rallyPointManagerInitialRequestSent(false)
- , _parameterManager(NULL)
+ , _parameterManager(nullptr)
#if defined(QGC_AIRMAP_ENABLED)
- , _airspaceVehicleManager(NULL)
+ , _airspaceVehicleManager(nullptr)
#endif
, _armed(false)
, _base_mode(0)
, _custom_mode(0)
, _nextSendMessageMultipleIndex(0)
, _firmwarePluginManager(firmwarePluginManager)
- , _joystickManager(NULL)
+ , _joystickManager(nullptr)
, _flowImageIndex(0)
, _allLinksInactiveSent(false)
, _messagesReceived(0)
@@ -462,6 +464,7 @@ void Vehicle::_commonInit(void)
_addFactGroup(&_temperatureFactGroup, _temperatureFactGroupName);
_addFactGroup(&_clockFactGroup, _clockFactGroupName);
_addFactGroup(&_distanceSensorFactGroup, _distanceSensorFactGroupName);
+ _addFactGroup(&_estimatorStatusFactGroup, _estimatorStatusFactGroupName);
// Add firmware-specific fact groups, if provided
QMap* fwFactGroups = _firmwarePlugin->factGroups();
@@ -493,13 +496,13 @@ Vehicle::~Vehicle()
qCDebug(VehicleLog) << "~Vehicle" << this;
delete _missionManager;
- _missionManager = NULL;
+ _missionManager = nullptr;
delete _autopilotPlugin;
- _autopilotPlugin = NULL;
+ _autopilotPlugin = nullptr;
delete _mav;
- _mav = NULL;
+ _mav = nullptr;
#if defined(QGC_AIRMAP_ENABLED)
if (_airspaceVehicleManager) {
@@ -512,7 +515,7 @@ void Vehicle::prepareDelete()
{
if(_cameras) {
delete _cameras;
- _cameras = NULL;
+ _cameras = nullptr;
emit dynamicCamerasChanged();
qApp->processEvents();
}
@@ -749,6 +752,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_DISTANCE_SENSOR:
_handleDistanceSensor(message);
break;
+ case MAVLINK_MSG_ID_ESTIMATOR_STATUS:
+ _handleEstimatorStatus(message);
+ break;
case MAVLINK_MSG_ID_PING:
_handlePing(link, message);
break;
@@ -816,6 +822,64 @@ void Vehicle::_handleVfrHud(mavlink_message_t& message)
_climbRateFact.setRawValue(qIsNaN(vfrHud.climb) ? 0 : vfrHud.climb);
}
+void Vehicle::_handleEstimatorStatus(mavlink_message_t& message)
+{
+ mavlink_estimator_status_t estimatorStatus;
+ mavlink_msg_estimator_status_decode(&message, &estimatorStatus);
+
+ _estimatorStatusFactGroup.goodAttitudeEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_ATTITUDE));
+ _estimatorStatusFactGroup.goodHorizVelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_VELOCITY_HORIZ));
+ _estimatorStatusFactGroup.goodVertVelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_VELOCITY_VERT));
+ _estimatorStatusFactGroup.goodHorizPosRelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_HORIZ_REL));
+ _estimatorStatusFactGroup.goodHorizPosAbsEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_HORIZ_ABS));
+ _estimatorStatusFactGroup.goodVertPosAbsEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_VERT_ABS));
+ _estimatorStatusFactGroup.goodVertPosAGLEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_VERT_AGL));
+ _estimatorStatusFactGroup.goodConstPosModeEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_CONST_POS_MODE));
+ _estimatorStatusFactGroup.goodPredHorizPosRelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_PRED_POS_HORIZ_REL));
+ _estimatorStatusFactGroup.goodPredHorizPosAbsEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_PRED_POS_HORIZ_ABS));
+ _estimatorStatusFactGroup.gpsGlitch()->setRawValue(estimatorStatus.flags & ESTIMATOR_GPS_GLITCH ? true : false);
+ _estimatorStatusFactGroup.accelError()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_ACCEL_ERROR));
+ _estimatorStatusFactGroup.velRatio()->setRawValue(estimatorStatus.vel_ratio);
+ _estimatorStatusFactGroup.horizPosRatio()->setRawValue(estimatorStatus.pos_horiz_ratio);
+ _estimatorStatusFactGroup.vertPosRatio()->setRawValue(estimatorStatus.pos_vert_ratio);
+ _estimatorStatusFactGroup.magRatio()->setRawValue(estimatorStatus.mag_ratio);
+ _estimatorStatusFactGroup.haglRatio()->setRawValue(estimatorStatus.hagl_ratio);
+ _estimatorStatusFactGroup.tasRatio()->setRawValue(estimatorStatus.tas_ratio);
+ _estimatorStatusFactGroup.horizPosAccuracy()->setRawValue(estimatorStatus.pos_horiz_accuracy);
+ _estimatorStatusFactGroup.vertPosAccuracy()->setRawValue(estimatorStatus.pos_vert_accuracy);
+
+#if 0
+ typedef enum ESTIMATOR_STATUS_FLAGS
+ {
+ ESTIMATOR_ATTITUDE=1, /* True if the attitude estimate is good | */
+ ESTIMATOR_VELOCITY_HORIZ=2, /* True if the horizontal velocity estimate is good | */
+ ESTIMATOR_VELOCITY_VERT=4, /* True if the vertical velocity estimate is good | */
+ ESTIMATOR_POS_HORIZ_REL=8, /* True if the horizontal position (relative) estimate is good | */
+ ESTIMATOR_POS_HORIZ_ABS=16, /* True if the horizontal position (absolute) estimate is good | */
+ ESTIMATOR_POS_VERT_ABS=32, /* True if the vertical position (absolute) estimate is good | */
+ ESTIMATOR_POS_VERT_AGL=64, /* True if the vertical position (above ground) estimate is good | */
+ ESTIMATOR_CONST_POS_MODE=128, /* True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) | */
+ ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */
+ ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */
+ ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */
+ ESTIMATOR_ACCEL_ERROR=2048, /* True if the EKF has detected bad accelerometer data | */
+
+ typedef struct __mavlink_estimator_status_t {
+ uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
+ float vel_ratio; /*< Velocity innovation test ratio*/
+ float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/
+ float pos_vert_ratio; /*< Vertical position innovation test ratio*/
+ float mag_ratio; /*< Magnetometer innovation test ratio*/
+ float hagl_ratio; /*< Height above terrain innovation test ratio*/
+ float tas_ratio; /*< True airspeed innovation test ratio*/
+ float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/
+ float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/
+ uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/
+ }) mavlink_estimator_status_t;
+
+#endif
+}
+
void Vehicle::_handleDistanceSensor(mavlink_message_t& message)
{
mavlink_distance_sensor_t distanceSensor;
@@ -1777,7 +1841,7 @@ void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand)
}
}
- LinkInterface* newPriorityLink = NULL;
+ LinkInterface* newPriorityLink = nullptr;
// This routine specifically does not clear _priorityLink when there are no links remaining.
// By doing this we hold a reference on the last link as the Vehicle shuts down. Thus preventing shutdown
@@ -2193,7 +2257,7 @@ void Vehicle::setPriorityLinkByName(const QString& priorityLinkName)
return;
}
- LinkInterface* newPriorityLink = NULL;
+ LinkInterface* newPriorityLink = nullptr;
for (int i=0; i<_links.count(); i++) {
@@ -3816,3 +3880,69 @@ VehicleDistanceSensorFactGroup::VehicleDistanceSensorFactGroup(QObject* parent)
_rotationPitch90Fact.setRawValue(std::numeric_limits::quiet_NaN());
_rotationPitch270Fact.setRawValue(std::numeric_limits::quiet_NaN());
}
+
+const char* VehicleEstimatorStatusFactGroup::_goodAttitudeEstimateFactName = "goodAttitudeEsimate";
+const char* VehicleEstimatorStatusFactGroup::_goodHorizVelEstimateFactName = "goodHorizVelEstimate";
+const char* VehicleEstimatorStatusFactGroup::_goodVertVelEstimateFactName = "goodVertVelEstimate";
+const char* VehicleEstimatorStatusFactGroup::_goodHorizPosRelEstimateFactName = "goodHorizPosRelEstimate";
+const char* VehicleEstimatorStatusFactGroup::_goodHorizPosAbsEstimateFactName = "goodHorizPosAbsEstimate";
+const char* VehicleEstimatorStatusFactGroup::_goodVertPosAbsEstimateFactName = "goodVertPosAbsEstimate";
+const char* VehicleEstimatorStatusFactGroup::_goodVertPosAGLEstimateFactName = "goodVertPosAGLEstimate";
+const char* VehicleEstimatorStatusFactGroup::_goodConstPosModeEstimateFactName = "goodConstPosModeEstimate";
+const char* VehicleEstimatorStatusFactGroup::_goodPredHorizPosRelEstimateFactName = "goodPredHorizPosRelEstimate";
+const char* VehicleEstimatorStatusFactGroup::_goodPredHorizPosAbsEstimateFactName = "goodPredHorizPosAbsEstimate";
+const char* VehicleEstimatorStatusFactGroup::_gpsGlitchFactName = "gpsGlitch";
+const char* VehicleEstimatorStatusFactGroup::_accelErrorFactName = "accelError";
+const char* VehicleEstimatorStatusFactGroup::_velRatioFactName = "velRatio";
+const char* VehicleEstimatorStatusFactGroup::_horizPosRatioFactName = "horizPosRatio";
+const char* VehicleEstimatorStatusFactGroup::_vertPosRatioFactName = "vertPosRatio";
+const char* VehicleEstimatorStatusFactGroup::_magRatioFactName = "magRatio";
+const char* VehicleEstimatorStatusFactGroup::_haglRatioFactName = "haglRatio";
+const char* VehicleEstimatorStatusFactGroup::_tasRatioFactName = "tasRatio";
+const char* VehicleEstimatorStatusFactGroup::_horizPosAccuracyFactName = "horizPosAccuracy";
+const char* VehicleEstimatorStatusFactGroup::_vertPosAccuracyFactName = "vertPosAccuracy";
+
+VehicleEstimatorStatusFactGroup::VehicleEstimatorStatusFactGroup(QObject* parent)
+ : FactGroup (500, ":/json/Vehicle/EstimatorStatusFactGroup.json", parent)
+ , _goodAttitudeEstimateFact (0, _goodAttitudeEstimateFactName, FactMetaData::valueTypeBool)
+ , _goodHorizVelEstimateFact (0, _goodHorizVelEstimateFactName, FactMetaData::valueTypeBool)
+ , _goodVertVelEstimateFact (0, _goodVertVelEstimateFactName, FactMetaData::valueTypeBool)
+ , _goodHorizPosRelEstimateFact (0, _goodHorizPosRelEstimateFactName, FactMetaData::valueTypeBool)
+ , _goodHorizPosAbsEstimateFact (0, _goodHorizPosAbsEstimateFactName, FactMetaData::valueTypeBool)
+ , _goodVertPosAbsEstimateFact (0, _goodVertPosAbsEstimateFactName, FactMetaData::valueTypeBool)
+ , _goodVertPosAGLEstimateFact (0, _goodVertPosAGLEstimateFactName, FactMetaData::valueTypeBool)
+ , _goodConstPosModeEstimateFact (0, _goodConstPosModeEstimateFactName, FactMetaData::valueTypeBool)
+ , _goodPredHorizPosRelEstimateFact (0, _goodPredHorizPosRelEstimateFactName, FactMetaData::valueTypeBool)
+ , _goodPredHorizPosAbsEstimateFact (0, _goodPredHorizPosAbsEstimateFactName, FactMetaData::valueTypeBool)
+ , _gpsGlitchFact (0, _gpsGlitchFactName, FactMetaData::valueTypeBool)
+ , _accelErrorFact (0, _accelErrorFactName, FactMetaData::valueTypeBool)
+ , _velRatioFact (0, _velRatioFactName, FactMetaData::valueTypeFloat)
+ , _horizPosRatioFact (0, _horizPosRatioFactName, FactMetaData::valueTypeFloat)
+ , _vertPosRatioFact (0, _vertPosRatioFactName, FactMetaData::valueTypeFloat)
+ , _magRatioFact (0, _magRatioFactName, FactMetaData::valueTypeFloat)
+ , _haglRatioFact (0, _haglRatioFactName, FactMetaData::valueTypeFloat)
+ , _tasRatioFact (0, _tasRatioFactName, FactMetaData::valueTypeFloat)
+ , _horizPosAccuracyFact (0, _horizPosAccuracyFactName, FactMetaData::valueTypeFloat)
+ , _vertPosAccuracyFact (0, _vertPosAccuracyFactName, FactMetaData::valueTypeFloat)
+{
+ _addFact(&_goodAttitudeEstimateFact, _goodAttitudeEstimateFactName);
+ _addFact(&_goodHorizVelEstimateFact, _goodHorizVelEstimateFactName);
+ _addFact(&_goodVertVelEstimateFact, _goodVertVelEstimateFactName);
+ _addFact(&_goodHorizPosRelEstimateFact, _goodHorizPosRelEstimateFactName);
+ _addFact(&_goodHorizPosAbsEstimateFact, _goodHorizPosAbsEstimateFactName);
+ _addFact(&_goodVertPosAbsEstimateFact, _goodVertPosAbsEstimateFactName);
+ _addFact(&_goodVertPosAGLEstimateFact, _goodVertPosAGLEstimateFactName);
+ _addFact(&_goodConstPosModeEstimateFact, _goodConstPosModeEstimateFactName);
+ _addFact(&_goodPredHorizPosRelEstimateFact, _goodPredHorizPosRelEstimateFactName);
+ _addFact(&_goodPredHorizPosAbsEstimateFact, _goodPredHorizPosAbsEstimateFactName);
+ _addFact(&_gpsGlitchFact, _gpsGlitchFactName);
+ _addFact(&_accelErrorFact, _accelErrorFactName);
+ _addFact(&_velRatioFact, _velRatioFactName);
+ _addFact(&_horizPosRatioFact, _horizPosRatioFactName);
+ _addFact(&_vertPosRatioFact, _vertPosRatioFactName);
+ _addFact(&_magRatioFact, _magRatioFactName);
+ _addFact(&_haglRatioFact, _haglRatioFactName);
+ _addFact(&_tasRatioFact, _tasRatioFactName);
+ _addFact(&_horizPosAccuracyFact, _horizPosAccuracyFactName);
+ _addFact(&_vertPosAccuracyFact, _vertPosAccuracyFactName);
+}
diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h
index 73931f8eb19ce2f432e75ae149b3c21ee2ebeeb1..7e81cb75400ea96d021ec7edad3a22aad7fcc6ef 100644
--- a/src/Vehicle/Vehicle.h
+++ b/src/Vehicle/Vehicle.h
@@ -48,7 +48,7 @@ class VehicleDistanceSensorFactGroup : public FactGroup
Q_OBJECT
public:
- VehicleDistanceSensorFactGroup(QObject* parent = NULL);
+ VehicleDistanceSensorFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* rotationNone READ rotationNone CONSTANT)
Q_PROPERTY(Fact* rotationYaw45 READ rotationYaw45 CONSTANT)
@@ -109,7 +109,7 @@ class VehicleSetpointFactGroup : public FactGroup
Q_OBJECT
public:
- VehicleSetpointFactGroup(QObject* parent = NULL);
+ VehicleSetpointFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* roll READ roll CONSTANT)
Q_PROPERTY(Fact* pitch READ pitch CONSTANT)
@@ -146,7 +146,7 @@ class VehicleVibrationFactGroup : public FactGroup
Q_OBJECT
public:
- VehicleVibrationFactGroup(QObject* parent = NULL);
+ VehicleVibrationFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* xAxis READ xAxis CONSTANT)
Q_PROPERTY(Fact* yAxis READ yAxis CONSTANT)
@@ -183,7 +183,7 @@ class VehicleWindFactGroup : public FactGroup
Q_OBJECT
public:
- VehicleWindFactGroup(QObject* parent = NULL);
+ VehicleWindFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* direction READ direction CONSTANT)
Q_PROPERTY(Fact* speed READ speed CONSTANT)
@@ -208,7 +208,7 @@ class VehicleGPSFactGroup : public FactGroup
Q_OBJECT
public:
- VehicleGPSFactGroup(QObject* parent = NULL);
+ VehicleGPSFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* lat READ lat CONSTANT)
Q_PROPERTY(Fact* lon READ lon CONSTANT)
@@ -249,7 +249,7 @@ class VehicleBatteryFactGroup : public FactGroup
Q_OBJECT
public:
- VehicleBatteryFactGroup(QObject* parent = NULL);
+ VehicleBatteryFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* voltage READ voltage CONSTANT)
Q_PROPERTY(Fact* percentRemaining READ percentRemaining CONSTANT)
@@ -308,7 +308,7 @@ class VehicleTemperatureFactGroup : public FactGroup
Q_OBJECT
public:
- VehicleTemperatureFactGroup(QObject* parent = NULL);
+ VehicleTemperatureFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* temperature1 READ temperature1 CONSTANT)
Q_PROPERTY(Fact* temperature2 READ temperature2 CONSTANT)
@@ -337,7 +337,7 @@ class VehicleClockFactGroup : public FactGroup
Q_OBJECT
public:
- VehicleClockFactGroup(QObject* parent = NULL);
+ VehicleClockFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* currentTime READ currentTime CONSTANT)
Q_PROPERTY(Fact* currentDate READ currentDate CONSTANT)
@@ -358,6 +358,131 @@ private:
Fact _currentDateFact;
};
+class VehicleEstimatorStatusFactGroup : public FactGroup
+{
+ Q_OBJECT
+
+public:
+ VehicleEstimatorStatusFactGroup(QObject* parent = nullptr);
+
+ Q_PROPERTY(Fact* goodAttitudeEstimate READ goodAttitudeEstimate CONSTANT)
+ Q_PROPERTY(Fact* goodHorizVelEstimate READ goodHorizVelEstimate CONSTANT)
+ Q_PROPERTY(Fact* goodVertVelEstimate READ goodVertVelEstimate CONSTANT)
+ Q_PROPERTY(Fact* goodHorizPosRelEstimate READ goodHorizPosRelEstimate CONSTANT)
+ Q_PROPERTY(Fact* goodHorizPosAbsEstimate READ goodHorizPosAbsEstimate CONSTANT)
+ Q_PROPERTY(Fact* goodVertPosAbsEstimate READ goodVertPosAbsEstimate CONSTANT)
+ Q_PROPERTY(Fact* goodVertPosAGLEstimate READ goodVertPosAGLEstimate CONSTANT)
+ Q_PROPERTY(Fact* goodConstPosModeEstimate READ goodConstPosModeEstimate CONSTANT)
+ Q_PROPERTY(Fact* goodPredHorizPosRelEstimate READ goodPredHorizPosRelEstimate CONSTANT)
+ Q_PROPERTY(Fact* goodPredHorizPosAbsEstimate READ goodPredHorizPosAbsEstimate CONSTANT)
+ Q_PROPERTY(Fact* gpsGlitch READ gpsGlitch CONSTANT)
+ Q_PROPERTY(Fact* accelError READ accelError CONSTANT)
+ Q_PROPERTY(Fact* velRatio READ velRatio CONSTANT)
+ Q_PROPERTY(Fact* horizPosRatio READ horizPosRatio CONSTANT)
+ Q_PROPERTY(Fact* vertPosRatio READ vertPosRatio CONSTANT)
+ Q_PROPERTY(Fact* magRatio READ magRatio CONSTANT)
+ Q_PROPERTY(Fact* haglRatio READ haglRatio CONSTANT)
+ Q_PROPERTY(Fact* tasRatio READ tasRatio CONSTANT)
+ Q_PROPERTY(Fact* horizPosAccuracy READ horizPosAccuracy CONSTANT)
+ Q_PROPERTY(Fact* vertPosAccuracy READ vertPosAccuracy CONSTANT)
+
+ Fact* goodAttitudeEstimate (void) { return &_goodAttitudeEstimateFact; }
+ Fact* goodHorizVelEstimate (void) { return &_goodHorizVelEstimateFact; }
+ Fact* goodVertVelEstimate (void) { return &_goodVertVelEstimateFact; }
+ Fact* goodHorizPosRelEstimate (void) { return &_goodHorizPosRelEstimateFact; }
+ Fact* goodHorizPosAbsEstimate (void) { return &_goodHorizPosAbsEstimateFact; }
+ Fact* goodVertPosAbsEstimate (void) { return &_goodVertPosAbsEstimateFact; }
+ Fact* goodVertPosAGLEstimate (void) { return &_goodVertPosAGLEstimateFact; }
+ Fact* goodConstPosModeEstimate (void) { return &_goodConstPosModeEstimateFact; }
+ Fact* goodPredHorizPosRelEstimate (void) { return &_goodPredHorizPosRelEstimateFact; }
+ Fact* goodPredHorizPosAbsEstimate (void) { return &_goodPredHorizPosAbsEstimateFact; }
+ Fact* gpsGlitch (void) { return &_gpsGlitchFact; }
+ Fact* accelError (void) { return &_accelErrorFact; }
+ Fact* velRatio (void) { return &_velRatioFact; }
+ Fact* horizPosRatio (void) { return &_horizPosRatioFact; }
+ Fact* vertPosRatio (void) { return &_vertPosRatioFact; }
+ Fact* magRatio (void) { return &_magRatioFact; }
+ Fact* haglRatio (void) { return &_haglRatioFact; }
+ Fact* tasRatio (void) { return &_tasRatioFact; }
+ Fact* horizPosAccuracy (void) { return &_horizPosAccuracyFact; }
+ Fact* vertPosAccuracy (void) { return &_vertPosAccuracyFact; }
+
+ static const char* _goodAttitudeEstimateFactName;
+ static const char* _goodHorizVelEstimateFactName;
+ static const char* _goodVertVelEstimateFactName;
+ static const char* _goodHorizPosRelEstimateFactName;
+ static const char* _goodHorizPosAbsEstimateFactName;
+ static const char* _goodVertPosAbsEstimateFactName;
+ static const char* _goodVertPosAGLEstimateFactName;
+ static const char* _goodConstPosModeEstimateFactName;
+ static const char* _goodPredHorizPosRelEstimateFactName;
+ static const char* _goodPredHorizPosAbsEstimateFactName;
+ static const char* _gpsGlitchFactName;
+ static const char* _accelErrorFactName;
+ static const char* _velRatioFactName;
+ static const char* _horizPosRatioFactName;
+ static const char* _vertPosRatioFactName;
+ static const char* _magRatioFactName;
+ static const char* _haglRatioFactName;
+ static const char* _tasRatioFactName;
+ static const char* _horizPosAccuracyFactName;
+ static const char* _vertPosAccuracyFactName;
+
+private:
+ Fact _goodAttitudeEstimateFact;
+ Fact _goodHorizVelEstimateFact;
+ Fact _goodVertVelEstimateFact;
+ Fact _goodHorizPosRelEstimateFact;
+ Fact _goodHorizPosAbsEstimateFact;
+ Fact _goodVertPosAbsEstimateFact;
+ Fact _goodVertPosAGLEstimateFact;
+ Fact _goodConstPosModeEstimateFact;
+ Fact _goodPredHorizPosRelEstimateFact;
+ Fact _goodPredHorizPosAbsEstimateFact;
+ Fact _gpsGlitchFact;
+ Fact _accelErrorFact;
+ Fact _velRatioFact;
+ Fact _horizPosRatioFact;
+ Fact _vertPosRatioFact;
+ Fact _magRatioFact;
+ Fact _haglRatioFact;
+ Fact _tasRatioFact;
+ Fact _horizPosAccuracyFact;
+ Fact _vertPosAccuracyFact;
+
+#if 0
+ typedef enum ESTIMATOR_STATUS_FLAGS
+ {
+ ESTIMATOR_ATTITUDE=1, /* True if the attitude estimate is good | */
+ ESTIMATOR_VELOCITY_HORIZ=2, /* True if the horizontal velocity estimate is good | */
+ ESTIMATOR_VELOCITY_VERT=4, /* True if the vertical velocity estimate is good | */
+ ESTIMATOR_POS_HORIZ_REL=8, /* True if the horizontal position (relative) estimate is good | */
+ ESTIMATOR_POS_HORIZ_ABS=16, /* True if the horizontal position (absolute) estimate is good | */
+ ESTIMATOR_POS_VERT_ABS=32, /* True if the vertical position (absolute) estimate is good | */
+ ESTIMATOR_POS_VERT_AGL=64, /* True if the vertical position (above ground) estimate is good | */
+ ESTIMATOR_CONST_POS_MODE=128, /* True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) | */
+ ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */
+ ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */
+ ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */
+ ESTIMATOR_ACCEL_ERROR=2048, /* True if the EKF has detected bad accelerometer data | */
+
+ typedef struct __mavlink_estimator_status_t {
+ uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
+ float vel_ratio; /*< Velocity innovation test ratio*/
+ float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/
+ float pos_vert_ratio; /*< Vertical position innovation test ratio*/
+ float mag_ratio; /*< Magnetometer innovation test ratio*/
+ float hagl_ratio; /*< Height above terrain innovation test ratio*/
+ float tas_ratio; /*< True airspeed innovation test ratio*/
+ float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/
+ float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/
+ uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/
+ }) mavlink_estimator_status_t;
+
+#endif
+};
+
+
class Vehicle : public FactGroup
{
Q_OBJECT
@@ -529,14 +654,15 @@ public:
Q_PROPERTY(Fact* distanceToHome READ distanceToHome CONSTANT)
Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT)
- Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
- Q_PROPERTY(FactGroup* battery READ battery1FactGroup CONSTANT)
- Q_PROPERTY(FactGroup* battery2 READ battery2FactGroup CONSTANT)
- Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
- Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
- Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT)
- Q_PROPERTY(FactGroup* clock READ clockFactGroup CONSTANT)
- Q_PROPERTY(FactGroup* setpoint READ setpointFactGroup CONSTANT)
+ Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
+ Q_PROPERTY(FactGroup* battery READ battery1FactGroup CONSTANT)
+ Q_PROPERTY(FactGroup* battery2 READ battery2FactGroup CONSTANT)
+ Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT)
+ Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
+ Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT)
+ Q_PROPERTY(FactGroup* clock READ clockFactGroup CONSTANT)
+ Q_PROPERTY(FactGroup* setpoint READ setpointFactGroup CONSTANT)
+ Q_PROPERTY(FactGroup* estimatorStatus READ estimatorStatusFactGroup CONSTANT)
Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareVersionChanged)
Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareVersionChanged)
@@ -826,6 +952,7 @@ public:
FactGroup* clockFactGroup (void) { return &_clockFactGroup; }
FactGroup* setpointFactGroup (void) { return &_setpointFactGroup; }
FactGroup* distanceSensorFactGroup (void) { return &_distanceSensorFactGroup; }
+ FactGroup* estimatorStatusFactGroup (void) { return &_estimatorStatusFactGroup; }
void setConnectionLostEnabled(bool connectionLostEnabled);
@@ -1094,6 +1221,7 @@ private:
void _handleAttitudeQuaternion(mavlink_message_t& message);
void _handleAttitudeTarget(mavlink_message_t& message);
void _handleDistanceSensor(mavlink_message_t& message);
+ void _handleEstimatorStatus(mavlink_message_t& message);
// ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
void _handleCameraFeedback(const mavlink_message_t& message);
@@ -1316,6 +1444,7 @@ private:
VehicleClockFactGroup _clockFactGroup;
VehicleSetpointFactGroup _setpointFactGroup;
VehicleDistanceSensorFactGroup _distanceSensorFactGroup;
+ VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup;
static const char* _rollFactName;
static const char* _pitchFactName;
@@ -1341,6 +1470,7 @@ private:
static const char* _temperatureFactGroupName;
static const char* _clockFactGroupName;
static const char* _distanceSensorFactGroupName;
+ static const char* _estimatorStatusFactGroupName;
static const int _vehicleUIUpdateRateMSecs = 100;
diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc
index 5c29162c4943ae56a666d694a8feb75b9161cba6..e984f1c0e07fcd457c8eb526e025abc064f0e944 100644
--- a/src/VehicleSetup/FirmwareUpgradeController.cc
+++ b/src/VehicleSetup/FirmwareUpgradeController.cc
@@ -36,20 +36,20 @@ struct FirmwareToUrlElement_t {
uint qHash(const FirmwareUpgradeController::FirmwareIdentifier& firmwareId)
{
- return ( firmwareId.autopilotStackType |
+ return static_cast(( firmwareId.autopilotStackType |
(firmwareId.firmwareType << 8) |
- (firmwareId.firmwareVehicleType << 16) );
+ (firmwareId.firmwareVehicleType << 16) ));
}
/// @Brief Constructs a new FirmwareUpgradeController Widget. This widget is used within the PX4VehicleConfig set of screens.
FirmwareUpgradeController::FirmwareUpgradeController(void)
: _singleFirmwareURL(qgcApp()->toolbox()->corePlugin()->options()->firmwareUpgradeSingleURL())
, _singleFirmwareMode(!_singleFirmwareURL.isEmpty())
- , _downloadManager(NULL)
- , _downloadNetworkReply(NULL)
- , _statusLog(NULL)
+ , _downloadManager(nullptr)
+ , _downloadNetworkReply(nullptr)
+ , _statusLog(nullptr)
, _selectedFirmwareType(StableFirmware)
- , _image(NULL)
+ , _image(nullptr)
{
_threadController = new PX4FirmwareUpgradeThreadController(this);
Q_CHECK_PTR(_threadController);
@@ -129,7 +129,7 @@ void FirmwareUpgradeController::cancel(void)
void FirmwareUpgradeController::_foundBoard(bool firstAttempt, const QSerialPortInfo& info, int boardType, QString boardName)
{
_foundBoardInfo = info;
- _foundBoardType = (QGCSerialPortInfo::BoardType_t)boardType;
+ _foundBoardType = static_cast(boardType);
_foundBoardTypeName = boardName;
_startFlashWhenBootloaderFound = false;
@@ -164,9 +164,9 @@ void FirmwareUpgradeController::_boardGone(void)
void FirmwareUpgradeController::_foundBootloader(int bootloaderVersion, int boardID, int flashSize)
{
_bootloaderFound = true;
- _bootloaderVersion = bootloaderVersion;
- _bootloaderBoardID = boardID;
- _bootloaderBoardFlashSize = flashSize;
+ _bootloaderVersion = static_cast(bootloaderVersion);
+ _bootloaderBoardID = static_cast(boardID);
+ _bootloaderBoardFlashSize = static_cast(flashSize);
_appendStatusLog(tr("Connected to bootloader:"));
_appendStatusLog(tr(" Version: %1").arg(_bootloaderVersion));
@@ -196,6 +196,7 @@ void FirmwareUpgradeController::_initFirmwareHash()
{ AutoPilotStackPX4, StableFirmware, DefaultVehicleFirmware, "http://gumstix-aerocore.s3.amazonaws.com/PX4/stable/aerocore_default.px4"},
{ AutoPilotStackPX4, BetaFirmware, DefaultVehicleFirmware, "http://gumstix-aerocore.s3.amazonaws.com/PX4/beta/aerocore_default.px4"},
{ AutoPilotStackPX4, DeveloperFirmware, DefaultVehicleFirmware, "http://gumstix-aerocore.s3.amazonaws.com/PX4/master/aerocore_default.px4"},
+ #if !defined(NO_ARDUPILOT_DIALECT)
{ AutoPilotStackAPM, BetaFirmware, CopterFirmware, "http://firmware.ardupilot.org/Copter/beta/PX4/ArduCopter-v2.px4"},
{ AutoPilotStackAPM, StableFirmware, HeliFirmware, "http://gumstix-aerocore.s3.amazonaws.com/Copter/stable/PX4-heli/ArduCopter-v2.px4"},
{ AutoPilotStackAPM, StableFirmware, PlaneFirmware, "http://gumstix-aerocore.s3.amazonaws.com/Plane/stable/PX4/ArduPlane-v2.px4"},
@@ -207,6 +208,7 @@ void FirmwareUpgradeController::_initFirmwareHash()
{ AutoPilotStackAPM, DeveloperFirmware, HeliFirmware, "http://gumstix-aerocore.s3.amazonaws.com/Copter/latest/PX4-heli/ArduCopter-v2.px4"},
{ AutoPilotStackAPM, DeveloperFirmware, PlaneFirmware, "http://gumstix-aerocore.s3.amazonaws.com/Plane/latest/PX4/ArduPlane-v2.px4"},
{ AutoPilotStackAPM, DeveloperFirmware, RoverFirmware, "http://gumstix-aerocore.s3.amazonaws.com/Rover/latest/PX4/APMrover2-v2.px4"}
+ #endif
};
//////////////////////////////////// AUAVX2_1 firmwares //////////////////////////////////////////////////
@@ -214,6 +216,7 @@ void FirmwareUpgradeController::_initFirmwareHash()
{ AutoPilotStackPX4, StableFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/stable/auav-x21_default.px4"},
{ AutoPilotStackPX4, BetaFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/beta/auav-x21_default.px4"},
{ AutoPilotStackPX4, DeveloperFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/master/auav-x21_default.px4"},
+ #if !defined(NO_ARDUPILOT_DIALECT)
{ AutoPilotStackAPM, StableFirmware, CopterFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4/ArduCopter-v3.px4"},
{ AutoPilotStackAPM, StableFirmware, HeliFirmware, "http://firmware.ardupilot.org/Copter/stable/PX4-heli/ArduCopter-v3.px4"},
{ AutoPilotStackAPM, StableFirmware, PlaneFirmware, "http://firmware.ardupilot.org/Plane/stable/PX4/ArduPlane-v2.px4"},
@@ -229,6 +232,7 @@ void FirmwareUpgradeController::_initFirmwareHash()
{ AutoPilotStackAPM, DeveloperFirmware, PlaneFirmware, "http://firmware.ardupilot.org/Plane/latest/PX4/ArduPlane-v3.px4"},
{ AutoPilotStackAPM, DeveloperFirmware, RoverFirmware, "http://firmware.ardupilot.org/Rover/latest/PX4/APMrover2-v3.px4"},
{ AutoPilotStackAPM, DeveloperFirmware, SubFirmware, "http://firmware.ardupilot.org/Sub/latest/PX4/ArduSub-v3.px4"}
+ #endif
};
//////////////////////////////////// MindPXFMUV2 firmwares //////////////////////////////////////////////////
FirmwareToUrlElement_t rgMindPXFMUV2FirmwareArray[] = {
@@ -260,7 +264,9 @@ void FirmwareUpgradeController::_initFirmwareHash()
/////////////////////////////// px4flow firmwares ///////////////////////////////////////
FirmwareToUrlElement_t rgPX4FLowFirmwareArray[] = {
{ PX4FlowPX4, StableFirmware, DefaultVehicleFirmware, "http://px4-travis.s3.amazonaws.com/Flow/master/px4flow.px4" },
+ #if !defined(NO_ARDUPILOT_DIALECT)
{ PX4FlowAPM, StableFirmware, DefaultVehicleFirmware, "http://firmware.ardupilot.org/Tools/PX4Flow/px4flow-klt-latest.px4" },
+ #endif
};
/////////////////////////////// 3dr radio firmwares ///////////////////////////////////////
@@ -286,52 +292,66 @@ void FirmwareUpgradeController::_initFirmwareHash()
px4MapFirmwareTypeToDir[BetaFirmware] = QStringLiteral("beta");
px4MapFirmwareTypeToDir[DeveloperFirmware] = QStringLiteral("master");
+#if !defined(NO_ARDUPILOT_DIALECT)
QMap apmMapVehicleTypeToDir;
apmMapVehicleTypeToDir[CopterFirmware] = QStringLiteral("Copter");
apmMapVehicleTypeToDir[HeliFirmware] = QStringLiteral("Copter");
apmMapVehicleTypeToDir[PlaneFirmware] = QStringLiteral("Plane");
apmMapVehicleTypeToDir[RoverFirmware] = QStringLiteral("Rover");
apmMapVehicleTypeToDir[SubFirmware] = QStringLiteral("Sub");
+#endif
+#if !defined(NO_ARDUPILOT_DIALECT)
QMap apmChibiOSMapVehicleTypeToDir;
apmChibiOSMapVehicleTypeToDir[CopterChibiOSFirmware] = QStringLiteral("Copter");
apmChibiOSMapVehicleTypeToDir[HeliChibiOSFirmware] = QStringLiteral("Copter");
apmChibiOSMapVehicleTypeToDir[PlaneChibiOSFirmware] = QStringLiteral("Plane");
apmChibiOSMapVehicleTypeToDir[RoverChibiOSFirmware] = QStringLiteral("Rover");
apmChibiOSMapVehicleTypeToDir[SubChibiOSFirmware] = QStringLiteral("Sub");
+#endif
+#if !defined(NO_ARDUPILOT_DIALECT)
QMap apmMapFirmwareTypeToDir;
apmMapFirmwareTypeToDir[StableFirmware] = QStringLiteral("stable");
apmMapFirmwareTypeToDir[BetaFirmware] = QStringLiteral("beta");
apmMapFirmwareTypeToDir[DeveloperFirmware] = QStringLiteral("latest");
+#endif
+#if !defined(NO_ARDUPILOT_DIALECT)
QMap apmMapVehicleTypeToPX4Dir;
apmMapVehicleTypeToPX4Dir[CopterFirmware] = QStringLiteral("PX4");
apmMapVehicleTypeToPX4Dir[HeliFirmware] = QStringLiteral("PX4-heli");
apmMapVehicleTypeToPX4Dir[PlaneFirmware] = QStringLiteral("PX4");
apmMapVehicleTypeToPX4Dir[RoverFirmware] = QStringLiteral("PX4");
apmMapVehicleTypeToPX4Dir[SubFirmware] = QStringLiteral("PX4");
+#endif
+#if !defined(NO_ARDUPILOT_DIALECT)
QMap apmMapVehicleTypeToFilename;
apmMapVehicleTypeToFilename[CopterFirmware] = QStringLiteral("ArduCopter");
apmMapVehicleTypeToFilename[HeliFirmware] = QStringLiteral("ArduCopter");
apmMapVehicleTypeToFilename[PlaneFirmware] = QStringLiteral("ArduPlane");
apmMapVehicleTypeToFilename[RoverFirmware] = QStringLiteral("APMrover2");
apmMapVehicleTypeToFilename[SubFirmware] = QStringLiteral("ArduSub");
+#endif
+#if !defined(NO_ARDUPILOT_DIALECT)
QMap apmChibiOSMapVehicleTypeToFmuDir;
apmChibiOSMapVehicleTypeToFmuDir[CopterChibiOSFirmware] = QString();
apmChibiOSMapVehicleTypeToFmuDir[HeliChibiOSFirmware] = QStringLiteral("-heli");
apmChibiOSMapVehicleTypeToFmuDir[PlaneChibiOSFirmware] = QString();
apmChibiOSMapVehicleTypeToFmuDir[RoverChibiOSFirmware] = QString();
apmChibiOSMapVehicleTypeToFmuDir[SubChibiOSFirmware] = QString();
+#endif
+#if !defined(NO_ARDUPILOT_DIALECT)
QMap apmChibiOSMapVehicleTypeToFilename;
apmChibiOSMapVehicleTypeToFilename[CopterChibiOSFirmware] = QStringLiteral("arducopter");
apmChibiOSMapVehicleTypeToFilename[HeliChibiOSFirmware] = QStringLiteral("arducopter-heli");
apmChibiOSMapVehicleTypeToFilename[PlaneChibiOSFirmware] = QStringLiteral("arduplane");
apmChibiOSMapVehicleTypeToFilename[RoverChibiOSFirmware] = QStringLiteral("ardurover");
apmChibiOSMapVehicleTypeToFilename[SubChibiOSFirmware] = QStringLiteral("ardusub");
+#endif
// PX4 Firmwares
foreach (const FirmwareType_t& firmwareType, px4MapFirmwareTypeToDir.keys()) {
@@ -343,6 +363,7 @@ void FirmwareUpgradeController::_initFirmwareHash()
_rgPX4FMUV2Firmware.insert (FirmwareIdentifier(AutoPilotStackPX4, firmwareType, DefaultVehicleFirmware), px4Url.arg(dir).arg("v2"));
}
+#if !defined(NO_ARDUPILOT_DIALECT)
// ArduPilot Firmwares
foreach (const FirmwareType_t& firmwareType, apmMapFirmwareTypeToDir.keys()) {
QString firmwareTypeDir = apmMapFirmwareTypeToDir[firmwareType];
@@ -357,7 +378,9 @@ void FirmwareUpgradeController::_initFirmwareHash()
_rgPX4FMUV2Firmware.insert (FirmwareIdentifier(AutoPilotStackAPM, firmwareType, vehicleType), apmUrl.arg(vehicleTypeDir).arg(firmwareTypeDir).arg(px4Dir).arg(filename).arg("2"));
}
}
+#endif
+#if !defined(NO_ARDUPILOT_DIALECT)
// ArduPilot ChibiOS Firmwares
foreach (const FirmwareType_t& firmwareType, apmMapFirmwareTypeToDir.keys()) {
QString firmwareTypeDir = apmMapFirmwareTypeToDir[firmwareType];
@@ -372,6 +395,7 @@ void FirmwareUpgradeController::_initFirmwareHash()
_rgPX4FMUV2Firmware.insert (FirmwareIdentifier(AutoPilotStackAPM, firmwareType, vehicleType), apmChibiOSUrl.arg(vehicleTypeDir).arg(firmwareTypeDir).arg("2").arg(fmuDir).arg(filename));
}
}
+#endif
int size = sizeof(rgAeroCoreFirmwareArray)/sizeof(rgAeroCoreFirmwareArray[0]);
for (int i = 0; i < size; i++) {
@@ -467,14 +491,14 @@ QHash* FirmwareUpgradeCo
case Bootloader::boardID3DRRadio:
return &_rg3DRRadioFirmware;
default:
- return NULL;
+ return nullptr;
}
}
/// @brief Prompts the user to select a firmware file if needed and moves the state machine to the next state.
void FirmwareUpgradeController::_getFirmwareFile(FirmwareIdentifier firmwareId)
{
- QHash* prgFirmware = _firmwareHashForBoardId(_bootloaderBoardID);
+ QHash* prgFirmware = _firmwareHashForBoardId(static_cast(_bootloaderBoardID));
if (!prgFirmware && firmwareId.firmwareType != CustomFirmware) {
_errorCancel(tr("Attempting to flash an unknown board type, you must select 'Custom firmware file'"));
@@ -482,9 +506,9 @@ void FirmwareUpgradeController::_getFirmwareFile(FirmwareIdentifier firmwareId)
}
if (firmwareId.firmwareType == CustomFirmware) {
- _firmwareFilename = QGCQFileDialog::getOpenFileName(NULL, // Parent to main window
- tr("Select Firmware File"), // Dialog Caption
- QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation), // Initial directory
+ _firmwareFilename = QGCQFileDialog::getOpenFileName(nullptr, // Parent to main window
+ tr("Select Firmware File"), // Dialog Caption
+ QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation), // Initial directory
tr("Firmware Files (*.px4 *.bin *.ihx)")); // File filter
} else {
if (prgFirmware->contains(firmwareId)) {
@@ -522,7 +546,7 @@ void FirmwareUpgradeController::_firmwareDownloadProgress(qint64 curr, qint64 to
{
// Take care of cases where 0 / 0 is emitted as error return value
if (total > 0) {
- _progressBar->setProperty("value", (float)curr / (float)total);
+ _progressBar->setProperty("value", static_cast(curr) / static_cast(total));
}
}
@@ -583,7 +607,7 @@ QString FirmwareUpgradeController::firmwareTypeAsString(FirmwareType_t type) con
void FirmwareUpgradeController::_flashComplete(void)
{
delete _image;
- _image = NULL;
+ _image = nullptr;
_appendStatusLog(tr("Upgrade complete"), true);
_appendStatusLog("------------------------------------------", false);
@@ -594,7 +618,7 @@ void FirmwareUpgradeController::_flashComplete(void)
void FirmwareUpgradeController::_error(const QString& errorString)
{
delete _image;
- _image = NULL;
+ _image = nullptr;
_errorCancel(QString("Error: %1").arg(errorString));
}
@@ -609,7 +633,7 @@ void FirmwareUpgradeController::_updateProgress(int curr, int total)
{
// Take care of cases where 0 / 0 is emitted as error return value
if (total > 0) {
- _progressBar->setProperty("value", (float)curr / (float)total);
+ _progressBar->setProperty("value", static_cast(curr) / static_cast(total));
}
}
@@ -617,7 +641,7 @@ void FirmwareUpgradeController::_updateProgress(int curr, int total)
void FirmwareUpgradeController::_eraseProgressTick(void)
{
_eraseTickCount++;
- _progressBar->setProperty("value", (float)(_eraseTickCount*_eraseTickMsec) / (float)_eraseTotalMsec);
+ _progressBar->setProperty("value", static_cast(_eraseTickCount*_eraseTickMsec) / static_cast(_eraseTotalMsec));
}
/// Appends the specified text to the status log area in the ui
@@ -666,7 +690,7 @@ void FirmwareUpgradeController::_loadAPMVersions(uint32_t bootloaderBoardID)
{
_apmVersionMap.clear();
- QHash* prgFirmware = _firmwareHashForBoardId(bootloaderBoardID);
+ QHash* prgFirmware = _firmwareHashForBoardId(static_cast(bootloaderBoardID));
foreach (FirmwareIdentifier firmwareId, prgFirmware->keys()) {
if (firmwareId.autopilotStackType == AutoPilotStackAPM) {
@@ -706,7 +730,7 @@ void FirmwareUpgradeController::_apmVersionDownloadFinished(QString remoteFile,
// In order to determine the firmware and vehicle type for this file we find the matching entry in the firmware list
- QHash* prgFirmware = _firmwareHashForBoardId(_bootloaderBoardID);
+ QHash* prgFirmware = _firmwareHashForBoardId(static_cast(_bootloaderBoardID));
QString remotePath = QFileInfo(remoteFile).path();
foreach (FirmwareIdentifier firmwareId, prgFirmware->keys()) {
diff --git a/src/api/QGCCorePlugin.cc b/src/api/QGCCorePlugin.cc
index 1e1abb49a8f50ef52f5f9d9312023c7001c287e4..5302be57df48df13d0105017301ea448cc7d4597 100644
--- a/src/api/QGCCorePlugin.cc
+++ b/src/api/QGCCorePlugin.cc
@@ -28,25 +28,25 @@ class QGCCorePlugin_p
{
public:
QGCCorePlugin_p()
- : pGeneral (NULL)
- , pCommLinks (NULL)
- , pOfflineMaps (NULL)
+ : pGeneral (nullptr)
+ , pCommLinks (nullptr)
+ , pOfflineMaps (nullptr)
#if defined(QGC_AIRMAP_ENABLED)
- , pAirmap (NULL)
+ , pAirmap (nullptr)
#endif
- , pMAVLink (NULL)
- , pConsole (NULL)
- , pHelp (NULL)
+ , pMAVLink (nullptr)
+ , pConsole (nullptr)
+ , pHelp (nullptr)
#if defined(QT_DEBUG)
- , pMockLink (NULL)
- , pDebug (NULL)
+ , pMockLink (nullptr)
+ , pDebug (nullptr)
#endif
- , defaultOptions (NULL)
- , valuesPageWidgetInfo (NULL)
- , cameraPageWidgetInfo (NULL)
- , videoPageWidgetInfo (NULL)
- , healthPageWidgetInfo (NULL)
- , vibrationPageWidgetInfo (NULL)
+ , defaultOptions (nullptr)
+ , valuesPageWidgetInfo (nullptr)
+ , cameraPageWidgetInfo (nullptr)
+ , videoPageWidgetInfo (nullptr)
+ , healthPageWidgetInfo (nullptr)
+ , vibrationPageWidgetInfo (nullptr)
{
}
@@ -129,41 +129,41 @@ QVariantList &QGCCorePlugin::settingsPages()
{
if(!_p->pGeneral) {
_p->pGeneral = new QmlComponentInfo(tr("General"),
- QUrl::fromUserInput("qrc:/qml/GeneralSettings.qml"),
- QUrl::fromUserInput("qrc:/res/gear-white.svg"));
- _p->settingsList.append(QVariant::fromValue((QmlComponentInfo*)_p->pGeneral));
+ QUrl::fromUserInput("qrc:/qml/GeneralSettings.qml"),
+ QUrl::fromUserInput("qrc:/res/gear-white.svg"));
+ _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pGeneral)));
_p->pCommLinks = new QmlComponentInfo(tr("Comm Links"),
- QUrl::fromUserInput("qrc:/qml/LinkSettings.qml"),
- QUrl::fromUserInput("qrc:/res/waves.svg"));
- _p->settingsList.append(QVariant::fromValue((QmlComponentInfo*)_p->pCommLinks));
+ QUrl::fromUserInput("qrc:/qml/LinkSettings.qml"),
+ QUrl::fromUserInput("qrc:/res/waves.svg"));
+ _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pCommLinks)));
_p->pOfflineMaps = new QmlComponentInfo(tr("Offline Maps"),
- QUrl::fromUserInput("qrc:/qml/OfflineMap.qml"),
- QUrl::fromUserInput("qrc:/res/waves.svg"));
- _p->settingsList.append(QVariant::fromValue((QmlComponentInfo*)_p->pOfflineMaps));
+ QUrl::fromUserInput("qrc:/qml/OfflineMap.qml"),
+ QUrl::fromUserInput("qrc:/res/waves.svg"));
+ _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pOfflineMaps)));
#if defined(QGC_AIRMAP_ENABLED)
_p->pAirmap = new QmlComponentInfo(tr("AirMap"),
- QUrl::fromUserInput("qrc:/qml/AirmapSettings.qml"),
- QUrl::fromUserInput(""));
- _p->settingsList.append(QVariant::fromValue((QmlComponentInfo*)_p->pAirmap));
+ QUrl::fromUserInput("qrc:/qml/AirmapSettings.qml"),
+ QUrl::fromUserInput(""));
+ _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pAirmap)));
#endif
_p->pMAVLink = new QmlComponentInfo(tr("MAVLink"),
- QUrl::fromUserInput("qrc:/qml/MavlinkSettings.qml"),
- QUrl::fromUserInput("qrc:/res/waves.svg"));
- _p->settingsList.append(QVariant::fromValue((QmlComponentInfo*)_p->pMAVLink));
+ QUrl::fromUserInput("qrc:/qml/MavlinkSettings.qml"),
+ QUrl::fromUserInput("qrc:/res/waves.svg"));
+ _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pMAVLink)));
_p->pConsole = new QmlComponentInfo(tr("Console"),
- QUrl::fromUserInput("qrc:/qml/QGroundControl/Controls/AppMessages.qml"));
- _p->settingsList.append(QVariant::fromValue((QmlComponentInfo*)_p->pConsole));
+ QUrl::fromUserInput("qrc:/qml/QGroundControl/Controls/AppMessages.qml"));
+ _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pConsole)));
_p->pHelp = new QmlComponentInfo(tr("Help"),
- QUrl::fromUserInput("qrc:/qml/HelpSettings.qml"));
- _p->settingsList.append(QVariant::fromValue((QmlComponentInfo*)_p->pHelp));
+ QUrl::fromUserInput("qrc:/qml/HelpSettings.qml"));
+ _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pHelp)));
#if defined(QT_DEBUG)
//-- These are always present on Debug builds
_p->pMockLink = new QmlComponentInfo(tr("Mock Link"),
- QUrl::fromUserInput("qrc:/qml/MockLink.qml"));
- _p->settingsList.append(QVariant::fromValue((QmlComponentInfo*)_p->pMockLink));
+ QUrl::fromUserInput("qrc:/qml/MockLink.qml"));
+ _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pMockLink)));
_p->pDebug = new QmlComponentInfo(tr("Debug"),
- QUrl::fromUserInput("qrc:/qml/DebugWindow.qml"));
- _p->settingsList.append(QVariant::fromValue((QmlComponentInfo*)_p->pDebug));
+ QUrl::fromUserInput("qrc:/qml/DebugWindow.qml"));
+ _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pDebug)));
#endif
}
return _p->settingsList;
diff --git a/src/api/QGCCorePlugin.h b/src/api/QGCCorePlugin.h
index b68f3245798d2bb231748da8caefbf00c0fdff6e..392db3c88e524e43f9c6a5c505463c7acf4d79c5 100644
--- a/src/api/QGCCorePlugin.h
+++ b/src/api/QGCCorePlugin.h
@@ -32,6 +32,7 @@ class Vehicle;
class LinkInterface;
class QmlObjectListModel;
class VideoReceiver;
+class PlanMasterController;
class QGCCorePlugin : public QGCTool
{
@@ -88,7 +89,7 @@ public:
virtual QString showAdvancedUIMessage(void) const;
/// @return An instance of an alternate position source (or NULL if not available)
- virtual QGeoPositionInfoSource* createPositionSource(QObject* parent) { Q_UNUSED(parent); return NULL; }
+ virtual QGeoPositionInfoSource* createPositionSource(QObject* parent) { Q_UNUSED(parent); return nullptr; }
/// Allows a plugin to override the specified color name from the palette
virtual void paletteOverride(QString colorName, QGCPalette::PaletteColorInfo_t& colorInfo);
@@ -110,6 +111,20 @@ public:
/// should derive from QmlComponentInfo and set the url property.
virtual QmlObjectListModel* customMapItems(void);
+ /// Allows custom builds to add custom items to the plan file. Either before the document is
+ /// created or after.
+ virtual void preSaveToJson (PlanMasterController* pController, QJsonObject& json) { Q_UNUSED(pController); Q_UNUSED(json); }
+ virtual void postSaveToJson (PlanMasterController* pController, QJsonObject& json) { Q_UNUSED(pController); Q_UNUSED(json); }
+
+ /// Same for the specific "mission" portion
+ virtual void preSaveToMissionJson (PlanMasterController* pController, QJsonObject& missionJson) { Q_UNUSED(pController); Q_UNUSED(missionJson); }
+ virtual void postSaveToMissionJson (PlanMasterController* pController, QJsonObject& missionJson) { Q_UNUSED(pController); Q_UNUSED(missionJson); }
+
+ /// Allows custom builds to load custom items from the plan file. Either before the document is
+ /// parsed or after.
+ virtual void preLoadFromJson (PlanMasterController* pController, QJsonObject& json) { Q_UNUSED(pController); Q_UNUSED(json); }
+ virtual void postLoadFromJson (PlanMasterController* pController, QJsonObject& json) { Q_UNUSED(pController); Q_UNUSED(json); }
+
bool showTouchAreas(void) const { return _showTouchAreas; }
bool showAdvancedUI(void) const { return _showAdvancedUI; }
void setShowTouchAreas(bool show);