diff --git a/Jenkinsfile b/Jenkinsfile
index 56e7fed77127117fe94d8ecf7a93275149c2a305..649233dbb9f40894aed1fc4c1bb6e1dfc7d927e0 100644
--- a/Jenkinsfile
+++ b/Jenkinsfile
@@ -2,9 +2,103 @@ pipeline {
agent any
stages {
stage('build') {
- steps {
- sh 'git status'
+ parallel {
+ stage('Linux Debug') {
+ environment {
+ CCACHE_BASEDIR = "${env.WORKSPACE}"
+ QGC_CONFIG = 'debug'
+ QMAKE_VER = "5.9.2/gcc_64/bin/qmake"
+ }
+ agent {
+ docker {
+ image 'mavlink/qgc-build-linux'
+ args '-v ${CCACHE_DIR}:${CCACHE_DIR}:rw'
+ }
+ }
+ steps {
+ sh 'export'
+ sh 'ccache -z'
+ sh 'git submodule deinit -f .'
+ sh 'git clean -ff -x -d .'
+ sh 'git submodule update --init --recursive --force'
+ sh 'mkdir build; cd build; ${QT_PATH}/${QMAKE_VER} -r ${WORKSPACE}/qgroundcontrol.pro CONFIG+=${QGC_CONFIG} CONFIG+=WarningsAsErrorsOn'
+ sh 'cd build; make -j`nproc --all`'
+ sh 'ccache -s'
+ }
+ }
+ stage('Linux Release') {
+ environment {
+ CCACHE_BASEDIR = "${env.WORKSPACE}"
+ QGC_CONFIG = 'release'
+ QMAKE_VER = "5.9.2/gcc_64/bin/qmake"
+ }
+ agent {
+ docker {
+ image 'mavlink/qgc-build-linux'
+ args '-v ${CCACHE_DIR}:${CCACHE_DIR}:rw'
+ }
+ }
+ steps {
+ sh 'export'
+ sh 'ccache -z'
+ sh 'git submodule deinit -f .'
+ sh 'git clean -ff -x -d .'
+ sh 'git submodule update --init --recursive --force'
+ sh 'mkdir build; cd build; ${QT_PATH}/${QMAKE_VER} -r ${WORKSPACE}/qgroundcontrol.pro CONFIG+=${QGC_CONFIG} CONFIG+=WarningsAsErrorsOn'
+ sh 'cd build; make -j`nproc --all`'
+ sh 'ccache -s'
+ }
+ }
+ stage('OSX Debug') {
+ agent {
+ node {
+ label 'mac'
+ }
+ }
+ environment {
+ CCACHE_BASEDIR = "${env.WORKSPACE}"
+ QGC_CONFIG = 'debug'
+ QMAKE_VER = "5.9.3/clang_64/bin/qmake"
+ }
+ steps {
+ sh 'export'
+ sh 'ccache -z'
+ sh 'git submodule deinit -f .'
+ sh 'git clean -ff -x -d .'
+ sh 'git submodule update --init --recursive --force'
+ sh 'mkdir build; cd build; ${QT_PATH}/${QMAKE_VER} -r ${WORKSPACE}/qgroundcontrol.pro CONFIG+=${QGC_CONFIG} CONFIG+=WarningsAsErrorsOn'
+ sh 'cd build; make -j`sysctl -n hw.ncpu`'
+ sh 'ccache -s'
+ }
+ }
+ stage('OSX Release') {
+ agent {
+ node {
+ label 'mac'
+ }
+ }
+ environment {
+ CCACHE_BASEDIR = "${env.WORKSPACE}"
+ QGC_CONFIG = 'release'
+ QMAKE_VER = "5.9.3/clang_64/bin/qmake"
+ }
+ steps {
+ sh 'export'
+ sh 'ccache -z'
+ sh 'git submodule deinit -f .'
+ sh 'git clean -ff -x -d .'
+ sh 'git submodule update --init --recursive --force'
+ sh 'mkdir build; cd build; ${QT_PATH}/${QMAKE_VER} -r ${WORKSPACE}/qgroundcontrol.pro CONFIG+=${QGC_CONFIG} CONFIG+=WarningsAsErrorsOn'
+ sh 'cd build; make -j`sysctl -n hw.ncpu`'
+ sh 'ccache -s'
+ }
+ }
}
}
}
-}
\ No newline at end of file
+ environment {
+ CCACHE_CPP2 = '1'
+ CCACHE_DIR = '/tmp/ccache'
+ QT_FATAL_WARNINGS = '1'
+ }
+}
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..f36b9c4c5c0c9b6d33621779469de0c1e7eea457 160000
--- a/libs/mavlink/include/mavlink/v2.0
+++ b/libs/mavlink/include/mavlink/v2.0
@@ -1 +1 @@
-Subproject commit a31f7d989dffc2e554c26ad2c22c2a432a48fa74
+Subproject commit f36b9c4c5c0c9b6d33621779469de0c1e7eea457
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 3b76e50c2e8ca58ea625bd5b8fc0566d123e7551..501ba7c03d2a0a5989904e4ac296e95ae56bab4f 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -7,14 +7,16 @@
# License terms set in COPYING.md
# -------------------------------------------------
+QMAKE_PROJECT_DEPTH = 0 # undocumented qmake flag to force absolute paths in make files
+
exists($${OUT_PWD}/qgroundcontrol.pro) {
error("You must use shadow build (e.g. mkdir build; cd build; qmake ../qgroundcontrol.pro).")
}
message(Qt version $$[QT_VERSION])
-!equals(QT_MAJOR_VERSION, 5) | !greaterThan(QT_MINOR_VERSION, 6) {
- error("Unsupported Qt version, 5.7+ is required")
+!equals(QT_MAJOR_VERSION, 5) | !greaterThan(QT_MINOR_VERSION, 8) {
+ error("Unsupported Qt version, 5.9+ is required")
}
include(QGCCommon.pri)
@@ -207,8 +209,7 @@ contains(DEFINES, ENABLE_VERBOSE_OUTPUT) {
} else:exists(user_config.pri):infile(user_config.pri, DEFINES, ENABLE_VERBOSE_OUTPUT) {
message("Enable verbose compiler output (manual override from user_config.pri)")
} else {
-CONFIG += \
- silent
+ CONFIG += silent
}
QT += \
@@ -414,7 +415,9 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/FactSystem/FactSystemTestGeneric.h \
src/FactSystem/FactSystemTestPX4.h \
src/FactSystem/ParameterManagerTest.h \
+ src/MissionManager/CameraCalcTest.h \
src/MissionManager/CameraSectionTest.h \
+ src/MissionManager/CorridorScanComplexItemTest.h \
src/MissionManager/MissionCommandTreeTest.h \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionControllerTest.h \
@@ -423,11 +426,13 @@ 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 \
src/MissionManager/StructureScanComplexItemTest.h \
src/MissionManager/SurveyMissionItemTest.h \
+ src/MissionManager/TransectStyleComplexItemTest.h \
src/MissionManager/VisualMissionItemTest.h \
src/qgcunittest/FileDialogTest.h \
src/qgcunittest/FileManagerTest.h \
@@ -451,7 +456,9 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/FactSystem/FactSystemTestGeneric.cc \
src/FactSystem/FactSystemTestPX4.cc \
src/FactSystem/ParameterManagerTest.cc \
+ src/MissionManager/CameraCalcTest.cc \
src/MissionManager/CameraSectionTest.cc \
+ src/MissionManager/CorridorScanComplexItemTest.cc \
src/MissionManager/MissionCommandTreeTest.cc \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionControllerTest.cc \
@@ -460,11 +467,13 @@ 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 \
src/MissionManager/StructureScanComplexItemTest.cc \
src/MissionManager/SurveyMissionItemTest.cc \
+ src/MissionManager/TransectStyleComplexItemTest.cc \
src/MissionManager/VisualMissionItemTest.cc \
src/qgcunittest/FileDialogTest.cc \
src/qgcunittest/FileManagerTest.cc \
@@ -508,6 +517,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 +536,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 \
@@ -534,6 +545,7 @@ HEADERS += \
src/MissionManager/SpeedSection.h \
src/MissionManager/StructureScanComplexItem.h \
src/MissionManager/SurveyMissionItem.h \
+ src/MissionManager/TransectStyleComplexItem.h \
src/MissionManager/VisualMissionItem.h \
src/PositionManager/PositionManager.h \
src/PositionManager/SimulatedPosition.h \
@@ -701,6 +713,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 \
@@ -719,6 +732,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 \
@@ -726,6 +740,7 @@ SOURCES += \
src/MissionManager/SpeedSection.cc \
src/MissionManager/StructureScanComplexItem.cc \
src/MissionManager/SurveyMissionItem.cc \
+ src/MissionManager/TransectStyleComplexItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/PositionManager/PositionManager.cpp \
src/PositionManager/SimulatedPosition.cc \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 366817258be621af4112dfb5b2c4aab8ac277cb6..f9679f4f4725995f1679cf46666d67d3fe1ae5c1 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
@@ -201,7 +204,9 @@
src/Settings/Guided.SettingsGroup.json
src/MissionManager/QGCMapCircle.Facts.json
src/Settings/RTK.SettingsGroup.json
+ src/MissionManager/TransectStyle.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/AutoPilotPlugins/Common/RadioComponentController.cc b/src/AutoPilotPlugins/Common/RadioComponentController.cc
index f14f07694d5a5e3336ff8c922ff391056ae63887..2884fec938d1ead79aaffa121b1fe9a6d829b82e 100644
--- a/src/AutoPilotPlugins/Common/RadioComponentController.cc
+++ b/src/AutoPilotPlugins/Common/RadioComponentController.cc
@@ -123,23 +123,23 @@ RadioComponentController::~RadioComponentController()
/// @brief Returns the state machine entry for the specified state.
const RadioComponentController::stateMachineEntry* RadioComponentController::_getStateMachineEntry(int step) const
{
- static const char* msgBeginPX4 = "Lower the Throttle stick all the way down as shown in diagram.\n\n"
+ static const char* msgBeginPX4 = QT_TR_NOOP("Lower the Throttle stick all the way down as shown in diagram.\n\n"
"It is recommended to disconnect all motors for additional safety, however, the system is designed to not arm during the calibration.\n\n"
- "Click Next to continue";
- static const char* msgBeginAPM = "Lower the Throttle stick all the way down as shown in diagram.\nReset all transmitter trims to center.\n\n"
+ "Click Next to continue");
+ static const char* msgBeginAPM = QT_TR_NOOP("Lower the Throttle stick all the way down as shown in diagram.\nReset all transmitter trims to center.\n\n"
"Please ensure all motor power is disconnected AND all props are removed from the vehicle.\n\n"
- "Click Next to continue";
- static const char* msgThrottleUp = "Move the Throttle stick all the way up and hold it there...";
- static const char* msgThrottleDown = "Move the Throttle stick all the way down and leave it there...";
- static const char* msgYawLeft = "Move the Yaw stick all the way to the left and hold it there...";
- static const char* msgYawRight = "Move the Yaw stick all the way to the right and hold it there...";
- static const char* msgRollLeft = "Move the Roll stick all the way to the left and hold it there...";
- static const char* msgRollRight = "Move the Roll stick all the way to the right and hold it there...";
- static const char* msgPitchDown = "Move the Pitch stick all the way down and hold it there...";
- static const char* msgPitchUp = "Move the Pitch stick all the way up and hold it there...";
- static const char* msgPitchCenter = "Allow the Pitch stick to move back to center...";
- static const char* msgSwitchMinMax = "Move all the transmitter switches and/or dials back and forth to their extreme positions.";
- static const char* msgComplete = "All settings have been captured. Click Next to write the new parameters to your board.";
+ "Click Next to continue");
+ static const char* msgThrottleUp = QT_TR_NOOP("Move the Throttle stick all the way up and hold it there...");
+ static const char* msgThrottleDown = QT_TR_NOOP("Move the Throttle stick all the way down and leave it there...");
+ static const char* msgYawLeft = QT_TR_NOOP("Move the Yaw stick all the way to the left and hold it there...");
+ static const char* msgYawRight = QT_TR_NOOP("Move the Yaw stick all the way to the right and hold it there...");
+ static const char* msgRollLeft = QT_TR_NOOP("Move the Roll stick all the way to the left and hold it there...");
+ static const char* msgRollRight = QT_TR_NOOP("Move the Roll stick all the way to the right and hold it there...");
+ static const char* msgPitchDown = QT_TR_NOOP("Move the Pitch stick all the way down and hold it there...");
+ static const char* msgPitchUp = QT_TR_NOOP("Move the Pitch stick all the way up and hold it there...");
+ static const char* msgPitchCenter = QT_TR_NOOP("Allow the Pitch stick to move back to center...");
+ static const char* msgSwitchMinMax = QT_TR_NOOP("Move all the transmitter switches and/or dials back and forth to their extreme positions.");
+ static const char* msgComplete = QT_TR_NOOP("All settings have been captured. Click Next to write the new parameters to your board.");
static const stateMachineEntry rgStateMachinePX4[] = {
//Function
@@ -206,9 +206,9 @@ void RadioComponentController::_advanceState(void)
/// @brief Sets up the state machine according to the current step from _currentStep.
void RadioComponentController::_setupCurrentState(void)
{
- static const char* msgBeginAPMRover = "Center the Throttle stick as shown in diagram.\nReset all transmitter trims to center.\n\n"
+ static const char* msgBeginAPMRover = QT_TR_NOOP("Center the Throttle stick as shown in diagram.\nReset all transmitter trims to center.\n\n"
"Please ensure all motor power is disconnected from the vehicle.\n\n"
- "Click Next to continue";
+ "Click Next to continue");
const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
const char* instructions = state->instructions;
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/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc
index e1fd2d659c7f135151fa690680168facf47487c8..54112718fceb900e7ae5e354f5fba5715b253383 100644
--- a/src/FirmwarePlugin/FirmwarePlugin.cc
+++ b/src/FirmwarePlugin/FirmwarePlugin.cc
@@ -620,4 +620,9 @@ QGCCameraControl* FirmwarePlugin::createCameraControl(const mavlink_camera_infor
return NULL;
}
+uint32_t FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode)
+{
+ // Standard implementation assumes no special handling. Upper part of 32 bit value is not used.
+ return hlCustomMode;
+}
diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h
index 4016383f19b0f1e3931d50ca3e2a793fe2efd113..7d95f4053584ab325563590104caeb1a32668702 100644
--- a/src/FirmwarePlugin/FirmwarePlugin.h
+++ b/src/FirmwarePlugin/FirmwarePlugin.h
@@ -304,6 +304,9 @@ public:
/// Returns true if the vehicle is a VTOL
virtual bool isVtol(const Vehicle* vehicle) const;
+ /// Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value.
+ virtual uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode);
+
// FIXME: Hack workaround for non pluginize FollowMe support
static const QString px4FollowMeFlightMode;
diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
index 3a5c7972eabcedf1c66a487c20bb5aa6f3c36519..8ea457b678810bf189621c5f3364dde3ddef3281 100644
--- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
@@ -589,3 +589,12 @@ QGCCameraControl* PX4FirmwarePlugin::createCameraControl(const mavlink_camera_in
{
return new QGCCameraControl(info, vehicle, compID, parent);
}
+
+uint32_t PX4FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode)
+{
+ union px4_custom_mode px4_cm;
+ px4_cm.data = 0;
+ px4_cm.custom_mode_hl = hlCustomMode;
+
+ return px4_cm.data;
+}
diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
index 0df75a1d5669e491017d1fa8efc55de3c5780d38..6497793e9295da58596cfaca371180d69f99c23c 100644
--- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
@@ -70,6 +70,7 @@ public:
QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("COM_DISARM_LAND"); }
QGCCameraManager* createCameraManager (Vehicle* vehicle) override;
QGCCameraControl* createCameraControl (const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL) override;
+ uint32_t highLatencyCustomModeTo32Bits (uint16_t hlCustomMode) override;
protected:
typedef struct {
diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml
index dddaf1e5fd646b202caa38e2ad9d3d076f0c1a87..b7404a0008d1a00bcde4ad8cc37c410f1eae7c1b 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
@@ -2480,7 +2483,7 @@ Set to 0 to disable heading hold
Launch detection
- lib/launchdetection
+ modules/fw_pos_control_l1/launchdetection
Catapult accelerometer threshold
@@ -2489,7 +2492,7 @@ Set to 0 to disable heading hold
m/s/s
1
0.5
- lib/launchdetection
+ modules/fw_pos_control_l1/launchdetection
Motor delay
@@ -2499,7 +2502,7 @@ Set to 0 to disable heading hold
s
1
0.5
- lib/launchdetection
+ modules/fw_pos_control_l1/launchdetection
Maximum pitch before the throttle is powered up (during motor delay phase)
@@ -2509,7 +2512,7 @@ Set to 0 to disable heading hold
deg
1
0.5
- lib/launchdetection
+ modules/fw_pos_control_l1/launchdetection
Catapult time threshold
@@ -2519,7 +2522,7 @@ Set to 0 to disable heading hold
s
2
0.05
- lib/launchdetection
+ modules/fw_pos_control_l1/launchdetection
@@ -4456,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
@@ -7253,14 +7267,14 @@ FW_AIRSPD_MIN * RWTO_AIRSPD_SCL
norm
2
0.01
- lib/runway_takeoff
+ modules/fw_pos_control_l1/runway_takeoff
Specifies which heading should be held during runnway takeoff
0: airframe heading, 1: heading towards takeoff waypoint
0
1
- lib/runway_takeoff
+ modules/fw_pos_control_l1/runway_takeoff
Airframe
Waypoint
@@ -7275,7 +7289,7 @@ pitch of 10 degrees during takeoff, so this must be larger if set
deg
1
0.5
- lib/runway_takeoff
+ modules/fw_pos_control_l1/runway_takeoff
Max roll during climbout.
@@ -7286,7 +7300,7 @@ navigation before we're on a safe height
deg
1
0.5
- lib/runway_takeoff
+ modules/fw_pos_control_l1/runway_takeoff
Max throttle during runway takeoff.
@@ -7296,7 +7310,7 @@ navigation before we're on a safe height
norm
2
0.01
- lib/runway_takeoff
+ modules/fw_pos_control_l1/runway_takeoff
Altitude AGL at which we have enough ground clearance to allow some roll.
@@ -7308,7 +7322,7 @@ FW_CLMBOUT_DIFF if FW_CLMBOUT_DIFF > 0
m
1
1
- lib/runway_takeoff
+ modules/fw_pos_control_l1/runway_takeoff
Pitch setpoint during taxi / before takeoff airspeed is reached.
@@ -7320,12 +7334,12 @@ to takeoff is reached
deg
1
0.5
- lib/runway_takeoff
+ modules/fw_pos_control_l1/runway_takeoff
Runway takeoff with landing gear
- lib/runway_takeoff
+ modules/fw_pos_control_l1/runway_takeoff
@@ -7966,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
+
@@ -8057,6 +8076,12 @@ This is used for gathering replay logs for the ekf2 module
deg
modules/sensors
+
+ LeddarOne rangefinder
+
+ true
+ modules/sensors
+
Lidar-Lite (LL40LS)
0
@@ -8384,6 +8409,10 @@ This is used for gathering replay logs for the ekf2 module
TEST_2
systemcmds/tests
+
+ TEST_3
+ systemcmds/tests
+
TEST_D
lib/controllib/controllib_test
diff --git a/src/FirmwarePlugin/PX4/px4_custom_mode.h b/src/FirmwarePlugin/PX4/px4_custom_mode.h
index 2c0087e8f165189f89ec4d35015d7b45697fb38d..48a29f2cda456b06abc950b0b99feb6eef6641c7 100644
--- a/src/FirmwarePlugin/PX4/px4_custom_mode.h
+++ b/src/FirmwarePlugin/PX4/px4_custom_mode.h
@@ -71,7 +71,11 @@ union px4_custom_mode {
uint8_t main_mode;
uint8_t sub_mode;
};
- uint32_t data;
+ struct {
+ uint16_t reserved_hl;
+ uint16_t custom_mode_hl;
+ };
+ uint32_t data;
float data_float;
};
diff --git a/src/FlightMap/Widgets/CameraPageWidget.qml b/src/FlightMap/Widgets/CameraPageWidget.qml
index efa6eb91d5adaeef832d27b96d0ff7c9c3849f92..672e279a2141179dfb307c35e1600fdb3bcebd69 100644
--- a/src/FlightMap/Widgets/CameraPageWidget.qml
+++ b/src/FlightMap/Widgets/CameraPageWidget.qml
@@ -26,23 +26,26 @@ import QGroundControl.FactControls 1.0
/// Camera page for Instrument Panel PageView
Column {
width: pageWidth
- spacing: ScreenTools.defaultFontPixelHeight
+ spacing: ScreenTools.defaultFontPixelHeight * 0.25
property bool showSettingsIcon: _camera !== null
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _dynamicCameras: _activeVehicle ? _activeVehicle.dynamicCameras : null
property bool _isCamera: _dynamicCameras ? _dynamicCameras.cameras.count > 0 : false
+ property var _camera: _isCamera ? _dynamicCameras.cameras.get(0) : null // Single camera support for the time being
property bool _cameraModeUndefined: _isCamera ? _dynamicCameras.cameras.get(0).cameraMode === QGCCameraControl.CAMERA_MODE_UNDEFINED : true
property bool _cameraVideoMode: _isCamera ? _dynamicCameras.cameras.get(0).cameraMode === 1 : false
property bool _cameraPhotoMode: _isCamera ? _dynamicCameras.cameras.get(0).cameraMode === 0 : false
- property var _camera: _isCamera ? _dynamicCameras.cameras.get(0) : null // Single camera support for the time being
+ property bool _cameraPhotoIdle: _isCamera && _camera.photoStatus === QGCCameraControl.PHOTO_CAPTURE_IDLE
+ property bool _cameraElapsedMode: _isCamera && _camera.cameraMode === QGCCameraControl.CAM_MODE_PHOTO && _camera.photoMode === QGCCameraControl.PHOTO_CAPTURE_TIMELAPSE
property real _spacers: ScreenTools.defaultFontPixelHeight * 0.5
property real _labelFieldWidth: ScreenTools.defaultFontPixelWidth * 30
property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 30
property bool _communicationLost: _activeVehicle ? _activeVehicle.connectionLost : false
property bool _hasModes: _isCamera && _camera && _camera.hasModes
property bool _videoRecording: _camera && _camera.videoStatus === QGCCameraControl.VIDEO_CAPTURE_STATUS_RUNNING
+ property bool _noStorage: _camera && _camera.storageTotal === 0
function showSettings() {
qgcView.showDialog(cameraSettings, _cameraVideoMode ? qsTr("Video Settings") : qsTr("Camera Settings"), 70, StandardButton.Ok)
@@ -60,13 +63,21 @@ Column {
//-- Actual controller
QGCLabel {
id: cameraLabel
- text: _isCamera ? _dynamicCameras.cameras.get(0).modelName : qsTr("Camera")
+ text: _isCamera ? _camera.modelName : qsTr("Camera")
visible: _isCamera
font.pointSize: ScreenTools.smallFontPointSize
anchors.horizontalCenter: parent.horizontalCenter
}
+ QGCLabel {
+ text: _camera ? qsTr("Free Space: ") + _camera.storageFreeStr : ""
+ font.pointSize: ScreenTools.smallFontPointSize
+ anchors.horizontalCenter: parent.horizontalCenter
+ visible: _camera && !_noStorage
+ }
//-- Camera Mode (visible only if camera has modes)
+ Item { width: 1; height: ScreenTools.defaultFontPixelHeight * 0.75; visible: camMode.visible; }
Rectangle {
+ id: camMode
width: _hasModes ? ScreenTools.defaultFontPixelWidth * 8 : 0
height: _hasModes ? ScreenTools.defaultFontPixelWidth * 4 : 0
color: qgcPal.button
@@ -129,19 +140,21 @@ Column {
}
}
//-- Shutter
+ Item { width: 1; height: ScreenTools.defaultFontPixelHeight * 0.75; visible: camShutter.visible; }
Rectangle {
+ id: camShutter
color: Qt.rgba(0,0,0,0)
width: ScreenTools.defaultFontPixelWidth * 6
height: width
radius: width * 0.5
- visible: _isCamera
+ visible: _isCamera
border.color: qgcPal.buttonText
border.width: 3
anchors.horizontalCenter: parent.horizontalCenter
Rectangle {
- width: parent.width * (_videoRecording ? 0.5 : 0.75)
+ width: parent.width * (_videoRecording || (_cameraPhotoMode && !_cameraPhotoIdle && _cameraElapsedMode) ? 0.5 : 0.75)
height: width
- radius: _videoRecording ? 0 : width * 0.5
+ radius: _videoRecording || (_cameraPhotoMode && !_cameraPhotoIdle && _cameraElapsedMode) ? 0 : width * 0.5
color: _cameraModeUndefined ? qgcPal.colorGrey : qgcPal.colorRed
anchors.centerIn: parent
}
@@ -152,11 +165,28 @@ Column {
if(_cameraVideoMode) {
_camera.toggleVideo()
} else {
- _camera.takePhoto()
+ if(_cameraPhotoMode && !_cameraPhotoIdle && _cameraElapsedMode) {
+ _camera.stopTakePhoto()
+ } else {
+ _camera.takePhoto()
+ }
}
}
}
}
+ Item { width: 1; height: ScreenTools.defaultFontPixelHeight * 0.75; visible: _isCamera; }
+ QGCLabel {
+ text: (_cameraVideoMode && _camera.videoStatus === QGCCameraControl.VIDEO_CAPTURE_STATUS_RUNNING) ? _camera.recordTimeStr : "00:00:00"
+ font.pointSize: ScreenTools.smallFontPointSize
+ visible: _cameraVideoMode
+ anchors.horizontalCenter: parent.horizontalCenter
+ }
+ QGCLabel {
+ text: _activeVehicle && _cameraPhotoMode ? ('00000' + _activeVehicle.cameraTriggerPoints.count).slice(-5) : "00000"
+ font.pointSize: ScreenTools.smallFontPointSize
+ visible: _cameraPhotoMode
+ anchors.horizontalCenter: parent.horizontalCenter
+ }
Item { width: 1; height: ScreenTools.defaultFontPixelHeight; visible: _isCamera; }
Component {
id: cameraSettings
@@ -232,6 +262,54 @@ Column {
}
}
//-------------------------------------------
+ //-- Time Lapse
+ Row {
+ spacing: ScreenTools.defaultFontPixelWidth
+ anchors.horizontalCenter: parent.horizontalCenter
+ visible: _cameraPhotoMode
+ property var photoModes: [qsTr("Single"), qsTr("Time Lapse")]
+ QGCLabel {
+ text: qsTr("Photo Mode")
+ width: _labelFieldWidth
+ anchors.verticalCenter: parent.verticalCenter
+ }
+ QGCComboBox {
+ id: photoModeCombo
+ width: _editFieldWidth
+ model: parent.photoModes
+ currentIndex: _camera ? _camera.photoMode : 0
+ onActivated: _camera.photoMode = index
+ }
+ }
+ //-------------------------------------------
+ //-- Time Lapse Interval
+ Row {
+ spacing: ScreenTools.defaultFontPixelWidth
+ anchors.horizontalCenter: parent.horizontalCenter
+ visible: _cameraPhotoMode && _camera.photoMode === QGCCameraControl.PHOTO_CAPTURE_TIMELAPSE
+ QGCLabel {
+ text: qsTr("Photo Interval (seconds)")
+ width: _labelFieldWidth
+ anchors.verticalCenter: parent.verticalCenter
+ }
+ Item {
+ height: photoModeCombo.height
+ width: _editFieldWidth
+ QGCSlider {
+ maximumValue: 60
+ minimumValue: 1
+ stepSize: 1
+ value: _camera ? _camera.photoLapse : 5
+ displayValue: true
+ updateValueWhileDragging: true
+ anchors.fill: parent
+ onValueChanged: {
+ _camera.photoLapse = value
+ }
+ }
+ }
+ }
+ //-------------------------------------------
//-- Reset Camera
Row {
spacing: ScreenTools.defaultFontPixelWidth
diff --git a/src/MissionManager/CameraCalc.cc b/src/MissionManager/CameraCalc.cc
index ef08fd61abce9d964c51504883187d693f9d0001..a1efa9c5e71c18a8cf119f9e5b9e960bfedb3a5f 100644
--- a/src/MissionManager/CameraCalc.cc
+++ b/src/MissionManager/CameraCalc.cc
@@ -14,15 +14,16 @@
#include
-const char* CameraCalc::_valueSetIsDistanceName = "ValueSetIsDistance";
-const char* CameraCalc::_distanceToSurfaceName = "DistanceToSurface";
-const char* CameraCalc::_imageDensityName = "ImageDensity";
-const char* CameraCalc::_frontalOverlapName = "FrontalOverlap";
-const char* CameraCalc::_sideOverlapName = "SideOverlap";
-const char* CameraCalc::_adjustedFootprintFrontalName = "AdjustedFootprintFrontal";
-const char* CameraCalc::_adjustedFootprintSideName = "AdjustedFootprintSide";
-const char* CameraCalc::_jsonCameraNameKey = "CameraName";
-const char* CameraCalc::_jsonCameraSpecTypeKey = "CameraSpecType";
+const char* CameraCalc::_valueSetIsDistanceName = "ValueSetIsDistance";
+const char* CameraCalc::_distanceToSurfaceName = "DistanceToSurface";
+const char* CameraCalc::_distanceToSurfaceRelativeName = "DistanceToSurfaceRelative";
+const char* CameraCalc::_imageDensityName = "ImageDensity";
+const char* CameraCalc::_frontalOverlapName = "FrontalOverlap";
+const char* CameraCalc::_sideOverlapName = "SideOverlap";
+const char* CameraCalc::_adjustedFootprintFrontalName = "AdjustedFootprintFrontal";
+const char* CameraCalc::_adjustedFootprintSideName = "AdjustedFootprintSide";
+const char* CameraCalc::_jsonCameraNameKey = "CameraName";
+const char* CameraCalc::_jsonCameraSpecTypeKey = "CameraSpecType";
CameraCalc::CameraCalc(Vehicle* vehicle, QObject* parent)
: CameraSpec (parent)
@@ -30,6 +31,7 @@ CameraCalc::CameraCalc(Vehicle* vehicle, QObject* parent)
, _dirty (false)
, _cameraName (manualCameraName())
, _disableRecalc (false)
+ , _distanceToSurfaceRelative (true)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CameraCalc.FactMetaData.json"), this))
, _valueSetIsDistanceFact (0, _valueSetIsDistanceName, FactMetaData::valueTypeBool)
, _distanceToSurfaceFact (0, _distanceToSurfaceName, FactMetaData::valueTypeDouble)
@@ -52,7 +54,18 @@ CameraCalc::CameraCalc(Vehicle* vehicle, QObject* parent)
_adjustedFootprintSideFact.setMetaData (_metaDataMap[_adjustedFootprintSideName], true);
_adjustedFootprintFrontalFact.setMetaData (_metaDataMap[_adjustedFootprintFrontalName], true);
+ connect(&_valueSetIsDistanceFact, &Fact::valueChanged, this, &CameraCalc::_setDirty);
+ connect(&_distanceToSurfaceFact, &Fact::valueChanged, this, &CameraCalc::_setDirty);
+ connect(&_imageDensityFact, &Fact::valueChanged, this, &CameraCalc::_setDirty);
+ connect(&_frontalOverlapFact, &Fact::valueChanged, this, &CameraCalc::_setDirty);
+ connect(&_sideOverlapFact, &Fact::valueChanged, this, &CameraCalc::_setDirty);
+ connect(&_adjustedFootprintSideFact, &Fact::valueChanged, this, &CameraCalc::_setDirty);
+ connect(&_adjustedFootprintFrontalFact, &Fact::valueChanged, this, &CameraCalc::_setDirty);
+ connect(this, &CameraCalc::cameraNameChanged, this, &CameraCalc::_setDirty);
+ connect(this, &CameraCalc::distanceToSurfaceRelativeChanged, this, &CameraCalc::_setDirty);
+
connect(this, &CameraCalc::cameraNameChanged, this, &CameraCalc::_recalcTriggerDistance);
+ connect(this, &CameraCalc::cameraNameChanged, this, &CameraCalc::_adjustDistanceToSurfaceRelative);
connect(&_distanceToSurfaceFact, &Fact::rawValueChanged, this, &CameraCalc::_recalcTriggerDistance);
connect(&_imageDensityFact, &Fact::rawValueChanged, this, &CameraCalc::_recalcTriggerDistance);
@@ -167,8 +180,9 @@ void CameraCalc::save(QJsonObject& json) const
json[JsonHelper::jsonVersionKey] = 1;
json[_adjustedFootprintSideName] = _adjustedFootprintSideFact.rawValue().toDouble();
json[_adjustedFootprintFrontalName] = _adjustedFootprintFrontalFact.rawValue().toDouble();
- json[_distanceToSurfaceName] = _distanceToSurfaceFact.rawValue().toDouble();
- json[_jsonCameraNameKey] = _cameraName;
+ json[_distanceToSurfaceName] = _distanceToSurfaceFact.rawValue().toDouble();
+ json[_distanceToSurfaceRelativeName] = _distanceToSurfaceRelative;
+ json[_jsonCameraNameKey] = _cameraName;
if (_cameraName != manualCameraName()) {
CameraSpec::save(json);
@@ -209,6 +223,7 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString)
{ _adjustedFootprintSideName, QJsonValue::Double, true },
{ _adjustedFootprintFrontalName, QJsonValue::Double, true },
{ _distanceToSurfaceName, QJsonValue::Double, true },
+ { _distanceToSurfaceRelativeName, QJsonValue::Bool, true },
};
if (!JsonHelper::validateKeys(v1Json, keyInfoList1, errorString)) {
return false;
@@ -221,6 +236,8 @@ bool CameraCalc::load(const QJsonObject& json, QString& errorString)
_adjustedFootprintFrontalFact.setRawValue (v1Json[_adjustedFootprintFrontalName].toDouble());
_distanceToSurfaceFact.setRawValue (v1Json[_distanceToSurfaceName].toDouble());
+ _distanceToSurfaceRelative = v1Json[_distanceToSurfaceRelativeName].toBool();
+
if (_cameraName != manualCameraName()) {
QList keyInfoList2 = {
{ _valueSetIsDistanceName, QJsonValue::Bool, true },
@@ -257,3 +274,23 @@ QString CameraCalc::manualCameraName(void)
{
return tr("Manual (no camera specs)");
}
+
+void CameraCalc::_adjustDistanceToSurfaceRelative(void)
+{
+ if (!isManualCamera()) {
+ setDistanceToSurfaceRelative(true);
+ }
+}
+
+void CameraCalc::setDistanceToSurfaceRelative(bool distanceToSurfaceRelative)
+{
+ if (distanceToSurfaceRelative != _distanceToSurfaceRelative) {
+ _distanceToSurfaceRelative = distanceToSurfaceRelative;
+ emit distanceToSurfaceRelativeChanged(distanceToSurfaceRelative);
+ }
+}
+
+void CameraCalc::_setDirty(void)
+{
+ setDirty(true);
+}
diff --git a/src/MissionManager/CameraCalc.h b/src/MissionManager/CameraCalc.h
index 2ec3b97bffb89d0ef560a8d05670d55987e50c64..953114ec5b6cb3950404350a16660311e8605873 100644
--- a/src/MissionManager/CameraCalc.h
+++ b/src/MissionManager/CameraCalc.h
@@ -20,17 +20,18 @@ class CameraCalc : public CameraSpec
public:
CameraCalc(Vehicle* vehicle, QObject* parent = NULL);
- Q_PROPERTY(QString cameraName READ cameraName WRITE setCameraName NOTIFY cameraNameChanged)
- Q_PROPERTY(QString customCameraName READ customCameraName CONSTANT) ///< Camera name for custom camera setting
- Q_PROPERTY(QString manualCameraName READ manualCameraName CONSTANT) ///< Camera name for manual camera setting
- Q_PROPERTY(bool isManualCamera READ isManualCamera NOTIFY cameraNameChanged) ///< true: using manual camera
- Q_PROPERTY(Fact* valueSetIsDistance READ valueSetIsDistance CONSTANT) ///< true: distance specified, resolution calculated
- Q_PROPERTY(Fact* distanceToSurface READ distanceToSurface CONSTANT) ///< Distance to surface for image foot print calculation
- Q_PROPERTY(Fact* imageDensity READ imageDensity CONSTANT) ///< Image density on surface (cm/px)
- Q_PROPERTY(Fact* frontalOverlap READ frontalOverlap CONSTANT)
- Q_PROPERTY(Fact* sideOverlap READ sideOverlap CONSTANT)
- Q_PROPERTY(Fact* adjustedFootprintSide READ adjustedFootprintSide CONSTANT) ///< Side footprint adjusted down for overlap
- Q_PROPERTY(Fact* adjustedFootprintFrontal READ adjustedFootprintFrontal CONSTANT) ///< Frontal footprint adjusted down for overlap
+ Q_PROPERTY(QString cameraName READ cameraName WRITE setCameraName NOTIFY cameraNameChanged)
+ Q_PROPERTY(QString customCameraName READ customCameraName CONSTANT) ///< Camera name for custom camera setting
+ Q_PROPERTY(QString manualCameraName READ manualCameraName CONSTANT) ///< Camera name for manual camera setting
+ Q_PROPERTY(bool isManualCamera READ isManualCamera NOTIFY cameraNameChanged) ///< true: using manual camera
+ Q_PROPERTY(Fact* valueSetIsDistance READ valueSetIsDistance CONSTANT) ///< true: distance specified, resolution calculated
+ Q_PROPERTY(Fact* distanceToSurface READ distanceToSurface CONSTANT) ///< Distance to surface for image foot print calculation
+ Q_PROPERTY(Fact* imageDensity READ imageDensity CONSTANT) ///< Image density on surface (cm/px)
+ Q_PROPERTY(Fact* frontalOverlap READ frontalOverlap CONSTANT)
+ Q_PROPERTY(Fact* sideOverlap READ sideOverlap CONSTANT)
+ Q_PROPERTY(Fact* adjustedFootprintSide READ adjustedFootprintSide CONSTANT) ///< Side footprint adjusted down for overlap
+ Q_PROPERTY(Fact* adjustedFootprintFrontal READ adjustedFootprintFrontal CONSTANT) ///< Frontal footprint adjusted down for overlap
+ Q_PROPERTY(bool distanceToSurfaceRelative READ distanceToSurfaceRelative WRITE setDistanceToSurfaceRelative NOTIFY distanceToSurfaceRelativeChanged)
// The following values are calculated from the camera properties
Q_PROPERTY(double imageFootprintSide READ imageFootprintSide NOTIFY imageFootprintSideChanged) ///< Size of image size side in meters
@@ -49,30 +50,44 @@ public:
Fact* adjustedFootprintSide (void) { return &_adjustedFootprintSideFact; }
Fact* adjustedFootprintFrontal (void) { return &_adjustedFootprintFrontalFact; }
- bool isManualCamera (void) { return cameraName() == manualCameraName(); }
- double imageFootprintSide (void) const { return _imageFootprintSide; }
- double imageFootprintFrontal (void) const { return _imageFootprintFrontal; }
+ 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 dirty (void) const { return _dirty; }
- void setDirty (bool dirty);
+ bool dirty (void) const { return _dirty; }
+ bool isManualCamera (void) { return cameraName() == manualCameraName(); }
+ double imageFootprintSide (void) const { return _imageFootprintSide; }
+ double imageFootprintFrontal (void) const { return _imageFootprintFrontal; }
+ bool distanceToSurfaceRelative (void) const { return _distanceToSurfaceRelative; }
+
+ void setDirty (bool dirty);
+ void setDistanceToSurfaceRelative (bool distanceToSurfaceRelative);
void save(QJsonObject& json) const;
bool load(const QJsonObject& json, QString& errorString);
signals:
- void cameraNameChanged (QString cameraName);
- void dirtyChanged (bool dirty);
- void imageFootprintSideChanged (double imageFootprintSide);
- void imageFootprintFrontalChanged (double imageFootprintFrontal);
+ void cameraNameChanged (QString cameraName);
+ void dirtyChanged (bool dirty);
+ void imageFootprintSideChanged (double imageFootprintSide);
+ void imageFootprintFrontalChanged (double imageFootprintFrontal);
+ void distanceToSurfaceRelativeChanged (bool distanceToSurfaceRelative);
private slots:
- void _recalcTriggerDistance(void);
+ void _recalcTriggerDistance (void);
+ void _adjustDistanceToSurfaceRelative (void);
+ void _setDirty (void);
private:
Vehicle* _vehicle;
bool _dirty;
QString _cameraName;
bool _disableRecalc;
+ bool _distanceToSurfaceRelative;
QMap _metaDataMap;
@@ -91,6 +106,7 @@ private:
static const char* _valueSetIsDistanceName;
static const char* _distanceToSurfaceName;
+ static const char* _distanceToSurfaceRelativeName;
static const char* _imageDensityName;
static const char* _frontalOverlapName;
static const char* _sideOverlapName;
diff --git a/src/MissionManager/CameraCalcTest.cc b/src/MissionManager/CameraCalcTest.cc
new file mode 100644
index 0000000000000000000000000000000000000000..cb44927c36a92ccb2994d10a0c50708865bad72c
--- /dev/null
+++ b/src/MissionManager/CameraCalcTest.cc
@@ -0,0 +1,91 @@
+/****************************************************************************
+ *
+ * (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 "CameraCalcTest.h"
+#include "QGCApplication.h"
+
+CameraCalcTest::CameraCalcTest(void)
+ : _offlineVehicle(NULL)
+{
+
+}
+
+void CameraCalcTest::init(void)
+{
+ UnitTest::init();
+
+ _offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
+ _cameraCalc = new CameraCalc(_offlineVehicle, this);
+
+ _rgSignals[cameraNameChangedIndex] = SIGNAL(cameraNameChanged(QString));
+ _rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
+ _rgSignals[imageFootprintSideChangedIndex] = SIGNAL(imageFootprintSideChanged(double));
+ _rgSignals[imageFootprintFrontalChangedIndex] = SIGNAL(imageFootprintFrontalChanged(double));
+ _rgSignals[distanceToSurfaceRelativeChangedIndex] = SIGNAL(distanceToSurfaceRelativeChanged(bool));
+
+ _multiSpy = new MultiSignalSpy();
+ QCOMPARE(_multiSpy->init(_cameraCalc, _rgSignals, _cSignals), true);
+}
+
+void CameraCalcTest::cleanup(void)
+{
+ delete _cameraCalc;
+ delete _offlineVehicle;
+ delete _multiSpy;
+}
+
+void CameraCalcTest::_testDirty(void)
+{
+ QVERIFY(!_cameraCalc->dirty());
+ _cameraCalc->setDirty(false);
+ QVERIFY(!_cameraCalc->dirty());
+ QVERIFY(_multiSpy->checkNoSignals());
+
+ _cameraCalc->setDirty(true);
+ QVERIFY(_cameraCalc->dirty());
+ QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
+ QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
+ _multiSpy->clearAllSignals();
+
+ _cameraCalc->setDirty(false);
+ QVERIFY(!_cameraCalc->dirty());
+ QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
+ _multiSpy->clearAllSignals();
+
+ // These facts should set dirty when changed
+ QList rgFacts;
+ rgFacts << _cameraCalc->valueSetIsDistance()
+ << _cameraCalc->distanceToSurface()
+ << _cameraCalc->imageDensity()
+ << _cameraCalc->frontalOverlap ()
+ << _cameraCalc->sideOverlap ()
+ << _cameraCalc->adjustedFootprintSide()
+ << _cameraCalc->adjustedFootprintFrontal();
+ foreach(Fact* fact, rgFacts) {
+ qDebug() << fact->name();
+ QVERIFY(!_cameraCalc->dirty());
+ if (fact->typeIsBool()) {
+ fact->setRawValue(!fact->rawValue().toBool());
+ } else {
+ fact->setRawValue(fact->rawValue().toDouble() + 1);
+ }
+ QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
+ _cameraCalc->setDirty(false);
+ _multiSpy->clearAllSignals();
+ }
+ rgFacts.clear();
+
+ _cameraCalc->setCameraName(_cameraCalc->customCameraName());
+ QVERIFY(_cameraCalc->dirty());
+ _multiSpy->clearAllSignals();
+
+ _cameraCalc->setDistanceToSurfaceRelative(!_cameraCalc->distanceToSurfaceRelative());
+ QVERIFY(_cameraCalc->dirty());
+ _multiSpy->clearAllSignals();
+}
diff --git a/src/MissionManager/CameraCalcTest.h b/src/MissionManager/CameraCalcTest.h
new file mode 100644
index 0000000000000000000000000000000000000000..02fa9b723a607a7d280da065ad7138836539baf1
--- /dev/null
+++ b/src/MissionManager/CameraCalcTest.h
@@ -0,0 +1,56 @@
+/****************************************************************************
+ *
+ * (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 "CameraCalc.h"
+
+#include
+
+class CameraCalcTest : public UnitTest
+{
+ Q_OBJECT
+
+public:
+ CameraCalcTest(void);
+
+protected:
+ void init(void) final;
+ void cleanup(void) final;
+
+private slots:
+ void _testDirty(void);
+
+private:
+ enum {
+ cameraNameChangedIndex = 0,
+ dirtyChangedIndex,
+ imageFootprintSideChangedIndex,
+ imageFootprintFrontalChangedIndex,
+ distanceToSurfaceRelativeChangedIndex,
+ maxSignalIndex
+ };
+
+ enum {
+ cameraNameChangedMask = 1 << cameraNameChangedIndex,
+ dirtyChangedMask = 1 << dirtyChangedIndex,
+ imageFootprintSideChangedMask = 1 << imageFootprintSideChangedIndex,
+ imageFootprintFrontalChangedMask = 1 << imageFootprintFrontalChangedIndex,
+ distanceToSurfaceRelativeChangedMask = 1 << distanceToSurfaceRelativeChangedIndex,
+ };
+
+ static const size_t _cSignals = maxSignalIndex;
+ const char* _rgSignals[_cSignals];
+
+ Vehicle* _offlineVehicle;
+ MultiSignalSpy* _multiSpy;
+ CameraCalc* _cameraCalc;
+};
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..78e0a7bb017ce004f72a8829ae7aa6cf3efac4d4
--- /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": "TurnaroundDistance",
+ "shortDescription": "Amount of additional distance to add outside the survey 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..2a93b928bd2eb8bc704f2aa1cd7979e0281fce4c
--- /dev/null
+++ b/src/MissionManager/CorridorScanComplexItem.cc
@@ -0,0 +1,464 @@
+/****************************************************************************
+ *
+ * (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::settingsGroup = "CorridorScan";
+const char* CorridorScanComplexItem::corridorWidthName = "CorridorWidth";
+const char* CorridorScanComplexItem::_entryPointName = "EntryPoint";
+
+const char* CorridorScanComplexItem::jsonComplexItemTypeValue = "CorridorScan";
+
+CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, QObject* parent)
+ : TransectStyleComplexItem (vehicle, settingsGroup, parent)
+ , _ignoreRecalc (false)
+ , _entryPoint (0)
+ , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CorridorScan.SettingsGroup.json"), this))
+ , _corridorWidthFact (settingsGroup, _metaDataMap[corridorWidthName])
+{
+ _editorQml = "qrc:/qml/CorridorScanEditor.qml";
+
+ // We override the altitude to the mission default
+ if (_cameraCalc.isManualCamera() || !_cameraCalc.valueSetIsDistance()->rawValue().toBool()) {
+ _cameraCalc.distanceToSurface()->setRawValue(qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue());
+ }
+
+ connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_setDirty);
+ connect(&_corridorPolyline, &QGCMapPolyline::pathChanged, this, &CorridorScanComplexItem::_setDirty);
+
+ connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &CorridorScanComplexItem::coordinateHasRelativeAltitudeChanged);
+ connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &CorridorScanComplexItem::exitCoordinateHasRelativeAltitudeChanged);
+
+ connect(&_corridorPolyline, &QGCMapPolyline::dirtyChanged, this, &CorridorScanComplexItem::_polylineDirtyChanged);
+ connect(&_corridorPolyline, &QGCMapPolyline::countChanged, this, &CorridorScanComplexItem::_polylineCountChanged);
+
+ connect(&_corridorPolyline, &QGCMapPolyline::pathChanged, this, &CorridorScanComplexItem::_rebuildCorridor);
+ connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_rebuildCorridor);
+
+ _rebuildCorridor();
+}
+
+void CorridorScanComplexItem::_polylineCountChanged(int count)
+{
+ Q_UNUSED(count);
+ emit lastSequenceNumberChanged(lastSequenceNumber());
+}
+
+int CorridorScanComplexItem::lastSequenceNumber(void) const
+{
+ int itemCount = _transectPoints.count(); // Each transpect point represents a waypoint item
+
+ if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
+ // Only one camera start and on camera stop
+ itemCount += 2;
+ } else {
+ // Each transect will have a camera start and stop in it
+ itemCount += _transectCount() * 2;
+ }
+
+ return _sequenceNumber + itemCount - 1;
+}
+
+void CorridorScanComplexItem::save(QJsonArray& missionItems)
+{
+ QJsonObject saveObject;
+
+ saveObject[JsonHelper::jsonVersionKey] = 1;
+ saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
+ saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
+ saveObject[corridorWidthName] = _corridorWidthFact.rawValue().toDouble();
+ saveObject[turnAroundDistanceName] = _turnAroundDistanceFact.rawValue().toDouble();
+ saveObject[_entryPointName] = _entryPoint;
+
+ QJsonObject cameraCalcObject;
+ _cameraCalc.save(cameraCalcObject);
+ saveObject[_jsonCameraCalcKey] = cameraCalcObject;
+
+ _corridorPolyline.saveToJson(saveObject);
+
+ _save(saveObject);
+
+ missionItems.append(saveObject);
+}
+
+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 },
+ { corridorWidthName, QJsonValue::Double, true },
+ { turnAroundDistanceName, QJsonValue::Double, true },
+ { _entryPointName, QJsonValue::Double, true },
+ { QGCMapPolyline::jsonPolylineKey, QJsonValue::Array, true },
+ { _jsonCameraCalcKey, QJsonValue::Object, true },
+ };
+ if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
+ return false;
+ }
+
+ if (!_corridorPolyline.loadFromJson(complexObject, true, errorString)) {
+ return false;
+ }
+
+ 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 (!_load(complexObject, errorString)) {
+ return false;
+ }
+
+ _corridorWidthFact.setRawValue (complexObject[corridorWidthName].toDouble());
+
+ _entryPoint = complexObject[_entryPointName].toInt();
+
+ _rebuildCorridor();
+
+ return true;
+}
+
+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;
+ bool imagesEverywhere = _cameraTriggerInTurnAroundFact.rawValue().toBool();
+
+ while (pointIndex < _transectPoints.count()) {
+ if (_hasTurnaround()) {
+ QGeoCoordinate vertexCoord = _transectPoints[pointIndex++].value();
+ MissionItem* item = new MissionItem(seqNum++,
+ MAV_CMD_NAV_WAYPOINT,
+ _cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
+ 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 (imagesEverywhere && pointIndex == 1) {
+ 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);
+ }
+ }
+
+ bool addTrigger = imagesEverywhere ? false : true;
+ for (int i=0; i<_corridorPolyline.count(); i++) {
+ QGeoCoordinate vertexCoord = _transectPoints[pointIndex++].value();
+ MissionItem* item = new MissionItem(seqNum++,
+ MAV_CMD_NAV_WAYPOINT,
+ _cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
+ 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);
+ }
+ }
+
+ if (!imagesEverywhere) {
+ 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);
+ }
+
+ if (_hasTurnaround()) {
+ QGeoCoordinate vertexCoord = _transectPoints[pointIndex++].value();
+ MissionItem* item = new MissionItem(seqNum++,
+ MAV_CMD_NAV_WAYPOINT,
+ _cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
+ 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 (imagesEverywhere) {
+ 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::applyNewAltitude(double newAltitude)
+{
+ _cameraCalc.valueSetIsDistance()->setRawValue(true);
+ _cameraCalc.distanceToSurface()->setRawValue(newAltitude);
+ _cameraCalc.setDistanceToSurfaceRelative(true);
+}
+
+void CorridorScanComplexItem::_polylineDirtyChanged(bool dirty)
+{
+ if (dirty) {
+ setDirty(true);
+ }
+}
+
+void CorridorScanComplexItem::rotateEntryPoint(void)
+{
+ _entryPoint++;
+ if (_entryPoint > 3) {
+ _entryPoint = 0;
+ }
+
+ _rebuildCorridor();
+}
+
+void CorridorScanComplexItem::_rebuildCorridorPolygon(void)
+{
+ if (_corridorPolyline.count() < 2) {
+ _surveyAreaPolygon.clear();
+ return;
+ }
+
+ double halfWidth = _corridorWidthFact.rawValue().toDouble() / 2.0;
+
+ QList firstSideVertices = _corridorPolyline.offsetPolyline(halfWidth);
+ QList secondSideVertices = _corridorPolyline.offsetPolyline(-halfWidth);
+
+ _surveyAreaPolygon.clear();
+ foreach (const QGeoCoordinate& vertex, firstSideVertices) {
+ _surveyAreaPolygon.appendVertex(vertex);
+ }
+ for (int i=secondSideVertices.count() - 1; i >= 0; i--) {
+ _surveyAreaPolygon.appendVertex(secondSideVertices[i]);
+ }
+}
+
+void CorridorScanComplexItem::_rebuildTransects(void)
+{
+ _transectPoints.clear();
+ _cameraShots = 0;
+
+ double transectSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
+ double fullWidth = _corridorWidthFact.rawValue().toDouble();
+ double halfWidth = fullWidth / 2.0;
+ int transectCount = _transectCount();
+ double normalizedTransectPosition = transectSpacing / 2.0;
+
+ if (_corridorPolyline.count() >= 2) {
+ int singleTransectImageCount = qCeil(_corridorPolyline.length() / _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble());
+
+ // First build up the transects all going the same direction
+ QList> transects;
+ for (int i=0; i transect = _corridorPolyline.offsetPolyline(offsetDistance);
+ if (_hasTurnaround()) {
+ QGeoCoordinate extensionCoord;
+
+ // Extend the transect ends for turnaround
+ double azimuth = transect[0].azimuthTo(transect[1]);
+ extensionCoord = transect[0].atDistanceAndAzimuth(-_turnAroundDistanceFact.rawValue().toDouble(), azimuth);
+ transect.prepend(extensionCoord);
+ azimuth = transect.last().azimuthTo(transect[transect.count() - 2]);
+ extensionCoord = transect.last().atDistanceAndAzimuth(-_turnAroundDistanceFact.rawValue().toDouble(), azimuth);
+ transect.append(extensionCoord);
+ }
+
+ transects.append(transect);
+ normalizedTransectPosition += transectSpacing;
+ }
+
+ // Now deal with fixing up the entry point:
+ // 0: Leave alone
+ // 1: Start at same end, opposite side of center
+ // 2: Start at opposite end, same side
+ // 3: Start at opposite end, opposite side
+
+ bool reverseTransects = false;
+ bool reverseVertices = false;
+ switch (_entryPoint) {
+ case 0:
+ reverseTransects = false;
+ reverseVertices = false;
+ break;
+ case 1:
+ reverseTransects = true;
+ reverseVertices = false;
+ break;
+ case 2:
+ reverseTransects = false;
+ reverseVertices = true;
+ break;
+ case 3:
+ reverseTransects = true;
+ reverseVertices = true;
+ break;
+ }
+ if (reverseTransects) {
+ QList> reversedTransects;
+ foreach (const QList& transect, transects) {
+ reversedTransects.prepend(transect);
+ }
+ transects = reversedTransects;
+ }
+ if (reverseVertices) {
+ for (int i=0; i reversedVertices;
+ foreach (const QGeoCoordinate& vertex, transects[i]) {
+ reversedVertices.prepend(vertex);
+ }
+ transects[i] = reversedVertices;
+ }
+ }
+
+ // Convert the list of transects to grid points
+ reverseVertices = false;
+ for (int i=0; i transectVertices = transects[i];
+ 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().distanceTo(_transectPoints[i+1].value());
+ }
+
+ if (_cameraTriggerInTurnAroundFact.rawValue().toDouble()) {
+ _cameraShots = qCeil(_complexDistance / _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble());
+ }
+
+ _coordinate = _transectPoints.count() ? _transectPoints.first().value() : QGeoCoordinate();
+ _exitCoordinate = _transectPoints.count() ? _transectPoints.last().value() : QGeoCoordinate();
+
+ emit transectPointsChanged();
+ emit cameraShotsChanged();
+ emit complexDistanceChanged();
+ emit coordinateChanged(_coordinate);
+ emit exitCoordinateChanged(_exitCoordinate);
+}
+
+void CorridorScanComplexItem::_rebuildCorridor(void)
+{
+ _rebuildCorridorPolygon();
+ _rebuildTransects();
+}
diff --git a/src/MissionManager/CorridorScanComplexItem.h b/src/MissionManager/CorridorScanComplexItem.h
new file mode 100644
index 0000000000000000000000000000000000000000..01c1983ff05f465ee1dbb8e084a62570cafb03b9
--- /dev/null
+++ b/src/MissionManager/CorridorScanComplexItem.h
@@ -0,0 +1,79 @@
+/****************************************************************************
+ *
+ * (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 "TransectStyleComplexItem.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 TransectStyleComplexItem
+{
+ 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(Fact* corridorWidth READ corridorWidth CONSTANT)
+
+ Fact* corridorWidth (void) { return &_corridorWidthFact; }
+ QGCMapPolyline* corridorPolyline(void) { return &_corridorPolyline; }
+
+ Q_INVOKABLE void rotateEntryPoint(void);
+
+ // Overrides from ComplexMissionItem
+
+ int lastSequenceNumber (void) const final;
+ bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
+ QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); }
+
+ // Overrides from TransectStyleComplexItem
+
+ void save (QJsonArray& missionItems) final;
+ bool specifiesCoordinate (void) const final;
+ void appendMissionItems (QList& items, QObject* missionItemParent) final;
+ void applyNewAltitude (double newAltitude) final;
+
+ static const char* jsonComplexItemTypeValue;
+
+ static const char* settingsGroup;
+ static const char* corridorWidthName;
+
+private slots:
+ void _polylineDirtyChanged (bool dirty);
+ void _polylineCountChanged (int count);
+ void _rebuildCorridor (void);
+
+ // Overrides from TransectStyleComplexItem
+ virtual void _rebuildTransects (void) final;
+
+private:
+ int _transectCount (void) const;
+ void _rebuildCorridorPolygon(void);
+
+
+ QGCMapPolyline _corridorPolyline;
+ QList> _transectSegments; ///< Internal transect segments including grid exit, turnaround and internal camera points
+
+ bool _ignoreRecalc;
+ int _entryPoint;
+
+ QMap _metaDataMap;
+ SettingsFact _corridorWidthFact;
+
+ static const char* _entryPointName;
+};
diff --git a/src/MissionManager/CorridorScanComplexItemTest.cc b/src/MissionManager/CorridorScanComplexItemTest.cc
new file mode 100644
index 0000000000000000000000000000000000000000..bcbd9cf3fd56484e9bfa9f6517c98c333fe746b9
--- /dev/null
+++ b/src/MissionManager/CorridorScanComplexItemTest.cc
@@ -0,0 +1,157 @@
+/****************************************************************************
+ *
+ * (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
+ _setPolyline();
+ _corridorItem->setDirty(false);
+
+ _rgCorridorPolygonSignals[corridorPolygonPathChangedIndex] = SIGNAL(pathChanged());
+
+ _multiSpyCorridorPolygon = new MultiSignalSpy();
+ QCOMPARE(_multiSpyCorridorPolygon->init(_corridorItem->surveyAreaPolygon(), _rgCorridorPolygonSignals, _cCorridorPolygonSignals), true);
+}
+
+void CorridorScanComplexItemTest::cleanup(void)
+{
+ delete _corridorItem;
+ delete _offlineVehicle;
+}
+
+void CorridorScanComplexItemTest::_testDirty(void)
+{
+ Fact* fact = _corridorItem->corridorWidth();
+ fact->setRawValue(fact->rawValue().toDouble() + 1);
+ QVERIFY(_corridorItem->dirty());
+ _corridorItem->setDirty(false);
+
+ changeFactValue(_corridorItem->cameraCalc()->distanceToSurface());
+ QVERIFY(_corridorItem->dirty());
+ _corridorItem->setDirty(false);
+
+ QGeoCoordinate coord = _corridorItem->corridorPolyline()->vertexCoordinate(0);
+ coord.setLatitude(coord.latitude() + 1);
+ _corridorItem->corridorPolyline()->adjustVertex(1, coord);
+ QVERIFY(_corridorItem->dirty());
+ _corridorItem->setDirty(false);
+}
+
+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];
+ _corridorItem->corridorPolyline()->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;
+
+ _corridorItem->turnAroundDistance()->setRawValue(20);
+
+ _corridorItem->cameraTriggerInTurnAround()->setRawValue(false);
+ _corridorItem->appendMissionItems(items, this);
+ QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
+ items.clear();
+
+ _corridorItem->cameraTriggerInTurnAround()->setRawValue(true);
+ _corridorItem->appendMissionItems(items, this);
+ QCOMPARE(items.count() - 1, _corridorItem->lastSequenceNumber());
+ items.clear();
+}
+
+void CorridorScanComplexItemTest::_testPathChanges(void)
+{
+ QGeoCoordinate vertex = _corridorItem->corridorPolyline()->vertexCoordinate(1);
+ vertex.setLatitude(vertex.latitude() + 0.01);
+ _corridorItem->corridorPolyline()->adjustVertex(1, vertex);
+
+ QVERIFY(_multiSpyCorridorPolygon->checkSignalsByMask(corridorPolygonPathChangedMask));
+}
diff --git a/src/MissionManager/CorridorScanComplexItemTest.h b/src/MissionManager/CorridorScanComplexItemTest.h
new file mode 100644
index 0000000000000000000000000000000000000000..2f793843801054b69263de9965d0f647dc05d358
--- /dev/null
+++ b/src/MissionManager/CorridorScanComplexItemTest.h
@@ -0,0 +1,56 @@
+/****************************************************************************
+ *
+ * (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 {
+ corridorPolygonPathChangedIndex = 0,
+ maxCorridorPolygonSignalIndex
+ };
+
+ enum {
+ corridorPolygonPathChangedMask = 1 << corridorPolygonPathChangedIndex,
+ };
+
+ static const size_t _cCorridorPolygonSignals = maxCorridorPolygonSignalIndex;
+ const char* _rgCorridorPolygonSignals[_cCorridorPolygonSignals];
+
+ Vehicle* _offlineVehicle;
+ MultiSignalSpy* _multiSpyCorridorPolygon;
+ CorridorScanComplexItem* _corridorItem;
+ QList _linePoints;
+};
diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc
index c8ccd571f3caacd5663a14e6f2ee656de017ab5b..b093c3f58acc82e934cbb2104249a54ee7e7dcd9 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;
}
@@ -698,6 +712,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);
@@ -1842,6 +1865,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/PlanManager.cc b/src/MissionManager/PlanManager.cc
index febd71bffedfe1b1d8776c4e3ea274be37794df9..29fad41b1e6ba53ba937bfdb1d903d423d8b1840 100644
--- a/src/MissionManager/PlanManager.cc
+++ b/src/MissionManager/PlanManager.cc
@@ -30,13 +30,13 @@ PlanManager::PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType)
, _transactionInProgress(TransactionNone)
, _resumeMission(false)
, _lastMissionRequest(-1)
+ , _missionItemCountToRead(-1)
, _currentMissionIndex(-1)
, _lastCurrentIndex(-1)
{
_ackTimeoutTimer = new QTimer(this);
_ackTimeoutTimer->setSingleShot(true);
- _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
-
+
connect(_ackTimeoutTimer, &QTimer::timeout, this, &PlanManager::_ackTimeout);
}
@@ -254,6 +254,24 @@ void PlanManager::_ackTimeout(void)
void PlanManager::_startAckTimeout(AckType_t ack)
{
+ switch (ack) {
+ case AckMissionItem:
+ // We are actively trying to get the mission item, so we don't want to wait as long.
+ _ackTimeoutTimer->setInterval(_retryTimeoutMilliseconds);
+ break;
+ case AckNone:
+ // FALLTHROUGH
+ case AckMissionCount:
+ // FALLTHROUGH
+ case AckMissionRequest:
+ // FALLTHROUGH
+ case AckMissionClearAll:
+ // FALLTHROUGH
+ case AckGuidedItem:
+ _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
+ break;
+ }
+
_expectedAck = ack;
_ackTimeoutTimer->start();
}
@@ -327,6 +345,7 @@ void PlanManager::_handleMissionCount(const mavlink_message_t& message)
for (int i=0; i& missionItems(void) { return _missionItems; }
@@ -41,11 +41,11 @@ public:
/// Last current mission item reported while in Mission flight mode
int lastCurrentIndex(void) const { return _lastCurrentIndex; }
-
+
/// Load the mission items from the vehicle
/// Signals newMissionItemsAvailable when done
void loadFromVehicle(void);
-
+
/// Writes the specified set of mission items to the vehicle
/// IMPORTANT NOTE: PlanManager will take control of the MissionItem objects with the missionItems list. It will free them when done.
/// @param missionItems Items to send to vehicle
@@ -70,9 +70,12 @@ public:
} ErrorCode_t;
// These values are public so the unit test can set appropriate signal wait times
+ // When passively waiting for a mission process, use a longer timeout.
static const int _ackTimeoutMilliseconds = 1000;
+ // When actively retrying to request mission items, use a shorter timeout instead.
+ static const int _retryTimeoutMilliseconds = 250;
static const int _maxRetryCount = 5;
-
+
signals:
void newMissionItemsAvailable (bool removeAllRequested);
void inProgressChanged (bool inProgress);
@@ -88,7 +91,7 @@ signals:
private slots:
void _mavlinkMessageReceived(const mavlink_message_t& message);
void _ackTimeout(void);
-
+
protected:
typedef enum {
AckNone, ///< State machine is idle
@@ -134,17 +137,18 @@ protected:
Vehicle* _vehicle;
MAV_MISSION_TYPE _planType;
LinkInterface* _dedicatedLink;
-
+
QTimer* _ackTimeoutTimer;
AckType_t _expectedAck;
int _retryCount;
-
+
TransactionType_t _transactionInProgress;
bool _resumeMission;
QList _itemIndicesToWrite; ///< List of mission items which still need to be written to vehicle
QList _itemIndicesToRead; ///< List of mission items which still need to be requested from vehicle
int _lastMissionRequest; ///< Index of item last requested by MISSION_REQUEST
-
+ int _missionItemCountToRead;///< Count of all mission items to read
+
QList _missionItems; ///< Set of mission items on vehicle
QList _writeMissionItems; ///< Set of mission items currently being written to vehicle
int _currentMissionIndex;
diff --git a/src/MissionManager/PlanMasterController.cc b/src/MissionManager/PlanMasterController.cc
index a2041f935c4c1268df122af79f6a5739b66d3506..7896e4c7c8b93fd593cfb47947a31dad31b5a580 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 a9ab76c0486ffab685488491c6f46ee72b8043dd..3942ef5cc4aadcf6ff0fe9731ccca47774c05ca1 100644
--- a/src/MissionManager/StructureScanComplexItem.cc
+++ b/src/MissionManager/StructureScanComplexItem.cc
@@ -91,7 +91,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/TransectStyle.SettingsGroup.json b/src/MissionManager/TransectStyle.SettingsGroup.json
new file mode 100644
index 0000000000000000000000000000000000000000..d949f6ba24ec433e4aa073df3692bd887c904882
--- /dev/null
+++ b/src/MissionManager/TransectStyle.SettingsGroup.json
@@ -0,0 +1,38 @@
+[
+{
+ "name": "TurnAroundDistance",
+ "shortDescription": "Amount of additional distance to add outside the survey area for vehicle turn around.",
+ "type": "double",
+ "decimalPlaces": 2,
+ "min": 0,
+ "units": "m",
+ "defaultValue": 30
+},
+{
+ "name": "TurnAroundDistanceMultiRotor",
+ "shortDescription": "Amount of additional distance to add outside the survey area for vehicle turn around.",
+ "type": "double",
+ "decimalPlaces": 2,
+ "min": 0,
+ "units": "m",
+ "defaultValue": 10
+},
+{
+ "name": "CameraTriggerInTurnAround",
+ "shortDescription": "Camera continues taking images in turn arounds.",
+ "type": "bool",
+ "defaultValue": true
+},
+{
+ "name": "HoverAndCapture",
+ "shortDescription": "Stop and Hover at each image point before taking image",
+ "type": "bool",
+ "defaultValue": false
+},
+{
+ "name": "Refly90Degrees",
+ "shortDescription": "Refly the pattern at a 90 degree angle",
+ "type": "bool",
+ "defaultValue": false
+}
+]
diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc
new file mode 100644
index 0000000000000000000000000000000000000000..27c1f54018ff3df37873a45df5a86ffbe5fd83b7
--- /dev/null
+++ b/src/MissionManager/TransectStyleComplexItem.cc
@@ -0,0 +1,232 @@
+/****************************************************************************
+ *
+ * (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 "TransectStyleComplexItem.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(TransectStyleComplexItemLog, "TransectStyleComplexItemLog")
+
+const char* TransectStyleComplexItem::turnAroundDistanceName = "TurnAroundDistance";
+const char* TransectStyleComplexItem::turnAroundDistanceMultiRotorName = "TurnAroundDistanceMultiRotor";
+const char* TransectStyleComplexItem::cameraTriggerInTurnAroundName = "CameraTriggerInTurnAround";
+const char* TransectStyleComplexItem::hoverAndCaptureName = "HoverAndCapture";
+const char* TransectStyleComplexItem::refly90DegreesName = "Refly90Degrees";
+
+const char* TransectStyleComplexItem::_jsonCameraCalcKey = "CameraCalc";
+
+TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString settingsGroup, QObject* parent)
+ : ComplexMissionItem (vehicle, parent)
+ , _settingsGroup (settingsGroup)
+ , _sequenceNumber (0)
+ , _dirty (false)
+ , _ignoreRecalc (false)
+ , _complexDistance (0)
+ , _cameraShots (0)
+ , _cameraMinTriggerInterval (0)
+ , _cameraCalc (vehicle)
+ , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/TransectStyle.SettingsGroup.json"), this))
+ , _turnAroundDistanceFact (_settingsGroup, _metaDataMap[_vehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName])
+ , _cameraTriggerInTurnAroundFact(_settingsGroup, _metaDataMap[cameraTriggerInTurnAroundName])
+ , _hoverAndCaptureFact (_settingsGroup, _metaDataMap[hoverAndCaptureName])
+ , _refly90DegreesFact (_settingsGroup, _metaDataMap[refly90DegreesName])
+{
+ connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
+ connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
+ connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
+ connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::_rebuildTransects);
+ connect(&_cameraTriggerInTurnAroundFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
+ connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
+ connect(_cameraCalc.adjustedFootprintFrontal(), &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
+
+ connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
+ connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
+ connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
+ connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
+ connect(&_cameraTriggerInTurnAroundFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
+ connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
+ connect(_cameraCalc.adjustedFootprintFrontal(), &Fact::valueChanged, this, &TransectStyleComplexItem::_signalLastSequenceNumberChanged);
+
+ connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
+ connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
+ connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
+ connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
+
+ connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
+ connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
+ connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
+ connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
+
+ connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
+ connect(&_cameraTriggerInTurnAroundFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
+ connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
+ connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_setDirty);
+ connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::_setDirty);
+
+ connect(&_surveyAreaPolygon, &QGCMapPolygon::dirtyChanged, this, &TransectStyleComplexItem::_setIfDirty);
+ connect(&_cameraCalc, &CameraCalc::dirtyChanged, this, &TransectStyleComplexItem::_setIfDirty);
+
+ connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::coveredAreaChanged);
+
+ connect(this, &TransectStyleComplexItem::transectPointsChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
+ connect(this, &TransectStyleComplexItem::transectPointsChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
+}
+
+void TransectStyleComplexItem::_setCameraShots(int cameraShots)
+{
+ if (_cameraShots != cameraShots) {
+ _cameraShots = cameraShots;
+ emit cameraShotsChanged();
+ }
+}
+
+void TransectStyleComplexItem::setDirty(bool dirty)
+{
+ if (!dirty) {
+ _surveyAreaPolygon.setDirty(false);
+ _cameraCalc.setDirty(false);
+ }
+ if (_dirty != dirty) {
+ _dirty = dirty;
+ emit dirtyChanged(_dirty);
+ }
+}
+
+void TransectStyleComplexItem::_save(QJsonObject& complexObject)
+{
+ complexObject[turnAroundDistanceName] = _turnAroundDistanceFact.rawValue().toDouble();
+ complexObject[cameraTriggerInTurnAroundName] = _cameraTriggerInTurnAroundFact.rawValue().toBool();
+ complexObject[hoverAndCaptureName] = _hoverAndCaptureFact.rawValue().toBool();
+ complexObject[refly90DegreesName] = _refly90DegreesFact.rawValue().toBool();
+
+ QJsonObject cameraCalcObject;
+ _cameraCalc.save(cameraCalcObject);
+ complexObject[_jsonCameraCalcKey] = cameraCalcObject;
+}
+
+void TransectStyleComplexItem::setSequenceNumber(int sequenceNumber)
+{
+ if (_sequenceNumber != sequenceNumber) {
+ _sequenceNumber = sequenceNumber;
+ emit sequenceNumberChanged(sequenceNumber);
+ emit lastSequenceNumberChanged(lastSequenceNumber());
+ }
+}
+
+bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString& errorString)
+{
+ QList keyInfoList = {
+ { turnAroundDistanceName, QJsonValue::Double, true },
+ { cameraTriggerInTurnAroundName, QJsonValue::Bool, true },
+ { hoverAndCaptureName, QJsonValue::Bool, true },
+ { refly90DegreesName, QJsonValue::Bool, true },
+ { _jsonCameraCalcKey, QJsonValue::Object, true },
+ };
+ if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
+ return false;
+ }
+
+ if (!_cameraCalc.load(complexObject[_jsonCameraCalcKey].toObject(), errorString)) {
+ return false;
+ }
+
+ _turnAroundDistanceFact.setRawValue (complexObject[turnAroundDistanceName].toDouble());
+ _cameraTriggerInTurnAroundFact.setRawValue (complexObject[cameraTriggerInTurnAroundName].toBool());
+ _hoverAndCaptureFact.setRawValue (complexObject[hoverAndCaptureName].toBool());
+ _hoverAndCaptureFact.setRawValue (complexObject[refly90DegreesName].toBool());
+
+ return true;
+}
+
+double TransectStyleComplexItem::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;
+}
+
+void TransectStyleComplexItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
+{
+ ComplexMissionItem::setMissionFlightStatus(missionFlightStatus);
+ if (!qFuzzyCompare(_cruiseSpeed, missionFlightStatus.vehicleSpeed)) {
+ _cruiseSpeed = missionFlightStatus.vehicleSpeed;
+ emit timeBetweenShotsChanged();
+ }
+}
+
+void TransectStyleComplexItem::_setDirty(void)
+{
+ setDirty(true);
+}
+
+void TransectStyleComplexItem::_setIfDirty(bool dirty)
+{
+ if (dirty) {
+ setDirty(true);
+ }
+}
+
+void TransectStyleComplexItem::applyNewAltitude(double newAltitude)
+{
+ Q_UNUSED(newAltitude);
+ // FIXME: NYI
+ //_altitudeFact.setRawValue(newAltitude);
+}
+
+double TransectStyleComplexItem::timeBetweenShots(void)
+{
+ return _cruiseSpeed == 0 ? 0 : _cameraCalc.adjustedFootprintSide()->rawValue().toDouble() / _cruiseSpeed;
+}
+
+void TransectStyleComplexItem::_updateCoordinateAltitudes(void)
+{
+ emit coordinateChanged(coordinate());
+ emit exitCoordinateChanged(exitCoordinate());
+}
+
+void TransectStyleComplexItem::_signalLastSequenceNumberChanged(void)
+{
+ emit lastSequenceNumberChanged(lastSequenceNumber());
+}
+
+double TransectStyleComplexItem::coveredArea(void) const
+{
+ return _surveyAreaPolygon.area();
+}
+
+bool TransectStyleComplexItem::_hasTurnaround(void) const
+{
+ return _turnaroundDistance() > 0;
+}
+
+double TransectStyleComplexItem::_turnaroundDistance(void) const
+{
+ return _turnAroundDistanceFact.rawValue().toDouble();
+}
+
+bool TransectStyleComplexItem::hoverAndCaptureAllowed(void) const
+{
+ return _vehicle->multiRotor() || _vehicle->vtol();
+}
+
diff --git a/src/MissionManager/TransectStyleComplexItem.h b/src/MissionManager/TransectStyleComplexItem.h
new file mode 100644
index 0000000000000000000000000000000000000000..d624557eb4509d5736600147aa364a7b1253bb29
--- /dev/null
+++ b/src/MissionManager/TransectStyleComplexItem.h
@@ -0,0 +1,152 @@
+/****************************************************************************
+ *
+ * (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(TransectStyleComplexItemLog)
+
+class TransectStyleComplexItem : public ComplexMissionItem
+{
+ Q_OBJECT
+
+public:
+ TransectStyleComplexItem(Vehicle* vehicle, QString settignsGroup, QObject* parent = NULL);
+
+ Q_PROPERTY(QGCMapPolygon* surveyAreaPolygon READ surveyAreaPolygon CONSTANT)
+ Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
+ Q_PROPERTY(Fact* turnAroundDistance READ turnAroundDistance CONSTANT)
+ Q_PROPERTY(Fact* cameraTriggerInTurnAround READ cameraTriggerInTurnAround CONSTANT)
+ Q_PROPERTY(Fact* hoverAndCapture READ hoverAndCapture CONSTANT)
+ Q_PROPERTY(Fact* refly90Degrees READ refly90Degrees 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 READ cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged)
+ Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT)
+ Q_PROPERTY(QVariantList transectPoints READ transectPoints NOTIFY transectPointsChanged)
+
+ QGCMapPolygon* surveyAreaPolygon (void) { return &_surveyAreaPolygon; }
+ CameraCalc* cameraCalc (void) { return &_cameraCalc; }
+ QVariantList transectPoints (void) { return _transectPoints; }
+
+ Fact* turnAroundDistance (void) { return &_turnAroundDistanceFact; }
+ Fact* cameraTriggerInTurnAround (void) { return &_cameraTriggerInTurnAroundFact; }
+ Fact* hoverAndCapture (void) { return &_hoverAndCaptureFact; }
+ Fact* refly90Degrees (void) { return &_refly90DegreesFact; }
+
+ int cameraShots (void) const { return _cameraShots; }
+ double timeBetweenShots (void);
+ double coveredArea (void) const;
+ double cameraMinTriggerInterval(void) const { return _cameraMinTriggerInterval; }
+ bool hoverAndCaptureAllowed (void) const;
+
+ // Overrides from ComplexMissionItem
+
+ int lastSequenceNumber (void) const override = 0;
+ QString mapVisualQML (void) const override = 0;
+ bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) override = 0;
+
+ double complexDistance (void) const final { return _complexDistance; }
+ double greatestDistanceTo (const QGeoCoordinate &other) const final;
+
+ // Overrides from VisualMissionItem
+
+ void save (QJsonArray& missionItems) override = 0;
+ bool specifiesCoordinate (void) const override = 0;
+ void appendMissionItems (QList& items, QObject* missionItemParent) override = 0;
+ void applyNewAltitude (double newAltitude) override = 0;
+
+ bool dirty (void) const final { return _dirty; }
+ bool isSimpleItem (void) const final { return false; }
+ bool isStandaloneCoordinate (void) const final { return false; }
+ 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 setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) 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;
+
+ static const char* turnAroundDistanceName;
+ static const char* turnAroundDistanceMultiRotorName;
+ static const char* cameraTriggerInTurnAroundName;
+ static const char* hoverAndCaptureName;
+ static const char* refly90DegreesName;
+
+signals:
+ void cameraShotsChanged (void);
+ void timeBetweenShotsChanged (void);
+ void cameraMinTriggerIntervalChanged(double cameraMinTriggerInterval);
+ void transectPointsChanged (void);
+ void coveredAreaChanged (void);
+
+protected slots:
+ virtual void _rebuildTransects (void) = 0;
+
+ void _setDirty (void);
+ void _setIfDirty (bool dirty);
+ void _updateCoordinateAltitudes (void);
+ void _signalLastSequenceNumberChanged (void);
+
+protected:
+ void _save (QJsonObject& saveObject);
+ bool _load (const QJsonObject& complexObject, QString& errorString);
+ void _setExitCoordinate (const QGeoCoordinate& coordinate);
+ void _setCameraShots (int cameraShots);
+ double _triggerDistance (void) const;
+ int _transectCount (void) const;
+ bool _hasTurnaround (void) const;
+ double _turnaroundDistance (void) const;
+
+ QString _settingsGroup;
+ int _sequenceNumber;
+ bool _dirty;
+ QGeoCoordinate _coordinate;
+ QGeoCoordinate _exitCoordinate;
+ QVariantList _transectPoints;
+ QGCMapPolygon _surveyAreaPolygon;
+
+ bool _ignoreRecalc;
+ double _complexDistance;
+ int _cameraShots;
+ double _timeBetweenShots;
+ double _cameraMinTriggerInterval;
+ double _cruiseSpeed;
+ CameraCalc _cameraCalc;
+
+ QMap _metaDataMap;
+
+ SettingsFact _turnAroundDistanceFact;
+ SettingsFact _cameraTriggerInTurnAroundFact;
+ SettingsFact _hoverAndCaptureFact;
+ SettingsFact _refly90DegreesFact;
+
+ static const char* _jsonCameraCalcKey;
+};
diff --git a/src/MissionManager/TransectStyleComplexItemTest.cc b/src/MissionManager/TransectStyleComplexItemTest.cc
new file mode 100644
index 0000000000000000000000000000000000000000..a9f2372af32e32225d8bfdbf1612ce063f09f790
--- /dev/null
+++ b/src/MissionManager/TransectStyleComplexItemTest.cc
@@ -0,0 +1,180 @@
+/****************************************************************************
+ *
+ * (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 "TransectStyleComplexItemTest.h"
+#include "QGCApplication.h"
+
+TransectStyleComplexItemTest::TransectStyleComplexItemTest(void)
+ : _offlineVehicle(NULL)
+{
+ _polygonVertices << QGeoCoordinate(47.633550640000003, -122.08982199)
+ << QGeoCoordinate(47.634129020000003, -122.08887249)
+ << QGeoCoordinate(47.633619320000001, -122.08811074)
+ << QGeoCoordinate(47.633189139999999, -122.08900124);
+}
+
+void TransectStyleComplexItemTest::init(void)
+{
+ UnitTest::init();
+
+ _offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
+ _transectStyleItem = new TransectStyleItem(_offlineVehicle, this);
+ _setSurveyAreaPolygon();
+ _transectStyleItem->setDirty(false);
+
+ _rgSignals[cameraShotsChangedIndex] = SIGNAL(cameraShotsChanged());
+ _rgSignals[timeBetweenShotsChangedIndex] = SIGNAL(timeBetweenShotsChanged());
+ _rgSignals[cameraMinTriggerIntervalChangedIndex] = SIGNAL(cameraMinTriggerIntervalChanged(double));
+ _rgSignals[transectPointsChangedIndex] = SIGNAL(transectPointsChanged());
+ _rgSignals[coveredAreaChangedIndex] = SIGNAL(coveredAreaChanged());
+ _rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
+ _rgSignals[complexDistanceChangedIndex] = SIGNAL(complexDistanceChanged());
+ _rgSignals[greatestDistanceToChangedIndex] = SIGNAL(greatestDistanceToChanged());
+ _rgSignals[additionalTimeDelayChangedIndex] = SIGNAL(additionalTimeDelayChanged());
+ _rgSignals[lastSequenceNumberChangedIndex] = SIGNAL(lastSequenceNumberChanged(int));
+
+ _multiSpy = new MultiSignalSpy();
+ QCOMPARE(_multiSpy->init(_transectStyleItem, _rgSignals, _cSignals), true);
+}
+
+void TransectStyleComplexItemTest::cleanup(void)
+{
+ delete _transectStyleItem;
+ delete _offlineVehicle;
+ delete _multiSpy;
+}
+
+void TransectStyleComplexItemTest::_testDirty(void)
+{
+ QVERIFY(!_transectStyleItem->dirty());
+ _transectStyleItem->setDirty(false);
+ QVERIFY(!_transectStyleItem->dirty());
+ QVERIFY(_multiSpy->checkNoSignals());
+
+ _transectStyleItem->setDirty(true);
+ QVERIFY(_transectStyleItem->dirty());
+ QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
+ QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
+ _multiSpy->clearAllSignals();
+
+ _transectStyleItem->setDirty(false);
+ QVERIFY(!_transectStyleItem->dirty());
+ QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
+ _multiSpy->clearAllSignals();
+
+ // These facts should set dirty when changed
+ QList rgFacts;
+ rgFacts << _transectStyleItem->turnAroundDistance()
+ << _transectStyleItem->cameraTriggerInTurnAround()
+ << _transectStyleItem->hoverAndCapture()
+ << _transectStyleItem->refly90Degrees();
+ foreach(Fact* fact, rgFacts) {
+ qDebug() << fact->name();
+ QVERIFY(!_transectStyleItem->dirty());
+ changeFactValue(fact);
+ QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
+ _transectStyleItem->setDirty(false);
+ _multiSpy->clearAllSignals();
+ }
+ rgFacts.clear();
+
+ _adjustSurveAreaPolygon();
+ QVERIFY(_transectStyleItem->dirty());
+ _transectStyleItem->setDirty(false);
+ QVERIFY(!_transectStyleItem->surveyAreaPolygon()->dirty());
+ _multiSpy->clearAllSignals();
+
+ changeFactValue(_transectStyleItem->cameraCalc()->distanceToSurface());
+ QVERIFY(_transectStyleItem->dirty());
+ _transectStyleItem->setDirty(false);
+ QVERIFY(!_transectStyleItem->cameraCalc()->dirty());
+ _multiSpy->clearAllSignals();
+}
+
+void TransectStyleComplexItemTest::_setSurveyAreaPolygon(void)
+{
+ foreach (const QGeoCoordinate vertex, _polygonVertices) {
+ _transectStyleItem->surveyAreaPolygon()->appendVertex(vertex);
+ }
+}
+
+void TransectStyleComplexItemTest::_testRebuildTransects(void)
+{
+ // Changing the survey polygon should trigger:
+ // _rebuildTransects call
+ // coveredAreaChanged signal
+ // lastSequenceNumberChanged signal
+ _adjustSurveAreaPolygon();
+ QVERIFY(_transectStyleItem->rebuildTransectsCalled);
+ QVERIFY(_multiSpy->checkSignalsByMask(coveredAreaChangedMask | lastSequenceNumberChangedMask));
+ _transectStyleItem->rebuildTransectsCalled = false;
+ _transectStyleItem->setDirty(false);
+ _multiSpy->clearAllSignals();
+
+ // Changes to these facts should trigger:
+ // _rebuildTransects call
+ // lastSequenceNumberChanged signal
+ QList rgFacts;
+ rgFacts << _transectStyleItem->turnAroundDistance()
+ << _transectStyleItem->cameraTriggerInTurnAround()
+ << _transectStyleItem->hoverAndCapture()
+ << _transectStyleItem->refly90Degrees()
+ << _transectStyleItem->cameraCalc()->adjustedFootprintSide()
+ << _transectStyleItem->cameraCalc()->adjustedFootprintFrontal();
+ foreach(Fact* fact, rgFacts) {
+ qDebug() << fact->name();
+ changeFactValue(fact);
+ QVERIFY(_transectStyleItem->rebuildTransectsCalled);
+ QVERIFY(_multiSpy->checkSignalsByMask(lastSequenceNumberChangedMask));
+ _transectStyleItem->setDirty(false);
+ _multiSpy->clearAllSignals();
+ _transectStyleItem->rebuildTransectsCalled = false;
+ }
+ rgFacts.clear();
+}
+
+void TransectStyleComplexItemTest::_testDistanceSignalling(void)
+{
+ _adjustSurveAreaPolygon();
+ QVERIFY(_multiSpy->checkSignalsByMask(complexDistanceChangedMask | greatestDistanceToChangedMask));
+ _transectStyleItem->setDirty(false);
+ _multiSpy->clearAllSignals();
+
+ QList rgFacts;
+ rgFacts << _transectStyleItem->turnAroundDistance()
+ << _transectStyleItem->hoverAndCapture()
+ << _transectStyleItem->refly90Degrees();
+ foreach(Fact* fact, rgFacts) {
+ qDebug() << fact->name();
+ changeFactValue(fact);
+ QVERIFY(_multiSpy->checkSignalsByMask(complexDistanceChangedMask | greatestDistanceToChangedMask));
+ _transectStyleItem->setDirty(false);
+ _multiSpy->clearAllSignals();
+ }
+ rgFacts.clear();
+}
+
+void TransectStyleComplexItemTest::_adjustSurveAreaPolygon(void)
+{
+ QGeoCoordinate vertex = _transectStyleItem->surveyAreaPolygon()->vertexCoordinate(0);
+ vertex.setLatitude(vertex.latitude() + 1);
+ _transectStyleItem->surveyAreaPolygon()->adjustVertex(0, vertex);
+}
+
+TransectStyleItem::TransectStyleItem(Vehicle* vehicle, QObject* parent)
+ : TransectStyleComplexItem (vehicle, QStringLiteral("UnitTestTransect"), parent)
+ , rebuildTransectsCalled (false)
+{
+
+}
+
+void TransectStyleItem::_rebuildTransects(void)
+{
+ rebuildTransectsCalled = true;
+}
diff --git a/src/MissionManager/TransectStyleComplexItemTest.h b/src/MissionManager/TransectStyleComplexItemTest.h
new file mode 100644
index 0000000000000000000000000000000000000000..d3aeea3202af69898f5d74f5098f99b84182756f
--- /dev/null
+++ b/src/MissionManager/TransectStyleComplexItemTest.h
@@ -0,0 +1,105 @@
+/****************************************************************************
+ *
+ * (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 "CorridorScanComplexItem.h"
+
+#include
+
+class TransectStyleItem;
+
+class TransectStyleComplexItemTest : public UnitTest
+{
+ Q_OBJECT
+
+public:
+ TransectStyleComplexItemTest(void);
+
+protected:
+ void init(void) final;
+ void cleanup(void) final;
+
+private slots:
+ void _testDirty (void);
+ void _testRebuildTransects (void);
+ void _testDistanceSignalling (void);
+
+private:
+ void _setSurveyAreaPolygon (void);
+ void _adjustSurveAreaPolygon(void);
+
+ enum {
+ // These signals are from TransectStyleComplexItem
+ cameraShotsChangedIndex = 0,
+ timeBetweenShotsChangedIndex,
+ cameraMinTriggerIntervalChangedIndex,
+ transectPointsChangedIndex,
+ coveredAreaChangedIndex,
+ // These signals are from ComplexItem
+ dirtyChangedIndex,
+ complexDistanceChangedIndex,
+ greatestDistanceToChangedIndex,
+ additionalTimeDelayChangedIndex,
+ // These signals are from VisualMissionItem
+ lastSequenceNumberChangedIndex,
+ maxSignalIndex
+ };
+
+ enum {
+ // These signals are from TransectStyleComplexItem
+ cameraShotsChangedMask = 1 << cameraShotsChangedIndex,
+ timeBetweenShotsChangedMask = 1 << timeBetweenShotsChangedIndex,
+ cameraMinTriggerIntervalChangedMask = 1 << cameraMinTriggerIntervalChangedIndex,
+ transectPointsChangedMask = 1 << transectPointsChangedIndex,
+ coveredAreaChangedMask = 1 << coveredAreaChangedIndex,
+ // These signals are from ComplexItem
+ dirtyChangedMask = 1 << dirtyChangedIndex,
+ complexDistanceChangedMask = 1 << complexDistanceChangedIndex,
+ greatestDistanceToChangedMask = 1 << greatestDistanceToChangedIndex,
+ additionalTimeDelayChangedMask = 1 << additionalTimeDelayChangedIndex,
+ // These signals are from VisualMissionItem
+ lastSequenceNumberChangedMask = 1 << lastSequenceNumberChangedIndex,
+ };
+
+ static const size_t _cSignals = maxSignalIndex;
+ const char* _rgSignals[_cSignals];
+
+ Vehicle* _offlineVehicle;
+ MultiSignalSpy* _multiSpy;
+ QList _polygonVertices;
+ TransectStyleItem* _transectStyleItem;
+};
+
+class TransectStyleItem : public TransectStyleComplexItem
+{
+ Q_OBJECT
+
+public:
+ TransectStyleItem(Vehicle* vehicle, QObject* parent = NULL);
+
+ // Overrides from ComplexMissionItem
+ int lastSequenceNumber (void) const final { return _sequenceNumber; }
+ QString mapVisualQML (void) const final { return QString(); }
+ bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final { Q_UNUSED(complexObject); Q_UNUSED(sequenceNumber); Q_UNUSED(errorString); return false; }
+
+ // Overrides from VisualMissionItem
+ void save (QJsonArray& missionItems) final { Q_UNUSED(missionItems); }
+ bool specifiesCoordinate (void) const final { return true; }
+ void appendMissionItems (QList& items, QObject* missionItemParent) final { Q_UNUSED(items); Q_UNUSED(missionItemParent); }
+ void applyNewAltitude (double newAltitude) final { Q_UNUSED(newAltitude); }
+
+ bool rebuildTransectsCalled;
+
+private slots:
+ // Overrides from TransectStyleComplexItem
+ void _rebuildTransects (void) final;
+};
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..72cd5d3d80a7bb1f5672f00b8f6373b85ead7873
--- /dev/null
+++ b/src/PlanView/CorridorScanEditor.qml
@@ -0,0 +1,146 @@
+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
+ }
+
+ QGCLabel { text: qsTr("Turnaround dist") }
+ FactTextField {
+ fact: missionItem.turnAroundDistance
+ Layout.fillWidth: true
+ }
+
+ FactCheckBox {
+ text: qsTr("Take images in turnarounds")
+ fact: missionItem.cameraTriggerInTurnAround
+ enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true
+ Layout.columnSpan: 2
+ }
+
+ QGCCheckBox {
+ id: relAlt
+ anchors.left: parent.left
+ text: qsTr("Relative altitude")
+ checked: missionItem.cameraCalc.distanceToSurfaceRelative
+ enabled: missionItem.cameraCalc.isManualCamera
+ Layout.columnSpan: 2
+ onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
+
+ Connections {
+ target: missionItem.cameraCalc
+ onDistanceToSurfaceRelativeChanged: relAlt.checked = missionItem.cameraCalc.distanceToSurfaceRelative
+ }
+ }
+ }
+
+ QGCButton {
+ text: qsTr("Rotate Entry Point")
+ onClicked: missionItem.rotateEntryPoint()
+ }
+
+ 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..616120b29c42e6c6a8c8c9fe7a6b6b8469534103
--- /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.surveyAreaPolygon
+ 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/OfflineMapButton.qml b/src/QmlControls/OfflineMapButton.qml
index 8df92397e6b91b04bb14b0caeafb3d9bd1325cfa..956ce6bb3c54ba5bc3884624d353321880437cb0 100644
--- a/src/QmlControls/OfflineMapButton.qml
+++ b/src/QmlControls/OfflineMapButton.qml
@@ -20,6 +20,8 @@ Rectangle {
border.width: _showBorder ? 1: 0
border.color: qgcPal.buttonText
+ property var tileSet: null
+ property var currentSet: null
property bool checked: false
property bool complete: false
property alias text: nameLabel.text
@@ -37,6 +39,19 @@ Rectangle {
signal clicked()
+ property ExclusiveGroup exclusiveGroup: null
+ onExclusiveGroupChanged: {
+ if (exclusiveGroup) {
+ checked = false
+ exclusiveGroup.bindCheckable(mapButton)
+ }
+ }
+ onCheckedChanged: {
+ if(checked) {
+ currentSet = tileSet
+ }
+ }
+
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
Row {
@@ -85,26 +100,53 @@ Rectangle {
MouseArea {
anchors.fill: parent
- hoverEnabled: true
+ hoverEnabled: !ScreenTools.isMobile
onMouseXChanged: {
- _lastGlobalMouseX = ScreenTools.mouseX()
- _lastGlobalMouseY = ScreenTools.mouseY()
+ if(!ScreenTools.isMobile) {
+ _lastGlobalMouseX = ScreenTools.mouseX()
+ _lastGlobalMouseY = ScreenTools.mouseY()
+ }
}
onMouseYChanged: {
- _lastGlobalMouseX = ScreenTools.mouseX()
- _lastGlobalMouseY = ScreenTools.mouseY()
- }
- onEntered: { _hovered = true; _forceHoverOff = false; hoverTimer.start() }
- onExited: { _hovered = false; _forceHoverOff = false; hoverTimer.stop() }
- onPressed: { _pressed = true; }
- onReleased: { _pressed = false; }
- onClicked: mapButton.clicked()
+ if(!ScreenTools.isMobile) {
+ _lastGlobalMouseX = ScreenTools.mouseX()
+ _lastGlobalMouseY = ScreenTools.mouseY()
+ }
+ }
+ onEntered: {
+ if(!ScreenTools.isMobile) {
+ _hovered = true
+ _forceHoverOff = false
+ hoverTimer.start()
+ }
+ }
+ onExited: {
+ if(!ScreenTools.isMobile) {
+ _hovered = false
+ _forceHoverOff = false
+ hoverTimer.stop()
+ }
+ }
+ onPressed: {
+ if(!ScreenTools.isMobile) {
+ _pressed = true
+ }
+ }
+ onReleased: {
+ if(!ScreenTools.isMobile) {
+ _pressed = false
+ }
+ }
+ onClicked: {
+ checked = true
+ mapButton.clicked()
+ }
}
Timer {
id: hoverTimer
interval: 250
- repeat: true
+ repeat: !ScreenTools.isMobile
onTriggered: {
if (_lastGlobalMouseX !== ScreenTools.mouseX() || _lastGlobalMouseY !== ScreenTools.mouseY()) {
_forceHoverOff = true
diff --git a/src/QmlControls/QGCSlider.qml b/src/QmlControls/QGCSlider.qml
index ff317b12b4a90daf8b5518baf34ab6805a675a73..5c0d427ab75a83c0ea756ae6179c2b3d99502ec7 100644
--- a/src/QmlControls/QGCSlider.qml
+++ b/src/QmlControls/QGCSlider.qml
@@ -21,6 +21,7 @@ Slider {
// Value indicator starts display from zero instead of min value
property bool zeroCentered: false
+ property bool displayValue: false
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
@@ -67,8 +68,15 @@ Slider {
implicitWidth: _radius * 2
implicitHeight: _radius * 2
radius: _radius
-
property real _radius: Math.round(ScreenTools.defaultFontPixelHeight * 0.75)
+ Label {
+ text: _root.value.toFixed(0)
+ visible: _root.displayValue
+ anchors.centerIn: parent
+ font.family: ScreenTools.normalFontFamily
+ font.pointSize: ScreenTools.smallFontPointSize
+ color: qgcPal.buttonText
+ }
}
}
}
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/QtLocationPlugin/QMLControl/OfflineMap.qml b/src/QtLocationPlugin/QMLControl/OfflineMap.qml
index e2d336c841adaa79c3a7210286e64131184b1cc7..eec0d0b84edb5ec2e601ab82b67a7e9da6f86d11 100644
--- a/src/QtLocationPlugin/QMLControl/OfflineMap.qml
+++ b/src/QtLocationPlugin/QMLControl/OfflineMap.qml
@@ -918,11 +918,14 @@ QGCView {
width: Math.min(_tileSetList.width, (ScreenTools.defaultFontPixelWidth * 50).toFixed(0))
spacing: ScreenTools.defaultFontPixelHeight * 0.5
anchors.horizontalCenter: parent.horizontalCenter
+ ExclusiveGroup { id: selectionGroup }
OfflineMapButton {
id: firstButton
text: qsTr("Add New Set")
width: _cacheList.width
- height: ScreenTools.defaultFontPixelHeight * 2
+ height: ScreenTools.defaultFontPixelHeight * (ScreenTools.isMobile ? 3 : 2)
+ currentSet: _currentSelection
+ exclusiveGroup: selectionGroup
onClicked: {
offlineMapView._currentSelection = null
addNewSet()
@@ -936,7 +939,10 @@ QGCView {
tiles: object.totalTileCount
complete: object.complete
width: firstButton.width
- height: ScreenTools.defaultFontPixelHeight * 2
+ height: ScreenTools.defaultFontPixelHeight * (ScreenTools.isMobile ? 3 : 2)
+ exclusiveGroup: selectionGroup
+ currentSet: _currentSelection
+ tileSet: object
onClicked: {
offlineMapView._currentSelection = object
showInfo()
diff --git a/src/Vehicle/MultiVehicleManager.cc b/src/Vehicle/MultiVehicleManager.cc
index 86e632823f89c065d441673f2a91fbbbeff73c94..cbe4bdea6ee1eb4de6842f290ff453a9e73d7b2d 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);
@@ -371,7 +359,7 @@ void MultiVehicleManager::_sendGCSHeartbeat(void)
LinkManager* linkMgr = _toolbox->linkManager();
for (int i=0; ilinks().count(); i++) {
LinkInterface* link = linkMgr->links()[i];
- if (link->isConnected()) {
+ if (link->isConnected() && !link->highLatency()) {
mavlink_message_t message;
mavlink_msg_heartbeat_pack_chan(_mavlinkProtocol->getSystemId(),
_mavlinkProtocol->getComponentId(),
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 1397bccedadadfef6cbe3a3dbf7cc84eaf95134d..20425ac38caff53bf91058fd380768a4b86ce376 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -227,7 +227,7 @@ Vehicle::Vehicle(LinkInterface* link,
// Send MAV_CMD ack timer
_mavCommandAckTimer.setSingleShot(true);
- _mavCommandAckTimer.setInterval(_mavCommandAckTimeoutMSecs);
+ _mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
connect(&_mavCommandAckTimer, &QTimer::timeout, this, &Vehicle::_sendMavCommandAgain);
_mav = uas();
@@ -239,18 +239,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);
@@ -708,13 +717,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:
{
@@ -724,7 +736,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);
@@ -828,6 +840,97 @@ 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);
+
+ QString previousFlightMode;
+ if (_base_mode != 0 || _custom_mode != 0){
+ // Vehicle is initialized with _base_mode=0 and _custom_mode=0. Don't pass this to flightMode() since it will complain about
+ // bad modes while unit testing.
+ previousFlightMode = flightMode();
+ }
+ _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
+ _custom_mode = _firmwarePlugin->highLatencyCustomModeTo32Bits(highLatency2.custom_mode);
+ if (previousFlightMode != flightMode()) {
+ emit flightModeChanged(flightMode());
+ }
+
+ // Assume armed since we don't know
+ if (_armed != true) {
+ _armed = true;
+ emit armedChanged(_armed);
+ }
+
+ _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);
+ _altitudeRelativeFact.setRawValue(std::numeric_limits::quiet_NaN());
+ _altitudeAMSLFact.setRawValue(highLatency2.altitude);
+
+ _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);
+
+ struct failure2Sensor_s {
+ HL_FAILURE_FLAG failureBit;
+ MAV_SYS_STATUS_SENSOR sensorBit;
+ };
+
+ static const failure2Sensor_s rgFailure2Sensor[] = {
+ { HL_FAILURE_FLAG_GPS, MAV_SYS_STATUS_SENSOR_GPS },
+ { HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE, MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE },
+ { HL_FAILURE_FLAG_ABSOLUTE_PRESSURE, MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE },
+ { HL_FAILURE_FLAG_3D_ACCEL, MAV_SYS_STATUS_SENSOR_3D_ACCEL },
+ { HL_FAILURE_FLAG_3D_GYRO, MAV_SYS_STATUS_SENSOR_3D_GYRO },
+ { HL_FAILURE_FLAG_3D_MAG, MAV_SYS_STATUS_SENSOR_3D_MAG },
+#if 0
+ // FIXME: These don't currently map to existing sensor health bits. Support needs to be added to show them
+ // on health page of instrument panel as well.
+ { HL_FAILURE_FLAG_TERRAIN=64, /* Terrain subsystem failure. | */
+ { HL_FAILURE_FLAG_BATTERY=128, /* Battery failure/critical low battery. | */
+ { HL_FAILURE_FLAG_RC_RECEIVER=256, /* RC receiver failure/no rc connection. | */
+ { HL_FAILURE_FLAG_OFFBOARD_LINK=512, /* Offboard link failure. | */
+ { HL_FAILURE_FLAG_ENGINE=1024, /* Engine failure. | */
+ { HL_FAILURE_FLAG_GEOFENCE=2048, /* Geofence violation. | */
+ { HL_FAILURE_FLAG_ESTIMATOR=4096, /* Estimator failure, for example measurement rejection or large variances. | */
+ { HL_FAILURE_FLAG_MISSION=8192, /* Mission failure. | */
+#endif
+ };
+
+ // Map from MAV_FAILURE bits to standard SYS_STATUS message handling
+ uint32_t newOnboardControlSensorsEnabled = 0;
+ for (size_t i=0; ifailureBit) {
+ // Assume if reporting as unhealthy that is it present and enabled
+ newOnboardControlSensorsEnabled |= pFailure2Sensor->sensorBit;
+ }
+ }
+ if (newOnboardControlSensorsEnabled != _onboardControlSensorsEnabled) {
+ _onboardControlSensorsEnabled = newOnboardControlSensorsEnabled;
+ _onboardControlSensorsPresent = newOnboardControlSensorsEnabled;
+ _onboardControlSensorsUnhealthy = 0;
+ emit unhealthySensorsChanged();
+ }
+}
+
void Vehicle::_handleAltitude(mavlink_message_t& message)
{
mavlink_altitude_t altitude;
@@ -940,14 +1043,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;
}
@@ -957,22 +1060,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)
@@ -985,19 +1088,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
@@ -1382,6 +1485,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);
@@ -1443,38 +1547,68 @@ void Vehicle::_updatePriorityLink(void)
{
LinkInterface* newPriorityLink = NULL;
-#ifndef NO_SERIAL_LINK
- // Note that this routine specificallty does not clear _priorityLink when there are no links remaining.
+ // This routine specifically does not clear _priorityLink when there are no links remaining.
// By doing this we hold a reference on the last link as the Vehicle shuts down. Thus preventing shutdown
// ordering NULL pointer crashes where priorityLink() is still called during shutdown sequence.
+ if (_links.count() == 0) {
+ return;
+ }
+
+ // Check for the existing priority link to still be valid
+ for (int i=0; i<_links.count(); i++) {
+ if (_priorityLink.data() == _links[i]) {
+ if (!_priorityLink.data()->highLatency()) {
+ // Link is still valid. Continue to use it unless it is high latency. In that case we still look for a better
+ // link to use as priority link.
+ return;
+ }
+ }
+ }
+
+ // The previous priority link is no longer valid. We must no find the best link available in this priority order:
+ // Direct USB connection
+ // Not a high latency link
+ // Any link
+
+#ifndef NO_SERIAL_LINK
+ // Search for direct usb connection
for (int i=0; i<_links.count(); i++) {
LinkInterface* link = _links[i];
- if (link->isConnected()) {
- SerialLink* pSerialLink = qobject_cast(link);
- if (pSerialLink) {
- LinkConfiguration* config = pSerialLink->getLinkConfiguration();
- if (config) {
- SerialConfiguration* pSerialConfig = qobject_cast(config);
- if (pSerialConfig && pSerialConfig->usbDirect()) {
- if (_priorityLink.data() != link) {
- newPriorityLink = link;
- break;
- }
- return;
+ SerialLink* pSerialLink = qobject_cast(link);
+ if (pSerialLink) {
+ LinkConfiguration* config = pSerialLink->getLinkConfiguration();
+ if (config) {
+ SerialConfiguration* pSerialConfig = qobject_cast(config);
+ if (pSerialConfig && pSerialConfig->usbDirect()) {
+ if (_priorityLink.data() != link) {
+ newPriorityLink = link;
+ break;
}
+ return;
}
}
}
}
#endif
- if (!newPriorityLink && !_priorityLink.data() && _links.count()) {
- newPriorityLink = _links[0];
+ if (!newPriorityLink) {
+ // Search for non-high latency link
+ for (int i=0; i<_links.count(); i++) {
+ LinkInterface* link = _links[i];
+ if (!link->highLatency()) {
+ newPriorityLink = link;
+ break;
+ }
+ }
}
- if (newPriorityLink) {
- _priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
+ if (!newPriorityLink) {
+ // Use any link
+ newPriorityLink = _links[0];
}
+
+ _priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
+ _updateHighLatencyLink();
}
void Vehicle::_updateAttitude(UASInterface*, double roll, double pitch, double yaw, quint64)
@@ -2129,9 +2263,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
}
}
@@ -2649,7 +2783,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);
@@ -2701,6 +2835,7 @@ QStringList Vehicle::unhealthySensors(void) const
{ MAV_SYS_STATUS_TERRAIN, "Terrain" },
{ MAV_SYS_STATUS_REVERSE_MOTOR, "Motors reversed" },
{ MAV_SYS_STATUS_LOGGING, "Logging" },
+ { MAV_SYS_STATUS_SENSOR_BATTERY, "Battery" },
};
for (size_t i=0; igetSystemId(),
- _mavlink->getComponentId(),
- priorityLink()->mavlinkChannel(),
- &msg,
- &ack);
+ _mavlink->getSystemId(),
+ _mavlink->getComponentId(),
+ priorityLink()->mavlinkChannel(),
+ &msg,
+ &ack);
sendMessageOnLink(priorityLink(), msg);
}
@@ -2809,7 +2944,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)
@@ -2818,7 +2953,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)
@@ -2977,7 +3112,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;
@@ -3005,6 +3140,7 @@ void Vehicle::_updateHighLatencyLink(void)
{
if (_priorityLink->highLatency() != _highLatencyLink) {
_highLatencyLink = _priorityLink->highLatency();
+ _mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
emit highLatencyLinkChanged(_highLatencyLink);
}
}
diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h
index 1cca1919aa7423d86d41f32d756f0eb0966ba166..8b1034a9a10972192bea79105940d95df52b16d9 100644
--- a/src/Vehicle/Vehicle.h
+++ b/src/Vehicle/Vehicle.h
@@ -941,6 +941,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);
@@ -1041,6 +1042,7 @@ private:
int _mavCommandRetryCount;
static const int _mavCommandMaxRetryCount = 3;
static const int _mavCommandAckTimeoutMSecs = 3000;
+ static const int _mavCommandAckTimeoutMSecsHighLatency = 120000;
QString _prearmError;
QTimer _prearmErrorTimer;
diff --git a/src/VehicleSetup/JoystickConfig.qml b/src/VehicleSetup/JoystickConfig.qml
index 7efe052d59ec5ced75b4a5ae1703669f054b7d1a..c4bc8430f731ae40456979d2b21d49a220c35ba8 100644
--- a/src/VehicleSetup/JoystickConfig.qml
+++ b/src/VehicleSetup/JoystickConfig.qml
@@ -85,6 +85,8 @@ SetupPage {
Item {
property int axisValue: 0
property int deadbandValue: 0
+ property bool narrowIndicator: false
+ property color deadbandColor: "#8c161a"
property color __barColor: qgcPal.windowShade
@@ -104,7 +106,7 @@ SetupPage {
x: _deadbandPosition
width: _deadbandWidth
height: parent.height / 2
- color: "#8c161a"
+ color: deadbandColor
visible: controller.deadbandToggle
property real _percentDeadband: ((2 * deadbandValue) / (32768.0 * 2))
@@ -123,8 +125,8 @@ SetupPage {
// Indicator
Rectangle {
anchors.verticalCenter: parent.verticalCenter
- width: parent.height * 0.75
- height: width
+ width: parent.narrowIndicator ? height/6 : height
+ height: parent.height * 0.75
x: (reversed ? (parent.width - _indicatorPosition) : _indicatorPosition) - (width / 2)
radius: width / 2
color: qgcPal.text
@@ -535,6 +537,21 @@ SetupPage {
onClicked: controller.deadbandToggle = checked
}
}
+ Row{
+ width: parent.width
+ spacing: ScreenTools.defaultFontPixelWidth
+ visible: advancedSettings.checked
+ QGCLabel{
+ width: parent.width * 0.85
+ font.pointSize: ScreenTools.smallFontPointSize
+ wrapMode: Text.WordWrap
+ text: qsTr("Deadband can be set during the first ") +
+ qsTr("step of calibration by gently wiggling each axis. ") +
+ qsTr("Deadband can also be adjusted by clicking and ") +
+ qsTr("dragging vertically on the corresponding axis monitor.")
+ visible: controller.deadbandToggle
+ }
+ }
}
} // Column - left column
@@ -790,11 +807,36 @@ SetupPage {
height: ScreenTools.defaultFontPixelHeight
width: 200
sourceComponent: axisMonitorDisplayComponent
+ Component.onCompleted: item.narrowIndicator = true
property real defaultTextWidth: ScreenTools.defaultFontPixelWidth
property bool mapped: true
readonly property bool reversed: false
+
+
+ MouseArea {
+ id: deadbandMouseArea
+ anchors.fill: parent.item
+ enabled: controller.deadbandToggle
+
+ property real startY
+
+ onPressed: {
+ startY = mouseY
+ parent.item.deadbandColor = "#3C6315"
+ }
+ onPositionChanged: {
+ var newValue = parent.item.deadbandValue + (startY - mouseY)*15
+ if ((newValue > 0) && (newValue <32768)){parent.item.deadbandValue=newValue;}
+ startY = mouseY
+ }
+ onReleased: {
+ controller.setDeadbandValue(modelData,parent.item.deadbandValue)
+ parent.item.deadbandColor = "#8c161a"
+ }
+ }
}
+
}
}
} // Column - Axis Monitor
diff --git a/src/VehicleSetup/JoystickConfigController.cc b/src/VehicleSetup/JoystickConfigController.cc
index 6168ce338f5052136ad9fc2fe9014fc7daa0846b..8b4f0b6fd450bedd2704ca263b6a1fdf29edb874 100644
--- a/src/VehicleSetup/JoystickConfigController.cc
+++ b/src/VehicleSetup/JoystickConfigController.cc
@@ -16,7 +16,6 @@
QGC_LOGGING_CATEGORY(JoystickConfigControllerLog, "JoystickConfigControllerLog")
-const int JoystickConfigController::_updateInterval = 150; ///< Interval for timer which updates radio channel widgets
const int JoystickConfigController::_calCenterPoint = 0;
const int JoystickConfigController::_calValidMinValue = -32768; ///< Largest valid minimum axis value
const int JoystickConfigController::_calValidMaxValue = 32767; ///< Smallest valid maximum axis value
@@ -71,6 +70,15 @@ void JoystickConfigController::start(void)
_stopCalibration();
}
+void JoystickConfigController::setDeadbandValue(int axis, int value)
+{
+ _axisDeadbandChanged(axis,value);
+ Joystick* joystick = _joystickManager->activeJoystick();
+ Joystick::Calibration_t calibration = joystick->getCalibration(axis);
+ calibration.deadband = value;
+ joystick->setCalibration(axis,calibration);
+}
+
JoystickConfigController::~JoystickConfigController()
{
if(_activeJoystick) {
@@ -407,8 +415,8 @@ void JoystickConfigController::_inputCenterWait(Joystick::AxisFunction_t functio
if (_stickDetectAxis == _axisNoAxis) {
// Sticks have not yet moved close enough to center
-
- if (abs(_calCenterPoint - value) < _calRoughCenterDelta) {
+ int roughCenter = getDeadbandToggle() ? std::max(_rgAxisInfo[axis].deadband,_calRoughCenterDelta) : _calRoughCenterDelta;
+ if (abs(_calCenterPoint - value) < roughCenter) {
// Stick has moved close enough to center that we can start waiting for it to settle
_stickDetectAxis = axis;
_stickDetectInitialValue = value;
diff --git a/src/VehicleSetup/JoystickConfigController.h b/src/VehicleSetup/JoystickConfigController.h
index d0e1faf231b5324ca8cb6eac1b024b3010f6cb4b..a947e43b924a40a392a4011b733e573c941b5593 100644
--- a/src/VehicleSetup/JoystickConfigController.h
+++ b/src/VehicleSetup/JoystickConfigController.h
@@ -67,6 +67,7 @@ public:
Q_INVOKABLE void skipButtonClicked(void);
Q_INVOKABLE void nextButtonClicked(void);
Q_INVOKABLE void start(void);
+ Q_INVOKABLE void setDeadbandValue(int axis, int value);
bool rollAxisMapped(void);
bool pitchAxisMapped(void);
@@ -207,8 +208,6 @@ private:
static const char* _imagePitchUp;
static const char* _imagePitchDown;
- static const int _updateInterval; ///< Interval for ui update timer
-
int _rgFunctionAxisMapping[Joystick::maxFunction]; ///< Maps from joystick function to axis index. _axisMax indicates axis not set for this function.
static const int _attitudeControls = 5;
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/LinkConfiguration.cc b/src/comm/LinkConfiguration.cc
index 915c20cda6217c6c3fe51a135a4c7e4c95590651..c27239517cea29e159682d3c78ba52c2d2fa3473 100644
--- a/src/comm/LinkConfiguration.cc
+++ b/src/comm/LinkConfiguration.cc
@@ -37,6 +37,7 @@ LinkConfiguration::LinkConfiguration(const QString& name)
, _name(name)
, _dynamic(false)
, _autoConnect(false)
+ , _highLatency(false)
{
_name = name;
if (_name.isEmpty()) {
@@ -50,6 +51,7 @@ LinkConfiguration::LinkConfiguration(LinkConfiguration* copy)
_name = copy->name();
_dynamic = copy->isDynamic();
_autoConnect= copy->isAutoConnect();
+ _highLatency= copy->isHighLatency();
Q_ASSERT(!_name.isEmpty());
}
@@ -60,6 +62,7 @@ void LinkConfiguration::copyFrom(LinkConfiguration* source)
_name = source->name();
_dynamic = source->isDynamic();
_autoConnect= source->isAutoConnect();
+ _highLatency= source->isHighLatency();
}
/*!
diff --git a/src/comm/LinkConfiguration.h b/src/comm/LinkConfiguration.h
index 76a4bed125f3d3f5f67d1c39c3731ce264a3a26a..8feda594d11c4cc3731a6354f733a6a28923cc30 100644
--- a/src/comm/LinkConfiguration.h
+++ b/src/comm/LinkConfiguration.h
@@ -33,6 +33,8 @@ public:
Q_PROPERTY(bool autoConnect READ isAutoConnect WRITE setAutoConnect NOTIFY autoConnectChanged)
Q_PROPERTY(bool autoConnectAllowed READ isAutoConnectAllowed CONSTANT)
Q_PROPERTY(QString settingsURL READ settingsURL CONSTANT)
+ Q_PROPERTY(bool highLatency READ isHighLatency WRITE setHighLatency NOTIFY highLatencyChanged)
+ Q_PROPERTY(bool highLatencyAllowed READ isHighLatencyAllowed CONSTANT)
// Property accessors
@@ -76,6 +78,13 @@ public:
*/
bool isAutoConnect() { return _autoConnect; }
+ /*!
+ *
+ * Is this a High Latency configuration?
+ * @return True if this is an High Latency configuration (link with large delays).
+ */
+ bool isHighLatency() { return _highLatency; }
+
/*!
* Set if this is this a dynamic configuration. (decided at runtime)
*/
@@ -86,6 +95,11 @@ public:
*/
void setAutoConnect(bool autoc = true) { _autoConnect = autoc; emit autoConnectChanged(); }
+ /*!
+ * Set if this is this an High Latency configuration.
+ */
+ void setHighLatency(bool hl = false) { _highLatency = hl; emit highLatencyChanged(); }
+
/// Virtual Methods
/*!
@@ -95,6 +109,13 @@ public:
*/
virtual bool isAutoConnectAllowed() { return false; }
+ /*!
+ *
+ * Is High Latency allowed for this type?
+ * @return True if this type can be set as an High Latency configuration
+ */
+ virtual bool isHighLatencyAllowed() { return false; }
+
/*!
* @brief Connection type
*
@@ -174,6 +195,7 @@ signals:
void dynamicChanged ();
void autoConnectChanged ();
void linkChanged (LinkInterface* link);
+ void highLatencyChanged ();
protected:
LinkInterface* _link; ///< Link currently using this configuration (if any)
@@ -181,6 +203,7 @@ private:
QString _name;
bool _dynamic; ///< A connection added automatically and not persistent (unless it's edited).
bool _autoConnect; ///< This connection is started automatically at boot
+ bool _highLatency;
};
typedef QSharedPointer SharedLinkConfigurationPointer;
diff --git a/src/comm/LinkInterface.cc b/src/comm/LinkInterface.cc
index 0dc594a9df52b8a78b4f140117277da4398de264..f2920712efce1b076baafeee3637bcf9fca352c5 100644
--- a/src/comm/LinkInterface.cc
+++ b/src/comm/LinkInterface.cc
@@ -23,7 +23,7 @@ uint8_t LinkInterface::mavlinkChannel(void) const
LinkInterface::LinkInterface(SharedLinkConfigurationPointer& config)
: QThread (0)
, _config (config)
- , _highLatency (false)
+ , _highLatency (config->isHighLatency())
, _mavlinkChannelSet (false)
, _active (false)
, _enableRateCollection (false)
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..9ad225d6a9e48914c7d531b5aaf8cf026421bdc5 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,46 @@ void MockLink::_sendHeartBeat(void)
respondWithMavlinkMessage(msg);
}
+void MockLink::_sendHighLatency2(void)
+{
+ mavlink_message_t msg;
+
+ union px4_custom_mode px4_cm;
+ px4_cm.data = _mavCustomMode;
+
+ qDebug() << "Sending" << _mavCustomMode;
+ mavlink_msg_high_latency2_pack_chan(_vehicleSystemId,
+ _vehicleComponentId,
+ _mavlinkChannel,
+ &msg,
+ 0, // timestamp
+ _vehicleType, // MAV_TYPE
+ _firmwareType, // MAV_AUTOPILOT
+ px4_cm.custom_mode_hl, // custom_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, 0, 0); // custom0, custom1, custom2
+ respondWithMavlinkMessage(msg);
+}
+
void MockLink::_sendVibration(void)
{
mavlink_message_t msg;
@@ -842,8 +894,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 +904,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 +995,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 +1024,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 +1289,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) {
diff --git a/src/comm/MockLink.h b/src/comm/MockLink.h
index 1eb0b48c155e19198ce0f964aa24a92dae8eadc6..105839a0d2a761874f336ddee07bb1f7b394b070 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);
diff --git a/src/comm/SerialLink.h b/src/comm/SerialLink.h
index a70e27a30c74542386c668bf6caf697e900f54f0..9430f20686586fd8193b571ef6b67db5944f3dac 100644
--- a/src/comm/SerialLink.h
+++ b/src/comm/SerialLink.h
@@ -86,6 +86,7 @@ public:
/// From LinkConfiguration
LinkType type () { return LinkConfiguration::TypeSerial; }
void copyFrom (LinkConfiguration* source);
+ bool isHighLatencyAllowed () { return true; }
void loadSettings (QSettings& settings, const QString& root);
void saveSettings (QSettings& settings, const QString& root);
void updateSettings ();
diff --git a/src/comm/TCPLink.h b/src/comm/TCPLink.h
index 9eb2827feb43a947f8ccec9e975e9dff23017050..907af9cbc5dfe0aa2ee6d479a114b066ce97826f 100644
--- a/src/comm/TCPLink.h
+++ b/src/comm/TCPLink.h
@@ -97,6 +97,7 @@ public:
/// From LinkConfiguration
LinkType type () { return LinkConfiguration::TypeTcp; }
void copyFrom (LinkConfiguration* source);
+ bool isHighLatencyAllowed () { return true; }
void loadSettings (QSettings& settings, const QString& root);
void saveSettings (QSettings& settings, const QString& root);
void updateSettings ();
diff --git a/src/comm/UDPLink.h b/src/comm/UDPLink.h
index c8632cecdcae919f8fe1964ed906aa4202bfd4b6..6e12c6af7bdef0ad4b2a951cc1ee2f5d1ef94e4e 100644
--- a/src/comm/UDPLink.h
+++ b/src/comm/UDPLink.h
@@ -126,6 +126,7 @@ public:
void saveSettings (QSettings& settings, const QString& root);
void updateSettings ();
bool isAutoConnectAllowed () { return true; }
+ bool isHighLatencyAllowed () { return true; }
QString settingsURL () { return "UdpSettings.qml"; }
signals:
diff --git a/src/qgcunittest/UnitTest.cc b/src/qgcunittest/UnitTest.cc
index f2c9d260946f2cf890ae7cf0f477dede74887888..bf0f0854c8d49628a2742332b7ae2670baaf55a9 100644
--- a/src/qgcunittest/UnitTest.cc
+++ b/src/qgcunittest/UnitTest.cc
@@ -523,3 +523,12 @@ bool UnitTest::doubleNaNCompare(double value1, double value2)
return ret;
}
}
+
+void UnitTest::changeFactValue(Fact* fact)
+{
+ if (fact->typeIsBool()) {
+ fact->setRawValue(!fact->rawValue().toBool());
+ } else {
+ fact->setRawValue(fact->rawValue().toDouble() + 1);
+ }
+}
diff --git a/src/qgcunittest/UnitTest.h b/src/qgcunittest/UnitTest.h
index fa1d164f175ebeda594d3c909d5a4326686634ef..6690284e6f262ca42d62a3538383c948a2375e3b 100644
--- a/src/qgcunittest/UnitTest.h
+++ b/src/qgcunittest/UnitTest.h
@@ -24,6 +24,7 @@
#include "QGCMAVLink.h"
#include "LinkInterface.h"
+#include "Fact.h"
#define UT_REGISTER_TEST(className) static UnitTestWrapper className(#className);
@@ -96,6 +97,9 @@ public:
/// @return true: equal
static bool doubleNaNCompare(double value1, double value2);
+ /// Changes the Facts rawValue such that it emits a valueChanged signal.
+ void changeFactValue(Fact* fact);
+
protected slots:
// These are all pure virtuals to force the derived class to implement each one and in turn
diff --git a/src/qgcunittest/UnitTestList.cc b/src/qgcunittest/UnitTestList.cc
index fe67513cc739dcc3e4222173b87b48043dda3be0..97f11ce3a0dfa6ed4519556ebd1701152a21a5dd 100644
--- a/src/qgcunittest/UnitTestList.cc
+++ b/src/qgcunittest/UnitTestList.cc
@@ -40,6 +40,10 @@
#include "QGCMapPolygonTest.h"
#include "AudioOutputTest.h"
#include "StructureScanComplexItemTest.h"
+#include "QGCMapPolylineTest.h"
+#include "CorridorScanComplexItemTest.h"
+#include "TransectStyleComplexItemTest.h"
+#include "CameraCalcTest.h"
UT_REGISTER_TEST(FactSystemTestGeneric)
UT_REGISTER_TEST(FactSystemTestPX4)
@@ -67,6 +71,10 @@ UT_REGISTER_TEST(MissionSettingsTest)
UT_REGISTER_TEST(QGCMapPolygonTest)
UT_REGISTER_TEST(AudioOutputTest)
UT_REGISTER_TEST(StructureScanComplexItemTest)
+UT_REGISTER_TEST(CorridorScanComplexItemTest)
+UT_REGISTER_TEST(TransectStyleComplexItemTest)
+UT_REGISTER_TEST(QGCMapPolylineTest)
+UT_REGISTER_TEST(CameraCalcTest)
// List of unit test which are currently disabled.
// If disabling a new test, include reason in comment.
diff --git a/src/ui/preferences/SerialSettings.qml b/src/ui/preferences/SerialSettings.qml
index 07e495605085212cc6b9e53f5d25f3cc975e32cf..8438549d070b9ad7a6a3b8306bc3168c26accf53 100644
--- a/src/ui/preferences/SerialSettings.qml
+++ b/src/ui/preferences/SerialSettings.qml
@@ -235,5 +235,19 @@ Item {
}
}
}
+ QGCCheckBox {
+ text: "High Latency"
+ checked: false
+ visible: editConfig ? editConfig.highLatencyAllowed : false
+ onCheckedChanged: {
+ if(editConfig) {
+ editConfig.highLatency = checked
+ }
+ }
+ Component.onCompleted: {
+ if(editConfig)
+ checked = editConfig.highLatency
+ }
+ }
}
}
diff --git a/src/ui/preferences/TcpSettings.qml b/src/ui/preferences/TcpSettings.qml
index 182cf4d6167459bb9702999a11322ee114bc5044..6f0ac0e2d57ef50820f784181fded58f14d88a67 100644
--- a/src/ui/preferences/TcpSettings.qml
+++ b/src/ui/preferences/TcpSettings.qml
@@ -75,5 +75,19 @@ Item {
anchors.verticalCenter: parent.verticalCenter
}
}
+ QGCCheckBox {
+ text: "High Latency"
+ checked: false
+ visible: editConfig ? editConfig.highLatencyAllowed : false
+ onCheckedChanged: {
+ if(editConfig) {
+ editConfig.highLatency = checked
+ }
+ }
+ Component.onCompleted: {
+ if(editConfig)
+ checked = editConfig.highLatency
+ }
+ }
}
}
diff --git a/src/ui/preferences/UdpSettings.qml b/src/ui/preferences/UdpSettings.qml
index 825b1bd79b80efe7fdd7ee78fa749790510817a8..6332dc964933134b017b95b9ac68944f2d238c3f 100644
--- a/src/ui/preferences/UdpSettings.qml
+++ b/src/ui/preferences/UdpSettings.qml
@@ -175,5 +175,19 @@ Item {
}
}
}
+ QGCCheckBox {
+ text: "High Latency"
+ checked: false
+ visible: editConfig ? editConfig.highLatencyAllowed : false
+ onCheckedChanged: {
+ if(editConfig) {
+ editConfig.highLatency = checked
+ }
+ }
+ Component.onCompleted: {
+ if(editConfig)
+ checked = editConfig.highLatency
+ }
+ }
}
}