Commit a954332b authored by Gus Grubba's avatar Gus Grubba

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into pr-plugin-control

parents 01fe0bf2 7aa4b6a7
......@@ -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
......@@ -9,9 +9,10 @@
<file alias="MavCmdInfoVTOL.json">src/MissionManager/UnitTest/MavCmdInfoVTOL.json</file>
<file alias="MissionPlanner.waypoints">src/MissionManager/UnitTest/MissionPlanner.waypoints</file>
<file alias="OldFileFormat.mission">src/MissionManager/UnitTest/OldFileFormat.mission</file>
<file alias="GoodPolygon.kml">src/MissionManager/UnitTest/GoodPolygon.kml</file>
<file alias="MissingPolygonNode.kml">src/MissionManager/UnitTest/MissingPolygonNode.kml</file>
<file alias="BadXml.kml">src/MissionManager/UnitTest/BadXml.kml</file>
<file alias="BadCoordinatesNode.kml">src/MissionManager/UnitTest/BadCoordinatesNode.kml</file>
<file alias="PolygonAreaTest.kml">src/MissionManager/UnitTest/PolygonAreaTest.kml</file>
<file alias="PolygonGood.kml">src/MissionManager/UnitTest/PolygonGood.kml</file>
<file alias="PolygonMissingNode.kml">src/MissionManager/UnitTest/PolygonMissingNode.kml</file>
<file alias="PolygonBadXml.kml">src/MissionManager/UnitTest/PolygonBadXml.kml</file>
<file alias="PolygonBadCoordinatesNode.kml">src/MissionManager/UnitTest/PolygonBadCoordinatesNode.kml</file>
</qresource>
</RCC>
Subproject commit a31f7d989dffc2e554c26ad2c22c2a432a48fa74
Subproject commit 5db5e944048cd6126a3e58c67c9c4dcdb4d4e0ff
......@@ -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 \
......
......@@ -18,6 +18,7 @@
<file alias="AnalyzeView.qml">src/AnalyzeView/AnalyzeView.qml</file>
<file alias="AppSettings.qml">src/ui/AppSettings.qml</file>
<file alias="BluetoothSettings.qml">src/ui/preferences/BluetoothSettings.qml</file>
<file alias="CorridorScanEditor.qml">src/PlanView/CorridorScanEditor.qml</file>
<file alias="CustomCommandWidget.qml">src/ViewWidgets/CustomCommandWidget.qml</file>
<file alias="DebugWindow.qml">src/ui/preferences/DebugWindow.qml</file>
<file alias="ESP8266Component.qml">src/AutoPilotPlugins/Common/ESP8266Component.qml</file>
......@@ -48,6 +49,7 @@
<file alias="QGroundControl/Controls/CameraCalc.qml">src/PlanView/CameraCalc.qml</file>
<file alias="QGroundControl/Controls/CameraSection.qml">src/PlanView/CameraSection.qml</file>
<file alias="QGroundControl/Controls/ClickableColor.qml">src/QmlControls/ClickableColor.qml</file>
<file alias="QGroundControl/Controls/CorridorScanMapVisual.qml">src/PlanView/CorridorScanMapVisual.qml</file>
<file alias="QGroundControl/Controls/DropButton.qml">src/QmlControls/DropButton.qml</file>
<file alias="QGroundControl/Controls/EditPositionDialog.qml">src/QmlControls/EditPositionDialog.qml</file>
<file alias="QGroundControl/Controls/ExclusiveGroupItem.qml">src/QmlControls/ExclusiveGroupItem.qml</file>
......@@ -89,6 +91,7 @@
<file alias="QGroundControl/Controls/QGCMapLabel.qml">src/QmlControls/QGCMapLabel.qml</file>
<file alias="QGroundControl/Controls/QGCMapCircleVisuals.qml">src/MissionManager/QGCMapCircleVisuals.qml</file>
<file alias="QGroundControl/Controls/QGCMapPolygonVisuals.qml">src/MissionManager/QGCMapPolygonVisuals.qml</file>
<file alias="QGroundControl/Controls/QGCMapPolylineVisuals.qml">src/MissionManager/QGCMapPolylineVisuals.qml</file>
<file alias="QGroundControl/Controls/QGCMouseArea.qml">src/QmlControls/QGCMouseArea.qml</file>
<file alias="QGroundControl/Controls/QGCMovableItem.qml">src/QmlControls/QGCMovableItem.qml</file>
<file alias="QGroundControl/Controls/QGCPipable.qml">src/QmlControls/QGCPipable.qml</file>
......@@ -202,6 +205,7 @@
<file alias="QGCMapCircle.Facts.json">src/MissionManager/QGCMapCircle.Facts.json</file>
<file alias="RTK.SettingsGroup.json">src/Settings/RTK.SettingsGroup.json</file>
<file alias="Survey.SettingsGroup.json">src/MissionManager/Survey.SettingsGroup.json</file>
<file alias="CorridorScan.SettingsGroup.json">src/MissionManager/CorridorScan.SettingsGroup.json</file>
<file alias="StructureScan.SettingsGroup.json">src/MissionManager/StructureScan.SettingsGroup.json</file>
<file alias="Units.SettingsGroup.json">src/Settings/Units.SettingsGroup.json</file>
<file alias="Video.SettingsGroup.json">src/Settings/Video.SettingsGroup.json</file>
......
......@@ -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);
......
......@@ -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;
......
......@@ -67,7 +67,7 @@ private:
QTimer _paramRequestTimer;
bool _done;
bool _updateOnSet;
MAV_PARAM_TYPE _mavParamType;
MAV_PARAM_EXT_TYPE _mavParamType;
MAVLinkProtocol* _pMavlink;
bool _forceUIUpdate;
};
......
......@@ -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) {
......
......@@ -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;
......
......@@ -96,6 +96,7 @@ FactMetaData::FactMetaData(QObject* parent)
, _increment (std::numeric_limits<double>::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<double>::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<double>::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;
}
......
......@@ -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
......
......@@ -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();
......
......@@ -1119,7 +1119,9 @@ This parameter controls the time constant of the decay</short_desc>
</parameter>
<parameter default="0.0" name="EKF2_ARSP_THR" type="FLOAT">
<short_desc>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</short_desc>
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</short_desc>
<min>0.0</min>
<unit>m/s</unit>
<decimal>1</decimal>
......@@ -1291,7 +1293,7 @@ Increasing it makes the multi-rotor wind estimates adjust more slowly</short_des
</parameter>
<parameter default="0" name="EKF2_FUSE_BETA" type="INT32">
<short_desc>Boolean determining if synthetic sideslip measurements should fused</short_desc>
<long_desc>A value of 1 indicates that fusion is active</long_desc>
<long_desc>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.</long_desc>
<boolean />
<scope>modules/ekf2</scope>
</parameter>
......@@ -1653,7 +1655,8 @@ Assumes measurement is timestamped at trailing edge of integration period</short
<scope>modules/ekf2</scope>
</parameter>
<parameter default="2.5" name="EKF2_OF_RMAX" type="FLOAT">
<short_desc>Optical Flow data will not fused if the magnitude of the flow rate &gt; EKF2_OF_RMAX</short_desc>
<short_desc>Optical Flow data will not fused if the magnitude of the flow rate &gt; 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</short_desc>
<min>1.0</min>
<unit>rad/s</unit>
<decimal>2</decimal>
......@@ -3269,7 +3272,7 @@ but also ignore less noise</short_desc>
<decimal>3</decimal>
<scope>modules/landing_target_estimator</scope>
</parameter>
<parameter default="1.0" name="LTEST_VEL_UNC_IN" type="FLOAT">
<parameter default="0.1" name="LTEST_VEL_UNC_IN" type="FLOAT">
<short_desc>Initial landing target velocity uncertainty</short_desc>
<long_desc>Initial variance of the relative landing target velocity in x and y direction</long_desc>
<min>0.001</min>
......@@ -3801,6 +3804,17 @@ Used to calculate increased terrain random walk nosie due to movement</short_des
<increment>0.5</increment>
<scope>modules/navigator</scope>
</parameter>
<parameter default="0" name="MIS_MNT_YAW_CTL" type="INT32">
<short_desc>Enable yaw control of the mount. (Only affects multicopters and ROI mission items)</short_desc>
<long_desc>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.</long_desc>
<min>0</min>
<max>1</max>
<scope>modules/navigator</scope>
<values>
<value code="0">Disable</value>
<value code="1">Enable</value>
</values>
</parameter>
<parameter default="2.5" name="MIS_TAKEOFF_ALT" type="FLOAT">
<short_desc>Take-off altitude</short_desc>
<long_desc>This is the minimum altitude the system will take off to.</long_desc>
......@@ -3822,7 +3836,6 @@ Used to calculate increased terrain random walk nosie due to movement</short_des
<value code="1">Heading towards waypoint</value>
<value code="2">Heading towards home</value>
<value code="3">Heading away from home</value>
<value code="4">Heading towards ROI</value>
</values>
</parameter>
<parameter default="12.0" name="MIS_YAW_ERR" type="FLOAT">
......@@ -4446,6 +4459,17 @@ default 1.5 turns per second</short_desc>
<increment>1</increment>
<scope>modules/mc_pos_control</scope>
</parameter>
<parameter default="0.5" name="MPC_ACC_HOR_FLOW" type="FLOAT">
<short_desc>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</short_desc>
<min>0.2</min>
<max>2.0</max>
<unit>m/s/s</unit>
<decimal>1</decimal>
<increment>0.1</increment>
<scope>modules/mc_pos_control</scope>
</parameter>
<parameter default="10.0" name="MPC_ACC_HOR_MAX" type="FLOAT">
<short_desc>Maximum horizontal acceleration for auto mode and maximum deceleration for manual mode</short_desc>
<min>2.0</min>
......@@ -7956,6 +7980,11 @@ This is used for gathering replay logs for the ekf2 module</short_desc>
<long_desc>The offset (zero-reading) in Pascal</long_desc>
<scope>modules/sensors</scope>
</parameter>
<parameter default="0.7" name="SENS_FLOW_MINRNG" type="FLOAT">
<short_desc>Optical Flow minimum focus distance</short_desc>
<long_desc>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. *</long_desc>
<scope>modules/sensors</scope>
</parameter>
</group>
<group name="Sensors">
<parameter default="63" name="CAL_MAG_SIDES" type="INT32">
......
......@@ -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; }
......
......@@ -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
[
{
"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
}
]
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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<double>::quiet_NaN(); }
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void appendMissionItems (QList<MissionItem*>& 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<QString, FactMetaData*> _metaDataMap;
static const char* _corridorWidthFactName;
static const char* _jsonCameraCalcKey;
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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<Fact*> 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<QGeoCoordinate> rgSeenEntryCoords;
QList<int> rgEntryLocation;
rgEntryLocation << SurveyMissionItem::EntryLocationTopLeft
<< SurveyMissionItem::EntryLocationTopRight
<< SurveyMissionItem::EntryLocationBottomLeft
<< SurveyMissionItem::EntryLocationBottomRight;
// Validate that each entry location is unique
for (int i=0; i<rgEntryLocation.count(); i++) {
int entryLocation = rgEntryLocation[i];
_corridorItem->gridEntryLocation()->setRawValue(entryLocation);
QVERIFY(!rgSeenEntryCoords.contains(_corridorItem->coordinate()));
rgSeenEntryCoords << _corridorItem->coordinate();
}
rgSeenEntryCoords.clear();
}
}
#endif
void CorridorScanComplexItemTest::_testItemCount(void)
{
QList<MissionItem*> 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();
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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 <QGeoCoordinate>
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<QGeoCoordinate> _linePoints;
};
......@@ -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<MissionSettingsItem*>(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<SurveyMissionItem*>(index);
bool removeSurveyStyle = _visualItems->value<SurveyMissionItem*>(index) || _visualItems->value<CorridorScanComplexItem*>(index);
VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_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<SurveyMissionItem*>(i)) {
if (_visualItems->value<SurveyMissionItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(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);
}
......
......@@ -253,6 +253,7 @@ private:
QString _surveyMissionItemName;
QString _fwLandingMissionItemName;
QString _structureScanMissionItemName;
QString _corridorScanMissionItemName;
AppSettings* _appSettings;
double _progressPct;
int _currentPlanViewIndex;
......
......@@ -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()) {
......
......@@ -362,7 +362,7 @@ QGeoCoordinate QGCMapPolygon::vertexCoordinate(int vertex) const
}
}
QList<QPointF> QGCMapPolygon::nedPolygon(void)
QList<QPointF> QGCMapPolygon::nedPolygon(void) const
{
QList<QPointF> 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<QPointF> nedVertices = nedPolygon();
for (int i=0; i<nedVertices.count(); i++) {
if (i != 0) {
coveredArea += nedVertices[i - 1].x() * nedVertices[i].y() - nedVertices[i].x() * nedVertices[i -1].y();
} else {
coveredArea += nedVertices.last().x() * nedVertices[i].y() - nedVertices[i].x() * nedVertices.last().y();
}
}
return 0.5 * fabs(coveredArea);
}
......@@ -77,7 +77,10 @@ public:
bool loadFromJson(const QJsonObject& json, bool required, QString& errorString);
/// Convert polygon to NED and return (D is ignored)
QList<QPointF> nedPolygon(void);
QList<QPointF> nedPolygon(void) const;
/// Returns the area of the polygon in meters squared
double area(void) const;
// Property methods
......
......@@ -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();
}
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <QGeoCoordinate>
#include <QVariantList>
#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<QGeoCoordinate> 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<QGeoCoordinate> 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<QPointF> 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<QGeoCoordinate>& 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;
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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<QGeoCoordinate>(), _linePoints[i]);
QCOMPARE(_pathModel->count(), i+1);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(i)->coordinate(), _linePoints[i]);
_mapPolyline->setDirty(false);
_multiSpyPolyline->clearAllSignals();
_multiSpyModel->clearAllSignals();
}
// Vertex adjustment testing
QGCQGeoCoordinate* geoCoord = _pathModel->value<QGCQGeoCoordinate*>(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<QGeoCoordinate>(), _linePoints[0]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(0)->coordinate(), _linePoints[0]);
QCOMPARE(vertexList[2].value<QGeoCoordinate>(), _linePoints[2]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(2)->coordinate(), _linePoints[2]);
QCOMPARE(vertexList[3].value<QGeoCoordinate>(), _linePoints[3]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(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<QGeoCoordinate>(), _linePoints[0]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(0)->coordinate(), _linePoints[0]);
QCOMPARE(vertexList[1].value<QGeoCoordinate>(), _linePoints[2]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(1)->coordinate(), _linePoints[2]);
QCOMPARE(vertexList[2].value<QGeoCoordinate>(), _linePoints[3]);
QCOMPARE(_pathModel->value<QGCQGeoCoordinate*>(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
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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<QGeoCoordinate> _linePoints;
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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 = [ ]
}
}
}
}
}
......@@ -102,7 +102,7 @@ void StructureScanComplexItem::_setScanDistance(double scanDistance)
{
if (!qFuzzyCompare(_scanDistance, scanDistance)) {
_scanDistance = scanDistance;
emit complexDistanceChanged(_scanDistance);
emit complexDistanceChanged();
}
}
......
......@@ -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();
......
<?xml version="1.0" encoding="UTF-8"?>
<kml xmlns="http://www.opengis.net/kml/2.2" xmlns:gx="http://www.google.com/kml/ext/2.2" xmlns:kml="http://www.opengis.net/kml/2.2" xmlns:atom="http://www.w3.org/2005/Atom">
<Document>
<name>AreaTestPolygon.kmz</name>
<StyleMap id="m_ylw-pushpin">
<Pair>
<key>normal</key>
<styleUrl>#s_ylw-pushpin</styleUrl>
</Pair>
<Pair>
<key>highlight</key>
<styleUrl>#s_ylw-pushpin_hl</styleUrl>
</Pair>
</StyleMap>
<Style id="s_ylw-pushpin">
<IconStyle>
<scale>1.1</scale>
<Icon>
<href>http://maps.google.com/mapfiles/kml/pushpin/ylw-pushpin.png</href>
</Icon>
<hotSpot x="20" y="2" xunits="pixels" yunits="pixels"/>
</IconStyle>
</Style>
<Style id="s_ylw-pushpin_hl">
<IconStyle>
<scale>1.3</scale>
<Icon>
<href>http://maps.google.com/mapfiles/kml/pushpin/ylw-pushpin.png</href>
</Icon>
<hotSpot x="20" y="2" xunits="pixels" yunits="pixels"/>
</IconStyle>
</Style>
<Placemark>
<name>Untitled Polygon</name>
<styleUrl>#m_ylw-pushpin</styleUrl>
<Polygon>
<tessellate>1</tessellate>
<outerBoundaryIs>
<LinearRing>
<coordinates>
-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
</coordinates>
</LinearRing>
</outerBoundaryIs>
</Polygon>
</Placemark>
</Document>
</kml>
......@@ -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);
}
......
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<coordinates.length; i++) {
missionItem.addPolygonCoordinate(coordinates[i])
}
}
function polygonAdjustVertex(vertexIndex, vertexCoordinate) {
missionItem.adjustPolygonCoordinate(vertexIndex, vertexCoordinate)
}
function polygonAdjustStarted() { }
function polygonAdjustFinished() { }
QGCPalette { id: qgcPal; colorGroupEnabled: true }
Column {
id: editorColumn
anchors.margins: _margin
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("WARNING WORK IN PROGRESS: BE VERY CAREFUL WHEN FLYING")
wrapMode: Text.WordWrap
color: qgcPal.warningText
font.pointSize: ScreenTools.smallFontPointSize
}
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(missionItem.cameraMinTriggerInterval.toFixed(1))
wrapMode: Text.WordWrap
color: qgcPal.warningText
visible: missionItem.cameraShots > 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
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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
}
}
}
......@@ -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
......
......@@ -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
......
......@@ -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);
......
......@@ -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:
......
This diff is collapsed.
......@@ -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);
......
......@@ -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
......
......@@ -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
......
......@@ -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);
......
......@@ -13,7 +13,7 @@
#include "QGCApplication.h"
#ifdef UNITTEST_BUILD
#include "UnitTest.h"
#include "UnitTest.h"
#endif
#include <QTimer>
......@@ -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;
}
......@@ -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);
......
......@@ -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.
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment