diff --git a/Jenkinsfile b/Jenkinsfile
index 56e7fed77127117fe94d8ecf7a93275149c2a305..8cc6babe1fa3045a8d243a205afa9d1149df6d1a 100644
--- a/Jenkinsfile
+++ b/Jenkinsfile
@@ -2,9 +2,33 @@ pipeline {
agent any
stages {
stage('build') {
- steps {
- sh 'git status'
+ parallel {
+ stage('OSX Release') {
+ agent {
+ node {
+ label 'mac'
+ }
+ }
+ environment {
+ QT_FATAL_WARNINGS = '1'
+ QMAKESPEC = 'macx-clang'
+ }
+ steps {
+ sh 'git submodule deinit -f .'
+ sh 'git clean -ff -x -d .'
+ sh 'git submodule update --init --recursive --force'
+ sh 'rm -rf ${SHADOW_BUILD_DIR}; mkdir -p ${SHADOW_BUILD_DIR}'
+ sh 'cd ${SHADOW_BUILD_DIR}; ${QT_PATH}/5.9.3/clang_64/bin/qmake -r ${WORKSPACE}/qgroundcontrol.pro CONFIG+=release CONFIG+=WarningsAsErrorsOn'
+ sh 'cd ${SHADOW_BUILD_DIR}; make -j`sysctl -n hw.ncpu`'
+ sh 'ccache -s'
+ }
+ }
}
}
}
+ environment {
+ SHADOW_BUILD_DIR = '/tmp/jenkins/shadow_build_dir'
+ CCACHE_CPP2 = '1'
+ CCACHE_BASEDIR = '${WORKSPACE}'
+ }
}
\ No newline at end of file
diff --git a/UnitTest.qrc b/UnitTest.qrc
index 61510fde340a034be48ab0aee7593c72c27ebf2d..2bfa5bbb8062a9838d5fd3351bc49e074e13939d 100644
--- a/UnitTest.qrc
+++ b/UnitTest.qrc
@@ -9,9 +9,10 @@
src/MissionManager/UnitTest/MavCmdInfoVTOL.json
src/MissionManager/UnitTest/MissionPlanner.waypoints
src/MissionManager/UnitTest/OldFileFormat.mission
- src/MissionManager/UnitTest/GoodPolygon.kml
- src/MissionManager/UnitTest/MissingPolygonNode.kml
- src/MissionManager/UnitTest/BadXml.kml
- src/MissionManager/UnitTest/BadCoordinatesNode.kml
+ src/MissionManager/UnitTest/PolygonAreaTest.kml
+ src/MissionManager/UnitTest/PolygonGood.kml
+ src/MissionManager/UnitTest/PolygonMissingNode.kml
+ src/MissionManager/UnitTest/PolygonBadXml.kml
+ src/MissionManager/UnitTest/PolygonBadCoordinatesNode.kml
diff --git a/libs/mavlink/include/mavlink/v2.0 b/libs/mavlink/include/mavlink/v2.0
index a31f7d989dffc2e554c26ad2c22c2a432a48fa74..5db5e944048cd6126a3e58c67c9c4dcdb4d4e0ff 160000
--- a/libs/mavlink/include/mavlink/v2.0
+++ b/libs/mavlink/include/mavlink/v2.0
@@ -1 +1 @@
-Subproject commit a31f7d989dffc2e554c26ad2c22c2a432a48fa74
+Subproject commit 5db5e944048cd6126a3e58c67c9c4dcdb4d4e0ff
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 1609e178c8b4a21dcb710a0d5633787d8ebe40d2..d50187981078161eb4f839211b2e2bbef0dded2a 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -415,6 +415,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/FactSystem/FactSystemTestPX4.h \
src/FactSystem/ParameterManagerTest.h \
src/MissionManager/CameraSectionTest.h \
+ src/MissionManager/CorridorScanComplexItemTest.h \
src/MissionManager/MissionCommandTreeTest.h \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionControllerTest.h \
@@ -423,6 +424,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/MissionManager/MissionSettingsTest.h \
src/MissionManager/PlanMasterControllerTest.h \
src/MissionManager/QGCMapPolygonTest.h \
+ src/MissionManager/QGCMapPolylineTest.h \
src/MissionManager/SectionTest.h \
src/MissionManager/SimpleMissionItemTest.h \
src/MissionManager/SpeedSectionTest.h \
@@ -452,6 +454,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/FactSystem/FactSystemTestPX4.cc \
src/FactSystem/ParameterManagerTest.cc \
src/MissionManager/CameraSectionTest.cc \
+ src/MissionManager/CorridorScanComplexItemTest.cc \
src/MissionManager/MissionCommandTreeTest.cc \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionControllerTest.cc \
@@ -460,6 +463,7 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/MissionManager/MissionSettingsTest.cc \
src/MissionManager/PlanMasterControllerTest.cc \
src/MissionManager/QGCMapPolygonTest.cc \
+ src/MissionManager/QGCMapPolylineTest.cc \
src/MissionManager/SectionTest.cc \
src/MissionManager/SimpleMissionItemTest.cc \
src/MissionManager/SpeedSectionTest.cc \
@@ -508,6 +512,7 @@ HEADERS += \
src/MissionManager/CameraSection.h \
src/MissionManager/CameraSpec.h \
src/MissionManager/ComplexMissionItem.h \
+ src/MissionManager/CorridorScanComplexItem.h \
src/MissionManager/FixedWingLandingComplexItem.h \
src/MissionManager/GeoFenceController.h \
src/MissionManager/GeoFenceManager.h \
@@ -526,6 +531,7 @@ HEADERS += \
src/MissionManager/QGCFencePolygon.h \
src/MissionManager/QGCMapCircle.h \
src/MissionManager/QGCMapPolygon.h \
+ src/MissionManager/QGCMapPolyline.h \
src/MissionManager/RallyPoint.h \
src/MissionManager/RallyPointController.h \
src/MissionManager/RallyPointManager.h \
@@ -700,6 +706,7 @@ SOURCES += \
src/MissionManager/CameraSection.cc \
src/MissionManager/CameraSpec.cc \
src/MissionManager/ComplexMissionItem.cc \
+ src/MissionManager/CorridorScanComplexItem.cc \
src/MissionManager/FixedWingLandingComplexItem.cc \
src/MissionManager/GeoFenceController.cc \
src/MissionManager/GeoFenceManager.cc \
@@ -718,6 +725,7 @@ SOURCES += \
src/MissionManager/QGCFencePolygon.cc \
src/MissionManager/QGCMapCircle.cc \
src/MissionManager/QGCMapPolygon.cc \
+ src/MissionManager/QGCMapPolyline.cc \
src/MissionManager/RallyPoint.cc \
src/MissionManager/RallyPointController.cc \
src/MissionManager/RallyPointManager.cc \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 366817258be621af4112dfb5b2c4aab8ac277cb6..0a01d0ca96c32ca5853d42046061265d8734324d 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -18,6 +18,7 @@
src/AnalyzeView/AnalyzeView.qml
src/ui/AppSettings.qml
src/ui/preferences/BluetoothSettings.qml
+ src/PlanView/CorridorScanEditor.qml
src/ViewWidgets/CustomCommandWidget.qml
src/ui/preferences/DebugWindow.qml
src/AutoPilotPlugins/Common/ESP8266Component.qml
@@ -48,6 +49,7 @@
src/PlanView/CameraCalc.qml
src/PlanView/CameraSection.qml
src/QmlControls/ClickableColor.qml
+ src/PlanView/CorridorScanMapVisual.qml
src/QmlControls/DropButton.qml
src/QmlControls/EditPositionDialog.qml
src/QmlControls/ExclusiveGroupItem.qml
@@ -89,6 +91,7 @@
src/QmlControls/QGCMapLabel.qml
src/MissionManager/QGCMapCircleVisuals.qml
src/MissionManager/QGCMapPolygonVisuals.qml
+ src/MissionManager/QGCMapPolylineVisuals.qml
src/QmlControls/QGCMouseArea.qml
src/QmlControls/QGCMovableItem.qml
src/QmlControls/QGCPipable.qml
@@ -202,6 +205,7 @@
src/MissionManager/QGCMapCircle.Facts.json
src/Settings/RTK.SettingsGroup.json
src/MissionManager/Survey.SettingsGroup.json
+ src/MissionManager/CorridorScan.SettingsGroup.json
src/MissionManager/StructureScan.SettingsGroup.json
src/Settings/Units.SettingsGroup.json
src/Settings/Video.SettingsGroup.json
diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc
index ca491fd27401d7b0745b465b96497d3409bd9eef..d2cfe911cff25310d33e873a5c2c5f8a57eec9a7 100644
--- a/src/Camera/QGCCameraControl.cc
+++ b/src/Camera/QGCCameraControl.cc
@@ -40,6 +40,7 @@ static const char* kParameterrange = "parameterrange";
static const char* kParameterranges = "parameterranges";
static const char* kParameters = "parameters";
static const char* kReadOnly = "readonly";
+static const char* kWriteOnly = "writeonly";
static const char* kRoption = "roption";
static const char* kStep = "step";
static const char* kStrings = "strings";
@@ -659,6 +660,13 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
//-- Is it read only?
bool readOnly = false;
read_attribute(parameterNode, kReadOnly, readOnly);
+ //-- Is it write only?
+ bool writeOnly = false;
+ read_attribute(parameterNode, kWriteOnly, writeOnly);
+ //-- It can't be both
+ if(readOnly && writeOnly) {
+ qCritical() << QString("Parameter %1 cannot be both read only and write only").arg(factName);
+ }
//-- Param type
bool unknownType;
FactMetaData::ValueType_t factType = FactMetaData::stringToType(type, unknownType);
@@ -689,6 +697,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
metaData->setLongDescription(description);
metaData->setHasControl(control);
metaData->setReadOnly(readOnly);
+ metaData->setWriteOnly(writeOnly);
//-- Options (enums)
QDomElement optionElem = parameterNode.toElement();
QDomNodeList optionsRoot = optionElem.elementsByTagName(kOptions);
@@ -797,7 +806,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
metaData->setRawUnits(attr);
}
}
- qCDebug(CameraControlLog) << "New parameter:" << factName;
+ qCDebug(CameraControlLog) << "New parameter:" << factName << (readOnly ? "ReadOnly" : "Writable") << (writeOnly ? "WriteOnly" : "Readable");
_nameToFactMetaDataMap[factName] = metaData;
Fact* pFact = new Fact(_compID, factName, factType, this);
QQmlEngine::setObjectOwnership(pFact, QQmlEngine::CppOwnership);
diff --git a/src/Camera/QGCCameraIO.cc b/src/Camera/QGCCameraIO.cc
index 577c0207d0d9b70a8f6a6294825bf328edd31749..5f98ff41976989a57f8e57fe4f0c26ce0816d5ba 100644
--- a/src/Camera/QGCCameraIO.cc
+++ b/src/Camera/QGCCameraIO.cc
@@ -28,8 +28,13 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
_paramWriteTimer.setInterval(3000);
_paramRequestTimer.setSingleShot(true);
_paramRequestTimer.setInterval(3500);
+ if(_fact->writeOnly()) {
+ //-- Write mode is always "done" as it won't ever read
+ _done = true;
+ } else {
+ connect(&_paramRequestTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramRequestTimeout);
+ }
connect(&_paramWriteTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramWriteTimeout);
- connect(&_paramRequestTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramRequestTimeout);
connect(_fact, &Fact::rawValueChanged, this, &QGCCameraParamIO::_factChanged);
connect(_fact, &Fact::_containerRawValueChanged, this, &QGCCameraParamIO::_containerRawValueChanged);
_pMavlink = qgcApp()->toolbox()->mavlinkProtocol();
@@ -38,31 +43,33 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
switch (_fact->type()) {
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeBool:
- _mavParamType = MAV_PARAM_TYPE_UINT8;
+ _mavParamType = MAV_PARAM_EXT_TYPE_UINT8;
break;
case FactMetaData::valueTypeInt8:
- _mavParamType = MAV_PARAM_TYPE_INT8;
+ _mavParamType = MAV_PARAM_EXT_TYPE_INT8;
break;
case FactMetaData::valueTypeUint16:
- _mavParamType = MAV_PARAM_TYPE_UINT16;
+ _mavParamType = MAV_PARAM_EXT_TYPE_UINT16;
break;
case FactMetaData::valueTypeInt16:
- _mavParamType = MAV_PARAM_TYPE_INT16;
+ _mavParamType = MAV_PARAM_EXT_TYPE_INT16;
break;
case FactMetaData::valueTypeUint32:
- _mavParamType = MAV_PARAM_TYPE_UINT32;
+ _mavParamType = MAV_PARAM_EXT_TYPE_UINT32;
break;
case FactMetaData::valueTypeFloat:
- _mavParamType = MAV_PARAM_TYPE_REAL32;
+ _mavParamType = MAV_PARAM_EXT_TYPE_REAL32;
break;
+ //-- String and custom are the same for now
+ case FactMetaData::valueTypeString:
case FactMetaData::valueTypeCustom:
- _mavParamType = (MAV_PARAM_TYPE)11; // MAV_PARAM_TYPE_CUSTOM;
+ _mavParamType = MAV_PARAM_EXT_TYPE_CUSTOM;
break;
default:
qWarning() << "Unsupported fact type" << _fact->type() << "for" << _fact->name();
// Fall through
case FactMetaData::valueTypeInt32:
- _mavParamType = MAV_PARAM_TYPE_INT32;
+ _mavParamType = MAV_PARAM_EXT_TYPE_INT32;
break;
}
}
@@ -71,9 +78,11 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
void
QGCCameraParamIO::setParamRequest()
{
- _paramRequestReceived = false;
- _requestRetries = 0;
- _paramRequestTimer.start();
+ if(!_fact->writeOnly()) {
+ _paramRequestReceived = false;
+ _requestRetries = 0;
+ _paramRequestTimer.start();
+ }
}
//-----------------------------------------------------------------------------
@@ -139,6 +148,8 @@ QGCCameraParamIO::_sendParameter()
case FactMetaData::valueTypeFloat:
union_value.param_float = _fact->rawValue().toFloat();
break;
+ //-- String and custom are the same for now
+ case FactMetaData::valueTypeString:
case FactMetaData::valueTypeCustom:
{
QByteArray custom = _fact->rawValue().toByteArray();
@@ -250,28 +261,28 @@ QGCCameraParamIO::_valueFromMessage(const char* value, uint8_t param_type)
param_ext_union_t u;
memcpy(u.bytes, value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN);
switch (param_type) {
- case MAV_PARAM_TYPE_REAL32:
+ case MAV_PARAM_EXT_TYPE_REAL32:
var = QVariant(u.param_float);
break;
- case MAV_PARAM_TYPE_UINT8:
+ case MAV_PARAM_EXT_TYPE_UINT8:
var = QVariant(u.param_uint8);
break;
- case MAV_PARAM_TYPE_INT8:
+ case MAV_PARAM_EXT_TYPE_INT8:
var = QVariant(u.param_int8);
break;
- case MAV_PARAM_TYPE_UINT16:
+ case MAV_PARAM_EXT_TYPE_UINT16:
var = QVariant(u.param_uint16);
break;
- case MAV_PARAM_TYPE_INT16:
+ case MAV_PARAM_EXT_TYPE_INT16:
var = QVariant(u.param_int16);
break;
- case MAV_PARAM_TYPE_UINT32:
+ case MAV_PARAM_EXT_TYPE_UINT32:
var = QVariant(u.param_uint32);
break;
- case MAV_PARAM_TYPE_INT32:
+ case MAV_PARAM_EXT_TYPE_INT32:
var = QVariant(u.param_int32);
break;
- case 11: //MAV_PARAM_TYPE_CUSTOM:
+ case MAV_PARAM_EXT_TYPE_CUSTOM:
var = QVariant(QByteArray(value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN));
break;
default:
@@ -303,6 +314,14 @@ QGCCameraParamIO::_paramRequestTimeout()
void
QGCCameraParamIO::paramRequest(bool reset)
{
+ //-- If it's write only, we don't request it.
+ if(_fact->writeOnly()) {
+ if(!_done) {
+ _done = true;
+ _control->_paramDone();
+ }
+ return;
+ }
if(reset) {
_requestRetries = 0;
_forceUIUpdate = true;
diff --git a/src/Camera/QGCCameraIO.h b/src/Camera/QGCCameraIO.h
index a3f4d57a2e1a62c14639b29f534fb34875e022b0..0337266340912840fe9c46e79c50b39700ac1dd0 100644
--- a/src/Camera/QGCCameraIO.h
+++ b/src/Camera/QGCCameraIO.h
@@ -67,7 +67,7 @@ private:
QTimer _paramRequestTimer;
bool _done;
bool _updateOnSet;
- MAV_PARAM_TYPE _mavParamType;
+ MAV_PARAM_EXT_TYPE _mavParamType;
MAVLinkProtocol* _pMavlink;
bool _forceUIUpdate;
};
diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc
index 8930790b2698b8ad44da993a49c841e0b296848a..3afce178fd287c5a40d106ffde28be1d9a1b8c1d 100644
--- a/src/FactSystem/Fact.cc
+++ b/src/FactSystem/Fact.cc
@@ -663,6 +663,16 @@ bool Fact::readOnly(void) const
}
}
+bool Fact::writeOnly(void) const
+{
+ if (_metaData) {
+ return _metaData->writeOnly();
+ } else {
+ qWarning() << kMissingMetadata << name();
+ return false;
+ }
+}
+
bool Fact::volatileValue(void) const
{
if (_metaData) {
diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h
index 54ccd2214679a7d8528543b0624b4d80657c8679..cc0336ee80de34e289b58ae89fc77d5a51bc86c5 100644
--- a/src/FactSystem/Fact.h
+++ b/src/FactSystem/Fact.h
@@ -71,6 +71,7 @@ public:
Q_PROPERTY(bool typeIsBool READ typeIsBool CONSTANT)
Q_PROPERTY(bool hasControl READ hasControl CONSTANT)
Q_PROPERTY(bool readOnly READ readOnly CONSTANT)
+ Q_PROPERTY(bool writeOnly READ writeOnly CONSTANT)
Q_PROPERTY(bool volatileValue READ volatileValue CONSTANT)
/// Convert and validate value
@@ -119,7 +120,8 @@ public:
bool typeIsBool (void) const { return type() == FactMetaData::valueTypeBool; }
bool hasControl (void) const;
bool readOnly (void) const;
- bool volatileValue (void) const;
+ bool writeOnly (void) const;
+ bool volatileValue (void) const;
/// Returns the values as a string with full 18 digit precision if float/double.
QString rawValueStringFullPrecision(void) const;
diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc
index 2c811e63749003dfc431a3d7e17b004671d27e72..5dc608cf688cb83b7d835591c4f3625701db5ab9 100644
--- a/src/FactSystem/FactMetaData.cc
+++ b/src/FactSystem/FactMetaData.cc
@@ -96,6 +96,7 @@ FactMetaData::FactMetaData(QObject* parent)
, _increment (std::numeric_limits::quiet_NaN())
, _hasControl (true)
, _readOnly (false)
+ , _writeOnly (false)
, _volatile (false)
{
_category = kDefaultCategory;
@@ -118,6 +119,7 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
, _increment (std::numeric_limits::quiet_NaN())
, _hasControl (true)
, _readOnly (false)
+ , _writeOnly (false)
, _volatile (false)
{
_category = kDefaultCategory;
@@ -147,6 +149,7 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent
, _increment (std::numeric_limits::quiet_NaN())
, _hasControl (true)
, _readOnly (false)
+ , _writeOnly (false)
, _volatile (false)
{
_category = kDefaultCategory;
@@ -180,6 +183,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
_increment = other._increment;
_hasControl = other._hasControl;
_readOnly = other._readOnly;
+ _writeOnly = other._writeOnly;
_volatile = other._volatile;
return *this;
}
diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h
index 75eabaecf62ce91042573e6eb1930dd26533562b..28c924fa0bdc76b01d5956c4470957a32a13672a 100644
--- a/src/FactSystem/FactMetaData.h
+++ b/src/FactSystem/FactMetaData.h
@@ -104,6 +104,7 @@ public:
bool rebootRequired (void) const { return _rebootRequired; }
bool hasControl (void) const { return _hasControl; }
bool readOnly (void) const { return _readOnly; }
+ bool writeOnly (void) const { return _writeOnly; }
bool volatileValue (void) const { return _volatile; }
/// Amount to increment value when used in controls such as spin button or slider with detents.
@@ -135,6 +136,7 @@ public:
void setIncrement (double increment) { _increment = increment; }
void setHasControl (bool bValue) { _hasControl = bValue; }
void setReadOnly (bool bValue) { _readOnly = bValue; }
+ void setWriteOnly (bool bValue) { _writeOnly = bValue; }
void setVolatileValue (bool bValue);
void setTranslators(Translator rawTranslator, Translator cookedTranslator);
@@ -247,6 +249,7 @@ private:
double _increment;
bool _hasControl;
bool _readOnly;
+ bool _writeOnly;
bool _volatile;
// Exact conversion constants
diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc
index 03b994d2409ee873d2a9a7da5ef7aeb048f32cd9..0d223761eb9ca126439bd36e2a5d719064514a15 100644
--- a/src/FactSystem/ParameterManager.cc
+++ b/src/FactSystem/ParameterManager.cc
@@ -81,7 +81,17 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
// Ensure the cache directory exists
QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache");
- refreshAllParameters();
+ if (_vehicle->highLatencyLink()) {
+ // High latency links don't load parameters
+ _parametersReady = true;
+ _missingParameters = true;
+ _initialLoadComplete = true;
+ _waitingForDefaultComponent = false;
+ emit parametersReadyChanged(_parametersReady);
+ emit missingParametersChanged(_missingParameters);
+ } else {
+ refreshAllParameters();
+ }
}
ParameterManager::~ParameterManager()
@@ -133,12 +143,12 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
}
#endif
- if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") {
- if (!_initialLoadComplete && !_logReplay) {
- /* we received a cache hash, potentially load from cache */
- _tryCacheHashLoad(vehicleId, componentId, value);
- }
- return;
+ if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") {
+ if (!_initialLoadComplete && !_logReplay) {
+ /* we received a cache hash, potentially load from cache */
+ _tryCacheHashLoad(vehicleId, componentId, value);
+ }
+ return;
}
_initialRequestTimeoutTimer.stop();
diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
index 27c08dac87e12760d2dbbecfcb760ec8e3b81e7a..41a1d00434b1dd86f1fb12b478af810e782927b0 100644
--- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
+++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
@@ -1119,7 +1119,9 @@ This parameter controls the time constant of the decay
Airspeed fusion threshold. A value of zero will deactivate airspeed fusion. Any other positive
-value will determine the minimum airspeed which will still be fused
+value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed.
+Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS.
+Use EKF2_FUSE_BETA to activate sideslip fusion
0.0
m/s
1
@@ -1291,7 +1293,7 @@ Increasing it makes the multi-rotor wind estimates adjust more slowly
Boolean determining if synthetic sideslip measurements should fused
- A value of 1 indicates that fusion is active
+ A value of 1 indicates that fusion is active Both sideslip fusion and airspeed fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_ARSP_THR to activate airspeed fusion.
modules/ekf2
@@ -1653,7 +1655,8 @@ Assumes measurement is timestamped at trailing edge of integration periodmodules/ekf2
- Optical Flow data will not fused if the magnitude of the flow rate > EKF2_OF_RMAX
+ Optical Flow data will not fused if the magnitude of the flow rate > EKF2_OF_RMAX.
+Control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground is less than 50% of EKF2_OF_RMAX
1.0
rad/s
2
@@ -3269,7 +3272,7 @@ but also ignore less noise
3
modules/landing_target_estimator
-
+
Initial landing target velocity uncertainty
Initial variance of the relative landing target velocity in x and y direction
0.001
@@ -3801,6 +3804,17 @@ Used to calculate increased terrain random walk nosie due to movement0.5
modules/navigator
+
+ Enable yaw control of the mount. (Only affects multicopters and ROI mission items)
+ If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading mode as specified by MIS_YAWMODE. If disabled, the vehicle will yaw towards the ROI.
+ 0
+ 1
+ modules/navigator
+
+ Disable
+ Enable
+
+
Take-off altitude
This is the minimum altitude the system will take off to.
@@ -3822,7 +3836,6 @@ Used to calculate increased terrain random walk nosie due to movementHeading towards waypoint
Heading towards home
Heading away from home
- Heading towards ROI
@@ -4446,6 +4459,17 @@ default 1.5 turns per second
1
modules/mc_pos_control
+
+ Horizontal acceleration in manual modes when optical flow ground speed limit is removed.
+If full stick is being applied and the EKF starts using GPS whilst using optical flow,
+the vehicle will accelerate at this rate until the normal position control speed is achieved
+ 0.2
+ 2.0
+ m/s/s
+ 1
+ 0.1
+ modules/mc_pos_control
+
Maximum horizontal acceleration for auto mode and maximum deceleration for manual mode
2.0
@@ -7956,6 +7980,11 @@ This is used for gathering replay logs for the ekf2 module
The offset (zero-reading) in Pascal
modules/sensors
+
+ Optical Flow minimum focus distance
+ This parameter defines the minimum distance from ground required for the optical flow sensor to operate reliably. The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus. *
+ modules/sensors
+
diff --git a/src/MissionManager/CameraCalc.h b/src/MissionManager/CameraCalc.h
index 2ec3b97bffb89d0ef560a8d05670d55987e50c64..2445975c65b4f841ffb4ff6536c37bba834a4aa7 100644
--- a/src/MissionManager/CameraCalc.h
+++ b/src/MissionManager/CameraCalc.h
@@ -49,6 +49,14 @@ public:
Fact* adjustedFootprintSide (void) { return &_adjustedFootprintSideFact; }
Fact* adjustedFootprintFrontal (void) { return &_adjustedFootprintFrontalFact; }
+ const Fact* valueSetIsDistance (void) const { return &_valueSetIsDistanceFact; }
+ const Fact* distanceToSurface (void) const { return &_distanceToSurfaceFact; }
+ const Fact* imageDensity (void) const { return &_imageDensityFact; }
+ const Fact* frontalOverlap (void) const { return &_frontalOverlapFact; }
+ const Fact* sideOverlap (void) const { return &_sideOverlapFact; }
+ const Fact* adjustedFootprintSide (void) const { return &_adjustedFootprintSideFact; }
+ const Fact* adjustedFootprintFrontal (void) const { return &_adjustedFootprintFrontalFact; }
+
bool isManualCamera (void) { return cameraName() == manualCameraName(); }
double imageFootprintSide (void) const { return _imageFootprintSide; }
double imageFootprintFrontal (void) const { return _imageFootprintFrontal; }
diff --git a/src/MissionManager/ComplexMissionItem.h b/src/MissionManager/ComplexMissionItem.h
index 10ae81c92314137999302b2ef05c67095a5d5336..bc27fe7f80856a77f750925fb21b734bcc5fab0a 100644
--- a/src/MissionManager/ComplexMissionItem.h
+++ b/src/MissionManager/ComplexMissionItem.h
@@ -47,9 +47,9 @@ public:
static const char* jsonComplexItemTypeKey;
signals:
- void complexDistanceChanged (double complexDistance);
+ void complexDistanceChanged (void);
void greatestDistanceToChanged (void);
- void additionalTimeDelayChanged (double additionalTimeDelay);
+ void additionalTimeDelayChanged (void);
};
#endif
diff --git a/src/MissionManager/CorridorScan.SettingsGroup.json b/src/MissionManager/CorridorScan.SettingsGroup.json
new file mode 100644
index 0000000000000000000000000000000000000000..29a5eb62a73db448985169695ced9205c0dd129d
--- /dev/null
+++ b/src/MissionManager/CorridorScan.SettingsGroup.json
@@ -0,0 +1,46 @@
+[
+{
+ "name": "Altitude",
+ "shortDescription": "Altitude for the bottom layer of the structure scan.",
+ "type": "double",
+ "units": "m",
+ "decimalPlaces": 1,
+ "defaultValue": 50
+},
+{
+ "name": "CorridorWidth",
+ "shortDescription": "Corridor width. Specify 0 width for a single pass scan.",
+ "type": "double",
+ "units": "m",
+ "min": 0,
+ "decimalPlaces": 1,
+ "defaultValue": 50
+},
+{
+ "name": "Trigger distance",
+ "shortDescription": "Distance between each triggering of the camera. 0 specifies not camera trigger.",
+ "type": "double",
+ "decimalPlaces": 2,
+ "min": 0,
+ "units": "m",
+ "defaultValue": 25
+},
+{
+ "name": "GridSpacing",
+ "shortDescription": "Amount of spacing in between parallel grid lines.",
+ "type": "double",
+ "decimalPlaces": 2,
+ "min": 0.1,
+ "units": "m",
+ "defaultValue": 30
+},
+{
+ "name": "TurnaroundDist",
+ "shortDescription": "Amount of additional distance to add outside the grid area for vehicle turnaround.",
+ "type": "double",
+ "decimalPlaces": 2,
+ "min": 0,
+ "units": "m",
+ "defaultValue": 30
+}
+]
diff --git a/src/MissionManager/CorridorScanComplexItem.cc b/src/MissionManager/CorridorScanComplexItem.cc
new file mode 100644
index 0000000000000000000000000000000000000000..d3ea05a6c9299fb3270ce76df450af88760895fe
--- /dev/null
+++ b/src/MissionManager/CorridorScanComplexItem.cc
@@ -0,0 +1,418 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "CorridorScanComplexItem.h"
+#include "JsonHelper.h"
+#include "MissionController.h"
+#include "QGCGeo.h"
+#include "QGroundControlQmlGlobal.h"
+#include "QGCQGeoCoordinate.h"
+#include "SettingsManager.h"
+#include "AppSettings.h"
+#include "QGCQGeoCoordinate.h"
+
+#include
+
+QGC_LOGGING_CATEGORY(CorridorScanComplexItemLog, "CorridorScanComplexItemLog")
+
+const char* CorridorScanComplexItem::_corridorWidthFactName = "CorridorWidth";
+
+const char* CorridorScanComplexItem::jsonComplexItemTypeValue = "CorridorScan";
+const char* CorridorScanComplexItem::_jsonCameraCalcKey = "CameraCalc";
+
+QMap CorridorScanComplexItem::_metaDataMap;
+
+CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, QObject* parent)
+ : ComplexMissionItem (vehicle, parent)
+ , _sequenceNumber (0)
+ , _dirty (false)
+ , _corridorWidthFact (0, _corridorWidthFactName, FactMetaData::valueTypeDouble)
+ , _ignoreRecalc (false)
+ , _scanDistance (0.0)
+ , _cameraShots (0)
+ , _cameraMinTriggerInterval (0)
+ , _cameraCalc (vehicle)
+{
+ _editorQml = "qrc:/qml/CorridorScanEditor.qml";
+
+ if (_metaDataMap.isEmpty()) {
+ _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CorridorScan.SettingsGroup.json"), NULL /* QObject parent */);
+ }
+
+ _corridorWidthFact.setMetaData(_metaDataMap[_corridorWidthFactName]);
+
+ _corridorWidthFact.setRawValue(_corridorWidthFact.rawDefaultValue());
+
+ connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_setDirty);
+ connect(&_corridorPolyline, &QGCMapPolyline::pathChanged, this, &CorridorScanComplexItem::_setDirty);
+ connect(this, &CorridorScanComplexItem::altitudeRelativeChanged, this, &CorridorScanComplexItem::_setDirty);
+
+ connect(this, &CorridorScanComplexItem::altitudeRelativeChanged, this, &CorridorScanComplexItem::coordinateHasRelativeAltitudeChanged);
+ connect(this, &CorridorScanComplexItem::altitudeRelativeChanged, this, &CorridorScanComplexItem::exitCoordinateHasRelativeAltitudeChanged);
+
+ connect(&_corridorPolyline, &QGCMapPolyline::dirtyChanged, this, &CorridorScanComplexItem::_polylineDirtyChanged);
+ connect(&_corridorPolyline, &QGCMapPolyline::countChanged, this, &CorridorScanComplexItem::_polylineCountChanged);
+
+ connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &CorridorScanComplexItem::_rebuildTransects);
+
+ connect(&_corridorPolyline, &QGCMapPolyline::pathChanged, this, &CorridorScanComplexItem::_rebuildCorridor);
+ connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_rebuildCorridor);
+
+ connect(&_corridorPolyline, &QGCMapPolyline::countChanged, this, &CorridorScanComplexItem::_signalLastSequenceNumberChanged);
+ connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_signalLastSequenceNumberChanged);
+ connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &CorridorScanComplexItem::_signalLastSequenceNumberChanged);
+
+ connect(&_corridorPolygon, &QGCMapPolygon::pathChanged, this, &CorridorScanComplexItem::coveredAreaChanged);
+
+ connect(this, &CorridorScanComplexItem::transectPointsChanged, this, &CorridorScanComplexItem::complexDistanceChanged);
+ connect(this, &CorridorScanComplexItem::transectPointsChanged, this, &CorridorScanComplexItem::greatestDistanceToChanged);
+
+ _rebuildCorridor();
+}
+
+void CorridorScanComplexItem::_setScanDistance(double scanDistance)
+{
+ if (!qFuzzyCompare(_scanDistance, scanDistance)) {
+ _scanDistance = scanDistance;
+ emit complexDistanceChanged();
+ }
+}
+
+void CorridorScanComplexItem::_setCameraShots(int cameraShots)
+{
+ if (_cameraShots != cameraShots) {
+ _cameraShots = cameraShots;
+ emit cameraShotsChanged();
+ }
+}
+
+void CorridorScanComplexItem::_clearInternal(void)
+{
+ setDirty(true);
+
+ emit specifiesCoordinateChanged();
+ emit lastSequenceNumberChanged(lastSequenceNumber());
+}
+
+void CorridorScanComplexItem::_polylineCountChanged(int count)
+{
+ Q_UNUSED(count);
+ emit lastSequenceNumberChanged(lastSequenceNumber());
+}
+
+int CorridorScanComplexItem::lastSequenceNumber(void) const
+{
+ return _sequenceNumber + ((_corridorPolyline.count() + 2 /* trigger start/stop */) * _transectCount());
+}
+
+void CorridorScanComplexItem::setDirty(bool dirty)
+{
+ if (_dirty != dirty) {
+ _dirty = dirty;
+ emit dirtyChanged(_dirty);
+ }
+}
+
+void CorridorScanComplexItem::save(QJsonArray& missionItems)
+{
+ QJsonObject saveObject;
+
+ saveObject[JsonHelper::jsonVersionKey] = 1;
+ saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
+ saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
+ saveObject[_corridorWidthFactName] = _corridorWidthFact.rawValue().toDouble();
+
+ QJsonObject cameraCalcObject;
+ _cameraCalc.save(cameraCalcObject);
+ saveObject[_jsonCameraCalcKey] = cameraCalcObject;
+
+ _corridorPolyline.saveToJson(saveObject);
+
+ missionItems.append(saveObject);
+}
+
+void CorridorScanComplexItem::setSequenceNumber(int sequenceNumber)
+{
+ if (_sequenceNumber != sequenceNumber) {
+ _sequenceNumber = sequenceNumber;
+ emit sequenceNumberChanged(sequenceNumber);
+ emit lastSequenceNumberChanged(lastSequenceNumber());
+ }
+}
+
+bool CorridorScanComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
+{
+ QList keyInfoList = {
+ { JsonHelper::jsonVersionKey, QJsonValue::Double, true },
+ { VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
+ { ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
+ { _corridorWidthFactName, QJsonValue::Double, true },
+ { QGCMapPolyline::jsonPolylineKey, QJsonValue::Array, true },
+ { _jsonCameraCalcKey, QJsonValue::Object, true },
+ };
+ if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
+ return false;
+ }
+
+ _corridorPolyline.clear();
+
+ QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
+ QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
+ if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) {
+ errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(qgcApp()->applicationName()).arg(itemType).arg(complexType);
+ return false;
+ }
+
+ int version = complexObject[JsonHelper::jsonVersionKey].toInt();
+ if (version != 1) {
+ errorString = tr("%1 complex item version %2 not supported").arg(jsonComplexItemTypeValue).arg(version);
+ return false;
+ }
+
+ setSequenceNumber(sequenceNumber);
+
+ if (!_cameraCalc.load(complexObject[_jsonCameraCalcKey].toObject(), errorString)) {
+ return false;
+ }
+
+ if (!_corridorPolyline.loadFromJson(complexObject, true /* required */, errorString)) {
+ _corridorPolyline.clear();
+ _rebuildCorridor();
+ return false;
+ }
+
+ _rebuildCorridor();
+
+ return true;
+}
+
+double CorridorScanComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
+{
+ double greatestDistance = 0.0;
+ for (int i=0; i<_transectPoints.count(); i++) {
+ QGeoCoordinate vertex = _transectPoints[i].value();
+ double distance = vertex.distanceTo(other);
+ if (distance > greatestDistance) {
+ greatestDistance = distance;
+ }
+ }
+
+ return greatestDistance;
+}
+
+bool CorridorScanComplexItem::specifiesCoordinate(void) const
+{
+ return _corridorPolyline.count() > 1;
+}
+
+int CorridorScanComplexItem::_transectCount(void) const
+{
+ double transectSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
+ double fullWidth = _corridorWidthFact.rawValue().toDouble();
+ return fullWidth > 0.0 ? qCeil(fullWidth / transectSpacing) : 1;
+}
+
+void CorridorScanComplexItem::appendMissionItems(QList& items, QObject* missionItemParent)
+{
+ int seqNum = _sequenceNumber;
+ int pointIndex = 0;
+
+ while (pointIndex < _transectPoints.count()) {
+ bool addTrigger = true;
+
+ for (int i=0; i<_corridorPolyline.count(); i++) {
+ QGeoCoordinate vertexCoord = _transectPoints[pointIndex++].value();
+
+ MissionItem* item = new MissionItem(seqNum++,
+ MAV_CMD_NAV_WAYPOINT,
+ MAV_FRAME_GLOBAL_RELATIVE_ALT, // FIXME: Manual camera should support AMSL alt
+ 0, // No hold time
+ 0.0, // No acceptance radius specified
+ 0.0, // Pass through waypoint
+ std::numeric_limits::quiet_NaN(), // Yaw unchanged
+ vertexCoord.latitude(),
+ vertexCoord.longitude(),
+ _cameraCalc.distanceToSurface()->rawValue().toDouble(), // Altitude
+ true, // autoContinue
+ false, // isCurrentItem
+ missionItemParent);
+ items.append(item);
+
+ if (addTrigger) {
+ addTrigger = false;
+ item = new MissionItem(seqNum++,
+ MAV_CMD_DO_SET_CAM_TRIGG_DIST,
+ MAV_FRAME_MISSION,
+ _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(), // trigger distance
+ 0, // shutter integration (ignore)
+ 1, // trigger immediately when starting
+ 0, 0, 0, 0, // param 4-7 unused
+ true, // autoContinue
+ false, // isCurrentItem
+ missionItemParent);
+ items.append(item);
+ }
+ }
+
+ MissionItem* item = new MissionItem(seqNum++,
+ MAV_CMD_DO_SET_CAM_TRIGG_DIST,
+ MAV_FRAME_MISSION,
+ 0, // stop triggering
+ 0, // shutter integration (ignore)
+ 0, // trigger immediately when starting
+ 0, 0, 0, 0, // param 4-7 unused
+ true, // autoContinue
+ false, // isCurrentItem
+ missionItemParent);
+ items.append(item);
+ }
+
+}
+
+void CorridorScanComplexItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
+{
+ ComplexMissionItem::setMissionFlightStatus(missionFlightStatus);
+ if (!qFuzzyCompare(_cruiseSpeed, missionFlightStatus.vehicleSpeed)) {
+ _cruiseSpeed = missionFlightStatus.vehicleSpeed;
+ emit timeBetweenShotsChanged();
+ }
+}
+
+void CorridorScanComplexItem::_setDirty(void)
+{
+ setDirty(true);
+}
+
+void CorridorScanComplexItem::applyNewAltitude(double newAltitude)
+{
+ Q_UNUSED(newAltitude);
+ // FIXME: NYI
+ //_altitudeFact.setRawValue(newAltitude);
+}
+
+void CorridorScanComplexItem::_polylineDirtyChanged(bool dirty)
+{
+ if (dirty) {
+ setDirty(true);
+ }
+}
+
+double CorridorScanComplexItem::timeBetweenShots(void)
+{
+ return _cruiseSpeed == 0 ? 0 : _cameraCalc.adjustedFootprintSide()->rawValue().toDouble() / _cruiseSpeed;
+}
+
+void CorridorScanComplexItem::_updateCoordinateAltitudes(void)
+{
+ emit coordinateChanged(coordinate());
+ emit exitCoordinateChanged(exitCoordinate());
+}
+
+void CorridorScanComplexItem::rotateEntryPoint(void)
+{
+#if 0
+ _entryVertex++;
+ if (_entryVertex >= _flightPolygon.count()) {
+ _entryVertex = 0;
+ }
+ emit coordinateChanged(coordinate());
+ emit exitCoordinateChanged(exitCoordinate());
+#endif
+}
+
+void CorridorScanComplexItem::_rebuildCorridorPolygon(void)
+{
+ if (_corridorPolyline.count() < 2) {
+ _corridorPolygon.clear();
+ return;
+ }
+
+ double halfWidth = _corridorWidthFact.rawValue().toDouble() / 2.0;
+
+ QList firstSideVertices = _corridorPolyline.offsetPolyline(halfWidth);
+ QList secondSideVertices = _corridorPolyline.offsetPolyline(-halfWidth);
+
+ _corridorPolygon.clear();
+ foreach (const QGeoCoordinate& vertex, firstSideVertices) {
+ _corridorPolygon.appendVertex(vertex);
+ }
+ for (int i=secondSideVertices.count() - 1; i >= 0; i--) {
+ _corridorPolygon.appendVertex(secondSideVertices[i]);
+ }
+}
+
+void CorridorScanComplexItem::_rebuildTransects(void)
+{
+
+ _transectPoints.clear();
+
+ double transectSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
+ double fullWidth = _corridorWidthFact.rawValue().toDouble();
+ double halfWidth = fullWidth / 2.0;
+ int transectCount = _transectCount();
+ double normalizedTransectPosition = transectSpacing / 2.0;
+
+ _cameraShots = 0;
+ int singleTransectImageCount = qCeil(_corridorPolyline.length() / _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble());
+
+ bool reverseVertices = false;
+ for (int i=0; i transectVertices = _corridorPolyline.offsetPolyline(offsetDistance);
+ if (reverseVertices) {
+ reverseVertices = false;
+ QList reversedVertices;
+ for (int j=transectVertices.count()-1; j>=0; j--) {
+ reversedVertices.append(transectVertices[j]);
+ }
+ transectVertices = reversedVertices;
+ } else {
+ reverseVertices = true;
+ }
+ for (int i=0; i() : QGeoCoordinate();
+ _exitCoordinate = _transectPoints.count() ? _transectPoints.last().value() : QGeoCoordinate();
+
+ emit transectPointsChanged();
+ emit cameraShotsChanged();
+ emit coordinateChanged(_coordinate);
+ emit exitCoordinateChanged(_exitCoordinate);
+}
+
+void CorridorScanComplexItem::_rebuildCorridor(void)
+{
+ _rebuildCorridorPolygon();
+ _rebuildTransects();
+}
+
+void CorridorScanComplexItem::_signalLastSequenceNumberChanged(void)
+{
+ emit lastSequenceNumberChanged(lastSequenceNumber());
+}
+
+double CorridorScanComplexItem::coveredArea(void) const
+{
+ return _corridorPolygon.area();
+}
diff --git a/src/MissionManager/CorridorScanComplexItem.h b/src/MissionManager/CorridorScanComplexItem.h
new file mode 100644
index 0000000000000000000000000000000000000000..751ad2c4bc4349486c1a077d2845da35eebd0fe4
--- /dev/null
+++ b/src/MissionManager/CorridorScanComplexItem.h
@@ -0,0 +1,138 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include "ComplexMissionItem.h"
+#include "MissionItem.h"
+#include "SettingsFact.h"
+#include "QGCLoggingCategory.h"
+#include "QGCMapPolyline.h"
+#include "QGCMapPolygon.h"
+#include "CameraCalc.h"
+
+Q_DECLARE_LOGGING_CATEGORY(CorridorScanComplexItemLog)
+
+class CorridorScanComplexItem : public ComplexMissionItem
+{
+ Q_OBJECT
+
+public:
+ CorridorScanComplexItem(Vehicle* vehicle, QObject* parent = NULL);
+
+ Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
+ Q_PROPERTY(QGCMapPolyline* corridorPolyline READ corridorPolyline CONSTANT)
+ Q_PROPERTY(QGCMapPolygon* corridorPolygon READ corridorPolygon CONSTANT)
+ Q_PROPERTY(Fact* corridorWidth READ corridorWidth CONSTANT)
+ Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
+ Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
+ Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
+ Q_PROPERTY(double cameraMinTriggerInterval MEMBER _cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged)
+ Q_PROPERTY(QVariantList transectPoints READ transectPoints NOTIFY transectPointsChanged)
+
+ CameraCalc* cameraCalc (void) { return &_cameraCalc; }
+ QGCMapPolyline* corridorPolyline(void) { return &_corridorPolyline; }
+ QGCMapPolygon* corridorPolygon (void) { return &_corridorPolygon; }
+ Fact* corridorWidth (void) { return &_corridorWidthFact; }
+ QVariantList transectPoints (void) { return _transectPoints; }
+
+ int cameraShots (void) const { return _cameraShots; }
+ double timeBetweenShots (void);
+ double coveredArea (void) const;
+
+ Q_INVOKABLE void rotateEntryPoint(void);
+
+ // Overrides from ComplexMissionItem
+
+ double complexDistance (void) const final { return _scanDistance; }
+ int lastSequenceNumber (void) const final;
+ bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
+ double greatestDistanceTo (const QGeoCoordinate &other) const final;
+ QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); }
+
+ // Overrides from VisualMissionItem
+
+ bool dirty (void) const final { return _dirty; }
+ bool isSimpleItem (void) const final { return false; }
+ bool isStandaloneCoordinate (void) const final { return false; }
+ bool specifiesCoordinate (void) const final;
+ bool specifiesAltitudeOnly (void) const final { return false; }
+ QString commandDescription (void) const final { return tr("Corridor Scan"); }
+ QString commandName (void) const final { return tr("Corridor Scan"); }
+ QString abbreviation (void) const final { return "S"; }
+ QGeoCoordinate coordinate (void) const final { return _coordinate; }
+ QGeoCoordinate exitCoordinate (void) const final { return _exitCoordinate; }
+ int sequenceNumber (void) const final { return _sequenceNumber; }
+ double specifiedFlightSpeed (void) final { return std::numeric_limits::quiet_NaN(); }
+ double specifiedGimbalYaw (void) final { return std::numeric_limits::quiet_NaN(); }
+ double specifiedGimbalPitch (void) final { return std::numeric_limits::quiet_NaN(); }
+ void appendMissionItems (QList& items, QObject* missionItemParent) final;
+ void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
+ void applyNewAltitude (double newAltitude) final;
+
+ bool coordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; }
+ bool exitCoordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; }
+ bool exitCoordinateSameAsEntry (void) const final { return false; }
+
+ void setDirty (bool dirty) final;
+ void setCoordinate (const QGeoCoordinate& coordinate) final { Q_UNUSED(coordinate); }
+ void setSequenceNumber (int sequenceNumber) final;
+ void save (QJsonArray& missionItems) final;
+
+ static const char* jsonComplexItemTypeValue;
+
+signals:
+ void cameraShotsChanged (void);
+ void timeBetweenShotsChanged (void);
+ void cameraMinTriggerIntervalChanged(double cameraMinTriggerInterval);
+ void altitudeRelativeChanged (bool altitudeRelative);
+ void transectPointsChanged (void);
+ void coveredAreaChanged (void);
+
+private slots:
+ void _setDirty (void);
+ void _polylineDirtyChanged (bool dirty);
+ void _polylineCountChanged (int count);
+ void _clearInternal (void);
+ void _updateCoordinateAltitudes (void);
+ void _signalLastSequenceNumberChanged (void);
+ void _rebuildCorridor (void);
+ void _rebuildTransects (void);
+
+private:
+ void _setExitCoordinate (const QGeoCoordinate& coordinate);
+ void _setScanDistance (double scanDistance);
+ void _setCameraShots (int cameraShots);
+ double _triggerDistance (void) const;
+ int _transectCount (void) const;
+ void _rebuildCorridorPolygon(void);
+
+ int _sequenceNumber;
+ bool _dirty;
+ QGeoCoordinate _coordinate;
+ QGeoCoordinate _exitCoordinate;
+ QGCMapPolyline _corridorPolyline;
+ QGCMapPolygon _corridorPolygon;
+ Fact _corridorWidthFact;
+ QVariantList _transectPoints;
+
+ bool _ignoreRecalc;
+ double _scanDistance;
+ int _cameraShots;
+ double _timeBetweenShots;
+ double _cameraMinTriggerInterval;
+ double _cruiseSpeed;
+ CameraCalc _cameraCalc;
+
+ static QMap _metaDataMap;
+
+ static const char* _corridorWidthFactName;
+
+ static const char* _jsonCameraCalcKey;
+};
diff --git a/src/MissionManager/CorridorScanComplexItemTest.cc b/src/MissionManager/CorridorScanComplexItemTest.cc
new file mode 100644
index 0000000000000000000000000000000000000000..32ce4e6dd1c343c9ccdecb059cad26b7ab9edc82
--- /dev/null
+++ b/src/MissionManager/CorridorScanComplexItemTest.cc
@@ -0,0 +1,217 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "CorridorScanComplexItemTest.h"
+#include "QGCApplication.h"
+
+CorridorScanComplexItemTest::CorridorScanComplexItemTest(void)
+ : _offlineVehicle(NULL)
+{
+ _linePoints << QGeoCoordinate(47.633550640000003, -122.08982199)
+ << QGeoCoordinate(47.634129020000003, -122.08887249)
+ << QGeoCoordinate(47.633619320000001, -122.08811074);
+}
+
+void CorridorScanComplexItemTest::init(void)
+{
+ UnitTest::init();
+
+ _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
+ _corridorItem->setDirty(false);
+ _mapPolyline = _corridorItem->corridorPolyline();
+
+ _rgSignals[complexDistanceChangedIndex] = SIGNAL(complexDistanceChanged());
+ _rgSignals[greatestDistanceToChangedIndex] = SIGNAL(greatestDistanceToChanged());
+ _rgSignals[additionalTimeDelayChangedIndex] = SIGNAL(additionalTimeDelayChanged());
+ _rgSignals[transectPointsChangedIndex] = SIGNAL(transectPointsChanged());
+ _rgSignals[cameraShotsChangedIndex] = SIGNAL(cameraShotsChanged());
+ _rgSignals[coveredAreaChangedIndex] = SIGNAL(coveredAreaChanged());
+ _rgSignals[timeBetweenShotsChangedIndex] = SIGNAL(timeBetweenShotsChanged());
+ _rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
+
+ _multiSpy = new MultiSignalSpy();
+ QCOMPARE(_multiSpy->init(_corridorItem, _rgSignals, _cSignals), true);
+
+ _rgCorridorPolygonSignals[corridorPolygonPathChangedIndex] = SIGNAL(pathChanged());
+
+ _multiSpyCorridorPolygon = new MultiSignalSpy();
+ QCOMPARE(_multiSpyCorridorPolygon->init(_corridorItem->corridorPolygon(), _rgCorridorPolygonSignals, _cCorridorPolygonSignals), true);
+}
+
+void CorridorScanComplexItemTest::cleanup(void)
+{
+ delete _corridorItem;
+ delete _offlineVehicle;
+ delete _multiSpy;
+}
+
+void CorridorScanComplexItemTest::_testDirty(void)
+{
+ QVERIFY(!_corridorItem->dirty());
+ _corridorItem->setDirty(false);
+ QVERIFY(!_corridorItem->dirty());
+ QVERIFY(_multiSpy->checkNoSignals());
+
+ _corridorItem->setDirty(true);
+ QVERIFY(_corridorItem->dirty());
+ QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
+ QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
+ _multiSpy->clearAllSignals();
+
+ _corridorItem->setDirty(false);
+ QVERIFY(!_corridorItem->dirty());
+ QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
+ QVERIFY(!_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
+ _multiSpy->clearAllSignals();
+
+ // These facts should set dirty when changed
+ QList rgFacts;
+#if 0
+ rgFacts << _corridorItem->gridAltitude() << _corridorItem->gridAngle() << _corridorItem->gridSpacing() << _corridorItem->turnaroundDist() << _corridorItem->cameraTriggerDistance() <<
+ _corridorItem->gridAltitudeRelative() << _corridorItem->cameraTriggerInTurnaround() << _corridorItem->hoverAndCapture();
+#endif
+ rgFacts << _corridorItem->corridorWidth();
+ foreach(Fact* fact, rgFacts) {
+ qDebug() << fact->name();
+ QVERIFY(!_corridorItem->dirty());
+ if (fact->typeIsBool()) {
+ fact->setRawValue(!fact->rawValue().toBool());
+ } else {
+ fact->setRawValue(fact->rawValue().toDouble() + 1);
+ }
+ QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
+ QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
+ _corridorItem->setDirty(false);
+ _multiSpy->clearAllSignals();
+ }
+ rgFacts.clear();
+
+ // These facts should not change dirty bit
+#if 0
+ rgFacts << _corridorItem->groundResolution() << _corridorItem->frontalOverlap() << _corridorItem->sideOverlap() << _corridorItem->cameraSensorWidth() << _corridorItem->cameraSensorHeight() <<
+ _corridorItem->cameraResolutionWidth() << _corridorItem->cameraResolutionHeight() << _corridorItem->cameraFocalLength() << _corridorItem->cameraOrientationLandscape() <<
+ _corridorItem->fixedValueIsAltitude() << _corridorItem->camera() << _corridorItem->manualGrid();
+#endif
+ foreach(Fact* fact, rgFacts) {
+ qDebug() << fact->name();
+ QVERIFY(!_corridorItem->dirty());
+ if (fact->typeIsBool()) {
+ fact->setRawValue(!fact->rawValue().toBool());
+ } else {
+ fact->setRawValue(fact->rawValue().toDouble() + 1);
+ }
+ QVERIFY(_multiSpy->checkNoSignalByMask(dirtyChangedMask));
+ QVERIFY(!_corridorItem->dirty());
+ _multiSpy->clearAllSignals();
+ }
+ rgFacts.clear();
+}
+
+void CorridorScanComplexItemTest::_testCameraTrigger(void)
+{
+#if 0
+ QCOMPARE(_corridorItem->property("cameraTrigger").toBool(), true);
+
+ // Set up a grid
+
+ for (int i=0; i<3; i++) {
+ _mapPolyline->appendVertex(_linePoints[i]);
+ }
+
+ _corridorItem->setDirty(false);
+ _multiSpy->clearAllSignals();
+
+ int lastSeq = _corridorItem->lastSequenceNumber();
+ QVERIFY(lastSeq > 0);
+
+ // Turning off camera triggering should remove two camera trigger mission items, this should trigger:
+ // lastSequenceNumberChanged
+ // dirtyChanged
+
+ _corridorItem->setProperty("cameraTrigger", false);
+ QVERIFY(_multiSpy->checkOnlySignalByMask(lastSequenceNumberChangedMask | dirtyChangedMask | cameraTriggerChangedMask));
+ QCOMPARE(_multiSpy->pullIntFromSignalIndex(lastSequenceNumberChangedIndex), lastSeq - 2);
+
+ _corridorItem->setDirty(false);
+ _multiSpy->clearAllSignals();
+
+ // Turn on camera triggering and make sure things go back to previous count
+
+ _corridorItem->setProperty("cameraTrigger", true);
+ QVERIFY(_multiSpy->checkOnlySignalByMask(lastSequenceNumberChangedMask | dirtyChangedMask | cameraTriggerChangedMask));
+ QCOMPARE(_multiSpy->pullIntFromSignalIndex(lastSequenceNumberChangedIndex), lastSeq);
+#endif
+}
+
+void CorridorScanComplexItemTest::_setPolyline(void)
+{
+ for (int i=0; i<_linePoints.count(); i++) {
+ QGeoCoordinate& vertex = _linePoints[i];
+ _mapPolyline->appendVertex(vertex);
+ }
+}
+
+#if 0
+void CorridorScanComplexItemTest::_testEntryLocation(void)
+{
+ _setPolygon();
+
+ for (double gridAngle=-360.0; gridAngle<=360.0; gridAngle++) {
+ _corridorItem->gridAngle()->setRawValue(gridAngle);
+
+ QList rgSeenEntryCoords;
+ QList rgEntryLocation;
+ rgEntryLocation << SurveyMissionItem::EntryLocationTopLeft
+ << SurveyMissionItem::EntryLocationTopRight
+ << SurveyMissionItem::EntryLocationBottomLeft
+ << SurveyMissionItem::EntryLocationBottomRight;
+
+ // Validate that each entry location is unique
+ for (int i=0; igridEntryLocation()->setRawValue(entryLocation);
+ QVERIFY(!rgSeenEntryCoords.contains(_corridorItem->coordinate()));
+ rgSeenEntryCoords << _corridorItem->coordinate();
+ }
+ rgSeenEntryCoords.clear();
+ }
+}
+#endif
+
+void CorridorScanComplexItemTest::_testItemCount(void)
+{
+ QList items;
+
+ _setPolyline();
+
+// _corridorItem->cameraTriggerInTurnaround()->setRawValue(false);
+ _corridorItem->appendMissionItems(items, this);
+ QCOMPARE(items.count(), _corridorItem->lastSequenceNumber());
+ items.clear();
+}
+
+void CorridorScanComplexItemTest::_testPathChanges(void)
+{
+ _setPolyline();
+ _corridorItem->setDirty(false);
+ _multiSpy->clearAllSignals();
+ _multiSpyCorridorPolygon->clearAllSignals();
+
+ QGeoCoordinate vertex = _mapPolyline->vertexCoordinate(1);
+ vertex.setLatitude(vertex.latitude() + 0.01);
+ _mapPolyline->adjustVertex(1, vertex);
+
+ QVERIFY(_corridorItem->dirty());
+ QVERIFY(_multiSpy->checkOnlySignalsByMask(dirtyChangedMask | transectPointsChangedMask | cameraShotsChangedMask | coveredAreaChangedMask | complexDistanceChangedMask | greatestDistanceToChangedMask));
+ QVERIFY(_multiSpyCorridorPolygon->checkSignalsByMask(corridorPolygonPathChangedMask));
+ _multiSpy->clearAllSignals();
+}
diff --git a/src/MissionManager/CorridorScanComplexItemTest.h b/src/MissionManager/CorridorScanComplexItemTest.h
new file mode 100644
index 0000000000000000000000000000000000000000..c0dddd5d0e1aac207fc88cb5e47c3543cfcf2f72
--- /dev/null
+++ b/src/MissionManager/CorridorScanComplexItemTest.h
@@ -0,0 +1,84 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include "UnitTest.h"
+#include "TCPLink.h"
+#include "MultiSignalSpy.h"
+#include "CorridorScanComplexItem.h"
+
+#include
+
+class CorridorScanComplexItemTest : public UnitTest
+{
+ Q_OBJECT
+
+public:
+ CorridorScanComplexItemTest(void);
+
+protected:
+ void init(void) final;
+ void cleanup(void) final;
+
+private slots:
+ void _testDirty(void);
+ void _testCameraTrigger(void);
+// void _testEntryLocation(void);
+ void _testItemCount(void);
+ void _testPathChanges(void);
+
+private:
+ void _setPolyline(void);
+
+ enum {
+ complexDistanceChangedIndex = 0,
+ greatestDistanceToChangedIndex,
+ additionalTimeDelayChangedIndex,
+ transectPointsChangedIndex,
+ cameraShotsChangedIndex,
+ coveredAreaChangedIndex,
+ timeBetweenShotsChangedIndex,
+ dirtyChangedIndex,
+ maxSignalIndex
+ };
+
+ enum {
+ complexDistanceChangedMask = 1 << complexDistanceChangedIndex,
+ greatestDistanceToChangedMask = 1 << greatestDistanceToChangedIndex,
+ additionalTimeDelayChangedMask = 1 << additionalTimeDelayChangedIndex,
+ transectPointsChangedMask = 1 << transectPointsChangedIndex,
+ cameraShotsChangedMask = 1 << cameraShotsChangedIndex,
+ coveredAreaChangedMask = 1 << coveredAreaChangedIndex,
+ timeBetweenShotsChangedMask = 1 << timeBetweenShotsChangedIndex,
+ dirtyChangedMask = 1 << dirtyChangedIndex
+ };
+
+ static const size_t _cSignals = maxSignalIndex;
+ const char* _rgSignals[_cSignals];
+
+ enum {
+ corridorPolygonPathChangedIndex = 0,
+ maxCorridorPolygonSignalIndex
+ };
+
+ enum {
+ corridorPolygonPathChangedMask = 1 << corridorPolygonPathChangedIndex,
+ };
+
+ static const size_t _cCorridorPolygonSignals = maxCorridorPolygonSignalIndex;
+ const char* _rgCorridorPolygonSignals[_cCorridorPolygonSignals];
+
+ Vehicle* _offlineVehicle;
+ MultiSignalSpy* _multiSpy;
+ MultiSignalSpy* _multiSpyCorridorPolygon;
+ CorridorScanComplexItem* _corridorItem;
+ QGCMapPolyline* _mapPolyline;
+ QList _linePoints;
+};
diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc
index 0a4d899544d22a5d03ddb2ab2ed82864b7bf556c..5d8234ca1d8c94776169abfaa3a7b95ab4409267 100644
--- a/src/MissionManager/MissionController.cc
+++ b/src/MissionManager/MissionController.cc
@@ -19,7 +19,7 @@
#include "SurveyMissionItem.h"
#include "FixedWingLandingComplexItem.h"
#include "StructureScanComplexItem.h"
-#include "StructureScanComplexItem.h"
+#include "CorridorScanComplexItem.h"
#include "JsonHelper.h"
#include "ParameterManager.h"
#include "QGroundControlQmlGlobal.h"
@@ -63,6 +63,7 @@ MissionController::MissionController(PlanMasterController* masterController, QOb
, _surveyMissionItemName(tr("Survey"))
, _fwLandingMissionItemName(tr("Fixed Wing Landing"))
, _structureScanMissionItemName(tr("Structure Scan"))
+ , _corridorScanMissionItemName(tr("Corridor Scan"))
, _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings())
, _progressPct(0)
, _currentPlanViewIndex(-1)
@@ -388,22 +389,41 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int i)
{
ComplexMissionItem* newItem;
+ bool surveyStyleItem = false;
int sequenceNumber = _nextSequenceNumber();
if (itemName == _surveyMissionItemName) {
newItem = new SurveyMissionItem(_controllerVehicle, _visualItems);
newItem->setCoordinate(mapCenterCoordinate);
- // If the vehicle is known to have a gimbal then we automatically point the gimbal straight down if not already set
+ surveyStyleItem = true;
+ } else if (itemName == _fwLandingMissionItemName) {
+ newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
+ } else if (itemName == _structureScanMissionItemName) {
+ newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems);
+ } else if (itemName == _corridorScanMissionItemName) {
+ newItem = new CorridorScanComplexItem(_controllerVehicle, _visualItems);
+ surveyStyleItem = true;
+ } else {
+ qWarning() << "Internal error: Unknown complex item:" << itemName;
+ return sequenceNumber;
+ }
+
+ if (surveyStyleItem) {
bool rollSupported = false;
bool pitchSupported = false;
bool yawSupported = false;
+
+ // If the vehicle is known to have a gimbal then we automatically point the gimbal straight down if not already set
+
MissionSettingsItem* settingsItem = _visualItems->value(0);
CameraSection* cameraSection = settingsItem->cameraSection();
+
// Set camera to photo mode (leave alone if user already specified)
if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
cameraSection->setSpecifyCameraMode(true);
cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
}
+
// Point gimbal straight down
if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
// If the user already specified a gimbal angle leave it alone
@@ -412,14 +432,8 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
cameraSection->gimbalPitch()->setRawValue(-90.0);
}
}
- } else if (itemName == _fwLandingMissionItemName) {
- newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems);
- } else if (itemName == _structureScanMissionItemName) {
- newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems);
- } else {
- qWarning() << "Internal error: Unknown complex item:" << itemName;
- return sequenceNumber;
}
+
newItem->setSequenceNumber(sequenceNumber);
_initVisualItem(newItem);
@@ -437,17 +451,17 @@ void MissionController::removeMissionItem(int index)
return;
}
- bool surveyRemoved = _visualItems->value(index);
+ bool removeSurveyStyle = _visualItems->value(index) || _visualItems->value(index);
VisualMissionItem* item = qobject_cast(_visualItems->removeAt(index));
_deinitVisualItem(item);
item->deleteLater();
- if (surveyRemoved) {
- // Determine if the mission still has another survey in it
+ if (removeSurveyStyle) {
+ // Determine if the mission still has another survey style item in it
bool foundSurvey = false;
for (int i=1; i<_visualItems->count(); i++) {
- if (_visualItems->value(i)) {
+ if (_visualItems->value(i) || _visualItems->value(index)) {
foundSurvey = true;
break;
}
@@ -697,6 +711,15 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
visualItems->append(structureItem);
+ } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
+ qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
+ CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_controllerVehicle, visualItems);
+ if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
+ return false;
+ }
+ nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
+ qCDebug(MissionControllerLog) << "Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
+ visualItems->append(corridorItem);
} else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, visualItems);
@@ -1841,6 +1864,7 @@ QStringList MissionController::complexMissionItemNames(void) const
QStringList complexItems;
complexItems.append(_surveyMissionItemName);
+ complexItems.append(_corridorScanMissionItemName);
if (_controllerVehicle->fixedWing()) {
complexItems.append(_fwLandingMissionItemName);
}
diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h
index 1f2818823862dcb9bd834af176958c60a2d82f2d..390a4e8a62be8a3304959eea4d2168e90151068f 100644
--- a/src/MissionManager/MissionController.h
+++ b/src/MissionManager/MissionController.h
@@ -253,6 +253,7 @@ private:
QString _surveyMissionItemName;
QString _fwLandingMissionItemName;
QString _structureScanMissionItemName;
+ QString _corridorScanMissionItemName;
AppSettings* _appSettings;
double _progressPct;
int _currentPlanViewIndex;
diff --git a/src/MissionManager/PlanMasterController.cc b/src/MissionManager/PlanMasterController.cc
index e21b5607ebb7e51575729cc7a9db16462d28da8e..5f788998af9432b67c6aa795faac1d1167dbdae3 100644
--- a/src/MissionManager/PlanMasterController.cc
+++ b/src/MissionManager/PlanMasterController.cc
@@ -157,6 +157,11 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
void PlanMasterController::loadFromVehicle(void)
{
+ if (_managerVehicle->highLatencyLink()) {
+ qgcApp()->showMessage(tr("Download not supported on high latency links."));
+ return;
+ }
+
if (offline()) {
qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called while offline";
} else if (!_editMode) {
@@ -256,6 +261,11 @@ void PlanMasterController::_sendRallyPointsComplete(void)
void PlanMasterController::sendToVehicle(void)
{
+ if (_managerVehicle->highLatencyLink()) {
+ qgcApp()->showMessage(tr("Upload not supported on high latency links."));
+ return;
+ }
+
if (offline()) {
qCWarning(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle called while offline";
} else if (syncInProgress()) {
diff --git a/src/MissionManager/QGCMapPolygon.cc b/src/MissionManager/QGCMapPolygon.cc
index 18ae00fdfbc9bd9f90d48ed1b5f09a007f170d8b..3803e203ed08495ae8d2d3cb62dd9728999a143b 100644
--- a/src/MissionManager/QGCMapPolygon.cc
+++ b/src/MissionManager/QGCMapPolygon.cc
@@ -362,7 +362,7 @@ QGeoCoordinate QGCMapPolygon::vertexCoordinate(int vertex) const
}
}
-QList QGCMapPolygon::nedPolygon(void)
+QList QGCMapPolygon::nedPolygon(void) const
{
QList nedPolygon;
@@ -515,3 +515,19 @@ bool QGCMapPolygon::loadKMLFile(const QString& kmlFile)
return true;
}
+
+double QGCMapPolygon::area(void) const
+{
+ // https://www.mathopenref.com/coordpolygonarea2.html
+
+ double coveredArea = 0.0;
+ QList nedVertices = nedPolygon();
+ for (int i=0; i nedPolygon(void);
+ QList nedPolygon(void) const;
+
+ /// Returns the area of the polygon in meters squared
+ double area(void) const;
// Property methods
diff --git a/src/MissionManager/QGCMapPolygonTest.cc b/src/MissionManager/QGCMapPolygonTest.cc
index 679292ad3a4c202125450fa402c2a2c4bbe6e0ae..4de4c5ee8eabad481c549b18f08fe09b27a18824 100644
--- a/src/MissionManager/QGCMapPolygonTest.cc
+++ b/src/MissionManager/QGCMapPolygonTest.cc
@@ -205,17 +205,17 @@ void QGCMapPolygonTest::_testVertexManipulation(void)
void QGCMapPolygonTest::_testKMLLoad(void)
{
- QVERIFY(_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/GoodPolygon.kml")));
+ QVERIFY(_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/PolygonGood.kml")));
setExpectedMessageBox(QMessageBox::Ok);
- QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/BadXml.kml")));
+ QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/PolygonBadXml.kml")));
checkExpectedMessageBox();
setExpectedMessageBox(QMessageBox::Ok);
- QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/MissingPolygonNode.kml")));
+ QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/PolygonMissingNode.kml")));
checkExpectedMessageBox();
setExpectedMessageBox(QMessageBox::Ok);
- QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/BadCoordinatesNode.kml")));
+ QVERIFY(!_mapPolygon->loadKMLFile(QStringLiteral(":/unittest/PolygonBadCoordinatesNode.kml")));
checkExpectedMessageBox();
}
diff --git a/src/MissionManager/QGCMapPolyline.cc b/src/MissionManager/QGCMapPolyline.cc
new file mode 100644
index 0000000000000000000000000000000000000000..cb3a39ef8107a35e42d373b7a4d38d6a308ccf29
--- /dev/null
+++ b/src/MissionManager/QGCMapPolyline.cc
@@ -0,0 +1,440 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "QGCMapPolyline.h"
+#include "QGCGeo.h"
+#include "JsonHelper.h"
+#include "QGCQGeoCoordinate.h"
+#include "QGCApplication.h"
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+const char* QGCMapPolyline::jsonPolylineKey = "polyline";
+
+QGCMapPolyline::QGCMapPolyline(QObject* parent)
+ : QObject (parent)
+ , _dirty (false)
+ , _interactive (false)
+{
+ _init();
+}
+
+QGCMapPolyline::QGCMapPolyline(const QGCMapPolyline& other, QObject* parent)
+ : QObject (parent)
+ , _dirty (false)
+ , _interactive (false)
+{
+ *this = other;
+
+ _init();
+}
+
+const QGCMapPolyline& QGCMapPolyline::operator=(const QGCMapPolyline& other)
+{
+ clear();
+
+ QVariantList vertices = other.path();
+ for (int i=0; i());
+ }
+
+ setDirty(true);
+
+ return *this;
+}
+
+void QGCMapPolyline::_init(void)
+{
+ connect(&_polylineModel, &QmlObjectListModel::dirtyChanged, this, &QGCMapPolyline::_polylineModelDirtyChanged);
+ connect(&_polylineModel, &QmlObjectListModel::countChanged, this, &QGCMapPolyline::_polylineModelCountChanged);
+}
+
+void QGCMapPolyline::clear(void)
+{
+ _polylinePath.clear();
+ emit pathChanged();
+
+ _polylineModel.clearAndDeleteContents();
+
+ emit cleared();
+
+ setDirty(true);
+}
+
+void QGCMapPolyline::adjustVertex(int vertexIndex, const QGeoCoordinate coordinate)
+{
+ _polylinePath[vertexIndex] = QVariant::fromValue(coordinate);
+ emit pathChanged();
+ _polylineModel.value(vertexIndex)->setCoordinate(coordinate);
+ setDirty(true);
+}
+
+void QGCMapPolyline::setDirty(bool dirty)
+{
+ if (_dirty != dirty) {
+ _dirty = dirty;
+ if (!dirty) {
+ _polylineModel.setDirty(false);
+ }
+ emit dirtyChanged(dirty);
+ }
+}
+QGeoCoordinate QGCMapPolyline::_coordFromPointF(const QPointF& point) const
+{
+ QGeoCoordinate coord;
+
+ if (_polylinePath.count() > 0) {
+ QGeoCoordinate tangentOrigin = _polylinePath[0].value();
+ convertNedToGeo(-point.y(), point.x(), 0, tangentOrigin, &coord);
+ }
+
+ return coord;
+}
+
+QPointF QGCMapPolyline::_pointFFromCoord(const QGeoCoordinate& coordinate) const
+{
+ if (_polylinePath.count() > 0) {
+ double y, x, down;
+ QGeoCoordinate tangentOrigin = _polylinePath[0].value();
+
+ convertGeoToNed(coordinate, tangentOrigin, &y, &x, &down);
+ return QPointF(x, -y);
+ }
+
+ return QPointF();
+}
+
+void QGCMapPolyline::setPath(const QList& path)
+{
+ _polylinePath.clear();
+ _polylineModel.clearAndDeleteContents();
+ foreach (const QGeoCoordinate& coord, path) {
+ _polylinePath.append(QVariant::fromValue(coord));
+ _polylineModel.append(new QGCQGeoCoordinate(coord, this));
+ }
+
+ setDirty(true);
+ emit pathChanged();
+}
+
+void QGCMapPolyline::setPath(const QVariantList& path)
+{
+ _polylinePath = path;
+
+ _polylineModel.clearAndDeleteContents();
+ for (int i=0; i<_polylinePath.count(); i++) {
+ _polylineModel.append(new QGCQGeoCoordinate(_polylinePath[i].value(), this));
+ }
+
+ setDirty(true);
+ emit pathChanged();
+}
+
+
+void QGCMapPolyline::saveToJson(QJsonObject& json)
+{
+ QJsonValue jsonValue;
+
+ JsonHelper::saveGeoCoordinateArray(_polylinePath, false /* writeAltitude*/, jsonValue);
+ json.insert(jsonPolylineKey, jsonValue);
+ setDirty(false);
+}
+
+bool QGCMapPolyline::loadFromJson(const QJsonObject& json, bool required, QString& errorString)
+{
+ errorString.clear();
+ clear();
+
+ if (required) {
+ if (!JsonHelper::validateRequiredKeys(json, QStringList(jsonPolylineKey), errorString)) {
+ return false;
+ }
+ } else if (!json.contains(jsonPolylineKey)) {
+ return true;
+ }
+
+ if (!JsonHelper::loadGeoCoordinateArray(json[jsonPolylineKey], false /* altitudeRequired */, _polylinePath, errorString)) {
+ return false;
+ }
+
+ for (int i=0; i<_polylinePath.count(); i++) {
+ _polylineModel.append(new QGCQGeoCoordinate(_polylinePath[i].value(), this));
+ }
+
+ setDirty(false);
+ emit pathChanged();
+
+ return true;
+}
+
+QList QGCMapPolyline::coordinateList(void) const
+{
+ QList coords;
+
+ for (int i=0; i<_polylinePath.count(); i++) {
+ coords.append(_polylinePath[i].value());
+ }
+
+ return coords;
+}
+
+void QGCMapPolyline::splitSegment(int vertexIndex)
+{
+ int nextIndex = vertexIndex + 1;
+ if (nextIndex > _polylinePath.length() - 1) {
+ return;
+ }
+
+ QGeoCoordinate firstVertex = _polylinePath[vertexIndex].value();
+ QGeoCoordinate nextVertex = _polylinePath[nextIndex].value();
+
+ double distance = firstVertex.distanceTo(nextVertex);
+ double azimuth = firstVertex.azimuthTo(nextVertex);
+ QGeoCoordinate newVertex = firstVertex.atDistanceAndAzimuth(distance / 2, azimuth);
+
+ if (nextIndex == 0) {
+ appendVertex(newVertex);
+ } else {
+ _polylineModel.insert(nextIndex, new QGCQGeoCoordinate(newVertex, this));
+ _polylinePath.insert(nextIndex, QVariant::fromValue(newVertex));
+ emit pathChanged();
+ }
+}
+
+void QGCMapPolyline::appendVertex(const QGeoCoordinate& coordinate)
+{
+ _polylinePath.append(QVariant::fromValue(coordinate));
+ _polylineModel.append(new QGCQGeoCoordinate(coordinate, this));
+ emit pathChanged();
+}
+
+void QGCMapPolyline::removeVertex(int vertexIndex)
+{
+ if (vertexIndex < 0 || vertexIndex > _polylinePath.length() - 1) {
+ qWarning() << "Call to removeVertex with bad vertexIndex:count" << vertexIndex << _polylinePath.length();
+ return;
+ }
+
+ if (_polylinePath.length() <= 2) {
+ // Don't allow the user to trash the polyline
+ return;
+ }
+
+ QObject* coordObj = _polylineModel.removeAt(vertexIndex);
+ coordObj->deleteLater();
+
+ _polylinePath.removeAt(vertexIndex);
+ emit pathChanged();
+}
+
+void QGCMapPolyline::setInteractive(bool interactive)
+{
+ if (_interactive != interactive) {
+ _interactive = interactive;
+ emit interactiveChanged(interactive);
+ }
+}
+
+QGeoCoordinate QGCMapPolyline::vertexCoordinate(int vertex) const
+{
+ if (vertex >= 0 && vertex < _polylinePath.count()) {
+ return _polylinePath[vertex].value();
+ } else {
+ qWarning() << "QGCMapPolyline::vertexCoordinate bad vertex requested";
+ return QGeoCoordinate();
+ }
+}
+
+QList QGCMapPolyline::nedPolyline(void)
+{
+ QList nedPolyline;
+
+ if (count() > 0) {
+ QGeoCoordinate tangentOrigin = vertexCoordinate(0);
+
+ for (int i=0; i<_polylinePath.count(); i++) {
+ double y, x, down;
+ QGeoCoordinate vertex = vertexCoordinate(i);
+ if (i == 0) {
+ // This avoids a nan calculation that comes out of convertGeoToNed
+ x = y = 0;
+ } else {
+ convertGeoToNed(vertex, tangentOrigin, &y, &x, &down);
+ }
+ nedPolyline += QPointF(x, y);
+ }
+ }
+
+ return nedPolyline;
+}
+
+
+QList QGCMapPolyline::offsetPolyline(double distance)
+{
+ QList rgNewPolyline;
+
+ // I'm sure there is some beautiful famous algorithm to do this, but here is a brute force method
+
+ if (count() > 1) {
+ // Convert the polygon to NED
+ QList rgNedVertices = nedPolyline();
+
+ // Walk the edges, offsetting by the specified distance
+ QList rgOffsetEdges;
+ for (int i=0; ishowMessage(tr("File not found: %1").arg(kmlFile));
+ return false;
+ }
+
+ if (!file.open(QIODevice::ReadOnly)) {
+ qgcApp()->showMessage(tr("Unable to open file: %1 error: $%2").arg(kmlFile).arg(file.errorString()));
+ return false;
+ }
+
+ QDomDocument doc;
+ QString errorMessage;
+ int errorLine;
+ if (!doc.setContent(&file, &errorMessage, &errorLine)) {
+ qgcApp()->showMessage(tr("Unable to parse KML file: %1 error: %2 line: %3").arg(kmlFile).arg(errorMessage).arg(errorLine));
+ return false;
+ }
+
+ QDomNodeList rgNodes = doc.elementsByTagName("Polygon");
+ if (rgNodes.count() == 0) {
+ qgcApp()->showMessage(tr("Unable to find Polygon node in KML"));
+ return false;
+ }
+
+ QDomNode coordinatesNode = rgNodes.item(0).namedItem("outerBoundaryIs").namedItem("LinearRing").namedItem("coordinates");
+ if (coordinatesNode.isNull()) {
+ qgcApp()->showMessage(tr("Internal error: Unable to find coordinates node in KML"));
+ return false;
+ }
+
+ QString coordinatesString = coordinatesNode.toElement().text().simplified();
+ QStringList rgCoordinateStrings = coordinatesString.split(" ");
+
+ QList rgCoords;
+ for (int i=0; i rgReversed;
+
+ for (int i=0; i();
+ QGeoCoordinate to = _polylinePath[i+1].value();
+ length += from.distanceTo(to);
+ }
+
+ return length;
+}
diff --git a/src/MissionManager/QGCMapPolyline.h b/src/MissionManager/QGCMapPolyline.h
new file mode 100644
index 0000000000000000000000000000000000000000..f4ec936b2e2bebaab59f84c0d08d4f7b970d4ad3
--- /dev/null
+++ b/src/MissionManager/QGCMapPolyline.h
@@ -0,0 +1,114 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include
+#include
+#include
+
+#include "QmlObjectListModel.h"
+
+class QGCMapPolyline : public QObject
+{
+ Q_OBJECT
+
+public:
+ QGCMapPolyline(QObject* parent = NULL);
+ QGCMapPolyline(const QGCMapPolyline& other, QObject* parent = NULL);
+
+ const QGCMapPolyline& operator=(const QGCMapPolyline& other);
+
+ Q_PROPERTY(int count READ count NOTIFY countChanged)
+ Q_PROPERTY(QVariantList path READ path NOTIFY pathChanged)
+ Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT)
+ Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
+ Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged)
+
+ Q_INVOKABLE void clear(void);
+ Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate);
+ Q_INVOKABLE void removeVertex(int vertexIndex);
+
+ /// Adjust the value for the specified coordinate
+ /// @param vertexIndex Polygon point index to modify (0-based)
+ /// @param coordinate New coordinate for point
+ Q_INVOKABLE void adjustVertex(int vertexIndex, const QGeoCoordinate coordinate);
+
+ /// Splits the line segment comprised of vertexIndex -> vertexIndex + 1
+ Q_INVOKABLE void splitSegment(int vertexIndex);
+
+ /// Offsets the current polyline edges by the specified distance in meters
+ /// @return Offset set of vertices
+ QList offsetPolyline(double distance);
+
+ /// Loads a polyline from a KML file
+ /// @return true: success
+ Q_INVOKABLE bool loadKMLFile(const QString& kmlFile);
+
+ /// Returns the path in a list of QGeoCoordinate's format
+ QList coordinateList(void) const;
+
+ /// Returns the QGeoCoordinate for the vertex specified
+ QGeoCoordinate vertexCoordinate(int vertex) const;
+
+ /// Saves the polyline to the json object.
+ /// @param json Json object to save to
+ void saveToJson(QJsonObject& json);
+
+ /// Load a polyline from json
+ /// @param json Json object to load from
+ /// @param required true: no polygon in object will generate error
+ /// @param errorString Error string if return is false
+ /// @return true: success, false: failure (errorString set)
+ bool loadFromJson(const QJsonObject& json, bool required, QString& errorString);
+
+ /// Convert polyline to NED and return (D is ignored)
+ QList nedPolyline(void);
+
+ /// Returns the length of the polyline in meters
+ double length(void) const;
+
+ // Property methods
+
+ int count (void) const { return _polylinePath.count(); }
+ bool dirty (void) const { return _dirty; }
+ void setDirty (bool dirty);
+ bool interactive (void) const { return _interactive; }
+ QVariantList path (void) const { return _polylinePath; }
+
+ QmlObjectListModel* qmlPathModel(void) { return &_polylineModel; }
+ QmlObjectListModel& pathModel (void) { return _polylineModel; }
+
+ void setPath (const QList& path);
+ void setPath (const QVariantList& path);
+ void setInteractive (bool interactive);
+
+ static const char* jsonPolylineKey;
+
+signals:
+ void countChanged (int count);
+ void pathChanged (void);
+ void dirtyChanged (bool dirty);
+ void cleared (void);
+ void interactiveChanged (bool interactive);
+
+private slots:
+ void _polylineModelCountChanged(int count);
+ void _polylineModelDirtyChanged(bool dirty);
+
+private:
+ void _init(void);
+ QGeoCoordinate _coordFromPointF(const QPointF& point) const;
+ QPointF _pointFFromCoord(const QGeoCoordinate& coordinate) const;
+
+ QVariantList _polylinePath;
+ QmlObjectListModel _polylineModel;
+ bool _dirty;
+ bool _interactive;
+};
diff --git a/src/MissionManager/QGCMapPolylineTest.cc b/src/MissionManager/QGCMapPolylineTest.cc
new file mode 100644
index 0000000000000000000000000000000000000000..e53ee73ead9bffe3be49de09d208452b89a88d4b
--- /dev/null
+++ b/src/MissionManager/QGCMapPolylineTest.cc
@@ -0,0 +1,202 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "QGCMapPolylineTest.h"
+#include "QGCApplication.h"
+#include "QGCQGeoCoordinate.h"
+
+QGCMapPolylineTest::QGCMapPolylineTest(void)
+{
+ _linePoints << QGeoCoordinate(47.635638361473475, -122.09269407980834 ) <<
+ QGeoCoordinate(47.635638361473475, -122.08545246602667) <<
+ QGeoCoordinate(47.63057923872075, -122.08545246602667) <<
+ QGeoCoordinate(47.63057923872075, -122.09269407980834);
+}
+
+void QGCMapPolylineTest::init(void)
+{
+ UnitTest::init();
+
+ _rgSignals[countChangedIndex] = SIGNAL(countChanged(int));
+ _rgSignals[pathChangedIndex] = SIGNAL(pathChanged());
+ _rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
+ _rgSignals[clearedIndex] = SIGNAL(cleared());
+
+ _rgModelSignals[modelCountChangedIndex] = SIGNAL(countChanged(int));
+ _rgModelSignals[modelDirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
+
+ _mapPolyline = new QGCMapPolyline(this);
+ _pathModel = _mapPolyline->qmlPathModel();
+ QVERIFY(_pathModel);
+
+ _multiSpyPolyline = new MultiSignalSpy();
+ QCOMPARE(_multiSpyPolyline->init(_mapPolyline, _rgSignals, _cSignals), true);
+
+ _multiSpyModel = new MultiSignalSpy();
+ QCOMPARE(_multiSpyModel->init(_pathModel, _rgModelSignals, _cModelSignals), true);
+}
+
+void QGCMapPolylineTest::cleanup(void)
+{
+ delete _mapPolyline;
+ delete _multiSpyPolyline;
+ delete _multiSpyModel;
+}
+
+void QGCMapPolylineTest::_testDirty(void)
+{
+ // Check basic dirty bit set/get
+
+ QVERIFY(!_mapPolyline->dirty());
+ QVERIFY(!_pathModel->dirty());
+
+ _mapPolyline->setDirty(false);
+ QVERIFY(!_mapPolyline->dirty());
+ QVERIFY(!_pathModel->dirty());
+ QVERIFY(_multiSpyPolyline->checkNoSignals());
+ QVERIFY(_multiSpyModel->checkNoSignals());
+
+ _mapPolyline->setDirty(true);
+ QVERIFY(_mapPolyline->dirty());
+ QVERIFY(!_pathModel->dirty());
+ QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(dirtyChangedMask));
+ QVERIFY(_multiSpyPolyline->pullBoolFromSignalIndex(dirtyChangedIndex));
+ QVERIFY(_multiSpyModel->checkNoSignals());
+ _multiSpyPolyline->clearAllSignals();
+
+ _mapPolyline->setDirty(false);
+ QVERIFY(!_mapPolyline->dirty());
+ QVERIFY(!_pathModel->dirty());
+ QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(dirtyChangedMask));
+ QVERIFY(!_multiSpyPolyline->pullBoolFromSignalIndex(dirtyChangedIndex));
+ QVERIFY(_multiSpyModel->checkNoSignals());
+ _multiSpyPolyline->clearAllSignals();
+
+ _pathModel->setDirty(true);
+ QVERIFY(_pathModel->dirty());
+ QVERIFY(_mapPolyline->dirty());
+ QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(dirtyChangedMask));
+ QVERIFY(_multiSpyPolyline->pullBoolFromSignalIndex(dirtyChangedIndex));
+ QVERIFY(_multiSpyModel->checkOnlySignalByMask(modelDirtyChangedMask));
+ QVERIFY(_multiSpyModel->pullBoolFromSignalIndex(modelDirtyChangedIndex));
+ _multiSpyPolyline->clearAllSignals();
+ _multiSpyModel->clearAllSignals();
+
+ _mapPolyline->setDirty(false);
+ QVERIFY(!_mapPolyline->dirty());
+ QVERIFY(!_pathModel->dirty());
+ QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(dirtyChangedMask));
+ QVERIFY(!_multiSpyPolyline->pullBoolFromSignalIndex(dirtyChangedIndex));
+ QVERIFY(_multiSpyModel->checkOnlySignalByMask(modelDirtyChangedMask));
+ QVERIFY(!_multiSpyModel->pullBoolFromSignalIndex(modelDirtyChangedIndex));
+ _multiSpyPolyline->clearAllSignals();
+ _multiSpyModel->clearAllSignals();
+}
+
+void QGCMapPolylineTest::_testVertexManipulation(void)
+{
+ // Vertex addition testing
+
+ for (int i=0; i<_linePoints.count(); i++) {
+ QCOMPARE(_mapPolyline->count(), i);
+
+ _mapPolyline->appendVertex(_linePoints[i]);
+ QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(pathChangedMask | dirtyChangedMask | countChangedMask));
+ QVERIFY(_multiSpyModel->checkOnlySignalByMask(modelDirtyChangedMask | modelCountChangedMask));
+ QCOMPARE(_multiSpyPolyline->pullIntFromSignalIndex(countChangedIndex), i+1);
+ QCOMPARE(_multiSpyModel->pullIntFromSignalIndex(modelCountChangedIndex), i+1);
+
+ QVERIFY(_mapPolyline->dirty());
+ QVERIFY(_pathModel->dirty());
+
+ QCOMPARE(_mapPolyline->count(), i+1);
+
+ QVariantList vertexList = _mapPolyline->path();
+ QCOMPARE(vertexList.count(), i+1);
+ QCOMPARE(vertexList[i].value(), _linePoints[i]);
+
+ QCOMPARE(_pathModel->count(), i+1);
+ QCOMPARE(_pathModel->value(i)->coordinate(), _linePoints[i]);
+
+ _mapPolyline->setDirty(false);
+ _multiSpyPolyline->clearAllSignals();
+ _multiSpyModel->clearAllSignals();
+ }
+
+ // Vertex adjustment testing
+
+ QGCQGeoCoordinate* geoCoord = _pathModel->value(1);
+ QSignalSpy coordSpy(geoCoord, SIGNAL(coordinateChanged(QGeoCoordinate)));
+ QSignalSpy coordDirtySpy(geoCoord, SIGNAL(dirtyChanged(bool)));
+ QGeoCoordinate adjustCoord(_linePoints[1].latitude() + 1, _linePoints[1].longitude() + 1);
+ _mapPolyline->adjustVertex(1, adjustCoord);
+ QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(pathChangedMask | dirtyChangedMask));
+ QVERIFY(_multiSpyModel->checkOnlySignalByMask(modelDirtyChangedMask));
+ QCOMPARE(coordSpy.count(), 1);
+ QCOMPARE(coordDirtySpy.count(), 1);
+ QCOMPARE(geoCoord->coordinate(), adjustCoord);
+ QVariantList vertexList = _mapPolyline->path();
+ QCOMPARE(vertexList[0].value(), _linePoints[0]);
+ QCOMPARE(_pathModel->value(0)->coordinate(), _linePoints[0]);
+ QCOMPARE(vertexList[2].value(), _linePoints[2]);
+ QCOMPARE(_pathModel->value(2)->coordinate(), _linePoints[2]);
+ QCOMPARE(vertexList[3].value(), _linePoints[3]);
+ QCOMPARE(_pathModel->value(3)->coordinate(), _linePoints[3]);
+
+ _mapPolyline->setDirty(false);
+ _multiSpyPolyline->clearAllSignals();
+ _multiSpyModel->clearAllSignals();
+
+ // Vertex removal testing
+
+ _mapPolyline->removeVertex(1);
+ QVERIFY(_multiSpyPolyline->checkOnlySignalByMask(pathChangedMask | dirtyChangedMask | countChangedMask));
+ QVERIFY(_multiSpyModel->checkOnlySignalByMask(modelDirtyChangedMask | modelCountChangedMask));
+ QCOMPARE(_mapPolyline->count(), 3);
+ vertexList = _mapPolyline->path();
+ QCOMPARE(vertexList.count(), 3);
+ QCOMPARE(_pathModel->count(), 3);
+ QCOMPARE(vertexList[0].value(), _linePoints[0]);
+ QCOMPARE(_pathModel->value(0)->coordinate(), _linePoints[0]);
+ QCOMPARE(vertexList[1].value(), _linePoints[2]);
+ QCOMPARE(_pathModel->value(1)->coordinate(), _linePoints[2]);
+ QCOMPARE(vertexList[2].value(), _linePoints[3]);
+ QCOMPARE(_pathModel->value(2)->coordinate(), _linePoints[3]);
+
+ // Clear testing
+
+ _mapPolyline->clear();
+ QVERIFY(_multiSpyPolyline->checkOnlySignalsByMask(pathChangedMask | dirtyChangedMask | countChangedMask | clearedMask));
+ QVERIFY(_multiSpyModel->checkOnlySignalsByMask(modelDirtyChangedMask | modelCountChangedMask));
+ QVERIFY(_mapPolyline->dirty());
+ QVERIFY(_pathModel->dirty());
+ QCOMPARE(_mapPolyline->count(), 0);
+ vertexList = _mapPolyline->path();
+ QCOMPARE(vertexList.count(), 0);
+ QCOMPARE(_pathModel->count(), 0);
+}
+
+#if 0
+void QGCMapPolylineTest::_testKMLLoad(void)
+{
+ QVERIFY(_mapPolyline->loadKMLFile(QStringLiteral(":/unittest/PolygonGood.kml")));
+
+ setExpectedMessageBox(QMessageBox::Ok);
+ QVERIFY(!_mapPolyline->loadKMLFile(QStringLiteral(":/unittest/BadXml.kml")));
+ checkExpectedMessageBox();
+
+ setExpectedMessageBox(QMessageBox::Ok);
+ QVERIFY(!_mapPolyline->loadKMLFile(QStringLiteral(":/unittest/MissingPolygonNode.kml")));
+ checkExpectedMessageBox();
+
+ setExpectedMessageBox(QMessageBox::Ok);
+ QVERIFY(!_mapPolyline->loadKMLFile(QStringLiteral(":/unittest/BadCoordinatesNode.kml")));
+ checkExpectedMessageBox();
+}
+#endif
diff --git a/src/MissionManager/QGCMapPolylineTest.h b/src/MissionManager/QGCMapPolylineTest.h
new file mode 100644
index 0000000000000000000000000000000000000000..9b02ac54e3d22f1f08ecb594d416e8a9920e4010
--- /dev/null
+++ b/src/MissionManager/QGCMapPolylineTest.h
@@ -0,0 +1,71 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include "UnitTest.h"
+#include "MultiSignalSpy.h"
+#include "QGCMapPolyline.h"
+#include "QmlObjectListModel.h"
+
+class QGCMapPolylineTest : public UnitTest
+{
+ Q_OBJECT
+
+public:
+ QGCMapPolylineTest(void);
+
+protected:
+ void init(void) final;
+ void cleanup(void) final;
+
+private slots:
+ void _testDirty(void);
+ void _testVertexManipulation(void);
+// void _testKMLLoad(void);
+
+private:
+ enum {
+ countChangedIndex = 0,
+ pathChangedIndex,
+ dirtyChangedIndex,
+ clearedIndex,
+ maxSignalIndex
+ };
+
+ enum {
+ countChangedMask = 1 << countChangedIndex,
+ pathChangedMask = 1 << pathChangedIndex,
+ dirtyChangedMask = 1 << dirtyChangedIndex,
+ clearedMask = 1 << clearedIndex,
+ };
+
+ static const size_t _cSignals = maxSignalIndex;
+ const char* _rgSignals[_cSignals];
+
+ enum {
+ modelCountChangedIndex = 0,
+ modelDirtyChangedIndex,
+ maxModelSignalIndex
+ };
+
+ enum {
+ modelCountChangedMask = 1 << modelCountChangedIndex,
+ modelDirtyChangedMask = 1 << modelDirtyChangedIndex,
+ };
+
+ static const size_t _cModelSignals = maxModelSignalIndex;
+ const char* _rgModelSignals[_cModelSignals];
+
+ MultiSignalSpy* _multiSpyPolyline;
+ MultiSignalSpy* _multiSpyModel;
+ QGCMapPolyline* _mapPolyline;
+ QmlObjectListModel* _pathModel;
+ QList _linePoints;
+};
diff --git a/src/MissionManager/QGCMapPolylineVisuals.qml b/src/MissionManager/QGCMapPolylineVisuals.qml
new file mode 100644
index 0000000000000000000000000000000000000000..27f9ed8a787b0fb76effea19e02e4ed687fc69b4
--- /dev/null
+++ b/src/MissionManager/QGCMapPolylineVisuals.qml
@@ -0,0 +1,287 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+import QtQuick 2.3
+import QtQuick.Controls 1.2
+import QtLocation 5.3
+import QtPositioning 5.3
+import QtQuick.Dialogs 1.2
+
+import QGroundControl 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Palette 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.FlightMap 1.0
+
+/// QGCmapPolyline map visuals
+Item {
+ id: _root
+
+ property var qgcView ///< QGCView for popping dialogs
+ property var mapControl ///< Map control to place item in
+ property var mapPolyline ///< QGCMapPolyline object
+ property bool interactive: mapPolyline.interactive
+ property int lineWidth: 3
+ property color lineColor: "#be781c"
+
+
+ property var _polylineComponent
+ property var _dragHandlesComponent
+ property var _splitHandlesComponent
+
+ property real _zorderDragHandle: QGroundControl.zOrderMapItems + 3 // Highest to prevent splitting when items overlap
+ property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2
+
+ function addVisuals() {
+ _polylineComponent = polylineComponent.createObject(mapControl)
+ mapControl.addMapItem(_polylineComponent)
+ }
+
+ function removeVisuals() {
+ _polylineComponent.destroy()
+ }
+
+ function addHandles() {
+ if (!_dragHandlesComponent) {
+ _dragHandlesComponent = dragHandlesComponent.createObject(mapControl)
+ _splitHandlesComponent = splitHandlesComponent.createObject(mapControl)
+ }
+ }
+
+ function removeHandles() {
+ if (_dragHandlesComponent) {
+ _dragHandlesComponent.destroy()
+ _dragHandlesComponent = undefined
+ }
+ if (_splitHandlesComponent) {
+ _splitHandlesComponent.destroy()
+ _splitHandlesComponent = undefined
+ }
+ }
+
+ /// Calculate the default/initial polyline
+ function defaultPolylineVertices() {
+ var x = map.centerViewport.x + (map.centerViewport.width / 2)
+ var yInset = map.centerViewport.height / 4
+ var topPointCoord = map.toCoordinate(Qt.point(x, map.centerViewport.y + yInset), false /* clipToViewPort */)
+ var bottomPointCoord = map.toCoordinate(Qt.point(x, map.centerViewport.y + map.centerViewport.height - yInset), false /* clipToViewPort */)
+ return [ topPointCoord, bottomPointCoord ]
+ }
+
+ /// Add an initial 2 point polyline
+ function addInitialPolyline() {
+ if (mapPolyline.count < 2) {
+ mapPolyline.clear()
+ var initialVertices = defaultPolylineVertices()
+ mapPolyline.appendVertex(initialVertices[0])
+ mapPolyline.appendVertex(initialVertices[1])
+ }
+ }
+
+ /// Reset polyline back to initial default
+ function resetPolyline() {
+ mapPolyline.clear()
+ addInitialPolyline()
+ }
+
+ onInteractiveChanged: {
+ if (interactive) {
+ addHandles()
+ } else {
+ removeHandles()
+ }
+ }
+
+ Component.onCompleted: {
+ addVisuals()
+ if (interactive) {
+ addHandles()
+ }
+ }
+
+ Component.onDestruction: {
+ removeVisuals()
+ removeHandles()
+ }
+
+ QGCPalette { id: qgcPal }
+
+ QGCFileDialog {
+ id: kmlLoadDialog
+ qgcView: _root.qgcView
+ folder: QGroundControl.settingsManager.appSettings.missionSavePath
+ title: qsTr("Select KML File")
+ selectExisting: true
+ nameFilters: [ qsTr("KML files (*.kml)") ]
+
+
+ onAcceptedForLoad: {
+ mapPolyline.loadKMLFile(file)
+ close()
+ }
+ }
+
+ Component {
+ id: polylineComponent
+
+ MapPolyline {
+ line.width: lineWidth
+ line.color: lineColor
+ path: mapPolyline.path
+ }
+ }
+
+ Component {
+ id: splitHandleComponent
+
+ MapQuickItem {
+ id: mapQuickItem
+ anchorPoint.x: splitHandle.width / 2
+ anchorPoint.y: splitHandle.height / 2
+
+ property int vertexIndex
+
+ sourceItem: Rectangle {
+ id: splitHandle
+ width: ScreenTools.defaultFontPixelHeight * 1.5
+ height: width
+ radius: width / 2
+ border.color: "white"
+ color: "transparent"
+ opacity: .50
+ z: _zorderSplitHandle
+
+ QGCLabel {
+ anchors.horizontalCenter: parent.horizontalCenter
+ anchors.verticalCenter: parent.verticalCenter
+ text: "+"
+ }
+
+ QGCMouseArea {
+ fillItem: parent
+ onClicked: mapPolyline.splitSegment(mapQuickItem.vertexIndex)
+ }
+ }
+ }
+ }
+
+ Component {
+ id: splitHandlesComponent
+
+ Repeater {
+ model: mapPolyline.path
+
+ delegate: Item {
+ property var _splitHandle
+ property var _vertices: mapPolyline.path
+
+ function _setHandlePosition() {
+ var nextIndex = index + 1
+ var distance = _vertices[index].distanceTo(_vertices[nextIndex])
+ var azimuth = _vertices[index].azimuthTo(_vertices[nextIndex])
+ _splitHandle.coordinate = _vertices[index].atDistanceAndAzimuth(distance / 2, azimuth)
+ }
+
+ Component.onCompleted: {
+ if (index + 1 <= _vertices.length - 1) {
+ _splitHandle = splitHandleComponent.createObject(mapControl)
+ _splitHandle.vertexIndex = index
+ _setHandlePosition()
+ mapControl.addMapItem(_splitHandle)
+ }
+ }
+
+ Component.onDestruction: {
+ if (_splitHandle) {
+ _splitHandle.destroy()
+ }
+ }
+ }
+ }
+ }
+
+ // Control which is used to drag polygon vertices
+ Component {
+ id: dragAreaComponent
+
+ MissionItemIndicatorDrag {
+ id: dragArea
+ z: _zorderDragHandle
+
+ property int polylineVertex
+
+ property bool _creationComplete: false
+
+ Component.onCompleted: _creationComplete = true
+
+ onItemCoordinateChanged: {
+ if (_creationComplete) {
+ // During component creation some bad coordinate values got through which screws up draw
+ mapPolyline.adjustVertex(polylineVertex, itemCoordinate)
+ }
+ }
+
+ onClicked: mapPolyline.removeVertex(polylineVertex)
+ }
+ }
+
+ Component {
+ id: dragHandleComponent
+
+ MapQuickItem {
+ id: mapQuickItem
+ anchorPoint.x: dragHandle.width / 2
+ anchorPoint.y: dragHandle.height / 2
+ z: _zorderDragHandle
+
+ property int polylineVertex
+
+ sourceItem: Rectangle {
+ id: dragHandle
+ width: ScreenTools.defaultFontPixelHeight * 1.5
+ height: width
+ radius: width / 2
+ color: "white"
+ opacity: .90
+ }
+ }
+ }
+
+ // Add all polygon vertex drag handles to the map
+ Component {
+ id: dragHandlesComponent
+
+ Repeater {
+ model: mapPolyline.pathModel
+
+ delegate: Item {
+ property var _visuals: [ ]
+
+ Component.onCompleted: {
+ var dragHandle = dragHandleComponent.createObject(mapControl)
+ dragHandle.coordinate = Qt.binding(function() { return object.coordinate })
+ dragHandle.polylineVertex = Qt.binding(function() { return index })
+ mapControl.addMapItem(dragHandle)
+ var dragArea = dragAreaComponent.createObject(mapControl, { "itemIndicator": dragHandle, "itemCoordinate": object.coordinate })
+ dragArea.polylineVertex = Qt.binding(function() { return index })
+ _visuals.push(dragHandle)
+ _visuals.push(dragArea)
+ }
+
+ Component.onDestruction: {
+ for (var i=0; i<_visuals.length; i++) {
+ _visuals[i].destroy()
+ }
+ _visuals = [ ]
+ }
+ }
+ }
+ }
+}
+
diff --git a/src/MissionManager/StructureScanComplexItem.cc b/src/MissionManager/StructureScanComplexItem.cc
index a32b22848e47e6dfe7c711536447c84615da1a02..8c7aeeaf8b3d3aea23e6d6c0e7253c5b652d81c4 100644
--- a/src/MissionManager/StructureScanComplexItem.cc
+++ b/src/MissionManager/StructureScanComplexItem.cc
@@ -102,7 +102,7 @@ void StructureScanComplexItem::_setScanDistance(double scanDistance)
{
if (!qFuzzyCompare(_scanDistance, scanDistance)) {
_scanDistance = scanDistance;
- emit complexDistanceChanged(_scanDistance);
+ emit complexDistanceChanged();
}
}
diff --git a/src/MissionManager/SurveyMissionItem.cc b/src/MissionManager/SurveyMissionItem.cc
index 91d2989fea2f34a92daaf23574c4ac1d848f90c5..1e8b5e9f4590bde163effb055a5212090f76e4b0 100644
--- a/src/MissionManager/SurveyMissionItem.cc
+++ b/src/MissionManager/SurveyMissionItem.cc
@@ -159,7 +159,7 @@ void SurveyMissionItem::_setSurveyDistance(double surveyDistance)
{
if (!qFuzzyCompare(_surveyDistance, surveyDistance)) {
_surveyDistance = surveyDistance;
- emit complexDistanceChanged(_surveyDistance);
+ emit complexDistanceChanged();
}
}
@@ -742,7 +742,7 @@ void SurveyMissionItem::_generateGrid(void)
if (_hoverAndCaptureEnabled()) {
_additionalFlightDelaySeconds = cameraShots * _hoverAndCaptureDelaySeconds;
}
- emit additionalTimeDelayChanged(_additionalFlightDelaySeconds);
+ emit additionalTimeDelayChanged();
emit gridPointsChanged();
diff --git a/src/MissionManager/UnitTest/PolygonAreaTest.kml b/src/MissionManager/UnitTest/PolygonAreaTest.kml
new file mode 100755
index 0000000000000000000000000000000000000000..455643f37757e65fa10cd34aa3088ea31aafbbd6
--- /dev/null
+++ b/src/MissionManager/UnitTest/PolygonAreaTest.kml
@@ -0,0 +1,48 @@
+
+
+
+ AreaTestPolygon.kmz
+
+
+ normal
+ #s_ylw-pushpin
+
+
+ highlight
+ #s_ylw-pushpin_hl
+
+
+
+
+
+ Untitled Polygon
+ #m_ylw-pushpin
+
+ 1
+
+
+
+ -122.1059149362712,47.65965281788451,0 -122.1044593196253,47.66002598220988,0 -122.1047336695092,47.66034166158975,0 -122.1061470943783,47.6599810708829,0 -122.1059149362712,47.65965281788451,0
+
+
+
+
+
+
+
diff --git a/src/MissionManager/UnitTest/BadCoordinatesNode.kml b/src/MissionManager/UnitTest/PolygonBadCoordinatesNode.kml
similarity index 100%
rename from src/MissionManager/UnitTest/BadCoordinatesNode.kml
rename to src/MissionManager/UnitTest/PolygonBadCoordinatesNode.kml
diff --git a/src/MissionManager/UnitTest/BadXml.kml b/src/MissionManager/UnitTest/PolygonBadXml.kml
similarity index 100%
rename from src/MissionManager/UnitTest/BadXml.kml
rename to src/MissionManager/UnitTest/PolygonBadXml.kml
diff --git a/src/MissionManager/UnitTest/GoodPolygon.kml b/src/MissionManager/UnitTest/PolygonGood.kml
similarity index 100%
rename from src/MissionManager/UnitTest/GoodPolygon.kml
rename to src/MissionManager/UnitTest/PolygonGood.kml
diff --git a/src/MissionManager/UnitTest/MissingPolygonNode.kml b/src/MissionManager/UnitTest/PolygonMissingNode.kml
similarity index 100%
rename from src/MissionManager/UnitTest/MissingPolygonNode.kml
rename to src/MissionManager/UnitTest/PolygonMissingNode.kml
diff --git a/src/MissionManager/VisualMissionItem.cc b/src/MissionManager/VisualMissionItem.cc
index 1f0173f156851138b55adc3df8c39b93655f22bf..ba309b72f6ac54b434f2ca2d5aca0f85eab7d591 100644
--- a/src/MissionManager/VisualMissionItem.cc
+++ b/src/MissionManager/VisualMissionItem.cc
@@ -63,7 +63,7 @@ VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, QObject* pa
{
*this = other;
- // Don't get terrain altitude information for submarines or boards
+ // Don't get terrain altitude information for submarines or boats
if (_vehicle->vehicleType() != MAV_TYPE_SUBMARINE && _vehicle->vehicleType() != MAV_TYPE_SURFACE_BOAT) {
connect(this, &VisualMissionItem::coordinateChanged, this, &VisualMissionItem::_updateTerrainAltitude);
}
diff --git a/src/PlanView/CorridorScanEditor.qml b/src/PlanView/CorridorScanEditor.qml
new file mode 100644
index 0000000000000000000000000000000000000000..fcf37938841d0f1398c1613307d4e25a488dcd6e
--- /dev/null
+++ b/src/PlanView/CorridorScanEditor.qml
@@ -0,0 +1,122 @@
+import QtQuick 2.3
+import QtQuick.Controls 1.2
+import QtQuick.Controls.Styles 1.4
+import QtQuick.Dialogs 1.2
+import QtQuick.Extras 1.4
+import QtQuick.Layouts 1.2
+
+import QGroundControl 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Vehicle 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.FactControls 1.0
+import QGroundControl.Palette 1.0
+import QGroundControl.FlightMap 1.0
+
+// Editor for Survery mission items
+Rectangle {
+ id: _root
+ height: visible ? (editorColumn.height + (_margin * 2)) : 0
+ width: availableWidth
+ color: qgcPal.windowShadeDark
+ radius: _radius
+
+ // The following properties must be available up the hierarchy chain
+ //property real availableWidth ///< Width for control
+ //property var missionItem ///< Mission Item for editor
+
+ property real _margin: ScreenTools.defaultFontPixelWidth / 2
+ property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
+ property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
+
+ function polygonCaptureStarted() {
+ missionItem.clearPolygon()
+ }
+
+ function polygonCaptureFinished(coordinates) {
+ for (var i=0; i 0 && missionItem.cameraMinTriggerInterval !== 0 && missionItem.cameraMinTriggerInterval > missionItem.timeBetweenShots
+ }
+
+ CameraCalc {
+ cameraCalc: missionItem.cameraCalc
+ vehicleFlightIsFrontal: true
+ distanceToSurfaceLabel: qsTr("Altitude")
+ frontalDistanceLabel: qsTr("Trigger Distance")
+ sideDistanceLabel: qsTr("Spacing")
+ }
+
+ SectionHeader {
+ id: corridorHeader
+ text: qsTr("Corridor")
+ }
+
+ GridLayout {
+ anchors.left: parent.left
+ anchors.right: parent.right
+ columnSpacing: _margin
+ rowSpacing: _margin
+ columns: 2
+ visible: corridorHeader.checked
+
+ QGCLabel { text: qsTr("Width") }
+ FactTextField {
+ fact: missionItem.corridorWidth
+ Layout.fillWidth: true
+ }
+ }
+
+ SectionHeader {
+ id: statsHeader
+ text: qsTr("Statistics")
+ }
+
+ Grid {
+ columns: 2
+ columnSpacing: ScreenTools.defaultFontPixelWidth
+ visible: statsHeader.checked
+
+ QGCLabel { text: qsTr("Photo count") }
+ QGCLabel { text: missionItem.cameraShots }
+
+ QGCLabel { text: qsTr("Photo interval") }
+ QGCLabel { text: missionItem.timeBetweenShots.toFixed(1) + " " + qsTr("secs") }
+ }
+ } // Column
+} // Rectangle
diff --git a/src/PlanView/CorridorScanMapVisual.qml b/src/PlanView/CorridorScanMapVisual.qml
new file mode 100644
index 0000000000000000000000000000000000000000..014bbe9a77f3470e169abac0cc6b04ccb9da5106
--- /dev/null
+++ b/src/PlanView/CorridorScanMapVisual.qml
@@ -0,0 +1,125 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+import QtQuick 2.3
+import QtQuick.Controls 1.2
+import QtLocation 5.3
+import QtPositioning 5.3
+
+import QGroundControl 1.0
+import QGroundControl.Controls 1.0
+
+/// Corridor Scan Complex Mission Item visuals
+Item {
+ id: _root
+
+ property var map ///< Map control to place item in
+ property var qgcView ///< QGCView to use for popping dialogs
+
+ property var _missionItem: object
+ property var _entryCoordinate
+ property var _exitCoordinate
+ property var _transectLines
+
+ signal clicked(int sequenceNumber)
+
+ function _addVisualElements() {
+ _entryCoordinate = entryPointComponent.createObject(map)
+ _exitCoordinate = exitPointComponent.createObject(map)
+ _transectLines = transectsComponent.createObject(map)
+ map.addMapItem(_entryCoordinate)
+ map.addMapItem(_exitCoordinate)
+ map.addMapItem(_transectLines)
+ }
+
+ function _destroyVisualElements() {
+ _entryCoordinate.destroy()
+ _exitCoordinate.destroy()
+ _transectLines.destroy()
+ }
+
+ Component.onCompleted: {
+ mapPolylineVisuals.addInitialPolyline()
+ _addVisualElements()
+ }
+
+ Component.onDestruction: {
+ _destroyVisualElements()
+ }
+
+ QGCMapPolygonVisuals {
+ qgcView: _root.qgcView
+ mapControl: map
+ mapPolygon: object.corridorPolygon
+ interactive: false
+ interiorColor: "green"
+ interiorOpacity: 0.25
+ }
+
+ QGCMapPolylineVisuals {
+ id: mapPolylineVisuals
+ qgcView: _root.qgcView
+ mapControl: map
+ mapPolyline: object.corridorPolyline
+ interactive: _missionItem.isCurrentItem
+ lineWidth: 3
+ lineColor: "#be781c"
+ }
+
+ // Entry point
+ Component {
+ id: entryPointComponent
+
+ MapQuickItem {
+ anchorPoint.x: sourceItem.anchorPointX
+ anchorPoint.y: sourceItem.anchorPointY
+ z: QGroundControl.zOrderMapItems
+ coordinate: _missionItem.coordinate
+ visible: _missionItem.coordinate.isValid
+
+ sourceItem: MissionItemIndexLabel {
+ index: _missionItem.sequenceNumber
+ label: "Entry"
+ checked: _missionItem.isCurrentItem
+ onClicked: _root.clicked(_missionItem.sequenceNumber)
+ }
+ }
+ }
+
+ // Exit point
+ Component {
+ id: exitPointComponent
+
+ MapQuickItem {
+ anchorPoint.x: sourceItem.anchorPointX
+ anchorPoint.y: sourceItem.anchorPointY
+ z: QGroundControl.zOrderMapItems
+ coordinate: _missionItem.exitCoordinate
+ visible: _missionItem.exitCoordinate.isValid
+
+ sourceItem: MissionItemIndexLabel {
+ index: _missionItem.lastSequenceNumber
+ label: "Exit"
+ checked: _missionItem.isCurrentItem
+ onClicked: _root.clicked(_missionItem.sequenceNumber)
+ }
+ }
+ }
+
+ // Transect lines
+ Component {
+ id: transectsComponent
+
+ MapPolyline {
+ line.color: "white"
+ line.width: 2
+ path: _missionItem.transectPoints
+ }
+ }
+}
diff --git a/src/QGCFileDownload.cc b/src/QGCFileDownload.cc
index 014d5c6fada27f2738ca874e29e8167578d934e9..153f9b8d841683c54cd5b5089e2a67a1a1b37aba 100644
--- a/src/QGCFileDownload.cc
+++ b/src/QGCFileDownload.cc
@@ -95,7 +95,8 @@ void QGCFileDownload::_downloadFinished(void)
// When an error occurs or the user cancels the download, we still end up here. So bail out in
// those cases.
- if (reply->error() != QNetworkReply::NoError) {
+ if (reply->error() != QNetworkReply::NoError) {
+ reply->deleteLater();
return;
}
@@ -128,6 +129,8 @@ void QGCFileDownload::_downloadFinished(void)
qWarning() << errorMsg;
emit error(errorMsg);
}
+
+ reply->deleteLater();
}
/// @brief Called when an error occurs during download
diff --git a/src/QmlControls/QGroundControl.Controls.qmldir b/src/QmlControls/QGroundControl.Controls.qmldir
index 82ffdc70fad541820d0fdb1e6095de125cb289b0..02680ff52d8632d517d830ff2f053a9ef7bfcdbb 100644
--- a/src/QmlControls/QGroundControl.Controls.qmldir
+++ b/src/QmlControls/QGroundControl.Controls.qmldir
@@ -48,6 +48,7 @@ QGCListView 1.0 QGCListView.qml
QGCMapLabel 1.0 QGCMapLabel.qml
QGCMapCircleVisuals 1.0 QGCMapCircleVisuals.qml
QGCMapPolygonVisuals 1.0 QGCMapPolygonVisuals.qml
+QGCMapPolylineVisuals 1.0 QGCMapPolylineVisuals.qml
QGCMouseArea 1.0 QGCMouseArea.qml
QGCMovableItem 1.0 QGCMovableItem.qml
QGCPipable 1.0 QGCPipable.qml
diff --git a/src/Vehicle/MultiVehicleManager.cc b/src/Vehicle/MultiVehicleManager.cc
index 86e632823f89c065d441673f2a91fbbbeff73c94..5fa0dceda761c04108a6d2d0a36cc53a54885cd7 100644
--- a/src/Vehicle/MultiVehicleManager.cc
+++ b/src/Vehicle/MultiVehicleManager.cc
@@ -72,7 +72,7 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
this);
}
-void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType)
+void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType)
{
if (componentId != MAV_COMP_ID_AUTOPILOT1) {
// Special case for PX4 Flow
@@ -82,7 +82,6 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
<< link->getName()
<< vehicleId
<< componentId
- << vehicleMavlinkVersion
<< vehicleFirmwareType
<< vehicleType;
return;
@@ -108,11 +107,10 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
break;
}
- qCDebug(MultiVehicleManagerLog()) << "Adding new vehicle link:vehicleId:componentId:vehicleMavlinkVersion:vehicleFirmwareType:vehicleType "
+ qCDebug(MultiVehicleManagerLog()) << "Adding new vehicle link:vehicleId:componentId:vehicleFirmwareType:vehicleType "
<< link->getName()
<< vehicleId
<< componentId
- << vehicleMavlinkVersion
<< vehicleFirmwareType
<< vehicleType;
@@ -120,16 +118,6 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle
_app->showMessage(tr("Warning: A vehicle is using the same system id as %1: %2").arg(qgcApp()->applicationName()).arg(vehicleId));
}
- // QSettings settings;
- // bool mavlinkVersionCheck = settings.value("VERSION_CHECK_ENABLED", true).toBool();
- // if (mavlinkVersionCheck && vehicleMavlinkVersion != MAVLINK_VERSION) {
- // _ignoreVehicleIds += vehicleId;
- // _app->showMessage(QString("The MAVLink protocol version on vehicle #%1 and %2 differ! "
- // "It is unsafe to use different MAVLink versions. "
- // "%2 therefore refuses to connect to vehicle #%1, which sends MAVLink version %3 (%2 uses version %4).").arg(vehicleId).arg(qgcApp()->applicationName()).arg(vehicleMavlinkVersion).arg(MAVLINK_VERSION));
- // return;
- // }
-
Vehicle* vehicle = new Vehicle(link, vehicleId, componentId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, _firmwarePluginManager, _joystickManager);
connect(vehicle, &Vehicle::allLinksInactive, this, &MultiVehicleManager::_deleteVehiclePhase1);
connect(vehicle, &Vehicle::requestProtocolVersion, this, &MultiVehicleManager::_requestProtocolVersion);
diff --git a/src/Vehicle/MultiVehicleManager.h b/src/Vehicle/MultiVehicleManager.h
index 5b2cfe6cabedad60c9dd76ff890ee806391d21ab..697d30d005e71c0faccf1f43f9fbb4dc61a57672 100644
--- a/src/Vehicle/MultiVehicleManager.h
+++ b/src/Vehicle/MultiVehicleManager.h
@@ -94,7 +94,7 @@ private slots:
void _setActiveVehiclePhase2(void);
void _vehicleParametersReadyChanged(bool parametersReady);
void _sendGCSHeartbeat(void);
- void _vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType);
+ void _vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType);
void _requestProtocolVersion(unsigned version);
private:
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index 64e27fa4774ce233995443e142a46f2415fa3102..21fca049a3bf9cdf98b0cc566dbd37c102eeaef9 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -233,18 +233,27 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_mav, SIGNAL(attitudeChanged (UASInterface*,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64)));
connect(_mav, SIGNAL(attitudeChanged (UASInterface*,int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64)));
+ if (_highLatencyLink) {
+ // High latency links don't request information
+ _setMaxProtoVersion(100);
+ _setCapabilities(0);
+ _initialPlanRequestComplete = true;
+ _missionManagerInitialRequestSent = true;
+ _geoFenceManagerInitialRequestSent = true;
+ _rallyPointManagerInitialRequestSent = true;
+ } else {
+ // Ask the vehicle for protocol version info.
+ sendMavCommand(MAV_COMP_ID_ALL, // Don't know default component id yet.
+ MAV_CMD_REQUEST_PROTOCOL_VERSION,
+ false, // No error shown if fails
+ 1); // Request protocol version
- // Ask the vehicle for protocol version info.
- sendMavCommand(MAV_COMP_ID_ALL, // Don't know default component id yet.
- MAV_CMD_REQUEST_PROTOCOL_VERSION,
- false, // No error shown if fails
- 1); // Request protocol version
-
- // Ask the vehicle for firmware version info.
- sendMavCommand(MAV_COMP_ID_ALL, // Don't know default component id yet.
- MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
- false, // No error shown if fails
- 1); // Request firmware version
+ // Ask the vehicle for firmware version info.
+ sendMavCommand(MAV_COMP_ID_ALL, // Don't know default component id yet.
+ MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
+ false, // No error shown if fails
+ 1); // Request firmware version
+ }
_firmwarePlugin->initializeVehicle(this);
@@ -677,13 +686,16 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
break;
case MAVLINK_MSG_ID_SCALED_PRESSURE3:
_handleScaledPressure3(message);
- break;
+ break;
case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
_handleCameraImageCaptured(message);
break;
case MAVLINK_MSG_ID_ADSB_VEHICLE:
_handleADSBVehicle(message);
break;
+ case MAVLINK_MSG_ID_HIGH_LATENCY2:
+ _handleHighLatency2(message);
+ break;
case MAVLINK_MSG_ID_SERIAL_CONTROL:
{
@@ -693,7 +705,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
}
break;
- // Following are ArduPilot dialect messages
+ // Following are ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
_handleCameraFeedback(message);
@@ -797,6 +809,47 @@ void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
emit coordinateChanged(_coordinate);
}
+void Vehicle::_handleHighLatency2(mavlink_message_t& message)
+{
+ mavlink_high_latency2_t highLatency2;
+ mavlink_msg_high_latency2_decode(&message, &highLatency2);
+
+#if 0
+ typedef struct __mavlink_high_latency2_t {
+ uint16_t wp_num; /*< Current waypoint number*/
+ uint16_t failure_flags; /*< Indicates failures as defined in MAV_FAILURE_FLAG ENUM. */
+ uint8_t flight_mode; /*< Flight Mode of the vehicle as defined in the FLIGHT_MODE ENUM*/
+ uint8_t failsafe; /*< Indicates if a failsafe mode is triggered, defined in MAV_FAILSAFE_FLAG ENUM*/
+ }) mavlink_high_latency2_t;
+#endif
+
+ // FIXME: flight mode not yet supported
+
+ _coordinate.setLatitude(highLatency2.latitude / (double)1E7);
+ _coordinate.setLongitude(highLatency2.longitude / (double)1E7);
+ _coordinate.setAltitude(highLatency2.altitude);
+ emit coordinateChanged(_coordinate);
+
+ _airSpeedFact.setRawValue((double)highLatency2.airspeed / 5.0);
+ _groundSpeedFact.setRawValue((double)highLatency2.groundspeed / 5.0);
+ _climbRateFact.setRawValue((double)highLatency2.climb_rate / 10.0);
+
+ _headingFact.setRawValue((double)highLatency2.heading * 2.0);
+
+ _windFactGroup.direction()->setRawValue((double)highLatency2.wind_heading * 2.0);
+ _windFactGroup.speed()->setRawValue((double)highLatency2.windspeed / 5.0);
+
+ _batteryFactGroup.percentRemaining()->setRawValue(highLatency2.battery);
+
+ _temperatureFactGroup.temperature1()->setRawValue(highLatency2.temperature_air);
+
+ _gpsFactGroup.lat()->setRawValue(highLatency2.latitude * 1e-7);
+ _gpsFactGroup.lon()->setRawValue(highLatency2.longitude * 1e-7);
+ _gpsFactGroup.count()->setRawValue(0);
+ _gpsFactGroup.hdop()->setRawValue(highLatency2.eph == UINT8_MAX ? std::numeric_limits::quiet_NaN() : highLatency2.eph / 10.0);
+ _gpsFactGroup.vdop()->setRawValue(highLatency2.epv == UINT8_MAX ? std::numeric_limits::quiet_NaN() : highLatency2.epv / 10.0);
+}
+
void Vehicle::_handleAltitude(mavlink_message_t& message)
{
mavlink_altitude_t altitude;
@@ -909,14 +962,14 @@ QString Vehicle::vehicleUIDStr()
QString uid;
uint8_t* pUid = (uint8_t*)(void*)&_uid;
uid.sprintf("%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X",
- pUid[0] & 0xff,
- pUid[1] & 0xff,
- pUid[2] & 0xff,
- pUid[3] & 0xff,
- pUid[4] & 0xff,
- pUid[5] & 0xff,
- pUid[6] & 0xff,
- pUid[7] & 0xff);
+ pUid[0] & 0xff,
+ pUid[1] & 0xff,
+ pUid[2] & 0xff,
+ pUid[3] & 0xff,
+ pUid[4] & 0xff,
+ pUid[5] & 0xff,
+ pUid[6] & 0xff,
+ pUid[7] & 0xff);
return uid;
}
@@ -926,22 +979,22 @@ void Vehicle::_handleHilActuatorControls(mavlink_message_t &message)
mavlink_msg_hil_actuator_controls_decode(&message, &hil);
emit hilActuatorControlsChanged(hil.time_usec, hil.flags,
hil.controls[0],
- hil.controls[1],
- hil.controls[2],
- hil.controls[3],
- hil.controls[4],
- hil.controls[5],
- hil.controls[6],
- hil.controls[7],
- hil.controls[8],
- hil.controls[9],
- hil.controls[10],
- hil.controls[11],
- hil.controls[12],
- hil.controls[13],
- hil.controls[14],
- hil.controls[15],
- hil.mode);
+ hil.controls[1],
+ hil.controls[2],
+ hil.controls[3],
+ hil.controls[4],
+ hil.controls[5],
+ hil.controls[6],
+ hil.controls[7],
+ hil.controls[8],
+ hil.controls[9],
+ hil.controls[10],
+ hil.controls[11],
+ hil.controls[12],
+ hil.controls[13],
+ hil.controls[14],
+ hil.controls[15],
+ hil.mode);
}
void Vehicle::_handleCommandLong(mavlink_message_t& message)
@@ -954,19 +1007,19 @@ void Vehicle::_handleCommandLong(mavlink_message_t& message)
mavlink_msg_command_long_decode(&message, &cmd);
switch (cmd.command) {
- // Other component on the same system
- // requests that QGC frees up the serial port of the autopilot
- case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
- if (cmd.param6 > 0) {
- // disconnect the USB link if its a direct connection to a Pixhawk
- for (int i = 0; i < _links.length(); i++) {
- SerialLink *sl = qobject_cast(_links.at(i));
- if (sl && sl->getSerialConfig()->usbDirect()) {
- qDebug() << "Disconnecting:" << _links.at(i)->getName();
- qgcApp()->toolbox()->linkManager()->disconnectLink(_links.at(i));
- }
+ // Other component on the same system
+ // requests that QGC frees up the serial port of the autopilot
+ case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
+ if (cmd.param6 > 0) {
+ // disconnect the USB link if its a direct connection to a Pixhawk
+ for (int i = 0; i < _links.length(); i++) {
+ SerialLink *sl = qobject_cast(_links.at(i));
+ if (sl && sl->getSerialConfig()->usbDirect()) {
+ qDebug() << "Disconnecting:" << _links.at(i)->getName();
+ qgcApp()->toolbox()->linkManager()->disconnectLink(_links.at(i));
}
}
+ }
break;
}
#endif
@@ -1351,6 +1404,7 @@ void Vehicle::_addLink(LinkInterface* link)
qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((ulong)link, 0, 16);
_links += link;
_updatePriorityLink();
+ _updateHighLatencyLink();
connect(_toolbox->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
connect(_toolbox->linkManager(), &LinkManager::linkDeleted, this, &Vehicle::_linkInactiveOrDeleted);
connect(link, &LinkInterface::highLatencyChanged, this, &Vehicle::_updateHighLatencyLink);
@@ -2098,9 +2152,9 @@ void Vehicle::_connectionActive(void)
// Re-negotiate protocol version for the link
sendMavCommand(MAV_COMP_ID_ALL, // Don't know default component id yet.
- MAV_CMD_REQUEST_PROTOCOL_VERSION,
+ MAV_CMD_REQUEST_PROTOCOL_VERSION,
false, // No error shown if fails
- 1); // Request protocol version
+ 1); // Request protocol version
}
}
@@ -2618,7 +2672,7 @@ void Vehicle::setSoloFirmware(bool soloFirmware)
}
#if 0
- // Temporarily removed, waiting for new command implementation
+// Temporarily removed, waiting for new command implementation
void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
{
doCommandLongUnverified(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs);
@@ -2765,11 +2819,11 @@ void Vehicle::_ackMavlinkLogData(uint16_t sequence)
ack.target_component = _defaultComponentId;
ack.target_system = id();
mavlink_msg_logging_ack_encode_chan(
- _mavlink->getSystemId(),
- _mavlink->getComponentId(),
- priorityLink()->mavlinkChannel(),
- &msg,
- &ack);
+ _mavlink->getSystemId(),
+ _mavlink->getComponentId(),
+ priorityLink()->mavlinkChannel(),
+ &msg,
+ &ack);
sendMessageOnLink(priorityLink(), msg);
}
@@ -2778,7 +2832,7 @@ void Vehicle::_handleMavlinkLoggingData(mavlink_message_t& message)
mavlink_logging_data_t log;
mavlink_msg_logging_data_decode(&message, &log);
emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
- log.first_message_offset, QByteArray((const char*)log.data, log.length), false);
+ log.first_message_offset, QByteArray((const char*)log.data, log.length), false);
}
void Vehicle::_handleMavlinkLoggingDataAcked(mavlink_message_t& message)
@@ -2787,7 +2841,7 @@ void Vehicle::_handleMavlinkLoggingDataAcked(mavlink_message_t& message)
mavlink_msg_logging_data_acked_decode(&message, &log);
_ackMavlinkLogData(log.sequence);
emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
- log.first_message_offset, QByteArray((const char*)log.data, log.length), true);
+ log.first_message_offset, QByteArray((const char*)log.data, log.length), true);
}
void Vehicle::setFirmwarePluginInstanceData(QObject* firmwarePluginInstanceData)
@@ -2946,7 +3000,7 @@ QString Vehicle::hobbsMeter()
static const char* HOOBS_LO = "LND_FLIGHT_T_LO";
//-- TODO: Does this exist on non PX4?
if (_parameterManager->parameterExists(FactSystem::defaultComponentId, HOOBS_HI) &&
- _parameterManager->parameterExists(FactSystem::defaultComponentId, HOOBS_LO)) {
+ _parameterManager->parameterExists(FactSystem::defaultComponentId, HOOBS_LO)) {
Fact* factHi = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_HI);
Fact* factLo = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_LO);
uint64_t hobbsTimeSeconds = ((uint64_t)factHi->rawValue().toUInt() << 32 | (uint64_t)factLo->rawValue().toUInt()) / 1000000;
diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h
index 8159e2c4ea99f0ccaeff53b494ce01c2ca3f9ab7..35ba2a188856a859508bc27a21e3f594b9c9a68c 100644
--- a/src/Vehicle/Vehicle.h
+++ b/src/Vehicle/Vehicle.h
@@ -915,6 +915,7 @@ private:
void _handleScaledPressure(mavlink_message_t& message);
void _handleScaledPressure2(mavlink_message_t& message);
void _handleScaledPressure3(mavlink_message_t& message);
+ void _handleHighLatency2(mavlink_message_t& message);
// ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
void _handleCameraFeedback(const mavlink_message_t& message);
diff --git a/src/VehicleSetup/SetupView.qml b/src/VehicleSetup/SetupView.qml
index 1fb0418e5932cd0c319861f9b6ecae543f6d623a..9b94e26c72a696d83d3ecf87b62fc3b82a605b73 100644
--- a/src/VehicleSetup/SetupView.qml
+++ b/src/VehicleSetup/SetupView.qml
@@ -299,7 +299,9 @@ Rectangle {
SubMenuButton {
setupIndicator: false
exclusiveGroup: setupButtonGroup
- visible: QGroundControl.multiVehicleManager && QGroundControl.multiVehicleManager.parameterReadyVehicleAvailable && _corePlugin.showAdvancedUI
+ visible: QGroundControl.multiVehicleManager.parameterReadyVehicleAvailable &&
+ !QGroundControl.multiVehicleManager.activeVehicle.highLatencyLink &&
+ _corePlugin.showAdvancedUI
text: qsTr("Parameters")
Layout.fillWidth: true
diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc
index 9052ad608fcf52869de9edf186231c3692faac7a..d517a9a67b50b28e22c67f4a5dc94af341edf060 100644
--- a/src/comm/MAVLinkProtocol.cc
+++ b/src/comm/MAVLinkProtocol.cc
@@ -267,11 +267,17 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
}
if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
- // Start loggin on first heartbeat
_startLogging();
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&message, &heartbeat);
- emit vehicleHeartbeatInfo(link, message.sysid, message.compid, heartbeat.mavlink_version, heartbeat.autopilot, heartbeat.type);
+ emit vehicleHeartbeatInfo(link, message.sysid, message.compid, heartbeat.autopilot, heartbeat.type);
+ }
+
+ if (message.msgid == MAVLINK_MSG_ID_HIGH_LATENCY2) {
+ _startLogging();
+ mavlink_high_latency2_t highLatency2;
+ mavlink_msg_high_latency2_decode(&message, &highLatency2);
+ emit vehicleHeartbeatInfo(link, message.sysid, message.compid, highLatency2.autopilot, highLatency2.type);
}
// Detect if we are talking to an old radio not supporting v2
diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h
index 5d6311734020c37b270cc08cb8656cb58c0f337a..4d6ae9f79904e681c6f342a50a05c12d91b3cb0b 100644
--- a/src/comm/MAVLinkProtocol.h
+++ b/src/comm/MAVLinkProtocol.h
@@ -137,7 +137,7 @@ protected:
signals:
/// Heartbeat received on link
- void vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType);
+ void vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType);
/** @brief Message received and directly copied via signal */
void messageReceived(LinkInterface* link, mavlink_message_t message);
diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc
index 013e81e9538baa2baffd8f346005e5b2da0d541e..e2ce6a9959e0f4d56c44e4f87d66fc31333c4b13 100644
--- a/src/comm/MockLink.cc
+++ b/src/comm/MockLink.cc
@@ -13,7 +13,7 @@
#include "QGCApplication.h"
#ifdef UNITTEST_BUILD
- #include "UnitTest.h"
+#include "UnitTest.h"
#endif
#include
@@ -166,27 +166,35 @@ void MockLink::run(void)
void MockLink::_run1HzTasks(void)
{
if (_mavlinkStarted && _connected) {
- _sendVibration();
- _sendADSBVehicles();
- if (!qgcApp()->runningUnitTests()) {
- // Sending RC Channels during unit test breaks RC tests which does it's own RC simulation
- _sendRCChannels();
- }
- if (_sendHomePositionDelayCount > 0) {
- // We delay home position for better testing
- _sendHomePositionDelayCount--;
+ if (_highLatency) {
+ _sendHighLatency2();
} else {
- _sendHomePosition();
- }
- if (_sendStatusText) {
- _sendStatusText = false;
- _sendStatusTextMessages();
+ _sendVibration();
+ _sendADSBVehicles();
+ if (!qgcApp()->runningUnitTests()) {
+ // Sending RC Channels during unit test breaks RC tests which does it's own RC simulation
+ _sendRCChannels();
+ }
+ if (_sendHomePositionDelayCount > 0) {
+ // We delay home position for better testing
+ _sendHomePositionDelayCount--;
+ } else {
+ _sendHomePosition();
+ }
+ if (_sendStatusText) {
+ _sendStatusText = false;
+ _sendStatusTextMessages();
+ }
}
}
}
void MockLink::_run10HzTasks(void)
{
+ if (_highLatency) {
+ return;
+ }
+
if (_mavlinkStarted && _connected) {
_sendHeartBeat();
if (_sendGPSPositionDelayCount > 0) {
@@ -200,6 +208,10 @@ void MockLink::_run10HzTasks(void)
void MockLink::_run500HzTasks(void)
{
+ if (_highLatency) {
+ return;
+ }
+
if (_mavlinkStarted && _connected) {
_paramRequestListWorker();
_logDownloadWorker();
@@ -296,6 +308,44 @@ void MockLink::_sendHeartBeat(void)
respondWithMavlinkMessage(msg);
}
+void MockLink::_sendHighLatency2(void)
+{
+ mavlink_message_t msg;
+
+ mavlink_msg_high_latency2_pack_chan(_vehicleSystemId,
+ _vehicleComponentId,
+ _mavlinkChannel,
+ &msg,
+ 0, // timestamp
+ _vehicleType, // MAV_TYPE
+ _firmwareType, // MAV_AUTOPILOT
+ _flightModeEnumValue(), // flight_mode
+ (int32_t)(_vehicleLatitude * 1E7),
+ (int32_t)(_vehicleLongitude * 1E7),
+ (int16_t)_vehicleAltitude,
+ (int16_t)_vehicleAltitude, // target_altitude,
+ 0, // heading
+ 0, // target_heading
+ 0, // target_distance
+ 0, // throttle
+ 0, // airspeed
+ 0, // airspeed_sp
+ 0, // groundspeed
+ 0, // windspeed,
+ 0, // wind_heading
+ UINT8_MAX, // eph not known
+ UINT8_MAX, // epv not known
+ 0, // temperature_air
+ 0, // climb_rate
+ -1, // battery, do not use?
+ 0, // wp_num
+ 0, // failure_flags
+ 0, // failsafe
+ 0, 0, 0); // custom0, custom1, custom2
+
+ respondWithMavlinkMessage(msg);
+}
+
void MockLink::_sendVibration(void)
{
mavlink_message_t msg;
@@ -842,8 +892,8 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg)
case MAV_CMD_USER_3:
// Test command which returns MAV_RESULT_ACCEPTED on second attempt
if (firstCmdUser3) {
- firstCmdUser3 = false;
- return;
+ firstCmdUser3 = false;
+ return;
} else {
firstCmdUser3 = true;
commandResult = MAV_RESULT_ACCEPTED;
@@ -852,8 +902,8 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg)
case MAV_CMD_USER_4:
// Test command which returns MAV_RESULT_FAILED on second attempt
if (firstCmdUser4) {
- firstCmdUser4 = false;
- return;
+ firstCmdUser4 = false;
+ return;
} else {
firstCmdUser4 = true;
commandResult = MAV_RESULT_FAILED;
@@ -943,8 +993,8 @@ void MockLink::_sendHomePosition(void)
(int32_t)(_vehicleAltitude * 1000),
0.0f, 0.0f, 0.0f,
&bogus[0],
- 0.0f, 0.0f, 0.0f,
- 0);
+ 0.0f, 0.0f, 0.0f,
+ 0);
respondWithMavlinkMessage(msg);
}
@@ -972,7 +1022,7 @@ void MockLink::_sendGpsRawInt(void)
0, // Altitude uncertainty in meters * 1000 (positive for up).
0, // Speed uncertainty in meters * 1000 (positive for up).
0); // Heading / track uncertainty in degrees * 1e5.
- respondWithMavlinkMessage(msg);
+ respondWithMavlinkMessage(msg);
}
void MockLink::_sendStatusTextMessages(void)
@@ -1237,9 +1287,9 @@ void MockLink::_handleLogRequestData(const mavlink_message_t& msg)
mavlink_msg_log_request_data_decode(&msg, &request);
if (_logDownloadFilename.isEmpty()) {
- #ifdef UNITTEST_BUILD
+#ifdef UNITTEST_BUILD
_logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize);
- #endif
+#endif
}
if (request.id != 0) {
@@ -1320,3 +1370,8 @@ void MockLink::_sendADSBVehicles(void)
respondWithMavlinkMessage(responseMsg);
}
+
+uint8_t MockLink::_flightModeEnumValue(void)
+{
+ return FLIGHT_MODE_STABILIZED;
+}
diff --git a/src/comm/MockLink.h b/src/comm/MockLink.h
index 1eb0b48c155e19198ce0f964aa24a92dae8eadc6..f58730d1f065fa6b8caddd38ed5a96f4ce3637f0 100644
--- a/src/comm/MockLink.h
+++ b/src/comm/MockLink.h
@@ -175,6 +175,7 @@ private:
// MockLink methods
void _sendHeartBeat(void);
+ void _sendHighLatency2(void);
void _handleIncomingNSHBytes(const char* bytes, int cBytes);
void _handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes);
void _loadParams(void);
@@ -201,6 +202,7 @@ private:
void _logDownloadWorker(void);
void _sendADSBVehicles(void);
void _moveADSBVehicle(void);
+ uint8_t _flightModeEnumValue(void);
static MockLink* _startMockLink(MockConfiguration* mockConfig);
diff --git a/src/qgcunittest/UnitTestList.cc b/src/qgcunittest/UnitTestList.cc
index fe67513cc739dcc3e4222173b87b48043dda3be0..973636411581482b084ac99635169618a9db2906 100644
--- a/src/qgcunittest/UnitTestList.cc
+++ b/src/qgcunittest/UnitTestList.cc
@@ -40,6 +40,8 @@
#include "QGCMapPolygonTest.h"
#include "AudioOutputTest.h"
#include "StructureScanComplexItemTest.h"
+#include "QGCMapPolylineTest.h"
+#include "CorridorScanComplexItemTest.h"
UT_REGISTER_TEST(FactSystemTestGeneric)
UT_REGISTER_TEST(FactSystemTestPX4)
@@ -67,6 +69,8 @@ UT_REGISTER_TEST(MissionSettingsTest)
UT_REGISTER_TEST(QGCMapPolygonTest)
UT_REGISTER_TEST(AudioOutputTest)
UT_REGISTER_TEST(StructureScanComplexItemTest)
+UT_REGISTER_TEST(CorridorScanComplexItemTest)
+UT_REGISTER_TEST(QGCMapPolylineTest)
// List of unit test which are currently disabled.
// If disabling a new test, include reason in comment.