Commit 06272ff6 authored by Gus Grubba's avatar Gus Grubba

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

# Conflicts:
#	libs/mavlink/include/mavlink/v2.0
#	src/QmlControls/QmlObjectListModel.h
parents ab0f772c 9b9b9d74
......@@ -41,7 +41,7 @@ You **need to install Qt as described below** instead of using pre-built package
* Windows: Make sure to install VS 2015 32 bit package.
###### Install additional packages:
* Ubuntu: sudo apt-get install speech-dispatcher libudev-dev libsdl2-dev libgstreamer1.0-0 gstreamer1.0-plugins-base libgstreamer-plugins-base1.0-dev gstreamer1.0*
* Ubuntu: sudo apt-get install speech-dispatcher libudev-dev libsdl2-dev
* Fedora: sudo dnf install speech-dispatcher SDL2-devel SDL2 systemd-devel
* Arch Linux: pacman -Sy speech-dispatcher
* Windows: [USB Driver](http://www.pixhawk.org/firmware/downloads) to connect to Pixhawk/PX4Flow/3DR Radio
......
......@@ -346,6 +346,7 @@ INCLUDEPATH += \
src/QtLocationPlugin \
src/QtLocationPlugin/QMLControl \
src/Settings \
src/Terrain \
src/VehicleSetup \
src/ViewWidgets \
src/Audio \
......@@ -587,7 +588,7 @@ HEADERS += \
src/Settings/SettingsManager.h \
src/Settings/UnitsSettings.h \
src/Settings/VideoSettings.h \
src/Terrain.h \
src/Terrain/TerrainQuery.h \
src/Vehicle/MAVLinkLogManager.h \
src/VehicleSetup/JoystickConfigController.h \
src/comm/LinkConfiguration.h \
......@@ -781,7 +782,7 @@ SOURCES += \
src/Settings/SettingsManager.cc \
src/Settings/UnitsSettings.cc \
src/Settings/VideoSettings.cc \
src/Terrain.cc \
src/Terrain/TerrainQuery.cc \
src/Vehicle/MAVLinkLogManager.cc \
src/VehicleSetup/JoystickConfigController.cc \
src/comm/LinkConfiguration.cc \
......
......@@ -18,8 +18,8 @@
AudioOutput::AudioOutput(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
, _tts(new QTextToSpeech(this))
{
_tts = new QTextToSpeech(this);
connect(_tts, &QTextToSpeech::stateChanged, this, &AudioOutput::_stateChanged);
}
......
......@@ -1925,6 +1925,78 @@ This is the ratio of static pressure error to dynamic pressure generated by a wi
<boolean />
<scope>modules/fw_att_control</scope>
</parameter>
<parameter default="0.0" name="FW_DTRIM_P_FLPS" type="FLOAT">
<short_desc>Pitch trim increment for flaps configuration</short_desc>
<long_desc>This increment is added to the pitch trim whenever flaps are fully deployed.</long_desc>
<min>-0.25</min>
<max>0.25</max>
<decimal>2</decimal>
<increment>0.01</increment>
<scope>modules/fw_att_control</scope>
</parameter>
<parameter default="0.0" name="FW_DTRIM_P_VMAX" type="FLOAT">
<short_desc>Pitch trim increment at maximum airspeed</short_desc>
<long_desc>This increment is added to TRIM_PITCH when airspeed is FW_AIRSP_MAX.</long_desc>
<min>-0.25</min>
<max>0.25</max>
<decimal>2</decimal>
<increment>0.01</increment>
<scope>modules/fw_att_control</scope>
</parameter>
<parameter default="0.0" name="FW_DTRIM_P_VMIN" type="FLOAT">
<short_desc>Pitch trim increment at minimum airspeed</short_desc>
<long_desc>This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.</long_desc>
<min>-0.25</min>
<max>0.25</max>
<decimal>2</decimal>
<increment>0.01</increment>
<scope>modules/fw_att_control</scope>
</parameter>
<parameter default="0.0" name="FW_DTRIM_R_FLPS" type="FLOAT">
<short_desc>Roll trim increment for flaps configuration</short_desc>
<long_desc>This increment is added to TRIM_ROLL whenever flaps are fully deployed.</long_desc>
<min>-0.25</min>
<max>0.25</max>
<decimal>2</decimal>
<increment>0.01</increment>
<scope>modules/fw_att_control</scope>
</parameter>
<parameter default="0.0" name="FW_DTRIM_R_VMAX" type="FLOAT">
<short_desc>Roll trim increment at maximum airspeed</short_desc>
<long_desc>This increment is added to TRIM_ROLL when airspeed is FW_AIRSP_MAX.</long_desc>
<min>-0.25</min>
<max>0.25</max>
<decimal>2</decimal>
<increment>0.01</increment>
<scope>modules/fw_att_control</scope>
</parameter>
<parameter default="0.0" name="FW_DTRIM_R_VMIN" type="FLOAT">
<short_desc>Roll trim increment at minimum airspeed</short_desc>
<long_desc>This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.</long_desc>
<min>-0.25</min>
<max>0.25</max>
<decimal>2</decimal>
<increment>0.01</increment>
<scope>modules/fw_att_control</scope>
</parameter>
<parameter default="0.0" name="FW_DTRIM_Y_VMAX" type="FLOAT">
<short_desc>Yaw trim increment at maximum airspeed</short_desc>
<long_desc>This increment is added to TRIM_YAW when airspeed is FW_AIRSP_MAX.</long_desc>
<min>-0.25</min>
<max>0.25</max>
<decimal>2</decimal>
<increment>0.01</increment>
<scope>modules/fw_att_control</scope>
</parameter>
<parameter default="0.0" name="FW_DTRIM_Y_VMIN" type="FLOAT">
<short_desc>Yaw trim increment at minimum airspeed</short_desc>
<long_desc>This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.</long_desc>
<min>-0.25</min>
<max>0.25</max>
<decimal>2</decimal>
<increment>0.01</increment>
<scope>modules/fw_att_control</scope>
</parameter>
<parameter default="0.0" name="FW_FLAPERON_SCL" type="FLOAT">
<short_desc>Scale factor for flaperons</short_desc>
<min>0.0</min>
......@@ -2406,7 +2478,7 @@ Set to 0 to disable heading hold</short_desc>
<short_desc>Scale throttle by pressure change</short_desc>
<long_desc>Automatically adjust throttle to account for decreased air density at higher altitudes. Start with a scale factor of 1.0 and adjust for different propulsion systems. When flying without airspeed sensor this will help to keep a constant performance over large altitude ranges. The default value of 0 will disable scaling.</long_desc>
<min>0.0</min>
<max>2.0</max>
<max>10.0</max>
<decimal>1</decimal>
<increment>0.1</increment>
<scope>modules/fw_pos_control_l1</scope>
......@@ -4189,7 +4261,7 @@ default 1.5 turns per second</short_desc>
<boolean />
<scope>modules/mc_att_control</scope>
</parameter>
<parameter default="0." name="MC_DTERM_CUTOFF" type="FLOAT">
<parameter default="30." name="MC_DTERM_CUTOFF" type="FLOAT">
<short_desc>Cutoff frequency for the low pass filter on the D-term in the rate controller</short_desc>
<long_desc>The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to decrease the driver-level filtering, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter.</long_desc>
<min>0</min>
......@@ -4251,16 +4323,6 @@ default 1.5 turns per second</short_desc>
<increment>0.1</increment>
<scope>modules/mc_att_control</scope>
</parameter>
<parameter default="0.2" name="MC_PITCH_TC" type="FLOAT">
<short_desc>Pitch time constant</short_desc>
<long_desc>Reduce if the system is too twitchy, increase if the response is too slow and sluggish.</long_desc>
<min>0.15</min>
<max>0.25</max>
<unit>s</unit>
<decimal>2</decimal>
<increment>0.01</increment>
<scope>modules/mc_att_control</scope>
</parameter>
<parameter default="0.30" name="MC_PR_INT_LIM" type="FLOAT">
<short_desc>Pitch rate integrator limit</short_desc>
<long_desc>Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes.</long_desc>
......@@ -4331,16 +4393,6 @@ default 1.5 turns per second</short_desc>
<increment>0.1</increment>
<scope>modules/mc_att_control</scope>
</parameter>
<parameter default="0.2" name="MC_ROLL_TC" type="FLOAT">
<short_desc>Roll time constant</short_desc>
<long_desc>Reduce if the system is too twitchy, increase if the response is too slow and sluggish.</long_desc>
<min>0.15</min>
<max>0.25</max>
<unit>s</unit>
<decimal>2</decimal>
<increment>0.01</increment>
<scope>modules/mc_att_control</scope>
</parameter>
<parameter default="0.30" name="MC_RR_INT_LIM" type="FLOAT">
<short_desc>Roll rate integrator limit</short_desc>
<long_desc>Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes.</long_desc>
......@@ -8113,7 +8165,7 @@ This is used for gathering replay logs for the ekf2 module</short_desc>
<reboot_required>true</reboot_required>
<scope>modules/sensors</scope>
</parameter>
<parameter default="30.0" name="IMU_GYRO_CUTOFF" type="FLOAT">
<parameter default="80.0" name="IMU_GYRO_CUTOFF" type="FLOAT">
<short_desc>Driver level cutoff frequency for gyro</short_desc>
<long_desc>The cutoff frequency for the 2nd order butterworth filter on the gyro driver. This features is currently supported by the mpu6000 and mpu9250. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter.</long_desc>
<min>0</min>
......@@ -9240,15 +9292,16 @@ This is used for gathering replay logs for the ekf2 module</short_desc>
</parameter>
<parameter default="0" name="UAVCAN_ENABLE" type="INT32">
<short_desc>UAVCAN mode</short_desc>
<long_desc>0 - UAVCAN disabled. 1 - Basic support for UAVCAN actuators and sensors. 2 - Full support for dynamic node ID allocation and firmware update. 3 - Sets the motor control outputs to UAVCAN and enables support for dynamic node ID allocation and firmware update.</long_desc>
<long_desc>0 - UAVCAN disabled. 1 - Enables support for UAVCAN sensors without dynamic node ID allocation and firmware update. 2 - Enables support for UAVCAN sensors with dynamic node ID allocation and firmware update. 3 - Enables support for UAVCAN sensors and actuators with dynamic node ID allocation and firmware update. Also sets the motor control outputs to UAVCAN.</long_desc>
<min>0</min>
<max>3</max>
<reboot_required>true</reboot_required>
<scope>modules/uavcan</scope>
<values>
<value code="0">Disabled</value>
<value code="2">Only Sensors</value>
<value code="3">Sensors and Motors</value>
<value code="1">Sensors Manual Config</value>
<value code="2">Sensors Automatic Config</value>
<value code="3">Sensors and Actuators (ESCs) Automatic Config</value>
</values>
</parameter>
<parameter default="1" name="UAVCAN_ESC_IDLT" type="INT32">
......
......@@ -174,7 +174,7 @@ FlightMap {
}
MapFitFunctions {
id: mapFitFunctions
id: mapFitFunctions // The name for this id cannot be changed without breaking references outside of this code. Beware!
map: _flightMap
usePlannedHomePosition: false
planMasterController: _planMasterController
......
......@@ -146,7 +146,7 @@ Item {
z: QGroundControl.zOrderTopMost
color: mapPal.text
font.pointSize: ScreenTools.largeFontPointSize
text: "The vehicle has failed a pre-arm check. In order to arm the vehicle, resolve the failure or disable the arming check via the Safety tab on the Vehicle Setup page."
text: "The vehicle has failed a pre-arm check. In order to arm the vehicle, resolve the failure."
}
}
Column {
......
......@@ -90,10 +90,6 @@ Item {
}
function addMissionItemCoordsForFit(coordList) {
var homePosition = fitHomePosition()
if (homePosition.isValid) {
coordList.push(homePosition)
}
for (var i=1; i<_missionController.visualItems.count; i++) {
var missionItem = _missionController.visualItems.get(i)
if (missionItem.specifiesCoordinate && !missionItem.isStandaloneCoordinate) {
......
......@@ -25,6 +25,7 @@ const char* Joystick::_throttleModeSettingsKey = "ThrottleMode";
const char* Joystick::_exponentialSettingsKey = "Exponential";
const char* Joystick::_accumulatorSettingsKey = "Accumulator";
const char* Joystick::_deadbandSettingsKey = "Deadband";
const char* Joystick::_circleCorrectionSettingsKey = "Circle_Correction";
const char* Joystick::_txModeSettingsKey = NULL;
const char* Joystick::_fixedWingTXModeSettingsKey = "TXMode_FixedWing";
const char* Joystick::_multiRotorTXModeSettingsKey = "TXMode_MultiRotor";
......@@ -64,6 +65,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC
, _exponential(0)
, _accumulator(false)
, _deadband(false)
, _circleCorrection(false)
, _activeVehicle(NULL)
, _pollingStartedForCalibration(false)
, _multiVehicleManager(multiVehicleManager)
......@@ -124,6 +126,7 @@ void Joystick::_setDefaultCalibration(void) {
_exponential = 0;
_accumulator = false;
_deadband = false;
_circleCorrection = false;
_throttleMode = ThrottleModeCenterZero;
_calibrated = true;
......@@ -188,6 +191,7 @@ void Joystick::_loadSettings(void)
_exponential = settings.value(_exponentialSettingsKey, 0).toFloat();
_accumulator = settings.value(_accumulatorSettingsKey, false).toBool();
_deadband = settings.value(_deadbandSettingsKey, false).toBool();
_circleCorrection = settings.value(_circleCorrectionSettingsKey, false).toBool();
_throttleMode = (ThrottleMode_t)settings.value(_throttleModeSettingsKey, ThrottleModeCenterZero).toInt(&convertOk);
badSettings |= !convertOk;
......@@ -264,9 +268,10 @@ void Joystick::_saveSettings(void)
settings.setValue(_exponentialSettingsKey, _exponential);
settings.setValue(_accumulatorSettingsKey, _accumulator);
settings.setValue(_deadbandSettingsKey, _deadband);
settings.setValue(_circleCorrectionSettingsKey, _circleCorrection);
settings.setValue(_throttleModeSettingsKey, _throttleMode);
qCDebug(JoystickLog) << "_saveSettings calibrated:throttlemode:deadband:txmode" << _calibrated << _throttleMode << _deadband << _transmitterMode;
qCDebug(JoystickLog) << "_saveSettings calibrated:throttlemode:deadband:txmode" << _calibrated << _throttleMode << _deadband << _circleCorrection << _transmitterMode;
QString minTpl ("Axis%1Min");
QString maxTpl ("Axis%1Max");
......@@ -462,17 +467,19 @@ void Joystick::run(void)
throttle = throttle_accu;
}
float roll_limited = std::max(static_cast<float>(-M_PI_4), std::min(roll, static_cast<float>(M_PI_4)));
float pitch_limited = std::max(static_cast<float>(-M_PI_4), std::min(pitch, static_cast<float>(M_PI_4)));
float yaw_limited = std::max(static_cast<float>(-M_PI_4), std::min(yaw, static_cast<float>(M_PI_4)));
float throttle_limited = std::max(static_cast<float>(-M_PI_4), std::min(throttle, static_cast<float>(M_PI_4)));
// Map from unit circle to linear range and limit
roll = std::max(-1.0f, std::min(tanf(asinf(roll_limited)), 1.0f));
pitch = std::max(-1.0f, std::min(tanf(asinf(pitch_limited)), 1.0f));
yaw = std::max(-1.0f, std::min(tanf(asinf(yaw_limited)), 1.0f));
throttle = std::max(-1.0f, std::min(tanf(asinf(throttle_limited)), 1.0f));
if ( _circleCorrection ) {
float roll_limited = std::max(static_cast<float>(-M_PI_4), std::min(roll, static_cast<float>(M_PI_4)));
float pitch_limited = std::max(static_cast<float>(-M_PI_4), std::min(pitch, static_cast<float>(M_PI_4)));
float yaw_limited = std::max(static_cast<float>(-M_PI_4), std::min(yaw, static_cast<float>(M_PI_4)));
float throttle_limited = std::max(static_cast<float>(-M_PI_4), std::min(throttle, static_cast<float>(M_PI_4)));
// Map from unit circle to linear range and limit
roll = std::max(-1.0f, std::min(tanf(asinf(roll_limited)), 1.0f));
pitch = std::max(-1.0f, std::min(tanf(asinf(pitch_limited)), 1.0f));
yaw = std::max(-1.0f, std::min(tanf(asinf(yaw_limited)), 1.0f));
throttle = std::max(-1.0f, std::min(tanf(asinf(throttle_limited)), 1.0f));
}
if ( _exponential != 0 ) {
// Exponential (0% to -50% range like most RC radios)
//_exponential is set by a slider in joystickConfig.qml
......@@ -767,6 +774,19 @@ void Joystick::setDeadband(bool deadband)
_saveSettings();
}
bool Joystick::circleCorrection(void)
{
return _circleCorrection;
}
void Joystick::setCircleCorrection(bool circleCorrection)
{
_circleCorrection = circleCorrection;
_saveSettings();
emit circleCorrectionChanged(_circleCorrection);
}
void Joystick::setCalibrationMode(bool calibrating)
{
_calibrationMode = calibrating;
......
......@@ -76,8 +76,9 @@ public:
Q_PROPERTY(bool negativeThrust READ negativeThrust WRITE setNegativeThrust NOTIFY negativeThrustChanged)
Q_PROPERTY(float exponential READ exponential WRITE setExponential NOTIFY exponentialChanged)
Q_PROPERTY(bool accumulator READ accumulator WRITE setAccumulator NOTIFY accumulatorChanged)
Q_PROPERTY(bool requiresCalibration READ requiresCalibration CONSTANT)
Q_PROPERTY(bool requiresCalibration READ requiresCalibration CONSTANT)
Q_PROPERTY(bool circleCorrection READ circleCorrection WRITE setCircleCorrection NOTIFY circleCorrectionChanged)
// Property accessors
int axisCount(void) { return _axisCount; }
......@@ -120,6 +121,9 @@ public:
bool deadband(void);
void setDeadband(bool accu);
bool circleCorrection(void);
void setCircleCorrection(bool circleCorrection);
void setTXMode(int mode);
int getTXMode(void) { return _transmitterMode; }
......@@ -147,6 +151,8 @@ signals:
void enabledChanged(bool enabled);
void circleCorrectionChanged(bool circleCorrection);
/// Signal containing new joystick information
/// @param roll Range is -1:1, negative meaning roll left, positive meaning roll right
/// @param pitch Range i -1:1, negative meaning pitch down, positive meaning pitch up
......@@ -213,6 +219,7 @@ protected:
float _exponential;
bool _accumulator;
bool _deadband;
bool _circleCorrection;
Vehicle* _activeVehicle;
bool _pollingStartedForCalibration;
......@@ -229,6 +236,7 @@ private:
static const char* _exponentialSettingsKey;
static const char* _accumulatorSettingsKey;
static const char* _deadbandSettingsKey;
static const char* _circleCorrectionSettingsKey;
static const char* _txModeSettingsKey;
static const char* _fixedWingTXModeSettingsKey;
static const char* _multiRotorTXModeSettingsKey;
......
......@@ -138,7 +138,7 @@ bool JsonHelper::validateKeyTypes(const QJsonObject& jsonObject, const QStringLi
QString valueKey = keys[i];
if (jsonObject.contains(valueKey)) {
const QJsonValue& jsonValue = jsonObject[valueKey];
if (types[i] == QJsonValue::Null && jsonValue.type() == QJsonValue::Double) {
if (jsonValue.type() == QJsonValue::Null && types[i] == QJsonValue::Double) {
// Null type signals a NaN on a double value
continue;
}
......
......@@ -123,7 +123,7 @@ public:
static bool parseEnum(const QJsonObject& jsonObject, QStringList& enumStrings, QStringList& enumValues, QString& errorString, QString valueName = QString());
/// Returns NaN if the value is null, or it not the double value
/// Returns NaN if the value is null, or if not, the double value
static double possibleNaNJsonValue(const QJsonValue& value);
static const char* jsonVersionKey;
......
......@@ -36,17 +36,17 @@ public:
Q_INVOKABLE void rotateEntryPoint(void);
// Overrides from ComplexMissionItem
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); }
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); }
// Overrides from TransectStyleComplexItem
void save (QJsonArray& planItems) final;
bool specifiesCoordinate (void) const final;
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
void save (QJsonArray& missionItems) final;
bool specifiesCoordinate (void) const final;
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
// Overrides from VisualMissionionItem
bool readyForSave (void) const;
static const char* jsonComplexItemTypeValue;
......@@ -54,26 +54,25 @@ public:
static const char* corridorWidthName;
private slots:
void _polylineDirtyChanged (bool dirty);
void _polylineCountChanged (int count);
void _rebuildCorridor (void);
void _polylineDirtyChanged (bool dirty);
void _rebuildCorridorPolygon (void);
// Overrides from TransectStyleComplexItem
virtual void _rebuildTransects (void) final;
void _rebuildTransectsPhase1 (void) final;
void _rebuildTransectsPhase2 (void) final;
private:
int _transectCount (void) const;
void _rebuildCorridorPolygon(void);
int _transectCount (void) const;
void _buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent);
void _appendLoadedMissionItems (QList<MissionItem*>& items, QObject* missionItemParent);
QGCMapPolyline _corridorPolyline;
QList<QList<QGeoCoordinate>> _transectSegments; ///< Internal transect segments including grid exit, turnaround and internal camera points
bool _ignoreRecalc;
int _entryPoint;
int _entryPoint;
QMap<QString, FactMetaData*> _metaDataMap;
SettingsFact _corridorWidthFact;
static const char* _entryPointName;
static const char* _jsonEntryPointKey;
};
......@@ -24,7 +24,12 @@ void CorridorScanComplexItemTest::init(void)
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_corridorItem = new CorridorScanComplexItem(_offlineVehicle, this);
// _corridorItem->setTurnaroundDist(0); // Unit test written for no turnaround distance
// vehicleSpeed need for terrain calcs
MissionController::MissionFlightStatus_t missionFlightStatus;
missionFlightStatus.vehicleSpeed = 5;
_corridorItem->setMissionFlightStatus(missionFlightStatus);
_setPolyline();
_corridorItem->setDirty(false);
......@@ -130,21 +135,78 @@ void CorridorScanComplexItemTest::_testEntryLocation(void)
}
#endif
void CorridorScanComplexItemTest::_waitForReadyForSave(void)
{
int loops = 0;
while (loops++ < 8) {
if (_corridorItem->readyForSave()) {
return;
}
QTest::qWait(500);
}
QVERIFY(false);
}
void CorridorScanComplexItemTest::_testItemCount(void)
{
QList<MissionItem*> items;
_corridorItem->turnAroundDistance()->setRawValue(0);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(true);
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
_corridorItem->turnAroundDistance()->setRawValue(0);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(false);
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
_corridorItem->turnAroundDistance()->setRawValue(20);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(true);
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
_corridorItem->turnAroundDistance()->setRawValue(20);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(false);
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
#if 0
// Terrain queries seem to take random amount of time so these don't work 100%
_corridorItem->setFollowTerrain(true);
_corridorItem->turnAroundDistance()->setRawValue(0);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(true);
_waitForReadyForSave();
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
_corridorItem->turnAroundDistance()->setRawValue(0);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(false);
_waitForReadyForSave();
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
_corridorItem->turnAroundDistance()->setRawValue(20);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(true);
_waitForReadyForSave();
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
_corridorItem->turnAroundDistance()->setRawValue(20);
_corridorItem->cameraTriggerInTurnAround()->setRawValue(false);
_waitForReadyForSave();
_corridorItem->appendMissionItems(items, this);
QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
items.clear();
#endif
}
void CorridorScanComplexItemTest::_testPathChanges(void)
......
......@@ -36,6 +36,7 @@ private slots:
private:
void _setPolyline(void);
void _waitForReadyForSave(void);
enum {
corridorPolygonPathChangedIndex = 0,
......
......@@ -281,7 +281,7 @@ void MissionController::convertToKMLDocument(QDomDocument& document)
return;
}
float altitude = missionJson[_jsonPlannedHomePositionKey].toArray()[2].toDouble();
float homeAltitude = missionJson[_jsonPlannedHomePositionKey].toArray()[2].toDouble();
QString coord;
QStringList coords;
......@@ -296,11 +296,12 @@ void MissionController::convertToKMLDocument(QDomDocument& document)
qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());
if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homeAltitude);
coord = QString::number(item->param6(),'f',7) \
+ "," \
+ QString::number(item->param5(),'f',7) \
+ "," \
+ QString::number(item->param7() + altitude,'f',2);
+ QString::number(amslAltitude,'f',2);
coords.append(coord);
}
}
......@@ -347,13 +348,13 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
}
}
newItem->setDefaultsForCommand();
if ((MAV_CMD)newItem->command() == MAV_CMD_NAV_WAYPOINT) {
double prevAltitude;
MAV_FRAME prevFrame;
if (newItem->specifiesAltitude()) {
double prevAltitude;
int prevAltitudeMode;
if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
newItem->missionItem().setFrame(prevFrame);
newItem->missionItem().setParam7(prevAltitude);
if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
newItem->altitude()->setRawValue(prevAltitude);
newItem->setAltitudeMode((SimpleMissionItem::AltitudeMode)prevAltitudeMode);
}
}
newItem->setMissionFlightStatus(_missionFlightStatus);
......@@ -375,12 +376,12 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
newItem->setDefaultsForCommand();
newItem->setCoordinate(coordinate);
double prevAltitude;
MAV_FRAME prevFrame;
double prevAltitude;
int prevAltitudeMode;
if (_findPreviousAltitude(i, &prevAltitude, &prevFrame)) {
newItem->missionItem().setFrame(prevFrame);
newItem->missionItem().setParam7(prevAltitude);
if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
newItem->altitude()->setRawValue(prevAltitude);
newItem->setAltitudeMode((SimpleMissionItem::AltitudeMode)prevAltitudeMode);
}
_visualItems->insert(i, newItem);
......@@ -929,6 +930,18 @@ bool MissionController::loadTextFile(QFile& file, QString& errorString)
return true;
}
bool MissionController::readyForSaveSend(void) const
{
for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
if (!visualItem->readyForSave()) {
return false;
}
}
return true;
}
void MissionController::save(QJsonObject& json)
{
json[JsonHelper::jsonVersionKey] = _missionFileVersion;
......@@ -1289,7 +1302,7 @@ void MissionController::_recalcMissionFlightStatus()
}
// Link back to home if first item is takeoff and we have home position
if (firstCoordinateItem && simpleItem && simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
if (firstCoordinateItem && simpleItem && (simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF || simpleItem->command() == MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF)) {
if (showHomePosition) {
linkStartToHome = true;
if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
......@@ -1308,9 +1321,15 @@ void MissionController::_recalcMissionFlightStatus()
case MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF:
vtolInHover = false;
break;
case MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_TAKEOFF:
vtolInHover = true;
break;
case MavlinkQmlSingleton::MAV_CMD_NAV_LAND:
vtolInHover = false;
break;
case MavlinkQmlSingleton::MAV_CMD_NAV_VTOL_LAND:
vtolInHover = true;
break;
case MavlinkQmlSingleton::MAV_CMD_DO_VTOL_TRANSITION:
{
int transitionState = simpleItem->missionItem().param1();
......@@ -1656,11 +1675,11 @@ void MissionController::_inProgressChanged(bool inProgress)
emit syncInProgressChanged(inProgress);
}
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, MAV_FRAME* prevFrame)
bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode)
{
bool found = false;
double foundAltitude;
MAV_FRAME foundFrame;
int foundAltitudeMode;
if (newIndex > _visualItems->count()) {
return false;
......@@ -1673,9 +1692,9 @@ bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude
if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
if (visualItem->isSimpleItem()) {
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_WAYPOINT) {
foundAltitude = simpleItem->exitCoordinate().altitude();
foundFrame = simpleItem->missionItem().frame();
if (simpleItem->specifiesAltitude()) {