Commit 916d6ebd authored by DonLakeFlyer's avatar DonLakeFlyer

parent 988cd6a9
......@@ -669,6 +669,8 @@ HEADERS += \
src/Vehicle/GPSRTKFactGroup.h \
src/Vehicle/MAVLinkLogManager.h \
src/Vehicle/MultiVehicleManager.h \
src/Vehicle/TerrainFactGroup.h \
src/Vehicle/TerrainProtocolHandler.h \
src/Vehicle/TrajectoryPoints.h \
src/Vehicle/Vehicle.h \
src/Vehicle/VehicleObjectAvoidance.h \
......@@ -872,6 +874,8 @@ SOURCES += \
src/Vehicle/GPSRTKFactGroup.cc \
src/Vehicle/MAVLinkLogManager.cc \
src/Vehicle/MultiVehicleManager.cc \
src/Vehicle/TerrainFactGroup.cc \
src/Vehicle/TerrainProtocolHandler.cc \
src/Vehicle/TrajectoryPoints.cc \
src/Vehicle/Vehicle.cc \
src/Vehicle/VehicleObjectAvoidance.cc \
......
......@@ -197,6 +197,7 @@
<file alias="QGroundControl/FlightDisplay/PreFlightRCCheck.qml">src/FlightDisplay/PreFlightRCCheck.qml</file>
<file alias="QGroundControl/FlightDisplay/PreFlightSensorsHealthCheck.qml">src/FlightDisplay/PreFlightSensorsHealthCheck.qml</file>
<file alias="QGroundControl/FlightDisplay/PreFlightSoundCheck.qml">src/FlightDisplay/PreFlightSoundCheck.qml</file>
<file alias="QGroundControl/FlightDisplay/TerrainProgress.qml">src/FlightDisplay/TerrainProgress.qml</file>
<file alias="QGroundControl/FlightDisplay/qmldir">src/QmlControls/QGroundControl/FlightDisplay/qmldir</file>
<file alias="QGroundControl/FlightMap/CameraTriggerIndicator.qml">src/FlightMap/MapItems/CameraTriggerIndicator.qml</file>
<file alias="QGroundControl/FlightMap/CenterMapDropButton.qml">src/FlightMap/Widgets/CenterMapDropButton.qml</file>
......@@ -285,6 +286,7 @@
<file alias="Vehicle/SetpointFact.json">src/Vehicle/SetpointFact.json</file>
<file alias="Vehicle/SubmarineFact.json">src/Vehicle/SubmarineFact.json</file>
<file alias="Vehicle/TemperatureFact.json">src/Vehicle/TemperatureFact.json</file>
<file alias="Vehicle/TerrainFactGroup.json">src/Vehicle/TerrainFactGroup.json</file>
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
<file alias="Vehicle/VibrationFact.json">src/Vehicle/VibrationFact.json</file>
<file alias="Vehicle/WindFact.json">src/Vehicle/WindFact.json</file>
......
......@@ -105,7 +105,6 @@ public:
QObject* loadParameterMetaData (const QString& metaDataFile) override;
QString brandImageIndoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); }
QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); }
bool supportsTerrainFrame (void) const override { return true; }
protected:
/// All access to singleton is through stack specific implementation
......
......@@ -148,12 +148,6 @@ bool FirmwarePlugin::supportsJSButton(void)
return false;
}
bool FirmwarePlugin::supportsTerrainFrame(void) const
{
// Generic firmware supports this since we don't know
return true;
}
bool FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
{
Q_UNUSED(vehicle);
......
......@@ -182,9 +182,6 @@ public:
/// (CompassMot). Default is true.
virtual bool supportsMotorInterference(void);
/// Returns true if the firmware supports MAV_FRAME_GLOBAL_TERRAIN_ALT
virtual bool supportsTerrainFrame(void) const;
/// Called before any mavlink message is processed by Vehicle such that the firmwre plugin
/// can adjust any message characteristics. This is handy to adjust or differences in mavlink
/// spec implementations such that the base code can remain mavlink generic.
......
......@@ -68,7 +68,6 @@ public:
QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); }
QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("COM_DISARM_LAND"); }
uint32_t highLatencyCustomModeTo32Bits (uint16_t hlCustomMode) override;
bool supportsTerrainFrame (void) const override { return false; }
bool supportsNegativeThrust (Vehicle *vehicle) override;
protected:
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.12
import QtQuick.Layouts 1.12
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
Rectangle {
height: mainLayout.height + (_margins * 2)
visible: false
color: qgcPal.window
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property real _margins: ScreenTools.defaultFontPixelWidth / 2
property real _totalBlocks: _activeVehicle ? _activeVehicle.terrain.blocksPending.rawValue + _activeVehicle.terrain.blocksLoaded.rawValue : 0
property real _blocksLoaded: _activeVehicle ? _activeVehicle.terrain.blocksLoaded.rawValue : 0
property real _blocksPending: _activeVehicle ? _activeVehicle.terrain.blocksPending.rawValue : 0
property real _pctComplete: _activeVehicle && _totalBlocks ? _blocksLoaded / _totalBlocks : 0
on_BlocksPendingChanged: {
if (_blocksPending == 0) {
// UI doesn't go away immediately
visibilityTimer.restart()
} else {
visible = true
visibilityTimer.stop()
}
}
on_BlocksLoadedChanged: {
if (_blocksLoaded != 0) {
// This causes the progress indicator to display even if it starts out as complete
visible = true
if (_blocksPending == 0) {
visibilityTimer.restart()
}
}
}
Timer {
id: visibilityTimer
interval: 30 * 1000
onTriggered: parent.visible = false
}
QGCPalette { id: qgcPal }
ColumnLayout {
id: mainLayout
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
spacing: _margins
QGCLabel {
Layout.alignment: Qt.AlignHCenter
text: qsTr("Terrain Load Progress")
font.pointSize: ScreenTools.smallFontPointSize
}
Rectangle {
Layout.fillWidth: true
height: ScreenTools.defaultFontPixelHeight
color: "transparent"
border.color: "green"
Rectangle {
anchors.top: parent.top
anchors.bottom: parent.bottom
color: "green"
width: parent.width * _pctComplete
QGCLabel {
anchors.centerIn: parent
text: qsTr("Done")
visible: _blocksPending == 0
}
}
}
}
}
......@@ -7,73 +7,76 @@
*
****************************************************************************/
import QtQuick 2.3
import QtQuick 2.12
import QtQuick.Layouts 1.12
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FlightMap 1.0
import QGroundControl.FlightDisplay 1.0
import QGroundControl.Palette 1.0
Rectangle {
id: root
width: getPreferredInstrumentWidth()
height: _outerRadius * 2
radius: _outerRadius
color: qgcPal.window
border.width: 1
border.color: _isSatellite ? qgcPal.mapWidgetBorderLight : qgcPal.mapWidgetBorderDark
property real _innerRadius: (width - (_topBottomMargin * 3)) / 4
property real _outerRadius: _innerRadius + _topBottomMargin
property real _defaultSize: ScreenTools.defaultFontPixelHeight * (9)
property real _sizeRatio: ScreenTools.isTinyScreen ? (width / _defaultSize) * 0.5 : width / _defaultSize
property real _bigFontSize: ScreenTools.defaultFontPointSize * 2.5 * _sizeRatio
property real _normalFontSize: ScreenTools.defaultFontPointSize * 1.5 * _sizeRatio
property real _labelFontSize: ScreenTools.defaultFontPointSize * 0.75 * _sizeRatio
property real _spacing: ScreenTools.defaultFontPixelHeight * 0.33
property real _topBottomMargin: (width * 0.05) / 2
property real _availableValueHeight: maxHeight - (root.height + _valuesItem.anchors.topMargin)
ColumnLayout {
id: root
width: getPreferredInstrumentWidth()
spacing: ScreenTools.defaultFontPixelHeight / 4
// Prevent all clicks from going through to lower layers
DeadMouseArea {
anchors.fill: parent
}
property real _innerRadius: (width - (_topBottomMargin * 3)) / 4
property real _outerRadius: _innerRadius + _topBottomMargin
property real _defaultSize: ScreenTools.defaultFontPixelHeight * (9)
property real _sizeRatio: ScreenTools.isTinyScreen ? (width / _defaultSize) * 0.5 : width / _defaultSize
property real _bigFontSize: ScreenTools.defaultFontPointSize * 2.5 * _sizeRatio
property real _normalFontSize: ScreenTools.defaultFontPointSize * 1.5 * _sizeRatio
property real _labelFontSize: ScreenTools.defaultFontPointSize * 0.75 * _sizeRatio
property real _spacing: ScreenTools.defaultFontPixelHeight * 0.33
property real _topBottomMargin: (width * 0.05) / 2
property real _availableValueHeight: maxHeight - _valuesItem.y
QGCPalette { id: qgcPal }
QGCAttitudeWidget {
id: attitude
anchors.leftMargin: _topBottomMargin
anchors.left: parent.left
size: _innerRadius * 2
vehicle: activeVehicle
anchors.verticalCenter: parent.verticalCenter
Rectangle {
id: visualInstrument
height: _outerRadius * 2
Layout.fillWidth: true
radius: _outerRadius
color: qgcPal.window
border.width: 1
border.color: _isSatellite ? qgcPal.mapWidgetBorderLight : qgcPal.mapWidgetBorderDark
DeadMouseArea { anchors.fill: parent }
QGCAttitudeWidget {
id: attitude
anchors.leftMargin: _topBottomMargin
anchors.left: parent.left
size: _innerRadius * 2
vehicle: activeVehicle
anchors.verticalCenter: parent.verticalCenter
}
QGCCompassWidget {
id: compass
anchors.leftMargin: _spacing
anchors.left: attitude.right
size: _innerRadius * 2
vehicle: activeVehicle
anchors.verticalCenter: parent.verticalCenter
}
}
QGCCompassWidget {
id: compass
anchors.leftMargin: _spacing
anchors.left: attitude.right
size: _innerRadius * 2
vehicle: activeVehicle
anchors.verticalCenter: parent.verticalCenter
TerrainProgress {
Layout.fillWidth: true
}
Item {
id: _valuesItem
anchors.topMargin: ScreenTools.defaultFontPixelHeight / 4
anchors.top: parent.bottom
width: parent.width
Layout.fillWidth: true
height: _valuesWidget.height
visible: widgetRoot.showValues
// Prevent all clicks from going through to lower layers
DeadMouseArea {
anchors.fill: parent
}
DeadMouseArea { anchors.fill: parent }
Rectangle {
anchors.fill: _valuesWidget
......
......@@ -11,6 +11,7 @@
#include "JsonHelper.h"
#include "Vehicle.h"
#include "CameraMetaData.h"
#include "PlanMasterController.h"
#include <QQmlEngine>
......@@ -26,10 +27,9 @@ const char* CameraCalc::adjustedFootprintSideName = "AdjustedFootprintSi
const char* CameraCalc::_jsonCameraSpecTypeKey = "CameraSpecType";
CameraCalc::CameraCalc(Vehicle* vehicle, const QString& settingsGroup, QObject* parent)
CameraCalc::CameraCalc(PlanMasterController* masterController, const QString& settingsGroup, QObject* parent)
: CameraSpec (settingsGroup, parent)
, _vehicle (vehicle)
, _dirty (false)
, _dirty (masterController)
, _disableRecalc (false)
, _distanceToSurfaceRelative (true)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CameraCalc.FactMetaData.json"), this))
......@@ -43,7 +43,7 @@ CameraCalc::CameraCalc(Vehicle* vehicle, const QString& settingsGroup, QObject*
, _adjustedFootprintFrontalFact (settingsGroup, _metaDataMap[adjustedFootprintFrontalName])
, _imageFootprintSide (0)
, _imageFootprintFrontal (0)
, _knownCameraList (_vehicle->staticCameraList())
, _knownCameraList (masterController->controllerVehicle()->staticCameraList())
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
......
......@@ -12,14 +12,14 @@
#include "CameraSpec.h"
#include "SettingsFact.h"
class Vehicle;
class PlanMasterController;
class CameraCalc : public CameraSpec
{
Q_OBJECT
public:
CameraCalc(Vehicle* vehicle, const QString& settingsGroup, QObject* parent = nullptr);
CameraCalc(PlanMasterController* masterController, const QString& settingsGroup, QObject* parent = nullptr);
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
......@@ -97,7 +97,6 @@ private slots:
void _cameraNameChanged (void);
private:
Vehicle* _vehicle;
bool _dirty;
bool _disableRecalc;
bool _distanceToSurfaceRelative;
......
......@@ -9,9 +9,9 @@
#include "CameraCalcTest.h"
#include "QGCApplication.h"
#include "PlanMasterController.h"
CameraCalcTest::CameraCalcTest(void)
: _offlineVehicle(nullptr)
{
}
......@@ -20,8 +20,9 @@ void CameraCalcTest::init(void)
{
UnitTest::init();
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_cameraCalc = new CameraCalc(_offlineVehicle, "CameraCalcUnitTest" /* settingsGroup */, this);
_masterController = new PlanMasterController(this);
_controllerVehicle = _masterController->controllerVehicle();
_cameraCalc = new CameraCalc(_masterController, "CameraCalcUnitTest" /* settingsGroup */, this);
_cameraCalc->cameraName()->setRawValue(_cameraCalc->customCameraName());
_cameraCalc->setDirty(false);
......@@ -37,7 +38,6 @@ void CameraCalcTest::init(void)
void CameraCalcTest::cleanup(void)
{
delete _cameraCalc;
delete _offlineVehicle;
delete _multiSpy;
}
......
......@@ -12,6 +12,7 @@
#include "UnitTest.h"
#include "MultiSignalSpy.h"
#include "CameraCalc.h"
#include "PlanMasterController.h"
#include <QGeoCoordinate>
......@@ -50,7 +51,8 @@ private:
static const size_t _cSignals = maxSignalIndex;
const char* _rgSignals[_cSignals];
Vehicle* _offlineVehicle;
MultiSignalSpy* _multiSpy;
CameraCalc* _cameraCalc;
PlanMasterController* _masterController = nullptr;
Vehicle* _controllerVehicle = nullptr;
MultiSignalSpy* _multiSpy = nullptr;
CameraCalc* _cameraCalc = nullptr;
};
......@@ -10,6 +10,7 @@
#include "CameraSection.h"
#include "SimpleMissionItem.h"
#include "FirmwarePlugin.h"
#include "PlanMasterController.h"
QGC_LOGGING_CATEGORY(CameraSectionLog, "CameraSectionLog")
......@@ -22,19 +23,19 @@ const char* CameraSection::_cameraModeName = "CameraMode";
QMap<QString, FactMetaData*> CameraSection::_metaDataMap;
CameraSection::CameraSection(Vehicle* vehicle, QObject* parent)
: Section(vehicle, parent)
, _available(false)
, _settingsSpecified(false)
, _specifyGimbal(false)
, _specifyCameraMode(false)
CameraSection::CameraSection(PlanMasterController* masterController, QObject* parent)
: Section (masterController, parent)
, _available (false)
, _settingsSpecified (false)
, _specifyGimbal (false)
, _specifyCameraMode (false)
, _gimbalYawFact (0, _gimbalYawName, FactMetaData::valueTypeDouble)
, _gimbalPitchFact (0, _gimbalPitchName, FactMetaData::valueTypeDouble)
, _cameraActionFact (0, _cameraActionName, FactMetaData::valueTypeDouble)
, _cameraPhotoIntervalDistanceFact (0, _cameraPhotoIntervalDistanceName, FactMetaData::valueTypeDouble)
, _cameraPhotoIntervalTimeFact (0, _cameraPhotoIntervalTimeName, FactMetaData::valueTypeUint32)
, _cameraModeFact (0, _cameraModeName, FactMetaData::valueTypeUint32)
, _dirty(false)
, _dirty (false)
{
if (_metaDataMap.isEmpty()) {
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CameraSection.FactMetaData.json"), Q_NULLPTR /* metaDataParent */);
......@@ -579,7 +580,7 @@ void CameraSection::_cameraActionChanged(void)
bool CameraSection::cameraModeSupported(void) const
{
return _specifyCameraMode || _vehicle->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_SET_CAMERA_MODE);
return _specifyCameraMode || _masterController->controllerVehicle()->firmwarePlugin()->supportedMissionCommands().contains(MAV_CMD_SET_CAMERA_MODE);
}
void CameraSection::_dirtyIfSpecified(void)
......
......@@ -16,12 +16,14 @@
#define VIDEO_CAPTURE_STATUS_INTERVAL 0.2 //-- Send capture status every 5 seconds
class PlanMasterController;
class CameraSection : public Section
{
Q_OBJECT
public:
CameraSection(Vehicle* vehicle, QObject* parent = nullptr);
CameraSection(PlanMasterController* masterController, QObject* parent = nullptr);
// These enum values must match the json meta data
......
This diff is collapsed.
......@@ -11,6 +11,7 @@
#include "SectionTest.h"
#include "CameraSection.h"
#include "PlanMasterController.h"
/// Unit test for CameraSection
class CameraSectionTest : public SectionTest
......@@ -23,9 +24,9 @@ public:
void init(void) override;
void cleanup(void) override;
static SimpleMissionItem* createValidStopVideoItem (Vehicle* vehicle, QObject* parent);
static SimpleMissionItem* createValidStopDistanceItem(Vehicle* vehicle, QObject* parent);
static SimpleMissionItem* createValidStopTimeItem (Vehicle* vehicle, QObject* parent);
static SimpleMissionItem* createValidStopVideoItem (PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createValidStopDistanceItem(PlanMasterController* masterController, QObject* parent);
static SimpleMissionItem* createValidStopTimeItem (PlanMasterController* masterController, QObject* parent);
private slots:
void _testDirty (void);
......
......@@ -11,6 +11,7 @@
#include "QGCApplication.h"
#include "QGCCorePlugin.h"
#include "QGCOptions.h"
#include "PlanMasterController.h"
#include <QSettings>
......@@ -18,8 +19,8 @@ const char* ComplexMissionItem::jsonComplexItemTypeKey = "complexItemType";
const char* ComplexMissionItem::_presetSettingsKey = "_presets";
ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
: VisualMissionItem (vehicle, flyView, parent)
ComplexMissionItem::ComplexMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: VisualMissionItem (masterController, flyView, parent)
{
}
......
......@@ -7,20 +7,21 @@
*
****************************************************************************/
#ifndef ComplexMissionItem_H
#define ComplexMissionItem_H
#pragma once
#include "VisualMissionItem.h"
#include "QGCGeo.h"
#include <QSettings>
class PlanMasterController;
class ComplexMissionItem : public VisualMissionItem
{
Q_OBJECT
public:
ComplexMissionItem(Vehicle* vehicle, bool flyView, QObject* parent);
ComplexMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent);
const ComplexMissionItem& operator=(const ComplexMissionItem& other);
......@@ -88,5 +89,3 @@ protected:
static const char* _presetSettingsKey;
};
#endif
......@@ -16,6 +16,7 @@
#include "SettingsManager.h"
#include "AppSettings.h"
#include "QGCQGeoCoordinate.h"
#include "PlanMasterController.h"
#include <QPolygonF>
......@@ -27,8 +28,8 @@ const char* CorridorScanComplexItem::_jsonEntryPointKey = "EntryPoint";
const char* CorridorScanComplexItem::jsonComplexItemTypeValue = "CorridorScan";
CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, bool flyView, const QString& kmlFile, QObject* parent)
: TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent)
CorridorScanComplexItem::CorridorScanComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlFile, QObject* parent)
: TransectStyleComplexItem (masterController, flyView, settingsGroup, parent)
, _entryPoint (0)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/CorridorScan.SettingsGroup.json"), this))
, _corridorWidthFact (settingsGroup, _metaDataMap[corridorWidthName])
......
......@@ -23,10 +23,9 @@ class CorridorScanComplexItem : public TransectStyleComplexItem
Q_OBJECT
public:
/// @param vehicle Vehicle which this is being contructed for
/// @param flyView true: Created for use in the Fly View, false: Created for use in the Plan View
/// @param kmlFile Polyline comes from this file, empty for default polyline
CorridorScanComplexItem(Vehicle* vehicle, bool flyView, const QString& kmlFile, QObject* parent);
CorridorScanComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlFile, QObject* parent);
Q_PROPERTY(QGCMapPolyline* corridorPolyline READ corridorPolyline CONSTANT)
Q_PROPERTY(Fact* corridorWidth READ corridorWidth CONSTANT)
......
......@@ -11,7 +11,6 @@
#include "QGCApplication.h"
CorridorScanComplexItemTest::CorridorScanComplexItemTest(void)
: _offlineVehicle(nullptr)
{
_linePoints << QGeoCoordinate(47.633550640000003, -122.08982199)
<< QGeoCoordinate(47.634129020000003, -122.08887249)
......@@ -22,8 +21,9 @@ void CorridorScanComplexItemTest::init(void)
{
UnitTest::init();
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_corridorItem = new CorridorScanComplexItem(_offlineVehicle, false /* flyView */, QString() /* kmlFile */, this /* parent */);
_masterController = new PlanMasterController(this);
_controllerVehicle = _masterController->controllerVehicle();
_corridorItem = new CorridorScanComplexItem(_masterController, false /* flyView */, QString() /* kmlFile */, this /* parent */);
// vehicleSpeed need for terrain calcs
MissionController::MissionFlightStatus_t missionFlightStatus;
......@@ -42,7 +42,6 @@ void CorridorScanComplexItemTest::init(void)
void CorridorScanComplexItemTest::cleanup(void)
{
delete _corridorItem;
delete _offlineVehicle;
}
void CorridorScanComplexItemTest::_testDirty(void)
......
......@@ -13,6 +13,7 @@
#include "TCPLink.h"
#include "MultiSignalSpy.h"
#include "CorridorScanComplexItem.h"
#include "PlanMasterController.h"
#include <QGeoCoordinate>
......@@ -50,8 +51,9 @@ private:
static const size_t _cCorridorPolygonSignals = maxCorridorPolygonSignalIndex;
const char* _rgCorridorPolygonSignals[_cCorridorPolygonSignals];
Vehicle* _offlineVehicle;
MultiSignalSpy* _multiSpyCorridorPolygon;
CorridorScanComplexItem* _corridorItem;
PlanMasterController* _masterController = nullptr;
Vehicle* _controllerVehicle = nullptr;
MultiSignalSpy* _multiSpyCorridorPolygon = nullptr;
CorridorScanComplexItem* _corridorItem = nullptr;
QList<QGeoCoordinate> _linePoints;
};
......@@ -14,24 +14,17 @@
#include "CameraSectionTest.h"
FWLandingPatternTest::FWLandingPatternTest(void)
: _offlineVehicle (Q_NULLPTR)
, _fwItem (Q_NULLPTR)
, _multiSpy (Q_NULLPTR)
, _validStopVideoItem (Q_NULLPTR)
, _validStopDistanceItem (Q_NULLPTR)
, _validStopTimeItem (Q_NULLPTR)
{
}
void FWLandingPatternTest::init(void)
{
UnitTest::init();
VisualMissionItemTest::init();
rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_fwItem = new FixedWingLandingComplexItem(_offlineVehicle, false /* flyView */, this);
_fwItem = new FixedWingLandingComplexItem(_masterController, false /* flyView */, this);
_multiSpy = new MultiSignalSpy();
QCOMPARE(_multiSpy->init(_fwItem, rgSignals, cSignals), true);
......@@ -42,20 +35,19 @@ void FWLandingPatternTest::init(void)
QVERIFY(!_fwItem->dirty());
_multiSpy->clearAllSignals();
_validStopVideoItem = CameraSectionTest::createValidStopTimeItem(_offlineVehicle, this);
_validStopDistanceItem = CameraSectionTest::createValidStopTimeItem(_offlineVehicle, this);
_validStopTimeItem = CameraSectionTest::createValidStopTimeItem(_offlineVehicle, this);
_validStopVideoItem = CameraSectionTest::createValidStopTimeItem(_masterController, this);
_validStopDistanceItem = CameraSectionTest::createValidStopTimeItem(_masterController, this);
_validStopTimeItem = CameraSectionTest::createValidStopTimeItem(_masterController, this);
}
void FWLandingPatternTest::cleanup(void)
{
delete _fwItem;
delete _offlineVehicle;
delete _multiSpy;
delete _validStopVideoItem;
delete _validStopDistanceItem;
delete _validStopTimeItem;
UnitTest::cleanup();
VisualMissionItemTest::cleanup();
}
......@@ -97,14 +89,14 @@ void FWLandingPatternTest::_testAppendSectionItems(void)
QmlObjectListModel* simpleItems = new QmlObjectListModel(this);
for (MissionItem* item: rgMissionItems) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, simpleItems);
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, simpleItems);
simpleItem->missionItem() = *item;
simpleItems->append(simpleItem);
}
// Scan the items back in to verify the same values come back
// Note that the compares does the best it can with doubles going to floats and back causing inaccuracies beyond a fuzzy compare.
QVERIFY(FixedWingLandingComplexItem::scanForItem(simpleItems, false /* flyView */, _offlineVehicle));
QVERIFY(FixedWingLandingComplexItem::scanForItem(simpleItems, false /* flyView */, _masterController));
QCOMPARE(simpleItems->count(), 1);
_validateItem(simpleItems->value<FixedWingLandingComplexItem*>(0));
......@@ -118,11 +110,11 @@ void FWLandingPatternTest::_testAppendSectionItems(void)
_fwItem->appendMissionItems(rgMissionItems, this);
simpleItems = new QmlObjectListModel(this);
for (MissionItem* item: rgMissionItems) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, simpleItems);
SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, simpleItems);
simpleItem->missionItem() = *item;
simpleItems->append(simpleItem);
}
QVERIFY(FixedWingLandingComplexItem::scanForItem(simpleItems, false /* flyView */, _offlineVehicle));
QVERIFY(FixedWingLandingComplexItem::scanForItem(simpleItems, false /* flyView */, _masterController));
QCOMPARE(simpleItems->count(), 1);
_validateItem(simpleItems->value<FixedWingLandingComplexItem*>(0));
......@@ -204,7 +196,7 @@ void FWLandingPatternTest::_testSaveLoad(void)
_fwItem->save(items);
QString errorString;
FixedWingLandingComplexItem* newItem = new FixedWingLandingComplexItem(_offlineVehicle, false /* flyView */, this /* parent */);
FixedWingLandingComplexItem* newItem = new FixedWingLandingComplexItem(_masterController, false /* flyView */, this /* parent */);
bool success =newItem->load(items[0].toObject(), 10, errorString);
if (!success) {
qDebug() << errorString;
......
......@@ -9,11 +9,12 @@
#pragma once
#include "UnitTest.h"
#include "VisualMissionItemTest.h"
#include "FixedWingLandingComplexItem.h"
#include "MultiSignalSpy.h"
#include "PlanMasterController.h"
class FWLandingPatternTest : public UnitTest
class FWLandingPatternTest : public VisualMissionItemTest
{
Q_OBJECT
......@@ -45,10 +46,9 @@ private:
static const size_t cSignals = maxSignalIndex;
const char* rgSignals[cSignals];
Vehicle* _offlineVehicle;
FixedWingLandingComplexItem* _fwItem;
MultiSignalSpy* _multiSpy;
SimpleMissionItem* _validStopVideoItem;
SimpleMissionItem* _validStopDistanceItem;
SimpleMissionItem* _validStopTimeItem;
FixedWingLandingComplexItem* _fwItem = nullptr;
MultiSignalSpy* _multiSpy = nullptr;
SimpleMissionItem* _validStopVideoItem = nullptr;
SimpleMissionItem* _validStopDistanceItem = nullptr;
SimpleMissionItem* _validStopTimeItem = nullptr;
};
......@@ -13,6 +13,7 @@
#include "QGCGeo.h"
#include "QGroundControlQmlGlobal.h"
#include "SimpleMissionItem.h"
#include "PlanMasterController.h"
#include <QPolygonF>
......@@ -45,8 +46,8 @@ const char* FixedWingLandingComplexItem::_jsonFallRateKey = "fal
const char* FixedWingLandingComplexItem::_jsonLandingAltitudeRelativeKey = "landAltitudeRelative";
const char* FixedWingLandingComplexItem::_jsonLoiterAltitudeRelativeKey = "loiterAltitudeRelative";
FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool flyView, QObject* parent)
: ComplexMissionItem (vehicle, flyView, parent)
FixedWingLandingComplexItem::FixedWingLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: ComplexMissionItem (masterController, flyView, parent)
, _sequenceNumber (0)
, _dirty (false)
, _landingCoordSet (false)
......@@ -105,7 +106,7 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool
connect(this, &FixedWingLandingComplexItem::landingCoordSetChanged, this, &FixedWingLandingComplexItem::readyForSaveStateChanged);
connect(this, &FixedWingLandingComplexItem::wizardModeChanged, this, &FixedWingLandingComplexItem::readyForSaveStateChanged);
if (vehicle->apmFirmware()) {
if (_masterController->controllerVehicle()->apmFirmware()) {
// ArduPilot does not support camera commands
_stopTakingVideoFact.setRawValue(false);
_stopTakingPhotosFact.setRawValue(false);
......@@ -364,7 +365,7 @@ void FixedWingLandingComplexItem::appendMissionItems(QList<MissionItem*>& items,
items.append(item);
}
bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, bool flyView, Vehicle* vehicle)
bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController)
{
qCDebug(FixedWingLandingComplexItemLog) << "FixedWingLandingComplexItem::scanForItem count" << visualItems->count();
......@@ -455,7 +456,7 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, b
// Now stuff all the scanned information into the item
FixedWingLandingComplexItem* complexItem = new FixedWingLandingComplexItem(vehicle, flyView, visualItems);
FixedWingLandingComplexItem* complexItem = new FixedWingLandingComplexItem(masterController, flyView, visualItems);
complexItem->_ignoreRecalcSignals = true;
......
......@@ -18,13 +18,14 @@
Q_DECLARE_LOGGING_CATEGORY(FixedWingLandingComplexItemLog)
class FWLandingPatternTest;
class PlanMasterController;
class FixedWingLandingComplexItem : public ComplexMissionItem
{
Q_OBJECT
public:
FixedWingLandingComplexItem(Vehicle* vehicle, bool flyView, QObject* parent);
FixedWingLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent);
Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT)
Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT)
......@@ -62,7 +63,7 @@ public:
void setLoiterDragAngleOnly (bool loiterDragAngleOnly);
/// Scans the loaded items for a landing pattern complex item
static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, Vehicle* vehicle);
static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController);
static MissionItem* createDoLandStartItem (int seqNum, QObject* parent);
static MissionItem* createLoiterToAltItem (int seqNum, bool altRel, double loiterRaidus, double lat, double lon, double alt, QObject* parent);
......
......@@ -42,13 +42,10 @@ const char* GeoFenceController::_px4ParamCircularFence = "GF_MAX_HOR_DIST";
GeoFenceController::GeoFenceController(PlanMasterController* masterController, QObject* parent)
: PlanElementController (masterController, parent)
, _geoFenceManager (_managerVehicle->geoFenceManager())
, _dirty (false)
, _managerVehicle (masterController->managerVehicle())
, _geoFenceManager (masterController->managerVehicle()->geoFenceManager())
, _breachReturnAltitudeFact (0, _breachReturnAltitudeFactName, FactMetaData::valueTypeDouble)
, _breachReturnDefaultAltitude (qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble())
, _itemsRequested (false)
, _px4ParamCircularFenceFact(nullptr)
{
if (_metaDataMap.isEmpty()) {
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/BreachReturn.FactMetaData.json"), nullptr /* metaDataParent */);
......@@ -60,8 +57,6 @@ GeoFenceController::GeoFenceController(PlanMasterController* masterController, Q
connect(&_polygons, &QmlObjectListModel::countChanged, this, &GeoFenceController::_updateContainsItems);
connect(&_circles, &QmlObjectListModel::countChanged, this, &GeoFenceController::_updateContainsItems);
managerVehicleChanged(_managerVehicle);
connect(this, &GeoFenceController::breachReturnPointChanged, this, &GeoFenceController::_setDirty);
connect(&_breachReturnAltitudeFact, &Fact::rawValueChanged, this, &GeoFenceController::_setDirty);
connect(&_polygons, &QmlObjectListModel::dirtyChanged, this, &GeoFenceController::_setDirty);
......@@ -77,6 +72,9 @@ void GeoFenceController::start(bool flyView)
{
qCDebug(GeoFenceControllerLog) << "start flyView" << flyView;
_managerVehicleChanged(_masterController->managerVehicle());
connect(_masterController, &PlanMasterController::managerVehicleChanged, this, &GeoFenceController::_managerVehicleChanged);
PlanElementController::start(flyView);
_init();
}
......@@ -95,7 +93,7 @@ void GeoFenceController::setBreachReturnPoint(const QGeoCoordinate& breachReturn
}
}
void GeoFenceController::managerVehicleChanged(Vehicle* managerVehicle)
void GeoFenceController::_managerVehicleChanged(Vehicle* managerVehicle)
{
if (_managerVehicle) {
_geoFenceManager->disconnect(this);
......
......@@ -75,7 +75,6 @@ public:
bool dirty (void) const final;
void setDirty (bool dirty) final;
bool containsItems (void) const final;
void managerVehicleChanged (Vehicle* managerVehicle) final;
bool showPlanFromManagerVehicle (void) final;
QmlObjectListModel* polygons (void) { return &_polygons; }
......@@ -101,19 +100,21 @@ private slots:
void _managerSendComplete (bool error);
void _managerRemoveAllComplete (bool error);
void _parametersReady (void);
void _managerVehicleChanged (Vehicle* managerVehicle);
private:
void _init(void);
GeoFenceManager* _geoFenceManager;
bool _dirty;
Vehicle* _managerVehicle = nullptr;
GeoFenceManager* _geoFenceManager = nullptr;
bool _dirty = false;
QmlObjectListModel _polygons;
QmlObjectListModel _circles;
QGeoCoordinate _breachReturnPoint;
Fact _breachReturnAltitudeFact;
double _breachReturnDefaultAltitude;
bool _itemsRequested;
Fact* _px4ParamCircularFenceFact;
double _breachReturnDefaultAltitude = qQNaN();
bool _itemsRequested = false;
Fact* _px4ParamCircularFenceFact = nullptr;
static QMap<QString, FactMetaData*> _metaDataMap;
......
This diff is collapsed.
......@@ -190,7 +190,6 @@ public:
bool dirty (void) const final;
void setDirty (bool dirty) final;
bool containsItems (void) const final;
void managerVehicleChanged (Vehicle* managerVehicle) final;
bool showPlanFromManagerVehicle (void) final;
// Create KML file
......@@ -286,6 +285,7 @@ private slots:
void _updateTimeout (void);
void _complexBoundingBoxChanged (void);
void _recalcAll (void);
void _managerVehicleChanged (Vehicle* managerVehicle);
private:
void _init(void);
......@@ -310,7 +310,7 @@ private:
bool _loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
bool _loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString);
int _nextSequenceNumber(void);
void _scanForAdditionalSettings(QmlObjectListModel* visualItems, Vehicle* vehicle);
void _scanForAdditionalSettings(QmlObjectListModel* visualItems, PlanMasterController* masterController);
static bool _convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent);
void _setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate);
void _resetMissionFlightStatus(void);
......@@ -323,35 +323,36 @@ private:
void _addTimeDistance(bool vtolInHover, double hoverTime, double cruiseTime, double extraTime, double distance, int seqNum);
VisualMissionItem* _insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem);
void _insertComplexMissionItemWorker(const QGeoCoordinate& mapCenterCoordinate, ComplexMissionItem* complexItem, int visualItemIndex, bool makeCurrentItem);
void _warnIfTerrainFrameUsed(void);
bool _isROIBeginItem(SimpleMissionItem* simpleItem);
bool _isROICancelItem(SimpleMissionItem* simpleItem);
CoordinateVector* _createCoordinateVectorWorker(VisualItemPair& pair);
private:
MissionManager* _missionManager;
int _missionItemCount;
QmlObjectListModel* _visualItems;
MissionSettingsItem* _settingsItem;
Vehicle* _controllerVehicle = nullptr;
Vehicle* _managerVehicle = nullptr;
MissionManager* _missionManager = nullptr;
int _missionItemCount = 0;
QmlObjectListModel* _visualItems = nullptr;
MissionSettingsItem* _settingsItem = nullptr;
QmlObjectListModel _waypointLines;
QVariantList _waypointPath;
QmlObjectListModel _directionArrows;
QmlObjectListModel _incompleteComplexItemLines;
CoordVectHashTable _linesTable;
bool _firstItemsFromVehicle;
bool _itemsRequested;
bool _inRecalcSequence;
bool _firstItemsFromVehicle = false;
bool _itemsRequested = false;
bool _inRecalcSequence = false;
MissionFlightStatus_t _missionFlightStatus;
AppSettings* _appSettings;
double _progressPct;
int _currentPlanViewSeqNum;
int _currentPlanViewVIIndex;
VisualMissionItem* _currentPlanViewItem;
AppSettings* _appSettings = nullptr;
double _progressPct = 0;
int _currentPlanViewSeqNum = -1;
int _currentPlanViewVIIndex = -1;
VisualMissionItem* _currentPlanViewItem = nullptr;
QTimer _updateTimer;
QGCGeoBoundingCube _travelBoundingCube;
QGeoCoordinate _takeoffCoordinate;
QGeoCoordinate _previousCoordinate;
CoordinateVector* _splitSegment;
CoordinateVector* _splitSegment = nullptr;
bool _isInsertTakeoffValid = true;
bool _isInsertLandValid = true;
bool _isROIActive = false;
......
......@@ -28,22 +28,19 @@ const size_t MissionItemTest::_cTestCases = sizeof(_rgTestCases)/sizeof(_rgTestC
#endif
MissionItemTest::MissionItemTest(void)
: _offlineVehicle(nullptr)
: _masterController(nullptr)
{
}
void MissionItemTest::init(void)
{
UnitTest::init();
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4,
MAV_TYPE_QUADROTOR,
qgcApp()->toolbox()->firmwarePluginManager(),
this);
_masterController = new PlanMasterController(this);
}
void MissionItemTest::cleanup(void)
{
_offlineVehicle->deleteLater();
_masterController->deleteLater();
UnitTest::cleanup();
}
......@@ -281,7 +278,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void)
{
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, nullptr);
SimpleMissionItem simpleMissionItem(_masterController, false /* flyView */, nullptr);
QString testString("10\t0\t3\t80\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n");
QTextStream testStream(&testString, QIODevice::ReadOnly);
......@@ -451,7 +448,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void)
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, nullptr);
SimpleMissionItem simpleMissionItem(_masterController, false /* flyView */, nullptr);
QString errorString;
QJsonArray coordinateArray;
QJsonObject jsonObject;
......
......@@ -7,14 +7,13 @@
*
****************************************************************************/
#ifndef MissionItemTest_H
#define MissionItemTest_H
#pragma once
#include "UnitTest.h"
#include "MultiSignalSpy.h"
#include "MissionItem.h"
#include "Vehicle.h"
#include "PlanMasterController.h"
/// Unit test for the MissionItem Object
class MissionItemTest : public UnitTest
......@@ -46,8 +45,6 @@ private:
QJsonObject _createV2Json(void);
QJsonObject _createV3Json(bool allNaNs = false);
int _seq = 10;
Vehicle* _offlineVehicle;
int _seq = 10;
PlanMasterController* _masterController = nullptr;
};
#endif
......@@ -16,6 +16,7 @@
#include "SettingsManager.h"
#include "AppSettings.h"
#include "MissionCommandUIInfo.h"
#include "PlanMasterController.h"
#include <QPolygonF>
......@@ -25,11 +26,12 @@ const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHome
QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject* parent)
: ComplexMissionItem (vehicle, flyView, parent)
MissionSettingsItem::MissionSettingsItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: ComplexMissionItem (masterController, flyView, parent)
, _managerVehicle (masterController->managerVehicle())
, _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble)
, _cameraSection (vehicle)
, _speedSection (vehicle)
, _cameraSection (masterController)
, _speedSection (masterController)
{
_isIncomplete = false;
_editorQml = "qrc:/qml/MissionSettingsEditor.qml";
......@@ -54,10 +56,10 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject
connect(&_cameraSection, &CameraSection::specifiedGimbalYawChanged, this, &MissionSettingsItem::specifiedGimbalYawChanged);
connect(&_cameraSection, &CameraSection::specifiedGimbalPitchChanged, this, &MissionSettingsItem::specifiedGimbalPitchChanged);
connect(&_speedSection, &SpeedSection::specifiedFlightSpeedChanged, this, &MissionSettingsItem::specifiedFlightSpeedChanged);
connect(_vehicle, &Vehicle::homePositionChanged, this, &MissionSettingsItem::_updateHomePosition);
connect(&_plannedHomePositionAltitudeFact, &Fact::rawValueChanged, this, &MissionSettingsItem::_updateAltitudeInCoordinate);
_updateHomePosition(_vehicle->homePosition());
connect(_managerVehicle, &Vehicle::homePositionChanged, this, &MissionSettingsItem::_updateHomePosition);
_updateHomePosition(_managerVehicle->homePosition());
}
int MissionSettingsItem::lastSequenceNumber(void) const
......
......@@ -19,12 +19,14 @@
Q_DECLARE_LOGGING_CATEGORY(MissionSettingsComplexItemLog)
class PlanMasterController;
class MissionSettingsItem : public ComplexMissionItem
{
Q_OBJECT
public:
MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject* parent);
MissionSettingsItem(PlanMasterController* masterController, bool flyView, QObject* parent);
Q_PROPERTY(Fact* plannedHomePositionAltitude READ plannedHomePositionAltitude CONSTANT)
Q_PROPERTY(QObject* cameraSection READ cameraSection CONSTANT)
......@@ -103,6 +105,7 @@ private slots:
void _updateHomePosition (const QGeoCoordinate& homePosition);
private:
Vehicle* _managerVehicle = nullptr;
QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitude
Fact _plannedHomePositionAltitudeFact;
int _sequenceNumber = 0;
......
......@@ -22,7 +22,7 @@ void MissionSettingsTest::init(void)
{
VisualMissionItemTest::init();
_settingsItem = new MissionSettingsItem(_offlineVehicle, false /* flyView */, this);
_settingsItem = new MissionSettingsItem(_masterController, false /* flyView */, this);
}
void MissionSettingsTest::cleanup(void)
......
......@@ -17,8 +17,6 @@
PlanElementController::PlanElementController(PlanMasterController* masterController, QObject* parent)
: QObject (parent)
, _masterController (masterController)
, _controllerVehicle(masterController->controllerVehicle())
, _managerVehicle (masterController->managerVehicle())
, _flyView (false)
{
......@@ -33,8 +31,3 @@ void PlanElementController::start(bool flyView)
{
_flyView = flyView;
}
void PlanElementController::managerVehicleChanged(Vehicle* managerVehicle)
{
_managerVehicle = managerVehicle;
}
......@@ -27,10 +27,13 @@ public:
PlanElementController(PlanMasterController* masterController, QObject* parent = nullptr);
~PlanElementController();
Q_PROPERTY(bool supported READ supported NOTIFY supportedChanged) ///< true: Element is supported by Vehicle
Q_PROPERTY(bool containsItems READ containsItems NOTIFY containsItemsChanged) ///< true: Elemement is non-empty
Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) ///< true: information is currently being saved/sent, false: no active save/send in progress
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: unsaved/sent changes are present, false: no changes since last save/send
Q_PROPERTY(PlanMasterController* masterController READ masterController CONSTANT)
Q_PROPERTY(bool supported READ supported NOTIFY supportedChanged) ///< true: Element is supported by Vehicle
Q_PROPERTY(bool containsItems READ containsItems NOTIFY containsItemsChanged) ///< true: Elemement is non-empty
Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) ///< true: information is currently being saved/sent, false: no active save/send in progress
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: unsaved/sent changes are present, false: no changes since last save/send
PlanMasterController* masterController(void) { return _masterController; }
/// Should be called immediately upon Component.onCompleted.
virtual void start(bool flyView);
......@@ -55,9 +58,6 @@ public:
/// Signals removeAllComplete when done
virtual void removeAllFromVehicle(void) = 0;
/// Called when a new manager vehicle has been set.
virtual void managerVehicleChanged(Vehicle* managerVehicle) = 0;
signals:
void supportedChanged (bool supported);
void containsItemsChanged (bool containsItems);
......@@ -68,8 +68,6 @@ signals:
protected:
PlanMasterController* _masterController;
Vehicle* _controllerVehicle; ///< Offline controller vehicle
Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none
bool _flyView;
};
......
......@@ -37,24 +37,36 @@ const char* PlanMasterController::kJsonGeoFenceObjectKey = "geoFence";
const char* PlanMasterController::kJsonRallyPointsObjectKey = "rallyPoints";
PlanMasterController::PlanMasterController(QObject* parent)
: QObject (parent)
, _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager())
, _controllerVehicle (new Vehicle(
static_cast<MAV_AUTOPILOT>(qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->rawValue().toInt()),
static_cast<MAV_TYPE>(qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingVehicleType()->rawValue().toInt()),
qgcApp()->toolbox()->firmwarePluginManager()))
, _managerVehicle (_controllerVehicle)
, _flyView (true)
, _offline (true)
, _missionController (this)
, _geoFenceController (this)
, _rallyPointController (this)
, _loadGeoFence (false)
, _loadRallyPoints (false)
, _sendGeoFence (false)
, _sendRallyPoints (false)
, _deleteWhenSendCompleted (false)
, _planCreators (nullptr)
: QObject (parent)
, _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager())
, _controllerVehicle (new Vehicle(
static_cast<MAV_AUTOPILOT>(qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->rawValue().toInt()),
static_cast<MAV_TYPE>(qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingVehicleType()->rawValue().toInt()),
qgcApp()->toolbox()->firmwarePluginManager(),
this))
, _managerVehicle (_controllerVehicle)
, _missionController (this)
, _geoFenceController (this)
, _rallyPointController (this)
{
_commonInit();
}
#ifdef QT_DEBUG
PlanMasterController::PlanMasterController(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject* parent)
: QObject (parent)
, _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager())
, _controllerVehicle (new Vehicle(firmwareType, vehicleType, qgcApp()->toolbox()->firmwarePluginManager()))
, _managerVehicle (_controllerVehicle)
, _missionController (this)
, _geoFenceController (this)
, _rallyPointController (this)
{
_commonInit();
}
#endif
void PlanMasterController::_commonInit(void)
{
connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged);
connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged);
......@@ -67,8 +79,16 @@ PlanMasterController::PlanMasterController(QObject* parent)
connect(&_missionController, &MissionController::syncInProgressChanged, this, &PlanMasterController::syncInProgressChanged);
connect(&_geoFenceController, &GeoFenceController::syncInProgressChanged, this, &PlanMasterController::syncInProgressChanged);
connect(&_rallyPointController, &RallyPointController::syncInProgressChanged, this, &PlanMasterController::syncInProgressChanged);
// Offline vehicle can change firmware/vehicle type
connect(_controllerVehicle, &Vehicle::capabilityBitsChanged, this, &PlanMasterController::_updateSupportsTerrain);
connect(_controllerVehicle, &Vehicle::vehicleTypeChanged, this, &PlanMasterController::_updateSupportsTerrain);
connect(_controllerVehicle, &Vehicle::vehicleTypeChanged, this, &PlanMasterController::_updatePlanCreatorsList);
_updateSupportsTerrain();
}
PlanMasterController::~PlanMasterController()
{
......@@ -81,8 +101,8 @@ void PlanMasterController::start(bool flyView)
_geoFenceController.start(_flyView);
_rallyPointController.start(_flyView);
connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanMasterController::_activeVehicleChanged);
_activeVehicleChanged(_multiVehicleMgr->activeVehicle());
connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanMasterController::_activeVehicleChanged);
_updatePlanCreatorsList();
......@@ -115,22 +135,17 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
qCDebug(PlanMasterControllerLog) << "_activeVehicleChanged" << activeVehicle;
if (_managerVehicle) {
// Disconnect old vehicle
disconnect(_managerVehicle->missionManager(), &MissionManager::newMissionItemsAvailable, this, &PlanMasterController::_loadMissionComplete);
disconnect(_managerVehicle->geoFenceManager(), &GeoFenceManager::loadComplete, this, &PlanMasterController::_loadGeoFenceComplete);
disconnect(_managerVehicle->rallyPointManager(), &RallyPointManager::loadComplete, this, &PlanMasterController::_loadRallyPointsComplete);
disconnect(_managerVehicle->missionManager(), &MissionManager::sendComplete, this, &PlanMasterController::_sendMissionComplete);
disconnect(_managerVehicle->geoFenceManager(), &GeoFenceManager::sendComplete, this, &PlanMasterController::_sendGeoFenceComplete);
disconnect(_managerVehicle->rallyPointManager(), &RallyPointManager::sendComplete, this, &PlanMasterController::_sendRallyPointsComplete);
disconnect(_managerVehicle, &Vehicle::vehicleTypeChanged, this, &PlanMasterController::_updatePlanCreatorsList);
// Disconnect old vehicle. Be careful of wildcarding disconnect too much since _managerVehicle may equal _controllerVehicle
disconnect(_managerVehicle->missionManager(), nullptr, nullptr, nullptr);
disconnect(_managerVehicle->geoFenceManager(), nullptr, nullptr, nullptr);
disconnect(_managerVehicle->rallyPointManager(), nullptr, nullptr, nullptr);
disconnect(_managerVehicle, &Vehicle::capabilityBitsChanged, this, &PlanMasterController::_updateSupportsTerrain);
}
bool newOffline = false;
if (activeVehicle == nullptr) {
// Since there is no longer an active vehicle we use the offline controller vehicle as the manager vehicle
_managerVehicle = _controllerVehicle;
// The vehicle type can change on the offline vehicle. Keep the creators list in sync with that.
connect(_managerVehicle, &Vehicle::vehicleTypeChanged, this, &PlanMasterController::_updatePlanCreatorsList);
newOffline = true;
} else {
newOffline = false;
......@@ -150,9 +165,10 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
connect(_managerVehicle->rallyPointManager(), &RallyPointManager::sendComplete, this, &PlanMasterController::_sendRallyPointsComplete);
}
_missionController.managerVehicleChanged(_managerVehicle);
_geoFenceController.managerVehicleChanged(_managerVehicle);
_rallyPointController.managerVehicleChanged(_managerVehicle);
// Change in capabilities will affect terrain support
connect(_managerVehicle, &Vehicle::capabilityBitsChanged, this, &PlanMasterController::_updateSupportsTerrain);
emit managerVehicleChanged(_managerVehicle);
// Vehicle changed so we need to signal everything
_offline = newOffline;
......@@ -160,6 +176,7 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
emit syncInProgressChanged();
emit dirtyChanged(dirty());
emit offlineChanged(offline());
_updateSupportsTerrain();
if (!_flyView) {
if (!offline()) {
......@@ -618,3 +635,12 @@ void PlanMasterController::_updatePlanCreatorsList(void)
}
}
}
void PlanMasterController::_updateSupportsTerrain(void)
{
bool supportsTerrain = _managerVehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_TERRAIN;
if (supportsTerrain != _supportsTerrain) {
_supportsTerrain = supportsTerrain;
emit supportsTerrainChanged(supportsTerrain);
}
}
......@@ -28,12 +28,18 @@ class PlanMasterController : public QObject
public:
PlanMasterController(QObject* parent = nullptr);
#ifdef QT_DEBUG
// Used by test code to create master controll with specific firmware/vehicle type
PlanMasterController(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject* parent = nullptr);
#endif
~PlanMasterController();
Q_PROPERTY(Vehicle* controllerVehicle READ controllerVehicle CONSTANT) ///< Offline controller vehicle
Q_PROPERTY(Vehicle* managerVehicle READ managerVehicle NOTIFY managerVehicleChanged) ///< Either active vehicle or _controllerVehicle if no active vehicle
Q_PROPERTY(MissionController* missionController READ missionController CONSTANT)
Q_PROPERTY(GeoFenceController* geoFenceController READ geoFenceController CONSTANT)
Q_PROPERTY(RallyPointController* rallyPointController READ rallyPointController CONSTANT)
Q_PROPERTY(Vehicle* controllerVehicle MEMBER _controllerVehicle CONSTANT)
Q_PROPERTY(bool offline READ offline NOTIFY offlineChanged) ///< true: controller is not connected to an active vehicle
Q_PROPERTY(bool containsItems READ containsItems NOTIFY containsItemsChanged) ///< true: Elemement is non-empty
Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) ///< true: Information is currently being saved/sent, false: no active save/send in progress
......@@ -44,6 +50,7 @@ public:
Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT) ///< File filter list loading plan files
Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT) ///< File filter list saving plan files
Q_PROPERTY(QmlObjectListModel* planCreators MEMBER _planCreators NOTIFY planCreatorsChanged)
Q_PROPERTY(bool supportsTerrain READ supportsTerrain NOTIFY supportsTerrainChanged)
/// Should be called immediately upon Component.onCompleted.
Q_INVOKABLE void start(bool flyView);
......@@ -86,6 +93,7 @@ public:
QStringList loadNameFilters (void) const;
QStringList saveNameFilters (void) const;
bool isEmpty (void) const;
bool supportsTerrain (void) const { return _supportsTerrain; }
QJsonDocument saveToJson ();
......@@ -105,6 +113,8 @@ signals:
void offlineChanged (bool offlineEditing);
void currentPlanFileChanged ();
void planCreatorsChanged (QmlObjectListModel* planCreators);
void managerVehicleChanged (Vehicle* managerVehicle);
void supportsTerrainChanged (bool supportsTerrain);
private slots:
void _activeVehicleChanged (Vehicle* activeVehicle);
......@@ -115,27 +125,29 @@ private slots:
void _sendGeoFenceComplete (void);
void _sendRallyPointsComplete (void);
void _updatePlanCreatorsList (void);
void _updateSupportsTerrain (void);
#if defined(QGC_AIRMAP_ENABLED)
void _startFlightPlanning (void);
#endif
private:
void _commonInit (void);
void _showPlanFromManagerVehicle(void);
MultiVehicleManager* _multiVehicleMgr;
Vehicle* _controllerVehicle; ///< Offline controller vehicle
Vehicle* _managerVehicle; ///< Either active vehicle or _controllerVehicle if none
bool _flyView;
bool _offline;
MultiVehicleManager* _multiVehicleMgr = nullptr;
Vehicle* _controllerVehicle = nullptr; ///< Offline controller vehicle
Vehicle* _managerVehicle = nullptr; ///< Either active vehicle or _controllerVehicle if none
bool _flyView = true;
bool _offline = true;
MissionController _missionController;
GeoFenceController _geoFenceController;
RallyPointController _rallyPointController;
bool _loadGeoFence;
bool _loadRallyPoints;
bool _sendGeoFence;
bool _sendRallyPoints;
bool _loadGeoFence = false;
bool _loadRallyPoints = false;
bool _sendGeoFence = false;
bool _sendRallyPoints = false;
QString _currentPlanFile;
bool _deleteWhenSendCompleted;
QmlObjectListModel* _planCreators;
bool _deleteWhenSendCompleted = false;
QmlObjectListModel* _planCreators = nullptr;
bool _supportsTerrain = false;
};
......@@ -34,15 +34,11 @@ const char* RallyPointController::_jsonFileTypeValue = "RallyPoints";
const char* RallyPointController::_jsonPointsKey = "points";
RallyPointController::RallyPointController(PlanMasterController* masterController, QObject* parent)
: PlanElementController(masterController, parent)
, _rallyPointManager(_managerVehicle->rallyPointManager())
, _dirty(false)
, _currentRallyPoint(nullptr)
, _itemsRequested(false)
: PlanElementController (masterController, parent)
, _managerVehicle (masterController->managerVehicle())
, _rallyPointManager (masterController->managerVehicle()->rallyPointManager())
{
connect(&_points, &QmlObjectListModel::countChanged, this, &RallyPointController::_updateContainsItems);
managerVehicleChanged(_managerVehicle);
}
RallyPointController::~RallyPointController()
......@@ -50,7 +46,17 @@ RallyPointController::~RallyPointController()
}
void RallyPointController::managerVehicleChanged(Vehicle* managerVehicle)
void RallyPointController::start(bool flyView)
{
qCDebug(GeoFenceControllerLog) << "start flyView" << flyView;
_managerVehicleChanged(_masterController->managerVehicle());
connect(_masterController, &PlanMasterController::managerVehicleChanged, this, &RallyPointController::_managerVehicleChanged);
PlanElementController::start(flyView);
}
void RallyPointController::_managerVehicleChanged(Vehicle* managerVehicle)
{
if (_managerVehicle) {
_rallyPointManager->disconnect(this);
......
......@@ -36,6 +36,7 @@ public:
Q_INVOKABLE void addPoint (QGeoCoordinate point);
Q_INVOKABLE void removePoint (QObject* rallyPoint);
void start (bool flyView) final;
bool supported (void) const final;
void save (QJsonObject& json) final;
bool load (const QJsonObject& json, QString& errorString) final;
......@@ -47,7 +48,6 @@ public:
bool dirty (void) const final { return _dirty; }
void setDirty (bool dirty) final;
bool containsItems (void) const final;
void managerVehicleChanged (Vehicle* managerVehicle) final;
bool showPlanFromManagerVehicle (void) final;
QmlObjectListModel* points (void) { return &_points; }
......@@ -62,23 +62,24 @@ signals:
void loadComplete(void);
private slots:
void _managerLoadComplete(void);
void _managerSendComplete(bool error);
void _managerRemoveAllComplete(bool error);
void _setFirstPointCurrent(void);
void _updateContainsItems(void);
void _managerLoadComplete (void);
void _managerSendComplete (bool error);
void _managerRemoveAllComplete (bool error);
void _setFirstPointCurrent (void);
void _updateContainsItems (void);
void _managerVehicleChanged (Vehicle* managerVehicle);
private:
RallyPointManager* _rallyPointManager;
bool _dirty;
Vehicle* _managerVehicle = nullptr;
RallyPointManager* _rallyPointManager = nullptr;
bool _dirty = false;
QmlObjectListModel _points;
QObject* _currentRallyPoint;
bool _itemsRequested;
QObject* _currentRallyPoint = nullptr;
bool _itemsRequested = false;
static const int _jsonCurrentVersion = 2;
static const char* _jsonFileTypeValue;
static const char* _jsonPointsKey;
static const int _jsonCurrentVersion = 2;
static const char* _jsonFileTypeValue;
static const char* _jsonPointsKey;
};
#endif
......@@ -15,15 +15,17 @@
Q_DECLARE_LOGGING_CATEGORY(SectionLog)
class PlanMasterController;
// A Section encapsulates a set of mission commands which can be associated with another simple mission item.
class Section : public QObject
{
Q_OBJECT
public:
Section(Vehicle* vehicle, QObject* parent = nullptr)
: QObject(parent)
, _vehicle(vehicle)
Section(PlanMasterController* masterController, QObject* parent = nullptr)
: QObject (parent)
, _masterController (masterController)
{
}
......@@ -62,5 +64,5 @@ signals:
void itemCountChanged (int itemCount);
protected:
Vehicle* _vehicle;
PlanMasterController* _masterController = nullptr;
};
......@@ -37,7 +37,7 @@ void SectionTest::init(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
_simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this);
_simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, missionItem, this);
}
void SectionTest::cleanup(void)
......@@ -62,13 +62,13 @@ void SectionTest::_commonScanTest(Section* section)
QmlObjectListModel waypointVisualItems;
MissionItem waypointItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleItem(_offlineVehicle, false /* flyView */, waypointItem, this);
SimpleMissionItem simpleItem(_masterController, false /* flyView */, waypointItem, this);
waypointVisualItems.append(&simpleItem);
waypointVisualItems.append(&simpleItem);
waypointVisualItems.append(&simpleItem);
QmlObjectListModel complexVisualItems;
SurveyComplexItem surveyItem(_offlineVehicle, false /* fly View */, QString() /* kmlFile */, this /* parent */);
SurveyComplexItem surveyItem(_masterController, false /* fly View */, QString() /* kmlFile */, this /* parent */);
complexVisualItems.append(&surveyItem);
// This tests the common cases which should not lead to scan succeess
......
This diff is collapsed.
......@@ -24,8 +24,8 @@ class SimpleMissionItem : public VisualMissionItem
Q_OBJECT
public:
SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent);
SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent);
SimpleMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent);
SimpleMissionItem(PlanMasterController* masterController, bool flyView, const MissionItem& missionItem, QObject* parent);
//SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent);
~SimpleMissionItem();
......@@ -38,7 +38,6 @@ public:
Q_PROPERTY(QGroundControlQmlGlobal::AltitudeMode altitudeMode READ altitudeMode WRITE setAltitudeMode NOTIFY altitudeModeChanged)
Q_PROPERTY(Fact* amslAltAboveTerrain READ amslAltAboveTerrain CONSTANT) ///< Actual AMSL altitude for item if altitudeMode == AltitudeAboveTerrain
Q_PROPERTY(int command READ command WRITE setCommand NOTIFY commandChanged)
Q_PROPERTY(bool supportsTerrainFrame READ supportsTerrainFrame NOTIFY supportsTerrainFrameChanged)
/// Optional sections
Q_PROPERTY(QObject* speedSection READ speedSection NOTIFY speedSectionChanged)
......@@ -59,7 +58,7 @@ public:
/// @param scanIndex Index to start scanning from
/// @param vehicle Vehicle associated with this mission
/// @return true: section found, scanIndex updated
bool scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle);
bool scanForSections(QmlObjectListModel* visualItems, int scanIndex, PlanMasterController* masterController);
// Property accesors
......@@ -72,7 +71,6 @@ public:
QGroundControlQmlGlobal::AltitudeMode altitudeMode(void) const { return _altitudeMode; }
Fact* altitude (void) { return &_altitudeFact; }
Fact* amslAltAboveTerrain (void) { return &_amslAltAboveTerrainFact; }
bool supportsTerrainFrame(void) const { return _vehicle->supportsTerrainFrame(); }
CameraSection* cameraSection (void) { return _cameraSection; }
SpeedSection* speedSection (void) { return _speedSection; }
......@@ -140,7 +138,6 @@ signals:
void cameraSectionChanged (QObject* cameraSection);
void speedSectionChanged (QObject* cameraSection);
void altitudeModeChanged (void);
void supportsTerrainFrameChanged(void);
private slots:
void _setDirty (void);
......@@ -166,19 +163,19 @@ private:
void _rebuildComboBoxFacts (void);
MissionItem _missionItem;
bool _rawEdit;
bool _dirty;
bool _ignoreDirtyChangeSignals;
bool _rawEdit = false;
bool _dirty = false;
bool _ignoreDirtyChangeSignals = false;
QGeoCoordinate _mapCenterHint;
SpeedSection* _speedSection = nullptr;
CameraSection* _cameraSection = nullptr;
SpeedSection* _speedSection;
CameraSection* _cameraSection;
MissionCommandTree* _commandTree;
MissionCommandTree* _commandTree = nullptr;
bool _syncingHeadingDegreesAndParam4 = false; ///< true: already in a sync signal, prevents signal loop
Fact _supportedCommandFact;
QGroundControlQmlGlobal::AltitudeMode _altitudeMode;
QGroundControlQmlGlobal::AltitudeMode _altitudeMode = QGroundControlQmlGlobal::AltitudeModeRelative;
Fact _altitudeFact;
Fact _amslAltAboveTerrainFact;
......@@ -201,8 +198,6 @@ private:
FactMetaData _param6MetaData;
FactMetaData _param7MetaData;
bool _syncingHeadingDegreesAndParam4; ///< true: already in a sync signal, prevents signal loop
static const char* _jsonAltitudeModeKey;
static const char* _jsonAltitudeKey;
static const char* _jsonAMSLAltAboveTerrainKey;
......
......@@ -12,6 +12,7 @@
#include "QGCApplication.h"
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
#include "PlanMasterController.h"
const SimpleMissionItemTest::ItemInfo_t SimpleMissionItemTest::_rgItemInfo[] = {
{ MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT },
......@@ -92,7 +93,7 @@ void SimpleMissionItemTest::init(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
_simpleItem = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this);
_simpleItem = new SimpleMissionItem(_masterController, false /* flyView */, missionItem, this);
// It's important top check that the right signals are emitted at the right time since that drives ui change.
// It's also important to check that things are not being over-signalled when they should not be, since that can lead
......@@ -111,7 +112,7 @@ void SimpleMissionItemTest::cleanup(void)
void SimpleMissionItemTest::_testEditorFacts(void)
{
Vehicle* vehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_FIXED_WING, qgcApp()->toolbox()->firmwarePluginManager());
PlanMasterController fwMasterController(MAV_AUTOPILOT_PX4, MAV_TYPE_FIXED_WING);
for (size_t i=0; i<sizeof(_rgItemInfo)/sizeof(_rgItemInfo[0]); i++) {
const ItemInfo_t* info = &_rgItemInfo[i];
......@@ -131,7 +132,7 @@ void SimpleMissionItemTest::_testEditorFacts(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
SimpleMissionItem simpleMissionItem(vehicle, false /* flyView */, missionItem, nullptr);
SimpleMissionItem simpleMissionItem(&fwMasterController, false /* flyView */, missionItem, nullptr);
// Validate that the fact values are correctly returned
......@@ -161,13 +162,11 @@ void SimpleMissionItemTest::_testEditorFacts(void)
QCOMPARE(simpleMissionItem.altitude()->rawValue().toDouble(), expected->altValue);
}
}
delete vehicle;
}
void SimpleMissionItemTest::_testDefaultValues(void)
{
SimpleMissionItem item(_offlineVehicle, false /* flyView */, nullptr);
SimpleMissionItem item(_masterController, false /* flyView */, nullptr);
item.missionItem().setCommand(MAV_CMD_NAV_WAYPOINT);
item.missionItem().setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
......
......@@ -11,13 +11,14 @@
#include "JsonHelper.h"
#include "FirmwarePlugin.h"
#include "SimpleMissionItem.h"
#include "PlanMasterController.h"
const char* SpeedSection::_flightSpeedName = "FlightSpeed";
QMap<QString, FactMetaData*> SpeedSection::_metaDataMap;
SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent)
: Section (vehicle, parent)
SpeedSection::SpeedSection(PlanMasterController* masterController, QObject* parent)
: Section (masterController, parent)
, _available (false)
, _dirty (false)
, _specifyFlightSpeed (false)
......@@ -28,10 +29,10 @@ SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent)
}
double flightSpeed = 0;
if (_vehicle->multiRotor()) {
flightSpeed = _vehicle->defaultHoverSpeed();
if (_masterController->controllerVehicle()->multiRotor()) {
flightSpeed = _masterController->controllerVehicle()->defaultHoverSpeed();
} else {
flightSpeed = _vehicle->defaultCruiseSpeed();
flightSpeed = _masterController->controllerVehicle()->defaultCruiseSpeed();
}
_metaDataMap[_flightSpeedName]->setRawDefaultValue(flightSpeed);
......@@ -53,7 +54,7 @@ bool SpeedSection::settingsSpecified(void) const
void SpeedSection::setAvailable(bool available)
{
if (available != _available) {
if (available && (_vehicle->multiRotor() || _vehicle->fixedWing())) {
if (available && (_masterController->controllerVehicle()->multiRotor() || _masterController->controllerVehicle()->fixedWing())) {
_available = available;
emit availableChanged(available);
}
......@@ -91,7 +92,7 @@ void SpeedSection::appendSectionItems(QList<MissionItem*>& items, QObject* missi
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_DO_CHANGE_SPEED,
MAV_FRAME_MISSION,
_vehicle->multiRotor() ? 1 /* groundspeed */ : 0 /* airspeed */, // Change airspeed or groundspeed
_masterController->controllerVehicle()->multiRotor() ? 1 /* groundspeed */ : 0 /* airspeed */, // Change airspeed or groundspeed
_flightSpeedFact.rawValue().toDouble(),
-1, // No throttle change
0, // Absolute speed change
......@@ -119,9 +120,9 @@ bool SpeedSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex
// See SpeedSection::appendMissionItems for specs on what consitutes a known speed setting
if (missionItem.command() == MAV_CMD_DO_CHANGE_SPEED && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
if (_vehicle->multiRotor() && missionItem.param1() != 1) {
if (_masterController->controllerVehicle()->multiRotor() && missionItem.param1() != 1) {
return false;
} else if (_vehicle->fixedWing() && missionItem.param1() != 0) {
} else if (_masterController->controllerVehicle()->fixedWing() && missionItem.param1() != 0) {
return false;
}
visualItems->removeAt(scanIndex)->deleteLater();
......
......@@ -13,12 +13,14 @@
#include "FactSystem.h"
#include "QmlObjectListModel.h"
class PlanMasterController;
class SpeedSection : public Section
{
Q_OBJECT
public:
SpeedSection(Vehicle* vehicle, QObject* parent = nullptr);
SpeedSection(PlanMasterController* masterController, QObject* parent = nullptr);
Q_PROPERTY(bool specifyFlightSpeed READ specifyFlightSpeed WRITE setSpecifyFlightSpeed NOTIFY specifyFlightSpeedChanged)
Q_PROPERTY(Fact* flightSpeed READ flightSpeed CONSTANT)
......
......@@ -8,6 +8,7 @@
****************************************************************************/
#include "SpeedSectionTest.h"
#include "PlanMasterController.h"
SpeedSectionTest::SpeedSectionTest(void)
: _spySpeed(nullptr)
......@@ -134,7 +135,7 @@ void SpeedSectionTest::_checkAvailable(void)
70.1234567,
true, // autoContinue
false); // isCurrentItem
SimpleMissionItem* item = new SimpleMissionItem(_offlineVehicle, false /* flyView */, missionItem, this);
SimpleMissionItem* item = new SimpleMissionItem(_masterController, false /* flyView */, missionItem, this);
QVERIFY(item->speedSection());
QCOMPARE(item->speedSection()->available(), false);
}
......@@ -176,7 +177,7 @@ void SpeedSectionTest::_testAppendSectionItems(void)
_speedSection->appendSectionItems(rgMissionItems, this, seqNum);
QCOMPARE(rgMissionItems.count(), 1);
QCOMPARE(seqNum, 1);
MissionItem expectedSpeedItem(0, MAV_CMD_DO_CHANGE_SPEED, MAV_FRAME_MISSION, _offlineVehicle->multiRotor() ? 1 : 0, _speedSection->flightSpeed()->rawValue().toDouble(), -1, 0, 0, 0, 0, true, false);
MissionItem expectedSpeedItem(0, MAV_CMD_DO_CHANGE_SPEED, MAV_FRAME_MISSION, _controllerVehicle->multiRotor() ? 1 : 0, _speedSection->flightSpeed()->rawValue().toDouble(), -1, 0, 0, 0, 0, true, false);
_missionItemsEqual(*rgMissionItems[0], expectedSpeedItem);
}
......@@ -192,8 +193,8 @@ void SpeedSectionTest::_testScanForSection(void)
// Check for a scan success
double flightSpeed = 10.123456;
MissionItem validSpeedItem(0, MAV_CMD_DO_CHANGE_SPEED, MAV_FRAME_MISSION, _offlineVehicle->multiRotor() ? 1 : 0, flightSpeed, -1, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleItem(_offlineVehicle, false /* flyView */, validSpeedItem, nullptr);
MissionItem validSpeedItem(0, MAV_CMD_DO_CHANGE_SPEED, MAV_FRAME_MISSION, _controllerVehicle->multiRotor() ? 1 : 0, flightSpeed, -1, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleItem(_masterController, false /* flyView */, validSpeedItem, nullptr);
MissionItem& simpleMissionItem = simpleItem.missionItem();
visualItems.append(&simpleItem);
scanIndex = 0;
......@@ -209,7 +210,7 @@ void SpeedSectionTest::_testScanForSection(void)
// Flight speed command but incorrect settings
simpleMissionItem = validSpeedItem;
simpleMissionItem.setParam1(_offlineVehicle->multiRotor() ? 0 : 1);
simpleMissionItem.setParam1(_controllerVehicle->multiRotor() ? 0 : 1);
visualItems.append(&simpleItem);
QCOMPARE(_speedSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
......@@ -264,7 +265,7 @@ void SpeedSectionTest::_testScanForSection(void)
// Valid item in wrong position
MissionItem waypointMissionItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleWaypointItem(_offlineVehicle, false /* flyView */, waypointMissionItem, nullptr);
SimpleMissionItem simpleWaypointItem(_masterController, false /* flyView */, waypointMissionItem, nullptr);
simpleMissionItem = validSpeedItem;
visualItems.append(&simpleWaypointItem);
visualItems.append(&simpleMissionItem);
......
......@@ -16,6 +16,7 @@
#include "SettingsManager.h"
#include "AppSettings.h"
#include "QGCQGeoCoordinate.h"
#include "PlanMasterController.h"
#include <QPolygonF>
......@@ -32,15 +33,15 @@ const char* StructureScanComplexItem::startFromTopName = "StartFromTo
const char* StructureScanComplexItem::jsonComplexItemTypeValue = "StructureScan";
const char* StructureScanComplexItem::_jsonCameraCalcKey = "CameraCalc";
StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyView, const QString& kmlOrShpFile, QObject* parent)
: ComplexMissionItem (vehicle, flyView, parent)
StructureScanComplexItem::StructureScanComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrShpFile, QObject* parent)
: ComplexMissionItem (masterController, flyView, parent)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/StructureScan.SettingsGroup.json"), this /* QObject parent */))
, _sequenceNumber (0)
, _entryVertex (0)
, _ignoreRecalc (false)
, _scanDistance (0.0)
, _cameraShots (0)
, _cameraCalc (vehicle, settingsGroup)
, _cameraCalc (masterController, settingsGroup)
, _scanBottomAltFact (settingsGroup, _metaDataMap[scanBottomAltName])
, _structureHeightFact (settingsGroup, _metaDataMap[structureHeightName])
, _layersFact (settingsGroup, _metaDataMap[layersName])
......
......@@ -20,15 +20,16 @@
Q_DECLARE_LOGGING_CATEGORY(StructureScanComplexItemLog)
class PlanMasterController;
class StructureScanComplexItem : public ComplexMissionItem
{
Q_OBJECT
public:
/// @param vehicle Vehicle which this is being contructed for
/// @param flyView true: Created for use in the Fly View, false: Created for use in the Plan View
/// @param kmlOrSHPFile Polygon comes from this file, empty for default polygon
StructureScanComplexItem(Vehicle* vehicle, bool flyView, const QString& kmlOrSHPFile, QObject* parent);
StructureScanComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrSHPFile, QObject* parent);
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
Q_PROPERTY(Fact* entranceAlt READ entranceAlt CONSTANT)
......
......@@ -9,9 +9,9 @@
#include "StructureScanComplexItemTest.h"
#include "QGCApplication.h"
#include "PlanMasterController.h"
StructureScanComplexItemTest::StructureScanComplexItemTest(void)
: _offlineVehicle(nullptr)
{
_polyPoints << QGeoCoordinate(47.633550640000003, -122.08982199) << QGeoCoordinate(47.634129020000003, -122.08887249) <<
QGeoCoordinate(47.633619320000001, -122.08811074) << QGeoCoordinate(47.633189139999999, -122.08900124);
......@@ -23,8 +23,9 @@ void StructureScanComplexItemTest::init(void)
_rgSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_structureScanItem = new StructureScanComplexItem(_offlineVehicle, false /* flyView */, QString() /* kmlFile */, this /* parent */);
_masterController = new PlanMasterController(this);
_controllerVehicle = _masterController->controllerVehicle();
_structureScanItem = new StructureScanComplexItem(new PlanMasterController(this), false /* flyView */, QString() /* kmlFile */, this /* parent */);
_structureScanItem->setDirty(false);
_multiSpy = new MultiSignalSpy();
......@@ -35,7 +36,6 @@ void StructureScanComplexItemTest::init(void)
void StructureScanComplexItemTest::cleanup(void)
{
delete _structureScanItem;
delete _offlineVehicle;
}
void StructureScanComplexItemTest::_testDirty(void)
......@@ -114,7 +114,7 @@ void StructureScanComplexItemTest::_testSaveLoad(void)
_structureScanItem->save(items);
QString errorString;
StructureScanComplexItem* newItem = new StructureScanComplexItem(_offlineVehicle, false /* flyView */, QString() /* kmlFile */, this /* parent */);
StructureScanComplexItem* newItem = new StructureScanComplexItem(new PlanMasterController(this), false /* flyView */, QString() /* kmlFile */, this /* parent */);
QVERIFY(newItem->load(items[0].toObject(), 10, errorString));
QVERIFY(errorString.isEmpty());
_validateItem(newItem);
......
......@@ -12,6 +12,7 @@
#include "UnitTest.h"
#include "MultiSignalSpy.h"
#include "StructureScanComplexItem.h"
#include "PlanMasterController.h"
class StructureScanComplexItemTest : public UnitTest
{
......@@ -45,8 +46,9 @@ private:
static const size_t _cSignals = maxSignalIndex;
const char* _rgSignals[_cSignals];
Vehicle* _offlineVehicle;
MultiSignalSpy* _multiSpy;
StructureScanComplexItem* _structureScanItem;
PlanMasterController* _masterController = nullptr;
Vehicle* _controllerVehicle = nullptr;
MultiSignalSpy* _multiSpy = nullptr;
StructureScanComplexItem* _structureScanItem = nullptr;
QList<QGeoCoordinate> _polyPoints;
};
......@@ -16,6 +16,7 @@
#include "QGCQGeoCoordinate.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include "PlanMasterController.h"
#include <QPolygonF>
......@@ -61,8 +62,8 @@ const char* SurveyComplexItem::_jsonV3Refly90DegreesKey = "refly90
const char* SurveyComplexItem::_jsonFlyAlternateTransectsKey = "flyAlternateTransects";
const char* SurveyComplexItem::_jsonSplitConcavePolygonsKey = "splitConcavePolygons";
SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, bool flyView, const QString& kmlOrShpFile, QObject* parent)
: TransectStyleComplexItem (vehicle, flyView, settingsGroup, parent)
SurveyComplexItem::SurveyComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrShpFile, QObject* parent)
: TransectStyleComplexItem (masterController, flyView, settingsGroup, parent)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this))
, _gridAngleFact (settingsGroup, _metaDataMap[gridAngleName])
, _flyAlternateTransectsFact(settingsGroup, _metaDataMap[flyAlternateTransectsName])
......@@ -73,7 +74,7 @@ SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, bool flyView, const QStri
// If the user hasn't changed turnaround from the default (which is a fixed wing default) and we are multi-rotor set the multi-rotor default.
// NULL check since object creation during unit testing passes NULL for vehicle
if (_vehicle && _vehicle->multiRotor() && _turnAroundDistanceFact.rawValue().toDouble() == _turnAroundDistanceFact.rawDefaultValue().toDouble()) {
if (_controllerVehicle && _controllerVehicle->multiRotor() && _turnAroundDistanceFact.rawValue().toDouble() == _turnAroundDistanceFact.rawDefaultValue().toDouble()) {
// Note this is set to 10 meters to work around a problem with PX4 Pro turnaround behavior. Don't change unless firmware gets better as well.
_turnAroundDistanceFact.setRawValue(10);
}
......
......@@ -16,15 +16,16 @@
Q_DECLARE_LOGGING_CATEGORY(SurveyComplexItemLog)
class PlanMasterController;
class SurveyComplexItem : public TransectStyleComplexItem
{
Q_OBJECT
public:
/// @param vehicle Vehicle which this is being contructed for
/// @param flyView true: Created for use in the Fly View, false: Created for use in the Plan View
/// @param kmlOrShpFile Polygon comes from this file, empty for default polygon
SurveyComplexItem(Vehicle* vehicle, bool flyView, const QString& kmlOrShpFile, QObject* parent);
SurveyComplexItem(PlanMasterController* masterController, bool flyView, const QString& kmlOrShpFile, QObject* parent);
Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT)
Q_PROPERTY(Fact* flyAlternateTransects READ flyAlternateTransects CONSTANT)
......
......@@ -11,7 +11,6 @@
#include "QGCApplication.h"
SurveyComplexItemTest::SurveyComplexItemTest(void)
: _offlineVehicle(nullptr)
{
_polyPoints << QGeoCoordinate(47.633550640000003, -122.08982199) << QGeoCoordinate(47.634129020000003, -122.08887249) <<
QGeoCoordinate(47.633619320000001, -122.08811074) << QGeoCoordinate(47.633189139999999, -122.08900124);
......@@ -28,8 +27,9 @@ void SurveyComplexItemTest::init(void)
_rgSurveySignals[surveyRefly90DegreesChangedIndex] = SIGNAL(refly90DegreesChanged(bool));
_rgSurveySignals[surveyDirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_surveyItem = new SurveyComplexItem(_offlineVehicle, false /* flyView */, QString() /* kmlFile */, this /* parent */);
_masterController = new PlanMasterController(this);
_controllerVehicle = _masterController->controllerVehicle();
_surveyItem = new SurveyComplexItem(_masterController, false /* flyView */, QString() /* kmlFile */, this /* parent */);
_surveyItem->turnAroundDistance()->setRawValue(0); // Unit test written for no turnaround distance
_surveyItem->setDirty(false);
_mapPolygon = _surveyItem->surveyAreaPolygon();
......@@ -46,7 +46,6 @@ void SurveyComplexItemTest::init(void)
void SurveyComplexItemTest::cleanup(void)
{
delete _surveyItem;
delete _offlineVehicle;
delete _multiSpy;
}
......
......@@ -13,6 +13,7 @@
#include "TCPLink.h"
#include "MultiSignalSpy.h"
#include "SurveyComplexItem.h"
#include "PlanMasterController.h"
#include <QGeoCoordinate>
......@@ -63,9 +64,10 @@ private:
static const size_t _cSurveySignals = surveyMaxSignalIndex;
const char* _rgSurveySignals[_cSurveySignals];
Vehicle* _offlineVehicle;
MultiSignalSpy* _multiSpy;
SurveyComplexItem* _surveyItem;
QGCMapPolygon* _mapPolygon;
PlanMasterController* _masterController = nullptr;
Vehicle* _controllerVehicle = nullptr;
MultiSignalSpy* _multiSpy = nullptr;
SurveyComplexItem* _surveyItem = nullptr;
QGCMapPolygon* _mapPolygon = nullptr;
QList<QGeoCoordinate> _polyPoints;
};
......@@ -18,24 +18,25 @@
#include "MissionCommandUIInfo.h"
#include "QGroundControlQmlGlobal.h"
#include "SettingsManager.h"
#include "PlanMasterController.h"
TakeoffMissionItem::TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
: SimpleMissionItem (vehicle, flyView, parent)
TakeoffMissionItem::TakeoffMissionItem(PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
: SimpleMissionItem (masterController, flyView, parent)
, _settingsItem (settingsItem)
{
_init();
}
TakeoffMissionItem::TakeoffMissionItem(MAV_CMD takeoffCmd, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
: SimpleMissionItem (vehicle, flyView, parent)
TakeoffMissionItem::TakeoffMissionItem(MAV_CMD takeoffCmd, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
: SimpleMissionItem (masterController, flyView, parent)
, _settingsItem (settingsItem)
{
setCommand(takeoffCmd);
_init();
}
TakeoffMissionItem::TakeoffMissionItem(const MissionItem& missionItem, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
: SimpleMissionItem (vehicle, flyView, missionItem, parent)
TakeoffMissionItem::TakeoffMissionItem(const MissionItem& missionItem, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
: SimpleMissionItem (masterController, flyView, missionItem, parent)
, _settingsItem (settingsItem)
{
_init();
......@@ -115,7 +116,7 @@ bool TakeoffMissionItem::isTakeoffCommand(MAV_CMD command)
void TakeoffMissionItem::_initLaunchTakeoffAtSameLocation(void)
{
if (specifiesCoordinate()) {
if (_vehicle->fixedWing() || _vehicle->vtol()) {
if (_controllerVehicle->fixedWing() || _controllerVehicle->vtol()) {
setLaunchTakeoffAtSameLocation(false);
} else {
// PX4 specifies a coordinate for takeoff even for non fixed wing. But it makes more sense to not have a coordinate
......
......@@ -12,6 +12,8 @@
#include "SimpleMissionItem.h"
#include "MissionSettingsItem.h"
class PlanMasterController;
/// Takeoff mission item is a special case of a SimpleMissionItem which supports Launch Location display/editing
/// which is tied to home position.
class TakeoffMissionItem : public SimpleMissionItem
......@@ -19,9 +21,9 @@ class TakeoffMissionItem : public SimpleMissionItem
Q_OBJECT
public:
TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
TakeoffMissionItem(MAV_CMD takeoffCmd, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
TakeoffMissionItem(const MissionItem& missionItem, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
TakeoffMissionItem(PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
TakeoffMissionItem(MAV_CMD takeoffCmd, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
TakeoffMissionItem(const MissionItem& missionItem, PlanMasterController* masterController, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
Q_PROPERTY(QGeoCoordinate launchCoordinate READ launchCoordinate WRITE setLaunchCoordinate NOTIFY launchCoordinateChanged)
Q_PROPERTY(bool launchTakeoffAtSameLocation READ launchTakeoffAtSameLocation WRITE setLaunchTakeoffAtSameLocation NOTIFY launchTakeoffAtSameLocationChanged)
......
......@@ -39,18 +39,18 @@ const char* TransectStyleComplexItem::_jsonCameraShotsKey = "Cam
const int TransectStyleComplexItem::_terrainQueryTimeoutMsecs = 1000;
TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, bool flyView, QString settingsGroup, QObject* parent)
: ComplexMissionItem (vehicle, flyView, parent)
TransectStyleComplexItem::TransectStyleComplexItem(PlanMasterController* masterController, bool flyView, QString settingsGroup, QObject* parent)
: ComplexMissionItem (masterController, flyView, parent)
, _sequenceNumber (0)
, _terrainPolyPathQuery (nullptr)
, _ignoreRecalc (false)
, _complexDistance (0)
, _cameraShots (0)
, _cameraCalc (vehicle, settingsGroup)
, _cameraCalc (masterController, settingsGroup)
, _followTerrain (false)
, _loadedMissionItemsParent (nullptr)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/TransectStyle.SettingsGroup.json"), this))
, _turnAroundDistanceFact (settingsGroup, _metaDataMap[_vehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName])
, _turnAroundDistanceFact (settingsGroup, _metaDataMap[_controllerVehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName])
, _cameraTriggerInTurnAroundFact (settingsGroup, _metaDataMap[cameraTriggerInTurnAroundName])
, _hoverAndCaptureFact (settingsGroup, _metaDataMap[hoverAndCaptureName])
, _refly90DegreesFact (settingsGroup, _metaDataMap[refly90DegreesName])
......@@ -347,7 +347,7 @@ double TransectStyleComplexItem::_turnaroundDistance(void) const
bool TransectStyleComplexItem::hoverAndCaptureAllowed(void) const
{
return _vehicle->multiRotor() || _vehicle->vtol();
return _controllerVehicle->multiRotor() || _controllerVehicle->vtol();
}
void TransectStyleComplexItem::_rebuildTransects(void)
......
......@@ -20,12 +20,14 @@
Q_DECLARE_LOGGING_CATEGORY(TransectStyleComplexItemLog)
class PlanMasterController;
class TransectStyleComplexItem : public ComplexMissionItem
{
Q_OBJECT
public:
TransectStyleComplexItem(Vehicle* vehicle, bool flyView, QString settignsGroup, QObject* parent);
TransectStyleComplexItem(PlanMasterController* masterController, bool flyView, QString settignsGroup, QObject* parent);
Q_PROPERTY(QGCMapPolygon* surveyAreaPolygon READ surveyAreaPolygon CONSTANT)
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
......
......@@ -11,7 +11,6 @@
#include "QGCApplication.h"
TransectStyleComplexItemTest::TransectStyleComplexItemTest(void)
: _offlineVehicle(nullptr)
{
_polygonVertices << QGeoCoordinate(47.633550640000003, -122.08982199)
<< QGeoCoordinate(47.634129020000003, -122.08887249)
......@@ -23,8 +22,9 @@ void TransectStyleComplexItemTest::init(void)
{
UnitTest::init();
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_transectStyleItem = new TransectStyleItem(_offlineVehicle, this);
_masterController = new PlanMasterController(this);
_controllerVehicle = _masterController->controllerVehicle();
_transectStyleItem = new TransectStyleItem(_masterController, this);
_transectStyleItem->cameraTriggerInTurnAround()->setRawValue(false);
_transectStyleItem->cameraCalc()->cameraName()->setRawValue(_transectStyleItem->cameraCalc()->customCameraName());
_transectStyleItem->cameraCalc()->valueSetIsDistance()->setRawValue(true);
......@@ -49,7 +49,6 @@ void TransectStyleComplexItemTest::init(void)
void TransectStyleComplexItemTest::cleanup(void)
{
delete _transectStyleItem;
delete _offlineVehicle;
delete _multiSpy;
}
......@@ -224,8 +223,8 @@ void TransectStyleComplexItemTest::_testAltMode(void)
QVERIFY(!_transectStyleItem->followTerrain());
}
TransectStyleItem::TransectStyleItem(Vehicle* vehicle, QObject* parent)
: TransectStyleComplexItem (vehicle, false /* flyView */, QStringLiteral("UnitTestTransect"), parent)
TransectStyleItem::TransectStyleItem(PlanMasterController* masterController, QObject* parent)
: TransectStyleComplexItem (masterController, false /* flyView */, QStringLiteral("UnitTestTransect"), parent)
, rebuildTransectsPhase1Called (false)
, recalcComplexDistanceCalled (false)
, recalcCameraShotsCalled (false)
......
......@@ -12,6 +12,7 @@
#include "UnitTest.h"
#include "MultiSignalSpy.h"
#include "CorridorScanComplexItem.h"
#include "PlanMasterController.h"
#include <QGeoCoordinate>
......@@ -72,10 +73,11 @@ private:
static const size_t _cSignals = maxSignalIndex;
const char* _rgSignals[_cSignals];
Vehicle* _offlineVehicle;
MultiSignalSpy* _multiSpy;
PlanMasterController* _masterController = nullptr;
Vehicle* _controllerVehicle = nullptr;
MultiSignalSpy* _multiSpy = nullptr;
QList<QGeoCoordinate> _polygonVertices;
TransectStyleItem* _transectStyleItem;
TransectStyleItem* _transectStyleItem = nullptr;
};
class TransectStyleItem : public TransectStyleComplexItem
......@@ -83,7 +85,7 @@ class TransectStyleItem : public TransectStyleComplexItem
Q_OBJECT
public:
TransectStyleItem(Vehicle* vehicle, QObject* parent = nullptr);
TransectStyleItem(PlanMasterController* masterController, QObject* parent = nullptr);
// Overrides from ComplexMissionItem
QString mapVisualQML (void) const final { return QString(); }
......
......@@ -17,22 +17,23 @@
#include "JsonHelper.h"
#include "TerrainQuery.h"
#include "TakeoffMissionItem.h"
#include "PlanMasterController.h"
const char* VisualMissionItem::jsonTypeKey = "type";
const char* VisualMissionItem::jsonTypeSimpleItemValue = "SimpleItem";
const char* VisualMissionItem::jsonTypeComplexItemValue = "ComplexItem";
VisualMissionItem::VisualMissionItem(Vehicle* vehicle, bool flyView, QObject* parent)
: QObject (parent)
, _vehicle (vehicle)
, _flyView (flyView)
VisualMissionItem::VisualMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: QObject (parent)
, _flyView (flyView)
, _masterController (masterController)
, _controllerVehicle(masterController->controllerVehicle())
{
_commonInit();
}
VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, bool flyView, QObject* parent)
: QObject (parent)
, _vehicle (nullptr)
, _flyView (flyView)
{
*this = other;
......@@ -43,7 +44,8 @@ VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, bool flyVie
void VisualMissionItem::_commonInit(void)
{
// Don't get terrain altitude information for submarines or boats
if (_vehicle->vehicleType() != MAV_TYPE_SUBMARINE && _vehicle->vehicleType() != MAV_TYPE_SURFACE_BOAT) {
Vehicle* controllerVehicle = _masterController->controllerVehicle();
if (controllerVehicle->vehicleType() != MAV_TYPE_SUBMARINE && controllerVehicle->vehicleType() != MAV_TYPE_SURFACE_BOAT) {
_updateTerrainTimer.setInterval(500);
_updateTerrainTimer.setSingleShot(true);
connect(&_updateTerrainTimer, &QTimer::timeout, this, &VisualMissionItem::_reallyUpdateTerrainAltitude);
......@@ -54,7 +56,8 @@ void VisualMissionItem::_commonInit(void)
const VisualMissionItem& VisualMissionItem::operator=(const VisualMissionItem& other)
{
_vehicle = other._vehicle;
_masterController = other._masterController;
_controllerVehicle = other._controllerVehicle;
setIsCurrentItem(other._isCurrentItem);
setDirty(other._dirty);
......
......@@ -26,6 +26,7 @@
#include "MissionController.h"
class MissionItem;
class PlanMasterController;
// Abstract base class for all Simple and Complex visual mission objects.
class VisualMissionItem : public QObject
......@@ -33,7 +34,7 @@ class VisualMissionItem : public QObject
Q_OBJECT
public:
VisualMissionItem(Vehicle* vehicle, bool flyView, QObject* parent);
VisualMissionItem(PlanMasterController* masterController, bool flyView, QObject* parent);
VisualMissionItem(const VisualMissionItem& other, bool flyView, QObject* parent);
~VisualMissionItem();
......@@ -47,7 +48,6 @@ public:
};
Q_ENUM(ReadyForSaveState)
Q_PROPERTY(Vehicle* vehicle READ vehicle CONSTANT)
Q_PROPERTY(bool homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) ///< This is the entry point for a waypoint line into the item. For a simple item it is also the location of the item
Q_PROPERTY(double terrainAltitude READ terrainAltitude NOTIFY terrainAltitudeChanged) ///< The altitude of terrain at the coordinate position, NaN if not known
......@@ -70,7 +70,6 @@ public:
Q_PROPERTY(bool isTakeoffItem READ isTakeoffItem NOTIFY isTakeoffItemChanged) ///< true: Takeoff item special case
Q_PROPERTY(QString editorQml MEMBER _editorQml CONSTANT) ///< Qml code for editing this item
Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT) ///< QMl code for map visuals
Q_PROPERTY(QmlObjectListModel* childItems READ childItems CONSTANT)
Q_PROPERTY(double specifiedFlightSpeed READ specifiedFlightSpeed NOTIFY specifiedFlightSpeedChanged) ///< NaN for not specified
Q_PROPERTY(double specifiedGimbalYaw READ specifiedGimbalYaw NOTIFY specifiedGimbalYawChanged) ///< NaN for not specified
Q_PROPERTY(double specifiedGimbalPitch READ specifiedGimbalPitch NOTIFY specifiedGimbalPitchChanged) ///< NaN for not specified
......@@ -79,10 +78,12 @@ public:
Q_PROPERTY(double missionVehicleYaw READ missionVehicleYaw NOTIFY missionVehicleYawChanged) ///< Expected vehicle yaw at this point in mission
Q_PROPERTY(bool flyView READ flyView CONSTANT)
Q_PROPERTY(bool wizardMode READ wizardMode WRITE setWizardMode NOTIFY wizardModeChanged)
Q_PROPERTY(ReadyForSaveState readyForSaveState READ readyForSaveState NOTIFY readyForSaveStateChanged)
Q_PROPERTY(VisualMissionItem* parentItem READ parentItem WRITE setParentItem NOTIFY parentItemChanged)
Q_PROPERTY(QGCGeoBoundingCube* boundingCube READ boundingCube NOTIFY boundingCubeChanged)
Q_PROPERTY(PlanMasterController* masterController READ masterController CONSTANT)
Q_PROPERTY(ReadyForSaveState readyForSaveState READ readyForSaveState NOTIFY readyForSaveStateChanged)
Q_PROPERTY(VisualMissionItem* parentItem READ parentItem WRITE setParentItem NOTIFY parentItemChanged)
Q_PROPERTY(QmlObjectListModel* childItems READ childItems CONSTANT)
Q_PROPERTY(QGCGeoBoundingCube* boundingCube READ boundingCube NOTIFY boundingCubeChanged)
// The following properties are calculated/set by the MissionController recalc methods
......@@ -123,7 +124,7 @@ public:
void setHomePositionSpecialCase (bool homePositionSpecialCase) { _homePositionSpecialCase = homePositionSpecialCase; }
Vehicle* vehicle(void) { return _vehicle; }
PlanMasterController* masterController(void) { return _masterController; }
// Pure virtuals which must be provides by derived classes
......@@ -229,23 +230,25 @@ signals:
void exitCoordinateSameAsEntryChanged (bool exitCoordinateSameAsEntry);
protected:
Vehicle* _vehicle;
bool _flyView = false;
bool _isCurrentItem = false;
bool _hasCurrentChildItem = false;
bool _dirty = false;
bool _homePositionSpecialCase = false; ///< true: This item is being used as a ui home position indicator
bool _wizardMode = false; ///< true: Item editor is showing wizard completion panel
double _terrainAltitude = qQNaN(); ///< Altitude of terrain at coordinate position, NaN for not known
double _altDifference = 0; ///< Difference in altitude from previous waypoint
double _altPercent = 0; ///< Percent of total altitude change in mission
double _terrainPercent = qQNaN(); ///< Percent of terrain altitude for coordinate
bool _terrainCollision = false; ///< true: item collides with terrain
double _azimuth = 0; ///< Azimuth to previous waypoint
double _distance = 0; ///< Distance to previous waypoint
QString _editorQml; ///< Qml resource for editing item
double _missionGimbalYaw = qQNaN();
double _missionVehicleYaw = qQNaN();
bool _flyView = false;
bool _isCurrentItem = false;
bool _hasCurrentChildItem = false;
bool _dirty = false;
bool _homePositionSpecialCase = false; ///< true: This item is being used as a ui home position indicator
bool _wizardMode = false; ///< true: Item editor is showing wizard completion panel
double _terrainAltitude = qQNaN(); ///< Altitude of terrain at coordinate position, NaN for not known
double _altDifference = 0; ///< Difference in altitude from previous waypoint
double _altPercent = 0; ///< Percent of total altitude change in mission
double _terrainPercent = qQNaN(); ///< Percent of terrain altitude for coordinate
bool _terrainCollision = false; ///< true: item collides with terrain
double _azimuth = 0; ///< Azimuth to previous waypoint
double _distance = 0; ///< Distance to previous waypoint
QString _editorQml; ///< Qml resource for editing item
double _missionGimbalYaw = qQNaN();
double _missionVehicleYaw = qQNaN();
PlanMasterController* _masterController = nullptr;
Vehicle* _controllerVehicle = nullptr;
VisualMissionItem* _parentItem = nullptr;
QGCGeoBoundingCube _boundingCube; ///< The bounding "cube" of this element.
......
......@@ -10,9 +10,9 @@
#include "VisualMissionItemTest.h"
#include "SimpleMissionItem.h"
#include "QGCApplication.h"
#include "PlanMasterController.h"
VisualMissionItemTest::VisualMissionItemTest(void)
: _offlineVehicle(nullptr)
{
}
......@@ -20,10 +20,9 @@ VisualMissionItemTest::VisualMissionItemTest(void)
void VisualMissionItemTest::init(void)
{
UnitTest::init();
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4,
MAV_TYPE_QUADROTOR,
qgcApp()->toolbox()->firmwarePluginManager(),
this);
_masterController = new PlanMasterController(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, this);
_controllerVehicle = _masterController->controllerVehicle();
rgVisualItemSignals[altDifferenceChangedIndex] = SIGNAL(altDifferenceChanged(double));
rgVisualItemSignals[altPercentChangedIndex] = SIGNAL(altPercentChanged(double));
......@@ -54,7 +53,7 @@ void VisualMissionItemTest::init(void)
void VisualMissionItemTest::cleanup(void)
{
_offlineVehicle->deleteLater();
_masterController->deleteLater();
UnitTest::cleanup();
}
......
......@@ -16,6 +16,8 @@
#include <QGeoCoordinate>
class PlanMasterController;
/// Unit test for SimpleMissionItem
class VisualMissionItemTest : public UnitTest
{
......@@ -90,5 +92,6 @@ protected:
static const size_t cVisualItemSignals = maxSignalIndex;
const char* rgVisualItemSignals[cVisualItemSignals];
Vehicle* _offlineVehicle;
PlanMasterController* _masterController = nullptr;
Vehicle* _controllerVehicle = nullptr;
};
......@@ -19,7 +19,8 @@ Rectangle {
property bool _specifiesAltitude: missionItem.specifiesAltitude
property real _margin: ScreenTools.defaultFontPixelHeight / 2
property bool _supportsTerrainFrame: missionItem
property bool _supportsTerrainFrame: missionItem.masterController.supportsTerrain
property var _controllerVehicle: missionItem.masterController.controllerVehicle
property string _altModeRelativeHelpText: qsTr("Altitude relative to launch altitude")
property string _altModeAbsoluteHelpText: qsTr("Altitude above mean sea level")
......@@ -66,7 +67,7 @@ Rectangle {
visible: missionItem.isTakeoffItem && missionItem.wizardMode // Hack special case for takeoff item
QGCLabel {
text: qsTr("Move 'T' Takeoff to the %1 location.").arg(missionItem.vehicle.vtol ? qsTr("desired") : qsTr("climbout"))
text: qsTr("Move 'T' Takeoff to the %1 location.").arg(_controllerVehicle.vtol ? qsTr("desired") : qsTr("climbout"))
Layout.fillWidth: true
wrapMode: Text.WordWrap
visible: !initialClickLabel.visible
......@@ -76,7 +77,7 @@ Rectangle {
text: qsTr("Ensure clear of obstacles and into the wind.")
Layout.fillWidth: true
wrapMode: Text.WordWrap
visible: !initialClickLabel.visible && !missionItem.vehicle.vtol
visible: !initialClickLabel.visible && !_controllerVehicle.vtol
}
QGCButton {
......@@ -214,7 +215,7 @@ Rectangle {
text: qsTr("Terrain Frame")
checkable: true
checked: missionItem.altitudeMode === QGroundControl.AltitudeModeTerrainFrame
visible: missionItem.altitudeMode === QGroundControl.AltitudeModeTerrainFrame
visible: _supportsTerrainFrame && (missionItem.specifiesCoordinate || missionItem.specifiesAltitudeOnly)
onTriggered: missionItem.altitudeMode = QGroundControl.AltitudeModeTerrainFrame
}
}
......
......@@ -14,3 +14,4 @@ PreFlightGPSCheck 1.0 PreFlightGPSCheck.qml
PreFlightRCCheck 1.0 PreFlightRCCheck.qml
PreFlightSensorsHealthCheck 1.0 PreFlightSensorsHealthCheck.qml
PreFlightSoundCheck 1.0 PreFlightSoundCheck.qml
TerrainProgress 1.0 TerrainProgress.qml
......@@ -341,7 +341,7 @@ void TerrainTileManager::addCoordinateQuery(TerrainOfflineAirMapQuery* terrainQu
bool error;
QList<double> altitudes;
if (!_getAltitudesForCoordinates(coordinates, altitudes, error)) {
if (!getAltitudesForCoordinates(coordinates, altitudes, error)) {
qCDebug(TerrainQueryLog) << "TerrainTileManager::addPathQuery queue count" << _requestQueue.count();
QueuedRequestInfo_t queuedRequestInfo = { terrainQueryInterface, QueryMode::QueryModeCoordinates, 0, 0, coordinates };
_requestQueue.append(queuedRequestInfo);
......@@ -380,7 +380,7 @@ void TerrainTileManager::addPathQuery(TerrainOfflineAirMapQuery* terrainQueryInt
bool error;
QList<double> altitudes;
if (!_getAltitudesForCoordinates(coordinates, altitudes, error)) {
if (!getAltitudesForCoordinates(coordinates, altitudes, error)) {
qCDebug(TerrainQueryLog) << "TerrainTileManager::addPathQuery queue count" << _requestQueue.count();
QueuedRequestInfo_t queuedRequestInfo = { terrainQueryInterface, QueryMode::QueryModePath, latStep, lonStep, coordinates };
_requestQueue.append(queuedRequestInfo);
......@@ -400,13 +400,13 @@ void TerrainTileManager::addPathQuery(TerrainOfflineAirMapQuery* terrainQueryInt
/// Either returns altitudes from cache or queues database request
/// @param[out] error true: altitude not returned due to error, false: altitudes returned
/// @return true: altitude returned (check error as well), false: database query queued (altitudes not returned)
bool TerrainTileManager::_getAltitudesForCoordinates(const QList<QGeoCoordinate>& coordinates, QList<double>& altitudes, bool& error)
bool TerrainTileManager::getAltitudesForCoordinates(const QList<QGeoCoordinate>& coordinates, QList<double>& altitudes, bool& error)
{
error = false;
for (const QGeoCoordinate& coordinate: coordinates) {
QString tileHash = _getTileHash(coordinate);
qCDebug(TerrainQueryLog) << "TerrainTileManager::_getAltitudesForCoordinates hash:coordinate" << tileHash << coordinate;
qCDebug(TerrainQueryLog) << "TerrainTileManager::getAltitudesForCoordinates hash:coordinate" << tileHash << coordinate;
_tilesMutex.lock();
if (_tiles.contains(tileHash)) {
......@@ -414,20 +414,20 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList<QGeoCoordinate>
double elevation = _tiles[tileHash].elevation(coordinate);
if (qIsNaN(elevation)) {
error = true;
qCWarning(TerrainQueryLog) << "TerrainTileManager::_getAltitudesForCoordinates Internal Error: negative elevation in tile cache";
qCWarning(TerrainQueryLog) << "TerrainTileManager::getAltitudesForCoordinates Internal Error: missing elevation in tile cache";
} else {
qCDebug(TerrainQueryLog) << "TerrainTileManager::_getAltitudesForCoordinates returning elevation from tile cache" << elevation;
qCDebug(TerrainQueryLog) << "TerrainTileManager::getAltitudesForCoordinates returning elevation from tile cache" << elevation;
}
altitudes.push_back(elevation);
} else {
qCWarning(TerrainQueryLog) << "TerrainTileManager::_getAltitudesForCoordinates Internal Error: coordinate not in tile region";
qCWarning(TerrainQueryLog) << "TerrainTileManager::getAltitudesForCoordinates Internal Error: coordinate not in tile region";
altitudes.push_back(qQNaN());
error = true;
}
} else {
if (_state != State::Downloading) {
QNetworkRequest request = getQGCMapEngine()->urlFactory()->getTileURL("Airmap Elevation", getQGCMapEngine()->urlFactory()->long2tileX("Airmap Elevation",coordinate.longitude(), 1), getQGCMapEngine()->urlFactory()->lat2tileY("Airmap Elevation", coordinate.latitude(), 1), 1, &_networkManager);
qCDebug(TerrainQueryLog) << "TerrainTileManager::_getAltitudesForCoordinates query from database" << request.url();
qCDebug(TerrainQueryLog) << "TerrainTileManager::getAltitudesForCoordinates query from database" << request.url();
QGeoTileSpec spec;
spec.setX(getQGCMapEngine()->urlFactory()->long2tileX("Airmap Elevation", coordinate.longitude(), 1));
spec.setY(getQGCMapEngine()->urlFactory()->lat2tileY("Airmap Elevation", coordinate.latitude(), 1));
......@@ -512,7 +512,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
QList<double> altitudes;
QueuedRequestInfo_t& requestInfo = _requestQueue[i];
if (_getAltitudesForCoordinates(requestInfo.coordinates, altitudes, error)) {
if (getAltitudesForCoordinates(requestInfo.coordinates, altitudes, error)) {
if (requestInfo.queryMode == QueryMode::QueryModeCoordinates) {
if (error) {
QList<double> noAltitudes;
......@@ -698,6 +698,11 @@ void TerrainAtCoordinateQuery::requestData(const QList<QGeoCoordinate>& coordina
_TerrainAtCoordinateBatchManager->addQuery(this, coordinates);
}
bool TerrainAtCoordinateQuery::getAltitudesForCoordinates(const QList<QGeoCoordinate>& coordinates, QList<double>& altitudes, bool& error)
{
return _terrainTileManager->getAltitudesForCoordinates(coordinates, altitudes, error);
}
void TerrainAtCoordinateQuery::_signalTerrainData(bool success, QList<double>& heights)
{
emit terrainDataReceived(success, heights);
......
......@@ -115,8 +115,9 @@ class TerrainTileManager : public QObject {
public:
TerrainTileManager(void);
void addCoordinateQuery (TerrainOfflineAirMapQuery* terrainQueryInterface, const QList<QGeoCoordinate>& coordinates);
void addPathQuery (TerrainOfflineAirMapQuery* terrainQueryInterface, const QGeoCoordinate& startPoint, const QGeoCoordinate& endPoint);
void addCoordinateQuery (TerrainOfflineAirMapQuery* terrainQueryInterface, const QList<QGeoCoordinate>& coordinates);
void addPathQuery (TerrainOfflineAirMapQuery* terrainQueryInterface, const QGeoCoordinate& startPoint, const QGeoCoordinate& endPoint);
bool getAltitudesForCoordinates (const QList<QGeoCoordinate>& coordinates, QList<double>& altitudes, bool& error);
private slots:
void _terrainDone (QByteArray responseBytes, QNetworkReply::NetworkError error);
......@@ -141,7 +142,6 @@ private:
} QueuedRequestInfo_t;
void _tileFailed (void);
bool _getAltitudesForCoordinates (const QList<QGeoCoordinate>& coordinates, QList<double>& altitudes, bool& error);
QString _getTileHash (const QGeoCoordinate& coordinate);
QList<QueuedRequestInfo_t> _requestQueue;
......@@ -207,6 +207,11 @@ public:
/// @param coordinates to query
void requestData(const QList<QGeoCoordinate>& coordinates);
/// Either returns altitudes from cache or queues database request
/// @param[out] error true: altitude not returned due to error, false: altitudes returned
/// @return true: altitude returned (check error as well), false: database query queued (altitudes not returned)
static bool getAltitudesForCoordinates(const QList<QGeoCoordinate>& coordinates, QList<double>& altitudes, bool& error);
// Internal method
void _signalTerrainData(bool success, QList<double>& heights);
......
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "TerrainFactGroup.h"
const char* TerrainFactGroup::_blocksPendingFactName = "blocksPending";
const char* TerrainFactGroup::_blocksLoadedFactName = "blocksLoaded";
TerrainFactGroup::TerrainFactGroup(QObject* parent)
: FactGroup (1000, ":/json/Vehicle/TerrainFactGroup.json", parent)
, _blocksPendingFact(0, _blocksPendingFactName, FactMetaData::valueTypeDouble)
, _blocksLoadedFact (0, _blocksLoadedFactName, FactMetaData::valueTypeDouble)
{
_addFact(&_blocksPendingFact, _blocksPendingFactName);
_addFact(&_blocksLoadedFact, _blocksLoadedFactName);
}
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "FactGroup.h"
#include <QGeoCoordinate>
class TerrainFactGroup : public FactGroup
{
Q_OBJECT
public:
TerrainFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* blocksPending READ blocksPending CONSTANT)
Q_PROPERTY(Fact* blocksLoaded READ blocksLoaded CONSTANT)
Fact* blocksPending () { return &_blocksPendingFact; }
Fact* blocksLoaded () { return &_blocksLoadedFact; }
static const char* _blocksPendingFactName;
static const char* _blocksLoadedFactName;
private:
Fact _blocksPendingFact;
Fact _blocksLoadedFact;
};
[
{
"name": "blocksPending",
"shortDescription": "Blocks Pending",
"type": "double",
"decimalPlaces": 0,
"default": 0
},
{
"name": "blocksLoaded",
"shortDescription": "Blocks Loaded",
"type": "double",
"decimalPlaces": 0,
"default": 0
}
]
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "TerrainProtocolHandler.h"
#include "TerrainQuery.h"
#include "QGCApplication.h"
QGC_LOGGING_CATEGORY(TerrainProtocolHandlerLog, "TerrainProtocolHandlerLog")
TerrainProtocolHandler::TerrainProtocolHandler(Vehicle* vehicle, TerrainFactGroup* terrainFactGroup, QObject *parent)
: QObject (parent)
, _vehicle (vehicle)
, _terrainFactGroup (terrainFactGroup)
{
_terrainDataSendTimer.setSingleShot(false);
_terrainDataSendTimer.setInterval(1000.0/12.0);
connect(&_terrainDataSendTimer, &QTimer::timeout, this, &TerrainProtocolHandler::_sendNextTerrainData);
}
bool TerrainProtocolHandler::mavlinkMessageReceived(const mavlink_message_t message)
{
switch (message.msgid) {
case MAVLINK_MSG_ID_TERRAIN_REQUEST:
_handleTerrainRequest(message);
return false;
case MAVLINK_MSG_ID_TERRAIN_REPORT:
_handleTerrainReport(message);
return false;
default:
return true;
}
}
void TerrainProtocolHandler::_handleTerrainRequest(const mavlink_message_t& message)
{
_terrainRequestActive = true;
mavlink_msg_terrain_request_decode(&message, &_currentTerrainRequest);
_sendNextTerrainData();
}
void TerrainProtocolHandler::_handleTerrainReport(const mavlink_message_t& message)
{
mavlink_terrain_report_t terrainReport;
mavlink_msg_terrain_report_decode(&message, &terrainReport);
_terrainFactGroup->blocksPending()->setRawValue(terrainReport.pending);
_terrainFactGroup->blocksLoaded()->setRawValue(terrainReport.loaded);
if (TerrainProtocolHandlerLog().isDebugEnabled()) {
bool error;
QGeoCoordinate coord(static_cast<double>(terrainReport.lat) / 1e7, static_cast<double>(terrainReport.lon) / 1e7);
QList<double> altitudes;
QList<QGeoCoordinate> coordinates;
coordinates.append(coord);
bool altAvailable = (TerrainAtCoordinateQuery::getAltitudesForCoordinates(coordinates, altitudes, error));
QString vehicleAlt = terrainReport.spacing ? QStringLiteral("%1").arg(terrainReport.terrain_height) : QStringLiteral("n/a");
QString qgcAlt = error ? QStringLiteral("error") :
(altAvailable ? QStringLiteral("%1").arg(altitudes[0]) : QStringLiteral("n/a"));
qDebug() << "TERRAIN_REPORT" << coord << QStringLiteral("Vehicle(%1) QGC(%2)").arg(vehicleAlt).arg(qgcAlt);
}
}
void TerrainProtocolHandler::_sendNextTerrainData(void)
{
if (!_terrainRequestActive) {
return;
}
QGeoCoordinate terrainRequestCoordSWCorner(static_cast<double>(_currentTerrainRequest.lat) / 1e7, static_cast<double>(_currentTerrainRequest.lon) / 1e7);
int spacingBetweenGrids = _currentTerrainRequest.grid_spacing * 4;
// Each TERRAIN_DATA sent to vehicle contains a 4x4 grid of heights
// TERRAIN_REQUEST.mask has a bit for each entry in an 8x7 grid
// gridBit = 0 refers to the the sw corner of the 8x7 grid
bool bitFound = false;
for (int rowIndex=0; rowIndex<7; rowIndex++) {
for (int colIndex=0; colIndex<8; colIndex++) {
uint8_t gridBit = (rowIndex * 8) + colIndex;
uint64_t checkBit = 1ull << gridBit;
if (_currentTerrainRequest.mask & checkBit) {
// Move east and then north to generate the coordinate for sw corner of the specific gridBit
QGeoCoordinate swCorner = terrainRequestCoordSWCorner.atDistanceAndAzimuth(spacingBetweenGrids * colIndex, 90);
swCorner = swCorner.atDistanceAndAzimuth(spacingBetweenGrids * rowIndex, 0);
_sendTerrainData(swCorner, gridBit);
bitFound = true;
break;
}
}
if (bitFound) {
break;
}
}
if (bitFound) {
// Kick timer to send next possible TERRAIN_DATA to vehicle
_terrainDataSendTimer.start();
} else {
_terrainRequestActive = false;
}
}
void TerrainProtocolHandler::_sendTerrainData(const QGeoCoordinate& swCorner, uint8_t gridBit)
{
QList<QGeoCoordinate> coordinates;
for (int rowIndex=0; rowIndex<4; rowIndex++) {
for (int colIndex=0; colIndex<4; colIndex++) {
// Move east and then north to generate the coordinate for grid point
QGeoCoordinate coord = swCorner.atDistanceAndAzimuth(_currentTerrainRequest.grid_spacing * colIndex, 90);
coord = coord.atDistanceAndAzimuth(_currentTerrainRequest.grid_spacing * rowIndex, 0);
coordinates.append(coord);
}
}
// Query terrain system for altitudes. If it has them available it will return them. If not they will be queued for download.
bool error = false;
QList<double> altitudes;
if (TerrainAtCoordinateQuery::getAltitudesForCoordinates(coordinates, altitudes, error)) {
if (error) {
qCWarning(TerrainProtocolHandlerLog) << "_sendTerrainData TerrainAtCoordinateQuery::getAltitudesForCoordinates failed";
} else {
// Only clear the bit if the query succeeds. Otherwise just let it try again on the next timer tick
uint64_t removeBit = ~(1ull << gridBit);
_currentTerrainRequest.mask &= removeBit;
int altIndex = 0;
int16_t terrainData[16];
for (const double& altitude : altitudes) {
terrainData[altIndex++] = static_cast<int16_t>(altitude);
}
mavlink_message_t msg;
mavlink_msg_terrain_data_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
_currentTerrainRequest.lat,
_currentTerrainRequest.lon,
_currentTerrainRequest.grid_spacing,
gridBit,
terrainData);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
}
}
}
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "Vehicle.h"
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include <QObject>
#include <QGeoCoordinate>
class TerrainFactGroup;
Q_DECLARE_LOGGING_CATEGORY(TerrainProtocolHandlerLog)
class TerrainProtocolHandler : public QObject
{
Q_OBJECT
public:
explicit TerrainProtocolHandler(Vehicle* vehicle, TerrainFactGroup* terrainFactGroup, QObject *parent = nullptr);
/// @return true: Allow vehicle to continue processing, false: Vehicle should not process message
bool mavlinkMessageReceived(const mavlink_message_t message);
private slots:
void _sendNextTerrainData(void);
private:
void _handleTerrainRequest (const mavlink_message_t& message);
void _handleTerrainReport (const mavlink_message_t& message);
void _sendTerrainData (const QGeoCoordinate& swCorner, uint8_t gridBit);
Vehicle* _vehicle;
TerrainFactGroup* _terrainFactGroup;
bool _terrainRequestActive = false;
mavlink_terrain_request_t _currentTerrainRequest;
QTimer _terrainDataSendTimer;
};
......@@ -45,6 +45,7 @@
#include "VehicleObjectAvoidance.h"
#include "TrajectoryPoints.h"
#include "QGCGeo.h"
#include "TerrainProtocolHandler.h"
#if defined(QGC_AIRMAP_ENABLED)
#include "AirspaceVehicleManager.h"
......@@ -91,6 +92,7 @@ const char* Vehicle::_temperatureFactGroupName = "temperature";
const char* Vehicle::_clockFactGroupName = "clock";
const char* Vehicle::_distanceSensorFactGroupName = "distanceSensor";
const char* Vehicle::_estimatorStatusFactGroupName = "estimatorStatus";
const char* Vehicle::_terrainFactGroupName = "terrain";
// Standard connected vehicle
Vehicle::Vehicle(LinkInterface* link,
......@@ -149,7 +151,9 @@ Vehicle::Vehicle(LinkInterface* link,
, _mavlinkProtocolRequestComplete(false)
, _maxProtoVersion(0)
, _vehicleCapabilitiesKnown(false)
, _capabilityBits(0)
, _capabilityBits(firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ?
MAV_PROTOCOL_CAPABILITY_MISSION_INT | MAV_PROTOCOL_CAPABILITY_COMMAND_INT | MAV_PROTOCOL_CAPABILITY_TERRAIN | MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY : // Hack workound for ArduPilot startup problems
0)
, _highLatencyLink(false)
, _receivingAttitudeQuaternion(false)
, _cameras(nullptr)
......@@ -222,6 +226,8 @@ Vehicle::Vehicle(LinkInterface* link,
, _clockFactGroup(this)
, _distanceSensorFactGroup(this)
, _estimatorStatusFactGroup(this)
, _terrainFactGroup(this)
, _terrainProtocolHandler(new TerrainProtocolHandler(this, &_terrainFactGroup, this))
{
connect(_joystickManager, &JoystickManager::activeJoystickChanged, this, &Vehicle::_loadSettings);
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleAvailableChanged, this, &Vehicle::_loadSettings);
......@@ -429,6 +435,9 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
connect(_settingsManager->appSettings()->offlineEditingCruiseSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineCruiseSpeedSettingChanged);
connect(_settingsManager->appSettings()->offlineEditingHoverSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineHoverSpeedSettingChanged);
// This add correct terrain capability bit
_offlineFirmwareTypeSettingChanged(_settingsManager->appSettings()->offlineEditingFirmwareType()->rawValue());
_firmwarePlugin->initializeVehicle(this);
}
......@@ -505,6 +514,7 @@ void Vehicle::_commonInit()
_addFactGroup(&_clockFactGroup, _clockFactGroupName);
_addFactGroup(&_distanceSensorFactGroup, _distanceSensorFactGroupName);
_addFactGroup(&_estimatorStatusFactGroup, _estimatorStatusFactGroupName);
_addFactGroup(&_terrainFactGroup, _terrainFactGroupName);
// Add firmware-specific fact groups, if provided
QMap<QString, FactGroup*>* fwFactGroups = _firmwarePlugin->factGroups();
......@@ -578,7 +588,13 @@ void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value)
{
_firmwareType = static_cast<MAV_AUTOPILOT>(value.toInt());
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
_capabilityBits |= MAV_PROTOCOL_CAPABILITY_TERRAIN;
} else {
_capabilityBits &= ~MAV_PROTOCOL_CAPABILITY_TERRAIN;
}
emit firmwareTypeChanged();
emit capabilityBitsChanged(_capabilityBits);
}
void Vehicle::_offlineVehicleTypeSettingChanged(QVariant value)
......@@ -692,6 +708,10 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
return;
}
if (!_terrainProtocolHandler->mavlinkMessageReceived(message)) {
return;
}
switch (message.msgid) {
case MAVLINK_MSG_ID_HOME_POSITION:
_handleHomePosition(message);
......@@ -1300,6 +1320,7 @@ void Vehicle::_setCapabilities(uint64_t capabilityBits)
qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_COMMAND_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_COMMAND_INT ? supports : doesNotSupport);
qCDebug(VehicleLog) << QString("Vehicle %1 GeoFence").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE ? supports : doesNotSupport);
qCDebug(VehicleLog) << QString("Vehicle %1 RallyPoints").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY ? supports : doesNotSupport);
qCDebug(VehicleLog) << QString("Vehicle %1 Terrain").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_TERRAIN ? supports : doesNotSupport);
}
void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& message)
......@@ -2906,7 +2927,7 @@ bool Vehicle::supportsMotorInterference() const
bool Vehicle::supportsTerrainFrame() const
{
return _firmwarePlugin->supportsTerrainFrame();
return _capabilityBits & MAV_PROTOCOL_CAPABILITY_TERRAIN;
}
QString Vehicle::vehicleTypeName() const {
......
......@@ -21,6 +21,7 @@
#include "UASMessageHandler.h"
#include "SettingsFact.h"
#include "QGCMapCircle.h"
#include "TerrainFactGroup.h"
class UAS;
class UASInterface;
......@@ -38,6 +39,7 @@ class QGCCameraManager;
class Joystick;
class VehicleObjectAvoidance;
class TrajectoryPoints;
class TerrainProtocolHandler;
#if defined(QGC_AIRMAP_ENABLED)
class AirspaceVehicleManager;
......@@ -619,7 +621,7 @@ public:
Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged)
Q_PROPERTY(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged)
Q_PROPERTY(bool highLatencyLink READ highLatencyLink NOTIFY highLatencyLinkChanged)
Q_PROPERTY(bool supportsTerrainFrame READ supportsTerrainFrame NOTIFY firmwareTypeChanged)
Q_PROPERTY(bool supportsTerrainFrame READ supportsTerrainFrame NOTIFY capabilityBitsChanged)
Q_PROPERTY(QString priorityLinkName READ priorityLinkName WRITE setPriorityLinkByName NOTIFY priorityLinkNameChanged)
Q_PROPERTY(QVariantList links READ links NOTIFY linksChanged)
Q_PROPERTY(LinkInterface* priorityLink READ priorityLink NOTIFY priorityLinkNameChanged)
......@@ -682,6 +684,7 @@ public:
Q_PROPERTY(FactGroup* clock READ clockFactGroup CONSTANT)
Q_PROPERTY(FactGroup* setpoint READ setpointFactGroup CONSTANT)
Q_PROPERTY(FactGroup* estimatorStatus READ estimatorStatusFactGroup CONSTANT)
Q_PROPERTY(FactGroup* terrain READ terrainFactGroup CONSTANT)
Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareVersionChanged)
Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareVersionChanged)
......@@ -996,6 +999,7 @@ public:
FactGroup* setpointFactGroup () { return &_setpointFactGroup; }
FactGroup* distanceSensorFactGroup () { return &_distanceSensorFactGroup; }
FactGroup* estimatorStatusFactGroup () { return &_estimatorStatusFactGroup; }
FactGroup* terrainFactGroup () { return &_terrainFactGroup; }
void setConnectionLostEnabled(bool connectionLostEnabled);
......@@ -1573,6 +1577,9 @@ private:
VehicleSetpointFactGroup _setpointFactGroup;
VehicleDistanceSensorFactGroup _distanceSensorFactGroup;
VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup;
TerrainFactGroup _terrainFactGroup;
TerrainProtocolHandler* _terrainProtocolHandler = nullptr;
static const char* _rollFactName;
static const char* _pitchFactName;
......@@ -1603,6 +1610,7 @@ private:
static const char* _clockFactGroupName;
static const char* _distanceSensorFactGroupName;
static const char* _estimatorStatusFactGroupName;
static const char* _terrainFactGroupName;
static const int _vehicleUIUpdateRateMSecs = 100;
......
......@@ -998,7 +998,7 @@ void MockLink::_respondWithAutopilotVersion(void)
_vehicleComponentId,
_mavlinkChannel,
&msg,
MAV_PROTOCOL_CAPABILITY_MAVLINK2 | (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY),
MAV_PROTOCOL_CAPABILITY_MAVLINK2 | MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY | (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? MAV_PROTOCOL_CAPABILITY_TERRAIN : 0),
flightVersion, // flight_sw_version,
0, // middleware_sw_version,
0, // os_sw_version,
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment