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

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;
};
This diff is collapsed.
......@@ -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;
......
......@@ -148,10 +148,6 @@ Item {
setCircleRadius(center, radius)
}
function loadKMLFile() {
mapPolygon.loadKMLFile("/Users/Don/Downloads/polygon.kml")
}
onInteractiveChanged: {
if (interactive) {
addHandles()
......@@ -418,7 +414,7 @@ Item {
MenuItem {
text: qsTr("Set radius..." )
enabled: _circle
visible: _circle
onTriggered: radiusDialog.visible = true
}
......
......@@ -87,7 +87,7 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_flightPathChanged);
connect(_cameraCalc.distanceToSurface(), &Fact::valueChanged, this, &StructureScanComplexItem::_rebuildFlightPolygon);
connect(&_cameraCalc, &CameraCalc::cameraSpecTypeChanged, this, &StructureScanComplexItem::_cameraSpecTypeChanged);
connect(&_cameraCalc, &CameraCalc::cameraNameChanged, this, &StructureScanComplexItem::_resetGimbal);
connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_recalcCameraShots);
connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &StructureScanComplexItem::_recalcCameraShots);
......@@ -205,12 +205,17 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
int version = complexObject[JsonHelper::jsonVersionKey].toInt();
if (version != 1) {
errorString = tr("Version %1 not supported").arg(version);
errorString = tr("%1 complex item version %2 not supported").arg(jsonComplexItemTypeValue).arg(version);
return false;
}
setSequenceNumber(sequenceNumber);
// Load CameraCalc first since it will trigger camera name change which will trounce gimbal angles
if (!_cameraCalc.load(complexObject[_jsonCameraCalcKey].toObject(), errorString)) {
return false;
}
_gimbalPitchFact.setRawValue(complexObject[_gimbalPitchFactName].toDouble());
_gimbalYawFact.setRawValue (complexObject[_gimbalYawFactName].toDouble());
_altitudeFact.setRawValue (complexObject[_altitudeFactName].toDouble());
......@@ -218,9 +223,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
_altitudeRelative = complexObject[_jsonAltitudeRelativeKey].toBool(true);
_yawVehicleToStructure = complexObject[_jsonYawVehicleToStructureKey].toBool(true);
if (!_cameraCalc.load(complexObject[_jsonCameraCalcKey].toObject(), errorString)) {
return false;
}
if (!_structurePolygon.loadFromJson(complexObject, true /* required */, errorString)) {
_structurePolygon.clear();
return false;
......@@ -455,10 +457,8 @@ void StructureScanComplexItem::_recalcCameraShots(void)
_setCameraShots(cameraShots * _layersFact.rawValue().toInt());
}
void StructureScanComplexItem::_cameraSpecTypeChanged(CameraCalc::CameraSpecType cameraSpecType)
void StructureScanComplexItem::_resetGimbal(void)
{
Q_UNUSED(cameraSpecType);
_gimbalPitchFact.setCookedValue(0);
_gimbalYawFact.setCookedValue(90);
}
......
......@@ -113,7 +113,7 @@ private slots:
void _updateCoordinateAltitudes (void);
void _rebuildFlightPolygon (void);
void _recalcCameraShots (void);
void _cameraSpecTypeChanged (CameraCalc::CameraSpecType cameraSpecType);
void _resetGimbal (void);
private:
void _setExitCoordinate(const QGeoCoordinate& coordinate);
......
......@@ -99,7 +99,7 @@ void StructureScanComplexItemTest::_initItem(void)
mapPolygon->appendVertex(vertex);
}
_structureScanItem->cameraCalc()->setCameraSpecType(CameraCalc::CameraSpecNone);
_structureScanItem->cameraCalc()->setCameraName(CameraCalc::manualCameraName());
_structureScanItem->gimbalPitch()->setCookedValue(45);
_structureScanItem->gimbalYaw()->setCookedValue(45);
_structureScanItem->layers()->setCookedValue(2);
......@@ -118,7 +118,7 @@ void StructureScanComplexItemTest::_validateItem(StructureScanComplexItem* item)
QCOMPARE(expectedVertex, actualVertex);
}
QCOMPARE((int)item->cameraCalc()->cameraSpecType(), (int)CameraCalc::CameraSpecNone);
QCOMPARE(_structureScanItem->cameraCalc()->cameraName() , CameraCalc::manualCameraName());
QCOMPARE(item->gimbalPitch()->cookedValue().toDouble(), 45.0);
QCOMPARE(item->gimbalYaw()->cookedValue().toDouble(), 45.0);
QCOMPARE(item->layers()->cookedValue().toInt(), 2);
......@@ -144,8 +144,8 @@ void StructureScanComplexItemTest::_testGimbalAngleUpdate(void)
// This sets the item to CameraCalc::CameraSpecNone and non-standard gimbal angles
_initItem();
// Switching to a camera specific setup should set gimbal angles to defaults surface scan
_structureScanItem->cameraCalc()->setCameraSpecType(CameraCalc::CameraSpecCustom);
// Switching to a camera specific setup should set gimbal angles to defaults
_structureScanItem->cameraCalc()->setCameraName(CameraCalc::customCameraName());
QCOMPARE(_structureScanItem->gimbalPitch()->cookedValue().toDouble(), 0.0);
QCOMPARE(_structureScanItem->gimbalYaw()->cookedValue().toDouble(), 90.0);
}
......
......@@ -23,7 +23,7 @@ Column {
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property int _cameraIndex: 1
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property var _cameraList: [ qsTr("Manual (no camera specs)"), qsTr("Custom Camera") ]
property var _cameraList: [ ]
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
property var _vehicleCameraList: _vehicle ? _vehicle.staticCameraList : []
......@@ -32,31 +32,18 @@ Column {
readonly property int _gridTypeCamera: 2
Component.onCompleted: {
_cameraList.push(cameraCalc.manualCameraName)
_cameraList.push(cameraCalc.customCameraName)
for (var i=0; i<_vehicle.staticCameraList.length; i++) {
_cameraList.push(_vehicle.staticCameraList[i].name)
}
gridTypeCombo.model = _cameraList
if (cameraCalc.cameraSpecType === CameraCalc.CameraSpecNone) {
gridTypeCombo.currentIndex = _gridTypeManual
var knownCameraIndex = gridTypeCombo.find(cameraCalc.cameraName)
if (knownCameraIndex != -1) {
gridTypeCombo.currentIndex = knownCameraIndex
} else {
var index = -1
for (index=0; index<_cameraList.length; index++) {
if (_cameraList[index] == cameraCalc.knownCameraName) {
break;
}
}
cameraCalc.fixedOrientation.value = false
if (index == _cameraList.length) {
gridTypeCombo.currentIndex = _gridTypeCustomCamera
} else {
gridTypeCombo.currentIndex = index
if (index != 1) {
// Specific camera is selected
var camera = _vehicleCameraList[index - _gridTypeCamera]
cameraCalc.fixedOrientation.value = camera.fixedOrientation
cameraCalc.minTriggerInterval.value = camera.minTriggerInterval
}
}
console.log("Internal error: Known camera not found", cameraCalc.cameraName)
gridTypeCombo.currentIndex = _gridTypeCustomCamera
}
}
......@@ -86,21 +73,7 @@ Column {
anchors.right: parent.right
model: _cameraList
currentIndex: -1
onActivated: {
if (index == _gridTypeManual) {
cameraCalc.cameraSpecType = CameraCalc.CameraSpecNone
cameraCalc.valueSetIsDistance.value = false
} else if (index == _gridTypeCustomCamera) {
cameraCalc.cameraSpecType = CameraCalc.CameraSpecCustom
cameraCalc.knownCameraName = gridTypeCombo.textAt(index)
cameraCalc.fixedOrientation.value = false
cameraCalc.minTriggerInterval.value = 0
} else {
cameraCalc.cameraSpecType = CameraCalc.CameraSpecKnown
cameraCalc.knownCameraName = gridTypeCombo.textAt(index)
}
}
onActivated: cameraCalc.cameraName = gridTypeCombo.textAt(index)
} // QGCComboxBox
// Camera based grid ui
......@@ -108,7 +81,7 @@ Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: cameraCalc.cameraSpecType !== CameraCalc.CameraSpecNone
visible: cameraCalc.cameraName !== cameraCalc.manualCameraName
Row {
spacing: _margin
......@@ -138,7 +111,7 @@ Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: cameraCalc.cameraSpecType === CameraCalc.CameraSpecCustom
visible: cameraCalc.cameraName === cameraCalc.customCameraName
RowLayout {
anchors.left: parent.left
......@@ -306,7 +279,7 @@ Column {
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: cameraCalc.cameraSpecType === CameraCalc.CameraSpecNone
visible: cameraCalc.cameraName === cameraCalc.manualCameraName
QGCLabel { text: distanceToSurfaceLabel }
FactTextField {
......
......@@ -52,6 +52,7 @@ Rectangle {
anchors.left: parent.left
anchors.right: parent.right
factList: [ missionItem.loiterAltitude, missionItem.loiterRadius ]
factLabels: [ qsTr("Altitude"), qsTr("Radius") ]
}
Item { width: 1; height: _spacer }
......@@ -82,14 +83,14 @@ Rectangle {
anchors.right: parent.right
columns: 2
QGCLabel { text: missionItem.landingHeading.name }
QGCLabel { text: qsTr("Heading") }
FactTextField {
Layout.fillWidth: true
fact: missionItem.landingHeading
}
QGCLabel { text: missionItem.landingAltitude.name }
QGCLabel { text: qsTr("Altitude") }
FactTextField {
Layout.fillWidth: true
......@@ -98,7 +99,7 @@ Rectangle {
QGCRadioButton {
id: useLandingDistance
text: missionItem.landingDistance.name
text: qsTr("Landing dist")
checked: !useFallRate.checked
onClicked: {
useFallRate.checked = false
......@@ -115,7 +116,7 @@ Rectangle {
QGCRadioButton {
id: useFallRate
text: missionItem.fallRate.name
text: qsTr("Descent rate")
checked: !useLandingDistance.checked
onClicked: {
useLandingDistance.checked = false
......@@ -160,19 +161,12 @@ Rectangle {
Column {
id: editorColumnNeedLandingPoint
anchors.margins: _margin
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
visible: !missionItem.landingCoordSet
spacing: ScreenTools.defaultFontPixelHeight
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
wrapMode: Text.WordWrap
font.pointSize: ScreenTools.smallFontPointSize
text: qsTr("WIP (NOT FOR REAL FLIGHT!)")
}
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
......
......@@ -92,7 +92,7 @@ Rectangle {
columnSpacing: ScreenTools.defaultFontPixelWidth / 2
rowSpacing: 0
columns: 3
enabled: missionItem.cameraCalc.cameraSpecType === CameraCalc.CameraSpecNone
enabled: missionItem.cameraCalc.cameraName === missionItem.cameraCalc.manualCameraName
Item { width: 1; height: 1 }
QGCLabel { text: qsTr("Pitch") }
......
......@@ -25,7 +25,7 @@ Item {
property bool _openForLoad: true
property real _margins: ScreenTools.defaultFontPixelHeight / 2
property bool _mobile: ScreenTools.isMobile
property bool _mobileDlg: QGroundControl.corePlugin.options.useMobileFileDialog
property var _rgExtensions
Component.onCompleted: {
......@@ -39,7 +39,7 @@ Item {
function openForLoad() {
_openForLoad = true
if (_mobile && folder.length !== 0) {
if (_mobileDlg && folder.length !== 0) {
qgcView.showDialog(mobileFileOpenDialog, title, qgcView.showDialogDefaultWidth, StandardButton.Cancel)
} else {
fullFileDialog.open()
......@@ -48,7 +48,7 @@ Item {
function openForSave() {
_openForLoad = false
if (_mobile && folder.length !== 0) {
if (_mobileDlg && folder.length !== 0) {
qgcView.showDialog(mobileFileSaveDialog, title, qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
} else {
fullFileDialog.open()
......
......@@ -50,11 +50,11 @@
#include <QtLocation/private/qgeocameracapabilities_p.h>
#include <QtLocation/private/qgeomaptype_p.h>
#if QT_VERSION < 0x050500
#if QT_VERSION < QT_VERSION_CHECK(5, 5, 0)
#include <QtLocation/private/qgeotiledmapdata_p.h>
#else
#include <QtLocation/private/qgeotiledmap_p.h>
#if QT_VERSION >= 0x050600
#if QT_VERSION >= QT_VERSION_CHECK(5, 6, 0)
#include <QtLocation/private/qgeofiletilecache_p.h>
#else
#include <QtLocation/private/qgeotilecache_p.h>
......@@ -64,7 +64,7 @@
#include <QDir>
#include <QStandardPaths>
#if QT_VERSION >= 0x050500
#if QT_VERSION >= QT_VERSION_CHECK(5, 5, 0)
//-----------------------------------------------------------------------------
QGeoTiledMapQGC::QGeoTiledMapQGC(QGeoTiledMappingManagerEngine *engine, QObject *parent)
: QGeoTiledMap(engine, parent)
......@@ -73,7 +73,9 @@ QGeoTiledMapQGC::QGeoTiledMapQGC(QGeoTiledMappingManagerEngine *engine, QObject
}
#endif
#if QT_VERSION >= 0x050900
#if QT_VERSION >= QT_VERSION_CHECK(5, 10, 0)
#define QGCGEOMAPTYPE(a,b,c,d,e,f) QGeoMapType(a,b,c,d,e,f,QByteArray("QGroundControl"), QGeoCameraCapabilities())
#elif QT_VERSION >= QT_VERSION_CHECK(5, 9, 0)
#define QGCGEOMAPTYPE(a,b,c,d,e,f) QGeoMapType(a,b,c,d,e,f,QByteArray("QGroundControl"))
#else
#define QGCGEOMAPTYPE(a,b,c,d,e,f) QGeoMapType(a,b,c,d,e,f)
......@@ -165,7 +167,7 @@ QGeoTiledMappingManagerEngineQGC::QGeoTiledMappingManagerEngineQGC(const QVarian
getQGCMapEngine()->setUserAgent(parameters.value(QStringLiteral("useragent")).toString().toLatin1());
}
#if QT_VERSION >= 0x050500
#if QT_VERSION >= QT_VERSION_CHECK(5, 5, 0)
_setCache(parameters);
#endif
......@@ -180,7 +182,7 @@ QGeoTiledMappingManagerEngineQGC::~QGeoTiledMappingManagerEngineQGC()
{
}
#if QT_VERSION < 0x050500
#if QT_VERSION < QT_VERSION_CHECK(5, 5, 0)
//-----------------------------------------------------------------------------
QGeoMapData *QGeoTiledMappingManagerEngineQGC::createMapData()
......@@ -199,7 +201,7 @@ QGeoTiledMappingManagerEngineQGC::createMap()
#endif
#if QT_VERSION >= 0x050500
#if QT_VERSION >= QT_VERSION_CHECK(5, 5, 0)
//-----------------------------------------------------------------------------
void
QGeoTiledMappingManagerEngineQGC::_setCache(const QVariantMap &parameters)
......@@ -242,7 +244,7 @@ QGeoTiledMappingManagerEngineQGC::_setCache(const QVariantMap &parameters)
if(memLimit > 1024 * 1024 * 1024)
memLimit = 1024 * 1024 * 1024;
//-- Disable Qt's disk cache (sort of)
#if QT_VERSION >= 0x050600
#if QT_VERSION >= QT_VERSION_CHECK(5, 6, 0)
QAbstractGeoTileCache *pTileCache = new QGeoFileTileCache(cacheDir);
setTileCache(pTileCache);
#else
......
......@@ -48,12 +48,12 @@
#define QGEOTILEDMAPPINGMANAGERENGINEQGC_H
#include <QtLocation/QGeoServiceProvider>
#if QT_VERSION >= 0x050500
#if QT_VERSION >= QT_VERSION_CHECK(5, 5, 0)
#include <QtLocation/private/qgeotiledmap_p.h>
#endif
#include <QtLocation/private/qgeotiledmappingmanagerengine_p.h>
#if QT_VERSION >= 0x050500
#if QT_VERSION >= QT_VERSION_CHECK(5, 5, 0)
class QGeoTiledMapQGC : public QGeoTiledMap
{
Q_OBJECT
......@@ -70,13 +70,13 @@ class QGeoTiledMappingManagerEngineQGC : public QGeoTiledMappingManagerEngine
public:
QGeoTiledMappingManagerEngineQGC(const QVariantMap &parameters, QGeoServiceProvider::Error *error, QString *errorString);
~QGeoTiledMappingManagerEngineQGC();
#if QT_VERSION < 0x050500
#if QT_VERSION < QT_VERSION_CHECK(5, 5, 0)
QGeoMapData *createMapData();
#else
QGeoMap *createMap();
#endif
private:
#if QT_VERSION >= 0x050500
#if QT_VERSION >= QT_VERSION_CHECK(5, 5, 0)
void _setCache(const QVariantMap &parameters);
#endif
};
......
......@@ -16,12 +16,14 @@ const char* UnitsSettings::unitsSettingsGroupName = "Units";
const char* UnitsSettings::distanceUnitsSettingsName = "DistanceUnits";
const char* UnitsSettings::areaUnitsSettingsName = "AreaUnits";
const char* UnitsSettings::speedUnitsSettingsName = "SpeedUnits";
const char* UnitsSettings::temperatureUnitsSettingsName = "TemperatureUnits";
UnitsSettings::UnitsSettings(QObject* parent)
: SettingsGroup(unitsSettingsGroupName, QString() /* root settings group */, parent)
, _distanceUnitsFact(NULL)
, _areaUnitsFact(NULL)
, _speedUnitsFact(NULL)
, _temperatureUnitsFact(NULL)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<UnitsSettings>("QGroundControl.SettingsManager", 1, 0, "UnitsSettings", "Reference only");
......@@ -92,3 +94,24 @@ Fact* UnitsSettings::speedUnits(void)
return _speedUnitsFact;
}
Fact* UnitsSettings::temperatureUnits(void)
{
if (!_temperatureUnitsFact) {
// Units settings can't be loaded from json since it creates an infinite loop of meta data loading.
QStringList enumStrings;
QVariantList enumValues;
enumStrings << "Celsius" << "Farenheit";
enumValues << QVariant::fromValue((uint32_t)TemperatureUnitsCelsius) << QVariant::fromValue((uint32_t)TemperatureUnitsFarenheit);
FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, this);
metaData->setName(temperatureUnitsSettingsName);
metaData->setEnumInfo(enumStrings, enumValues);
metaData->setRawDefaultValue(TemperatureUnitsCelsius);
_temperatureUnitsFact = new SettingsFact(QString() /* no settings group */, metaData, this);
}
return _temperatureUnitsFact;
}
......@@ -41,28 +41,38 @@ public:
SpeedUnitsKnots,
};
enum TemperatureUnits {
TemperatureUnitsCelsius = 0,
TemperatureUnitsFarenheit,
};
Q_ENUMS(DistanceUnits)
Q_ENUMS(AreaUnits)
Q_ENUMS(SpeedUnits)
Q_ENUMS(TemperatureUnits)
Q_PROPERTY(Fact* distanceUnits READ distanceUnits CONSTANT)
Q_PROPERTY(Fact* areaUnits READ areaUnits CONSTANT)
Q_PROPERTY(Fact* speedUnits READ speedUnits CONSTANT)
Q_PROPERTY(Fact* temperatureUnits READ temperatureUnits CONSTANT)
Fact* distanceUnits (void);
Fact* areaUnits (void);
Fact* speedUnits (void);
Fact* temperatureUnits (void);
static const char* unitsSettingsGroupName;
static const char* distanceUnitsSettingsName;
static const char* areaUnitsSettingsName;
static const char* speedUnitsSettingsName;
static const char* temperatureUnitsSettingsName;
private:
SettingsFact* _distanceUnitsFact;
SettingsFact* _areaUnitsFact;
SettingsFact* _speedUnitsFact;
SettingsFact* _temperatureUnitsFact;
};
#endif
......@@ -674,9 +674,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_SCALED_PRESSURE3:
_handleScaledPressure3(message);
break;
case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
_handleCameraFeedback(message);
break;
case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
_handleCameraImageCaptured(message);
break;
......@@ -691,11 +688,16 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
emit mavlinkSerialControl(ser.device, ser.flags, ser.timeout, ser.baudrate, QByteArray(reinterpret_cast<const char*>(ser.data), ser.count));
}
break;
// Following are ArduPilot dialect messages
// Following are ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
_handleCameraFeedback(message);
break;
case MAVLINK_MSG_ID_WIND:
_handleWind(message);
break;
#endif
}
// This must be emitted after the vehicle processes the message. This way the vehicle state is up to date when anyone else
......@@ -706,6 +708,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
}
#if !defined(NO_ARDUPILOT_DIALECT)
void Vehicle::_handleCameraFeedback(const mavlink_message_t& message)
{
mavlink_camera_feedback_t feedback;
......@@ -716,6 +719,7 @@ void Vehicle::_handleCameraFeedback(const mavlink_message_t& message)
qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx;
_cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
}
#endif
void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message)
{
......@@ -1014,6 +1018,7 @@ void Vehicle::_handleWindCov(mavlink_message_t& message)
_windFactGroup.verticalSpeed()->setRawValue(0);
}
#if !defined(NO_ARDUPILOT_DIALECT)
void Vehicle::_handleWind(mavlink_message_t& message)
{
mavlink_wind_t wind;
......@@ -1023,6 +1028,7 @@ void Vehicle::_handleWind(mavlink_message_t& message)
_windFactGroup.speed()->setRawValue(wind.speed);
_windFactGroup.verticalSpeed()->setRawValue(wind.speed_z);
}
#endif
void Vehicle::_handleSysStatus(mavlink_message_t& message)
{
......
......@@ -891,7 +891,6 @@ private:
void _handleBatteryStatus(mavlink_message_t& message);
void _handleSysStatus(mavlink_message_t& message);
void _handleWindCov(mavlink_message_t& message);
void _handleWind(mavlink_message_t& message);
void _handleVibration(mavlink_message_t& message);
void _handleExtendedSysState(mavlink_message_t& message);
void _handleCommandAck(mavlink_message_t& message);
......@@ -906,7 +905,11 @@ private:
void _handleScaledPressure(mavlink_message_t& message);
void _handleScaledPressure2(mavlink_message_t& message);
void _handleScaledPressure3(mavlink_message_t& message);
// ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
void _handleCameraFeedback(const mavlink_message_t& message);
void _handleWind(mavlink_message_t& message);
#endif
void _handleCameraImageCaptured(const mavlink_message_t& message);
void _handleADSBVehicle(const mavlink_message_t& message);
void _missionManagerError(int errorCode, const QString& errorMsg);
......
......@@ -44,6 +44,7 @@ public:
Q_PROPERTY(bool multiVehicleEnabled READ multiVehicleEnabled NOTIFY multiVehicleEnabledChanged)
Q_PROPERTY(bool showOfflineMapExport READ showOfflineMapExport NOTIFY showOfflineMapExportChanged)
Q_PROPERTY(bool showOfflineMapImport READ showOfflineMapImport NOTIFY showOfflineMapImportChanged)
Q_PROPERTY(bool useMobileFileDialog READ useMobileFileDialog CONSTANT)
/// Should QGC hide its settings menu and colapse it into one single menu (Settings and Vehicle Setup)?
/// @return true if QGC should consolidate both menus into one.
......@@ -80,9 +81,11 @@ public:
#if defined(__mobile__)
virtual bool showOfflineMapExport () const { return false; }
virtual bool showOfflineMapImport () const { return false; }
virtual bool useMobileFileDialog () const { return true;}
#else
virtual bool showOfflineMapExport () const { return true; }
virtual bool showOfflineMapImport () const { return true; }
virtual bool useMobileFileDialog () const { return false;}
#endif
/// If returned QString in non-empty it means that firmware upgrade will run in a mode which only
......
......@@ -883,18 +883,21 @@ void MockLink::_respondWithAutopilotVersion(void)
uint8_t customVersion[8] = { };
uint32_t flightVersion = 0;
#if !defined(NO_ARDUPILOT_DIALECT)
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
flightVersion |= 3 << (8*3);
flightVersion |= 5 << (8*2);
flightVersion |= 0 << (8*1);
flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
} else if (_firmwareType == MAV_AUTOPILOT_PX4) {
#endif
flightVersion |= 1 << (8*3);
flightVersion |= 4 << (8*2);
flightVersion |= 1 << (8*1);
flightVersion |= FIRMWARE_VERSION_TYPE_DEV << (8*0);
#if !defined(NO_ARDUPILOT_DIALECT)
}
#endif
mavlink_msg_autopilot_version_pack_chan(_vehicleSystemId,
_vehicleComponentId,
_mavlinkChannel,
......@@ -909,7 +912,12 @@ void MockLink::_respondWithAutopilotVersion(void)
(uint8_t *)&customVersion, // os_custom_version,
0, // vendor_id,
0, // product_id,
0); // uid
0 // uid
#if defined(NO_ARDUPILOT_DIALECT)
//-- Once the MAVLink module is updated, this should show up. In the mean time, it's disabled.
,0 // uid2
#endif
);
respondWithMavlinkMessage(msg);
}
......
......@@ -88,9 +88,9 @@ QGCView {
Repeater {
id: unitsRepeater
model: [ QGroundControl.settingsManager.unitsSettings.distanceUnits, QGroundControl.settingsManager.unitsSettings.areaUnits, QGroundControl.settingsManager.unitsSettings.speedUnits ]
model: [ QGroundControl.settingsManager.unitsSettings.distanceUnits, QGroundControl.settingsManager.unitsSettings.areaUnits, QGroundControl.settingsManager.unitsSettings.speedUnits, QGroundControl.settingsManager.unitsSettings.temperatureUnits ]
property var names: [ qsTr("Distance:"), qsTr("Area:"), qsTr("Speed:") ]
property var names: [ qsTr("Distance:"), qsTr("Area:"), qsTr("Speed:"), qsTr("Temperature:") ]
Row {
spacing: ScreenTools.defaultFontPixelWidth
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment