Commit 4a3e6e97 authored by Gus Grubba's avatar Gus Grubba
Browse files

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into singleFirmware

parents dbd23672 0aad76c5
......@@ -7,20 +7,35 @@ WindowsBuild {
#
# [REQUIRED] Add support for the MAVLink communications protocol.
# Mavlink dialect is hardwired to arudpilotmega for now. The reason being
#
# By default MAVLink dialect is hardwired to arudpilotmega. The reason being
# the current codebase supports both PX4 and APM flight stack. PX4 flight stack
# only usese common mavlink specifications, whereas APM flight stack uses custom
# mavlink specifications which add to common. So by using the adupilotmega dialect
# only uses common MAVLink specifications, whereas APM flight stack uses custom
# MAVLink specifications which adds to common. So by using the adupilotmega dialect
# QGC can support both in the same codebase.
#
# Once the mavlink helper routines include support for multiple dialects within
# a single compiled codebase this hardwiring of dialect can go away. But until then
# this "workaround" is needed.
MAVLINKPATH_REL = libs/mavlink/include/mavlink/v2.0
MAVLINKPATH = $$BASEDIR/$$MAVLINKPATH_REL
MAVLINK_CONF = ardupilotmega
DEFINES += MAVLINK_NO_DATA
# In the mean time, it’s possible to define a completely different dialect by defining the
# location and name below.
isEmpty(MAVLINKPATH_REL) {
MAVLINKPATH_REL = libs/mavlink/include/mavlink/v2.0
}
isEmpty(MAVLINKPATH) {
MAVLINKPATH = $$BASEDIR/$$MAVLINKPATH_REL
}
isEmpty(MAVLINK_CONF) {
MAVLINK_CONF = ardupilotmega
}
# If defined, all APM specific MAVLink messages are disabled
contains (CONFIG, QGC_DISABLE_APM_MAVLINK) {
message("Disable APM MAVLink support")
DEFINES += NO_ARDUPILOT_DIALECT
}
# First we select the dialect, checking for valid user selection
# Users can override all other settings by specifying MAVLINK_CONF as an argument to qmake
......
......@@ -31,8 +31,9 @@ installer {
# macdeploy is missing some relocations once in a while. "Fix" it:
QMAKE_POST_LINK += && python $$BASEDIR/tools/osxrelocator.py $${TARGET}.app/Contents @rpath @executable_path/../Frameworks -r > /dev/null 2>&1
# Create package
QMAKE_POST_LINK += && cd $${OUT_PWD}
QMAKE_POST_LINK += && hdiutil create -verbose -stretch 4g -layout SPUD -srcfolder $${DESTDIR}/$${TARGET}.app -volname $${TARGET} $${DESTDIR}/package/$${TARGET}.dmg
QMAKE_POST_LINK += && hdiutil create /tmp/tmp.dmg -ov -volname "$${TARGET}-$${MAC_VERSION}" -fs HFS+ -srcfolder "$${DESTDIR}/"
QMAKE_POST_LINK += && hdiutil convert /tmp/tmp.dmg -format UDBZ -o $${DESTDIR}/package/$${TARGET}.dmg
QMAKE_POST_LINK += && rm /tmp/tmp.dmg
}
WindowsBuild {
QMAKE_POST_LINK += $$escape_expand(\\n) cd $$BASEDIR_WIN && $$quote("\"C:\\Program Files \(x86\)\\NSIS\\makensis.exe\"" /DINSTALLER_ICON="\"$${QGC_INSTALLER_ICON}\"" /DHEADER_BITMAP="\"$${QGC_INSTALLER_HEADER_BITMAP}\"" /DAPPNAME="\"$${QGC_APP_NAME}\"" /DEXENAME="\"$${TARGET}\"" /DORGNAME="\"$${QGC_ORG_NAME}\"" /DDESTDIR=$${DESTDIR} /NOCD "\"/XOutFile $${DESTDIR_WIN}\\$${TARGET}-installer.exe\"" "$$BASEDIR_WIN\\deploy\\qgroundcontrol_installer.nsi")
......
......@@ -11,6 +11,7 @@
import QtQuick 2.3
import QtQuick.Controls 1.2
import QGroundControl 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
......@@ -32,6 +33,8 @@ SetupPage {
QGCPalette { id: palette; colorGroupEnabled: true }
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _oldFW: !(_activeVehicle.firmwareMajorVersion > 3 || _activeVehicle.firmwareMinorVersion > 5 || _activeVehicle.firmwarePatchVersion >= 2)
property Fact _rc5Function: controller.getParameterFact(-1, "r.SERVO5_FUNCTION")
property Fact _rc6Function: controller.getParameterFact(-1, "r.SERVO6_FUNCTION")
property Fact _rc7Function: controller.getParameterFact(-1, "r.SERVO7_FUNCTION")
......@@ -42,7 +45,8 @@ SetupPage {
property Fact _rc12Function: controller.getParameterFact(-1, "r.SERVO12_FUNCTION")
property Fact _rc13Function: controller.getParameterFact(-1, "r.SERVO13_FUNCTION")
property Fact _rc14Function: controller.getParameterFact(-1, "r.SERVO14_FUNCTION")
property Fact _stepSize: controller.getParameterFact(-1, "JS_LIGHTS_STEP")
property Fact _stepSize: _oldFW ? controller.getParameterFact(-1, "JS_LIGHTS_STEP") : null // v3.5.1 and prior
property Fact _numSteps: _oldFW ? null : controller.getParameterFact(-1, "JS_LIGHTS_STEPS") // v3.5.2 and up
readonly property real _margins: ScreenTools.defaultFontPixelHeight
readonly property int _rcFunctionDisabled: 0
......@@ -88,22 +92,30 @@ SetupPage {
}
function calcCurrentStep() {
var i = 1
for(i; i <= 10; i++) {
var stepSize = (1900-1100)/i
if(_stepSize.value >= stepSize) {
_stepSize.value = stepSize;
break;
if (_oldFW) {
var i = 1
for(i; i <= 10; i++) {
var stepSize = (1900-1100)/i
if(_stepSize.value >= stepSize) {
_stepSize.value = stepSize;
break;
}
}
if (_stepSize.value < 80) {
_stepSize.value = 80;
}
lightsLoader.lightsSteps = i
} else {
lightsLoader.lightsSteps = _numSteps.value
}
if (_stepSize.value < 80) {
_stepSize.value = 80;
}
lightsLoader.lightsSteps = i
}
function calcStepSize(steps) {
_stepSize.value = (1900-1100)/steps
if (_oldFW) {
_stepSize.value = (1900-1100)/steps
} else {
_numSteps.value = steps
}
}
// Whenever any SERVO#_FUNCTION parameters chagnes we need to go looking for light output channels again
......
......@@ -12,6 +12,7 @@ import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Dialogs 1.2
import QGroundControl 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
......@@ -22,12 +23,9 @@ import QGroundControl.Controllers 1.0
SetupPage {
id: subFramePage
pageComponent: subFramePageComponent
property var _flatParamList: ListModel {
ListElement {
name: "Blue Robotics BlueROV2"
file: "Sub/bluerov2-3_5.params"
}
}
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _oldFW: !(_activeVehicle.firmwareMajorVersion > 3 || _activeVehicle.firmwareMinorVersion > 5 || _activeVehicle.firmwarePatchVersion >= 2)
APMAirframeComponentController { id: controller; factPanel: subFramePage.viewPanel }
......@@ -194,18 +192,16 @@ SetupPage {
spacing : _margins
layoutDirection: Qt.Vertical;
Repeater {
id: airframePicker
model: _flatParamList
delegate: QGCButton {
width: parent.width
text: name
onClicked : {
controller.loadParameters(file)
hideDialog()
}
QGCButton {
width: parent.width
text: "Blue Robotics BlueROV2"
property var file: _oldFW ? "Sub/bluerov2-3_5.params" : "Sub/bluerov2-3_5_2.params"
onClicked : {
console.log(_oldFW)
console.log(_activeVehicle.firmwarePatchVersion)
controller.loadParameters(file)
hideDialog()
}
}
}
......
......@@ -7,12 +7,10 @@
*
****************************************************************************/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "Fact.h"
#include "QGCMAVLink.h"
#include "QGCApplication.h"
#include "QGCCorePlugin.h"
#include <QtQml>
#include <QQmlEngine>
......@@ -50,6 +48,21 @@ Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObjec
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
}
Fact::Fact(FactMetaData* metaData, QObject* parent)
: QObject(parent)
, _name (metaData->name())
, _componentId (0)
, _rawValue (0)
, _type (metaData->type())
, _metaData (NULL)
, _sendValueChangedSignals (true)
, _deferredValueChangeSignal(false)
{
// Allow core plugin a chance to override the default value
qgcApp()->toolbox()->corePlugin()->adjustSettingMetaData(*metaData);
setMetaData(metaData, true /* setDefaultFromMetaData */);
}
Fact::Fact(const Fact& other, QObject* parent)
: QObject(parent)
{
......
......@@ -31,6 +31,10 @@ public:
Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObject* parent = NULL);
Fact(const Fact& other, QObject* parent = NULL);
/// Creates a Fact using the name and type from metaData. Also calls QGCCorePlugin::adjustSettingsMetaData allowing
/// custom builds to override the metadata.
Fact(FactMetaData* metaData, QObject* parent = NULL);
const Fact& operator=(const Fact& other);
Q_PROPERTY(int componentId READ componentId CONSTANT)
......
......@@ -46,6 +46,7 @@ const FactMetaData::AppSettingsTranslation_s FactMetaData::_rgAppSettingsTransla
{ "meters", "meters", false, UnitsSettings::DistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
{ "cm/px", "cm/px", false, UnitsSettings::DistanceUnitsMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
{ "m/s", "m/s", true, UnitsSettings::SpeedUnitsMetersPerSecond, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
{ "C", "C", false, UnitsSettings::TemperatureUnitsCelsius, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
{ "m^2", "m^2", false, UnitsSettings::AreaUnitsSquareMeters, FactMetaData::_defaultTranslator, FactMetaData::_defaultTranslator },
{ "m", "ft", false, UnitsSettings::DistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
{ "meters", "ft", false, UnitsSettings::DistanceUnitsFeet, FactMetaData::_metersToFeet, FactMetaData::_feetToMeters },
......@@ -59,6 +60,7 @@ const FactMetaData::AppSettingsTranslation_s FactMetaData::_rgAppSettingsTransla
{ "m/s", "mph", true, UnitsSettings::SpeedUnitsMilesPerHour, FactMetaData::_metersPerSecondToMilesPerHour, FactMetaData::_milesPerHourToMetersPerSecond },
{ "m/s", "km/h", true, UnitsSettings::SpeedUnitsKilometersPerHour, FactMetaData::_metersPerSecondToKilometersPerHour, FactMetaData::_kilometersPerHourToMetersPerSecond },
{ "m/s", "kn", true, UnitsSettings::SpeedUnitsKnots, FactMetaData::_metersPerSecondToKnots, FactMetaData::_knotsToMetersPerSecond },
{ "C", "F", false, UnitsSettings::TemperatureUnitsFarenheit, FactMetaData::_celsiusToFarenheit, FactMetaData::_farenheitToCelsius },
};
const char* FactMetaData::_decimalPlacesJsonKey = "decimalPlaces";
......@@ -685,6 +687,16 @@ QVariant FactMetaData::_inchesToCentimeters(const QVariant& inches)
return QVariant(inches.toDouble() * constants.inchesToCentimeters);
}
QVariant FactMetaData::_celsiusToFarenheit(const QVariant& celsius)
{
return QVariant(celsius.toDouble() * (9.0 / 5.0) + 32);
}
QVariant FactMetaData::_farenheitToCelsius(const QVariant& farenheit)
{
return QVariant((farenheit.toDouble() - 32) * (5.0 / 9.0));
}
void FactMetaData::setRawUnits(const QString& rawUnits)
{
_rawUnits = rawUnits;
......@@ -774,9 +786,11 @@ void FactMetaData::_setAppSettingsTranslators(void)
for (size_t i=0; i<sizeof(_rgAppSettingsTranslations)/sizeof(_rgAppSettingsTranslations[0]); i++) {
const AppSettingsTranslation_s* pAppSettingsTranslation = &_rgAppSettingsTranslations[i];
if (pAppSettingsTranslation->rawUnits == _rawUnits.toLower() &&
if ((pAppSettingsTranslation->rawUnits == _rawUnits && // Temperature
(!pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == qgcApp()->toolbox()->settingsManager()->unitsSettings()->temperatureUnits()->rawValue().toUInt())) ||
(pAppSettingsTranslation->rawUnits == _rawUnits.toLower() && // Speed and Distance
((pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == qgcApp()->toolbox()->settingsManager()->unitsSettings()->speedUnits()->rawValue().toUInt()) ||
(!pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == qgcApp()->toolbox()->settingsManager()->unitsSettings()->distanceUnits()->rawValue().toUInt()))) {
(!pAppSettingsTranslation->speed && pAppSettingsTranslation->speedOrDistanceUnits == qgcApp()->toolbox()->settingsManager()->unitsSettings()->distanceUnits()->rawValue().toUInt())))) {
_cookedUnits = pAppSettingsTranslation->cookedUnits;
setTranslators(pAppSettingsTranslation->rawTranslator, pAppSettingsTranslation->cookedTranslator);
return;
......@@ -972,29 +986,58 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec
if (json.contains(_unitsJsonKey)) {
metaData->setRawUnits(json[_unitsJsonKey].toString());
}
QString defaultValueJsonKey;
#ifdef __mobile__
if (json.contains(_mobileDefaultValueJsonKey)) {
metaData->setRawDefaultValue(json[_mobileDefaultValueJsonKey].toVariant());
} else if (json.contains(_defaultValueJsonKey)) {
metaData->setRawDefaultValue(json[_defaultValueJsonKey].toVariant());
}
#else
if (json.contains(_defaultValueJsonKey)) {
metaData->setRawDefaultValue(json[_defaultValueJsonKey].toVariant());
defaultValueJsonKey = _mobileDefaultValueJsonKey;
}
#endif
if (defaultValueJsonKey.isEmpty() && json.contains(_defaultValueJsonKey)) {
defaultValueJsonKey = _defaultValueJsonKey;
}
if (!defaultValueJsonKey.isEmpty()) {
QVariant typedValue;
QString errorString;
QVariant initialValue = json[defaultValueJsonKey].toVariant();
if (metaData->convertAndValidateRaw(initialValue, true /* convertOnly */, typedValue, errorString)) {
metaData->setRawDefaultValue(typedValue);
} else {
qWarning() << "Invalid default value, name:" << metaData->name()
<< " type:" << metaData->type()
<< " value:" << initialValue
<< " error:" << errorString;
}
}
if (json.contains(_minJsonKey)) {
QVariant typedValue;
QString errorString;
metaData->convertAndValidateRaw(json[_minJsonKey].toVariant(), true /* convertOnly */, typedValue, errorString);
metaData->setRawMin(typedValue);
QVariant initialValue = json[_minJsonKey].toVariant();
if (metaData->convertAndValidateRaw(initialValue, true /* convertOnly */, typedValue, errorString)) {
metaData->setRawMin(typedValue);
} else {
qWarning() << "Invalid min value, name:" << metaData->name()
<< " type:" << metaData->type()
<< " value:" << initialValue
<< " error:" << errorString;
}
}
if (json.contains(_maxJsonKey)) {
QVariant typedValue;
QString errorString;
metaData->convertAndValidateRaw(json[_maxJsonKey].toVariant(), true /* convertOnly */, typedValue, errorString);
metaData->setRawMax(typedValue);
QVariant initialValue = json[_maxJsonKey].toVariant();
if (metaData->convertAndValidateRaw(initialValue, true /* convertOnly */, typedValue, errorString)) {
metaData->setRawMax(typedValue);
} else {
qWarning() << "Invalid max value, name:" << metaData->name()
<< " type:" << metaData->type()
<< " value:" << initialValue
<< " error:" << errorString;
}
}
if (json.contains(_hasControlJsonKey)) {
metaData->setHasControl(json[_hasControlJsonKey].toBool());
} else {
......
......@@ -193,6 +193,8 @@ private:
static QVariant _normToPercent(const QVariant& normalized);
static QVariant _centimetersToInches(const QVariant& centimeters);
static QVariant _inchesToCentimeters(const QVariant& inches);
static QVariant _celsiusToFarenheit(const QVariant& celsius);
static QVariant _farenheitToCelsius(const QVariant& farenheit);
struct AppSettingsTranslation_s {
const char* rawUnits;
......
......@@ -1093,9 +1093,9 @@ This parameter controls the time constant of the decay</short_desc>
</parameter>
<parameter default="1" name="EKF2_AID_MASK" type="INT32">
<short_desc>Integer bitmask controlling data fusion and aiding methods</short_desc>
<long_desc>Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion 5 : Set to true to enable multi-rotor drag specific force fusion</long_desc>
<long_desc>Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion 5 : Set to true to enable multi-rotor drag specific force fusion 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used</long_desc>
<min>0</min>
<max>63</max>
<max>127</max>
<reboot_required>true</reboot_required>
<scope>modules/ekf2</scope>
<bitmask>
......@@ -1105,6 +1105,7 @@ This parameter controls the time constant of the decay</short_desc>
<bit index="3">vision position fusion</bit>
<bit index="4">vision yaw fusion</bit>
<bit index="5">multi-rotor drag fusion</bit>
<bit index="6">rotate external vision</bit>
</bitmask>
</parameter>
<parameter default="0.1" name="EKF2_ANGERR_INIT" type="FLOAT">
......@@ -1184,6 +1185,14 @@ This should be adjusted to minimise variance of the Y-axis drag specific force i
<decimal>1</decimal>
<scope>modules/ekf2</scope>
</parameter>
<parameter default="5.0" name="EKF2_BETA_GATE" type="FLOAT">
<short_desc>Gate size for synthetic sideslip fusion</short_desc>
<long_desc>Sets the number of standard deviations used by the innovation consistency test.</long_desc>
<min>1.0</min>
<unit>SD</unit>
<decimal>1</decimal>
<scope>modules/ekf2</scope>
</parameter>
<parameter default="0.3" name="EKF2_BETA_NOISE" type="FLOAT">
<short_desc>Noise for synthetic sideslip fusion</short_desc>
<min>0.1</min>
......@@ -3124,7 +3133,7 @@ but also ignore less noise</short_desc>
<decimal>1</decimal>
<scope>modules/land_detector</scope>
</parameter>
<parameter default="4.0" name="LNDFW_VELI_MAX" type="FLOAT">
<parameter default="8.0" name="LNDFW_VELI_MAX" type="FLOAT">
<short_desc>Fixedwing max short-term velocity</short_desc>
<long_desc>Maximum velocity integral in flight direction allowed in the landed state (m/s)</long_desc>
<min>2</min>
......
......@@ -4,9 +4,9 @@ FlightDisplayView 1.0 FlightDisplayView.qml
FlightDisplayViewMap 1.0 FlightDisplayViewMap.qml
FlightDisplayViewVideo 1.0 FlightDisplayViewVideo.qml
FlightDisplayViewWidgets 1.0 FlightDisplayViewWidgets.qml
GuidedActionsConfirm 1.0 GuidedActionsConfirm.qml
GuidedActionConfirm 1.0 GuidedActionConfirm.qml
GuidedActionsController 1.0 GuidedActionsController.qml
GuidedActionsList 1.0 GuidedActionsList.qml
GuidedActionList 1.0 GuidedActionList.qml
GuidedAltitudeSlider 1.0 GuidedAltitudeSlider.qml
MultiVehicleList 1.0 MultiVehicleList.qml
......@@ -38,29 +38,26 @@ void RTCMMavlink::RTCMDataUpdate(QByteArray message)
if (message.size() < maxMessageLength) {
mavlinkRtcmData.len = message.size();
mavlinkRtcmData.flags = (_sequenceId & 0x1F) << 3;
memcpy(&mavlinkRtcmData.data, message.data(), message.size());
sendMessageToVehicle(mavlinkRtcmData);
} else {
// We need to fragment
static uint8_t sequenceId = 0; // Sequence id is used to indicate that the individual fragements belong to the same set
uint8_t fragmentId = 0; // Fragment id indicates the fragment within a set
int start = 0;
while (start < message.size()) {
int length = std::min(message.size() - start, maxMessageLength);
mavlinkRtcmData.flags = 1; // LSB set indicates message is fragmented
mavlinkRtcmData.flags |= fragmentId++ << 1; // Next 2 bits are fragment id
mavlinkRtcmData.flags |= sequenceId++ << 3; // Next 5 bits are sequence id
mavlinkRtcmData.flags |= (_sequenceId & 0x1F) << 3; // Next 5 bits are sequence id
mavlinkRtcmData.len = length;
memcpy(&mavlinkRtcmData.data, message.data() + start, length);
sendMessageToVehicle(mavlinkRtcmData);
start += length;
}
if (sequenceId == 0x1F) {
sequenceId = 0;
}
}
++_sequenceId;
}
void RTCMMavlink::sendMessageToVehicle(const mavlink_gps_rtcm_data_t& msg)
......
......@@ -36,4 +36,5 @@ private:
QGCToolbox& _toolbox;
QElapsedTimer _bandwidthTimer;
int _bandwidthByteCounter = 0;
uint8_t _sequenceId = 0;
};
......@@ -21,14 +21,14 @@ const char* CameraCalc::_frontalOverlapName = "FrontalOverlap";
const char* CameraCalc::_sideOverlapName = "SideOverlap";
const char* CameraCalc::_adjustedFootprintFrontalName = "AdjustedFootprintFrontal";
const char* CameraCalc::_adjustedFootprintSideName = "AdjustedFootprintSide";
const char* CameraCalc::_jsonCameraNameKey = "CameraName";
const char* CameraCalc::_jsonCameraSpecTypeKey = "CameraSpecType";
const char* CameraCalc::_jsonKnownCameraNameKey = "CameraName";
CameraCalc::CameraCalc(Vehicle* vehicle, QObject* parent)
: CameraSpec (parent)
, _vehicle (vehicle)
, _dirty (false)
, _cameraSpecType (CameraSpecNone)
, _cameraName (manualCameraName())
, _disableRecalc (false)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CameraCalc.FactMetaData.json"), this))
, _valueSetIsDistanceFact (0, _valueSetIsDistanceName, FactMetaData::valueTypeBool)
......@@ -52,9 +52,7 @@ CameraCalc::CameraCalc(Vehicle* vehicle, QObject* parent)
_adjustedFootprintSideFact.setMetaData (_metaDataMap[_adjustedFootprintSideName], true);
_adjustedFootprintFrontalFact.setMetaData (_metaDataMap[_adjustedFootprintFrontalName], true);
connect(this, &CameraCalc::knownCameraNameChanged, this, &CameraCalc::_knownCameraNameChanged);
connect(this, &CameraCalc::cameraSpecTypeChanged, this, &CameraCalc::_recalcTriggerDistance);
connect(this, &CameraCalc::cameraNameChanged, this, &CameraCalc::_recalcTriggerDistance);
connect(&_distanceToSurfaceFact, &Fact::rawValueChanged, this, &CameraCalc::_recalcTriggerDistance);
connect(&_imageDensityFact, &Fact::rawValueChanged, this, &CameraCalc::_recalcTriggerDistance);
......@@ -73,59 +71,57 @@ void CameraCalc::setDirty(bool dirty)
}
}
void CameraCalc::setCameraSpecType(CameraSpecType cameraSpecType)
{
if (cameraSpecType != _cameraSpecType) {
_cameraSpecType = cameraSpecType;
emit cameraSpecTypeChanged(_cameraSpecType);
}
}
void CameraCalc::setKnownCameraName(QString knownCameraName)
{
if (knownCameraName != _knownCameraName) {
_knownCameraName = knownCameraName;
emit knownCameraNameChanged(_knownCameraName);
}
}
void CameraCalc::_knownCameraNameChanged(QString knownCameraName)
void CameraCalc::setCameraName(QString cameraName)
{
if (_cameraSpecType == CameraSpecKnown) {
CameraMetaData* cameraMetaData = NULL;
// Update camera specs to new camera
for (int cameraIndex=0; cameraIndex<_knownCameraList.count(); cameraIndex++) {
cameraMetaData = _knownCameraList[cameraIndex].value<CameraMetaData*>();
if (knownCameraName == cameraMetaData->name()) {
break;
if (cameraName != _cameraName) {
_cameraName = cameraName;
if (_cameraName == manualCameraName() || _cameraName == customCameraName()) {
// These values are unknown for these types
fixedOrientation()->setRawValue(false);
minTriggerInterval()->setRawValue(0);
if (_cameraName == manualCameraName()) {
valueSetIsDistance()->setRawValue(false);
}
}
_disableRecalc = true;
if (cameraMetaData) {
sensorWidth()->setRawValue (cameraMetaData->sensorWidth());
sensorHeight()->setRawValue (cameraMetaData->sensorHeight());
imageWidth()->setRawValue (cameraMetaData->imageWidth());
imageHeight()->setRawValue (cameraMetaData->imageHeight());
focalLength()->setRawValue (cameraMetaData->focalLength());
landscape()->setRawValue (cameraMetaData->landscape());
fixedOrientation()->setRawValue (cameraMetaData->fixedOrientation());
minTriggerInterval()->setRawValue (cameraMetaData->minTriggerInterval());
} else {
// We don't know this camera, switch back to custom
_cameraSpecType = CameraSpecCustom;
emit cameraSpecTypeChanged(_cameraSpecType);
// This should be a known camera name. Update camera specs to new camera
bool foundKnownCamera = false;
CameraMetaData* cameraMetaData = NULL;
for (int cameraIndex=0; cameraIndex<_knownCameraList.count(); cameraIndex++) {
cameraMetaData = _knownCameraList[cameraIndex].value<CameraMetaData*>();
if (cameraName == cameraMetaData->name()) {
foundKnownCamera = true;
break;
}
}
_disableRecalc = true;
if (foundKnownCamera) {
sensorWidth()->setRawValue (cameraMetaData->sensorWidth());
sensorHeight()->setRawValue (cameraMetaData->sensorHeight());
imageWidth()->setRawValue (cameraMetaData->imageWidth());
imageHeight()->setRawValue (cameraMetaData->imageHeight());
focalLength()->setRawValue (cameraMetaData->focalLength());
landscape()->setRawValue (cameraMetaData->landscape());
fixedOrientation()->setRawValue (cameraMetaData->fixedOrientation());
minTriggerInterval()->setRawValue (cameraMetaData->minTriggerInterval());
} else {
// We don't know this camera, switch back to custom
_cameraName = customCameraName();
fixedOrientation()->setRawValue(false);
minTriggerInterval()->setRawValue(0);
}
_disableRecalc = false;
}
_disableRecalc = false;
_recalcTriggerDistance();
emit cameraNameChanged(_cameraName);
}
}
void CameraCalc::_recalcTriggerDistance(void)
{
if (_disableRecalc || _cameraSpecType == CameraSpecNone) {
if (_disableRecalc || _cameraName == manualCameraName()) {
return;
}
......@@ -168,14 +164,14 @@ void CameraCalc::_recalcTriggerDistance(void)
void CameraCalc::save(QJsonObject& json) const
{
json[_jsonCameraSpecTypeKey] = (int)_cameraSpecType;
json[JsonHelper::jsonVersionKey] = 1;
json[_adjustedFootprintSideName] = _adjustedFootprintSideFact.rawValue().toDouble();
json[_adjustedFootprintFrontalName] = _adjustedFootprintFrontalFact.rawValue().toDouble();
json[_distanceToSurfaceName] = _distanceToSurfaceFact.rawValue().toDouble();
json[_jsonCameraNameKey] = _cameraName;
if (_cameraSpecType != CameraSpecNone) {
if (_cameraName != manualCameraName()) {
CameraSpec::save(json);
json[_jsonKnownCameraNameKey] = _knownCameraName;
json[_valueSetIsDistanceName] = _valueSetIsDistanceFact.rawValue().toBool();
json[_imageDensityName] = _imageDensityFact.rawValue().toDouble();
json[_frontalOverlapName] = _frontalOverlapFact.rawValue().toDouble();
......@@ -184,55 +180,65 @@ void CameraCalc::save(QJsonObject& json) const
}
bool CameraCalc::load(const QJsonObject& json, QString& errorString)
{
{
QJsonObject v1Json = json;
if (!v1Json.contains(JsonHelper::jsonVersionKey)) {
// Version 0 file. Differences from Version 1 for conversion:
// JsonHelper::jsonVersionKey not stored
// _jsonCameraSpecTypeKey stores CameraSpecType
// _jsonCameraNameKey only set if CameraSpecKnown
int cameraSpec = v1Json[_jsonCameraSpecTypeKey].toInt(CameraSpecNone);
if (cameraSpec == CameraSpecCustom) {
v1Json[_jsonCameraNameKey] = customCameraName();
} else if (cameraSpec == CameraSpecNone) {
v1Json[_jsonCameraNameKey] = manualCameraName();
}
v1Json.remove(_jsonCameraSpecTypeKey);
v1Json[JsonHelper::jsonVersionKey] = 1;
}
int version = v1Json[JsonHelper::jsonVersionKey].toInt();
if (version != 1) {
errorString = tr("CameraCalc section version %1 not supported").arg(version);
return false;
}
QList<JsonHelper::KeyValidateInfo> keyInfoList1 = {
{ _jsonCameraSpecTypeKey, QJsonValue::Double, true },
{ _jsonCameraNameKey, QJsonValue::String, true },
{ _adjustedFootprintSideName, QJsonValue::Double, true },
{ _adjustedFootprintFrontalName, QJsonValue::Double, true },
{ _distanceToSurfaceName, QJsonValue::Double, true },
};
if (!JsonHelper::validateKeys(json, keyInfoList1, errorString)) {
return false;
}
int cameraSpecType = json[_jsonCameraSpecTypeKey].toInt();
switch (cameraSpecType) {
case CameraSpecNone:
case CameraSpecCustom:
case CameraSpecKnown:
break;
default:
errorString = tr("Unsupported CameraSpecType %d").arg(cameraSpecType);
if (!JsonHelper::validateKeys(v1Json, keyInfoList1, errorString)) {
return false;
}
_disableRecalc = true;
setCameraSpecType((CameraSpecType)cameraSpecType);
_adjustedFootprintSideFact.setRawValue (json[_adjustedFootprintSideName].toDouble());
_adjustedFootprintFrontalFact.setRawValue (json[_adjustedFootprintFrontalName].toDouble());
_distanceToSurfaceFact.setRawValue (json[_distanceToSurfaceName].toDouble());
setCameraName(v1Json[_jsonCameraNameKey].toString());
_adjustedFootprintSideFact.setRawValue (v1Json[_adjustedFootprintSideName].toDouble());
_adjustedFootprintFrontalFact.setRawValue (v1Json[_adjustedFootprintFrontalName].toDouble());
_distanceToSurfaceFact.setRawValue (v1Json[_distanceToSurfaceName].toDouble());
if (_cameraSpecType != CameraSpecNone) {
if (_cameraName != manualCameraName()) {
QList<JsonHelper::KeyValidateInfo> keyInfoList2 = {
{ _jsonKnownCameraNameKey, QJsonValue::String, true },
{ _valueSetIsDistanceName, QJsonValue::Bool, true },
{ _imageDensityName, QJsonValue::Double, true },
{ _frontalOverlapName, QJsonValue::Double, true },
{ _sideOverlapName, QJsonValue::Double, true },
};
if (!JsonHelper::validateKeys(json, keyInfoList2, errorString)) {
if (!JsonHelper::validateKeys(v1Json, keyInfoList2, errorString)) {
return false;
_disableRecalc = false;
}
setKnownCameraName(json[_jsonKnownCameraNameKey].toString());
_valueSetIsDistanceFact.setRawValue (json[_valueSetIsDistanceName].toBool());
_imageDensityFact.setRawValue (json[_imageDensityName].toDouble());
_frontalOverlapFact.setRawValue (json[_frontalOverlapName].toDouble());
_sideOverlapFact.setRawValue (json[_sideOverlapName].toDouble());
_valueSetIsDistanceFact.setRawValue (v1Json[_valueSetIsDistanceName].toBool());
_imageDensityFact.setRawValue (v1Json[_imageDensityName].toDouble());
_frontalOverlapFact.setRawValue (v1Json[_frontalOverlapName].toDouble());
_sideOverlapFact.setRawValue (v1Json[_sideOverlapName].toDouble());
if (!CameraSpec::load(json, errorString)) {
if (!CameraSpec::load(v1Json, errorString)) {
return false;
}
}
......@@ -241,3 +247,13 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString)
return true;
}
QString CameraCalc::customCameraName(void)
{
return tr("Custom Camera");
}
QString CameraCalc::manualCameraName(void)
{
return tr("Manual (no camera specs)");
}
......@@ -20,32 +20,25 @@ class CameraCalc : public CameraSpec
public:
CameraCalc(Vehicle* vehicle, QObject* parent = NULL);
Q_ENUMS(CameraSpecType)
Q_PROPERTY(CameraSpecType cameraSpecType READ cameraSpecType WRITE setCameraSpecType NOTIFY cameraSpecTypeChanged)
Q_PROPERTY(QString knownCameraName READ knownCameraName WRITE setKnownCameraName NOTIFY knownCameraNameChanged)
Q_PROPERTY(Fact* valueSetIsDistance READ valueSetIsDistance CONSTANT) ///< true: distance specified, resolution calculated
Q_PROPERTY(Fact* distanceToSurface READ distanceToSurface CONSTANT) ///< Distance to surface for image foot print calculation
Q_PROPERTY(Fact* imageDensity READ imageDensity CONSTANT) ///< Image density on surface (cm/px)
Q_PROPERTY(Fact* frontalOverlap READ frontalOverlap CONSTANT)
Q_PROPERTY(Fact* sideOverlap READ sideOverlap CONSTANT)
Q_PROPERTY(Fact* adjustedFootprintSide READ adjustedFootprintSide CONSTANT) ///< Side footprint adjusted down for overlap
Q_PROPERTY(Fact* adjustedFootprintFrontal READ adjustedFootprintFrontal CONSTANT) ///< Frontal footprint adjusted down for overlap
Q_PROPERTY(QString cameraName READ cameraName WRITE setCameraName NOTIFY cameraNameChanged)
Q_PROPERTY(QString customCameraName READ customCameraName CONSTANT) // Camera name for custom camera setting
Q_PROPERTY(QString manualCameraName READ manualCameraName CONSTANT) // Camera name for manual camera setting
Q_PROPERTY(Fact* valueSetIsDistance READ valueSetIsDistance CONSTANT) ///< true: distance specified, resolution calculated
Q_PROPERTY(Fact* distanceToSurface READ distanceToSurface CONSTANT) ///< Distance to surface for image foot print calculation
Q_PROPERTY(Fact* imageDensity READ imageDensity CONSTANT) ///< Image density on surface (cm/px)
Q_PROPERTY(Fact* frontalOverlap READ frontalOverlap CONSTANT)
Q_PROPERTY(Fact* sideOverlap READ sideOverlap CONSTANT)
Q_PROPERTY(Fact* adjustedFootprintSide READ adjustedFootprintSide CONSTANT) ///< Side footprint adjusted down for overlap
Q_PROPERTY(Fact* adjustedFootprintFrontal READ adjustedFootprintFrontal CONSTANT) ///< Frontal footprint adjusted down for overlap
// The following values are calculated from the camera properties
Q_PROPERTY(double imageFootprintSide READ imageFootprintSide NOTIFY imageFootprintSideChanged) ///< Size of image size side in meters
Q_PROPERTY(double imageFootprintFrontal READ imageFootprintFrontal NOTIFY imageFootprintFrontalChanged) ///< Size of image size frontal in meters
Q_PROPERTY(double imageFootprintSide READ imageFootprintSide NOTIFY imageFootprintSideChanged) ///< Size of image size side in meters
Q_PROPERTY(double imageFootprintFrontal READ imageFootprintFrontal NOTIFY imageFootprintFrontalChanged) ///< Size of image size frontal in meters
enum CameraSpecType {
CameraSpecNone,
CameraSpecCustom,
CameraSpecKnown
};
CameraSpecType cameraSpecType(void) const { return _cameraSpecType; }
QString knownCameraName(void) const { return _knownCameraName; }
void setCameraSpecType(CameraSpecType cameraSpecType);
void setKnownCameraName(QString knownCameraName);
static QString customCameraName(void);
static QString manualCameraName(void);
QString cameraName(void) const { return _cameraName; }
void setCameraName(QString cameraName);
Fact* valueSetIsDistance (void) { return &_valueSetIsDistanceFact; }
Fact* distanceToSurface (void) { return &_distanceToSurfaceFact; }
......@@ -65,21 +58,18 @@ public:
bool load(const QJsonObject& json, QString& errorString);
signals:
void cameraSpecTypeChanged (CameraSpecType cameraSpecType);
void knownCameraNameChanged (QString knownCameraName);
void cameraNameChanged (QString cameraName);
void dirtyChanged (bool dirty);
void imageFootprintSideChanged (double imageFootprintSide);
void imageFootprintFrontalChanged (double imageFootprintFrontal);
private slots:
void _knownCameraNameChanged(QString knownCameraName);
void _recalcTriggerDistance(void);
private:
Vehicle* _vehicle;
bool _dirty;
CameraSpecType _cameraSpecType;
QString _knownCameraName;
QString _cameraName;
bool _disableRecalc;
QMap<QString, FactMetaData*> _metaDataMap;
......@@ -104,6 +94,15 @@ private:
static const char* _sideOverlapName;
static const char* _adjustedFootprintSideName;
static const char* _adjustedFootprintFrontalName;
static const char* _jsonCameraNameKey;
// The following are deprecated usage and only included in order to convert older formats
enum CameraSpecType {
CameraSpecNone,
CameraSpecCustom,
CameraSpecKnown
};
static const char* _jsonCameraSpecTypeKey;
static const char* _jsonKnownCameraNameKey;
};
[
{
"name": "Landing dist",
"name": "LandingDistance",
"shortDescription": "Distance between landing and loiter points.",
"type": "double",
"units": "m",
......@@ -9,7 +9,7 @@
"defaultValue": 300.0
},
{
"name": "Landing heading",
"name": "LandingHeading",
"shortDescription": "Heading from loiter point to land point.",
"type": "double",
"units": "deg",
......@@ -19,7 +19,7 @@
"defaultValue": 270.0
},
{
"name": "Loiter altitude",
"name": "LoiterAltitude",
"shortDescription": "Aircraft will proceed to the loiter point and loiter until it reaches this altitude. Once altitude is reached the aircraft will proceed to land.",
"type": "double",
"units": "m",
......@@ -27,7 +27,7 @@
"defaultValue": 40.0
},
{
"name": "Loiter radius",
"name": "LoiterRadius",
"shortDescription": "Loiter radius.",
"type": "double",
"decimalPlaces": 1,
......@@ -36,7 +36,7 @@
"defaultValue": 75.0
},
{
"name": "Landing altitude",
"name": "LandingAltitude",
"shortDescription": "Altitude for landing point.",
"type": "double",
"units": "m",
......@@ -44,7 +44,7 @@
"defaultValue": 0.0
},
{
"name": "Descent rate",
"name": "DescentRate",
"shortDescription": "Descent rate between landing and loiter altitude.",
"type": "double",
"units": "%",
......
......@@ -20,12 +20,12 @@ QGC_LOGGING_CATEGORY(FixedWingLandingComplexItemLog, "FixedWingLandingComplexIte
const char* FixedWingLandingComplexItem::jsonComplexItemTypeValue = "fwLandingPattern";
const char* FixedWingLandingComplexItem::_loiterToLandDistanceName = "Landing dist";
const char* FixedWingLandingComplexItem::_landingHeadingName = "Landing heading";
const char* FixedWingLandingComplexItem::_loiterAltitudeName = "Loiter altitude";
const char* FixedWingLandingComplexItem::_loiterRadiusName = "Loiter radius";
const char* FixedWingLandingComplexItem::_landingAltitudeName = "Landing altitude";
const char* FixedWingLandingComplexItem::_fallRateName = "Descent rate";
const char* FixedWingLandingComplexItem::loiterToLandDistanceName = "LandingDistance";
const char* FixedWingLandingComplexItem::landingHeadingName = "LandingHeading";
const char* FixedWingLandingComplexItem::loiterAltitudeName = "LoiterAltitude";
const char* FixedWingLandingComplexItem::loiterRadiusName = "LoiterRadius";
const char* FixedWingLandingComplexItem::landingAltitudeName = "LandingAltitude";
const char* FixedWingLandingComplexItem::fallRateName = "DescentRate";
const char* FixedWingLandingComplexItem::_jsonLoiterCoordinateKey = "loiterCoordinate";
const char* FixedWingLandingComplexItem::_jsonLoiterRadiusKey = "loiterRadius";
......@@ -35,44 +35,25 @@ const char* FixedWingLandingComplexItem::_jsonLandingCoordinateKey = "lan
const char* FixedWingLandingComplexItem::_jsonLandingAltitudeRelativeKey = "landAltitudeRelative";
const char* FixedWingLandingComplexItem::_jsonFallRateKey = "fallRate";
QMap<QString, FactMetaData*> FixedWingLandingComplexItem::_metaDataMap;
FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, QObject* parent)
: ComplexMissionItem(vehicle, parent)
, _sequenceNumber(0)
, _dirty(false)
, _landingCoordSet(false)
, _ignoreRecalcSignals(false)
, _landingDistanceFact (0, _loiterToLandDistanceName, FactMetaData::valueTypeDouble)
, _loiterAltitudeFact (0, _loiterAltitudeName, FactMetaData::valueTypeDouble)
, _loiterRadiusFact (0, _loiterRadiusName, FactMetaData::valueTypeDouble)
, _landingHeadingFact (0, _landingHeadingName, FactMetaData::valueTypeDouble)
, _landingAltitudeFact (0, _landingAltitudeName, FactMetaData::valueTypeDouble)
, _fallRateFact (0, _fallRateName, FactMetaData::valueTypeDouble)
, _loiterClockwise(true)
, _loiterAltitudeRelative(true)
, _landingAltitudeRelative(true)
: ComplexMissionItem (vehicle, parent)
, _sequenceNumber (0)
, _dirty (false)
, _landingCoordSet (false)
, _ignoreRecalcSignals (false)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), this))
, _landingDistanceFact (_metaDataMap[loiterToLandDistanceName])
, _loiterAltitudeFact (_metaDataMap[loiterAltitudeName])
, _loiterRadiusFact (_metaDataMap[loiterRadiusName])
, _landingHeadingFact (_metaDataMap[landingHeadingName])
, _landingAltitudeFact (_metaDataMap[landingAltitudeName])
, _fallRateFact (_metaDataMap[fallRateName])
, _loiterClockwise (true)
, _loiterAltitudeRelative (true)
, _landingAltitudeRelative (true)
{
_editorQml = "qrc:/qml/FWLandingPatternEditor.qml";
if (_metaDataMap.isEmpty()) {
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), NULL /* metaDataParent */);
}
_landingDistanceFact.setMetaData (_metaDataMap[_loiterToLandDistanceName]);
_loiterAltitudeFact.setMetaData (_metaDataMap[_loiterAltitudeName]);
_loiterRadiusFact.setMetaData (_metaDataMap[_loiterRadiusName]);
_landingHeadingFact.setMetaData (_metaDataMap[_landingHeadingName]);
_landingAltitudeFact.setMetaData (_metaDataMap[_landingAltitudeName]);
_fallRateFact.setMetaData (_metaDataMap[_fallRateName]);
_landingDistanceFact.setRawValue (_landingDistanceFact.rawDefaultValue());
_loiterAltitudeFact.setRawValue (_loiterAltitudeFact.rawDefaultValue());
_loiterRadiusFact.setRawValue (_loiterRadiusFact.rawDefaultValue());
_landingHeadingFact.setRawValue (_landingHeadingFact.rawDefaultValue());
_landingAltitudeFact.setRawValue (_landingAltitudeFact.rawDefaultValue());
_fallRateFact.setRawValue (_fallRateFact.rawDefaultValue());
connect(&_loiterAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_updateLoiterCoodinateAltitudeFromFact);
connect(&_landingAltitudeFact, &Fact::valueChanged, this, &FixedWingLandingComplexItem::_updateLandingCoodinateAltitudeFromFact);
......
......@@ -92,6 +92,13 @@ public:
static const char* jsonComplexItemTypeValue;
static const char* loiterToLandDistanceName;
static const char* loiterAltitudeName;
static const char* loiterRadiusName;
static const char* landingHeadingName;
static const char* landingAltitudeName;
static const char* fallRateName;
signals:
void loiterCoordinateChanged (QGeoCoordinate coordinate);
void loiterTangentCoordinateChanged (QGeoCoordinate coordinate);
......@@ -122,6 +129,8 @@ private:
bool _landingCoordSet;
bool _ignoreRecalcSignals;
QMap<QString, FactMetaData*> _metaDataMap;
Fact _landingDistanceFact;
Fact _loiterAltitudeFact;
Fact _loiterRadiusFact;
......@@ -133,15 +142,6 @@ private:
bool _loiterAltitudeRelative;
bool _landingAltitudeRelative;
static QMap<QString, FactMetaData*> _metaDataMap;
static const char* _loiterToLandDistanceName;
static const char* _loiterAltitudeName;
static const char* _loiterRadiusName;
static const char* _landingHeadingName;
static const char* _landingAltitudeName;
static const char* _fallRateName;
static const char* _jsonLoiterCoordinateKey;
static const char* _jsonLoiterRadiusKey;
static const char* _jsonLoiterClockwiseKey;
......
......@@ -125,7 +125,7 @@ public:
bool loadTextFile(QFile& file, QString& errorString);
// Overrides from PlanElementController
bool supported (void) const final { return true; };
bool supported (void) const final { return true; }
void start (bool editMode) final;
void save (QJsonObject& json) final;
bool load (const QJsonObject& json, QString& errorString) final;
......
......@@ -588,7 +588,7 @@ void PlanManager::_handleMissionAck(const mavlink_message_t& message)
switch (savedExpectedAck) {
case AckNone:
// State machine is idle. Vehicle is confused.
_sendError(VehicleError, tr("Vehicle sent unexpected MISSION_ACK message, error: %1").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
qCDebug(PlanManagerLog) << QStringLiteral("Vehicle sent unexpected MISSION_ACK message, error: %1").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type));
break;
case AckMissionCount:
// MISSION_COUNT message expected
......
......@@ -273,7 +273,7 @@ void PlanMasterController::sendToVehicle(void)
void PlanMasterController::loadFromFile(const QString& filename)
{
QString errorString;
QString errorMessage = tr("Error reading Plan file (%1). %2").arg(filename).arg("%1");
QString errorMessage = tr("Error loading Plan file (%1). %2").arg(filename).arg("%1");
if (filename.isEmpty()) {
return;
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment