Commit 82aa7678 authored by DonLakeFlyer's avatar DonLakeFlyer

Use a master controller for all Plan elements

Update the user model to a single controller instead of multiple
parent da022f97
......@@ -472,6 +472,7 @@ HEADERS += \
src/MissionManager/MissionManager.h \
src/MissionManager/MissionSettingsItem.h \
src/MissionManager/PlanElementController.h \
src/MissionManager/PlanMasterController.h \
src/MissionManager/QGCMapPolygon.h \
src/MissionManager/RallyPoint.h \
src/MissionManager/RallyPointController.h \
......@@ -654,6 +655,7 @@ SOURCES += \
src/MissionManager/MissionManager.cc \
src/MissionManager/MissionSettingsItem.cc \
src/MissionManager/PlanElementController.cc \
src/MissionManager/PlanMasterController.cc \
src/MissionManager/QGCMapPolygon.cc \
src/MissionManager/RallyPoint.cc \
src/MissionManager/RallyPointController.cc \
......
......@@ -38,6 +38,10 @@ QGCView {
property bool activeVehicleJoystickEnabled: _activeVehicle ? _activeVehicle.joystickEnabled : false
property var _planMasterController: masterController
property var _missionController: _planMasterController.missionController
property var _geoFenceController: _planMasterController.geoFenceController
property var _rallyPointController: _planMasterController.rallyPointController
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _mainIsMap: QGroundControl.videoManager.hasVideo ? QGroundControl.loadBoolGlobalSetting(_mainIsMapKey, true) : true
property bool _isPipVisible: QGroundControl.videoManager.hasVideo ? QGroundControl.loadBoolGlobalSetting(_PIPVisibleKey, true) : false
......@@ -92,20 +96,14 @@ QGCView {
}
}
MissionController {
id: flyMissionController
Component.onCompleted: start(false /* editMode */)
onResumeMissionReady: guidedActionsController.confirmAction(guidedActionsController.actionResumeMissionReady)
}
GeoFenceController {
id: flyGeoFenceController
PlanElemementMasterController {
id: masterController
Component.onCompleted: start(false /* editMode */)
}
RallyPointController {
id: flyRallyPointController
Component.onCompleted: start(false /* editMode */)
Connections {
target: _missionController
onResumeMissionReady: guidedActionsController.confirmAction(guidedActionsController.actionResumeMissionReady)
}
MessageDialog {
......@@ -149,7 +147,7 @@ QGCView {
vehicleWasArmed = true
}
} else {
if (promptForMissionRemove && (flyMissionController.containsItems || flyGeoFenceController.containsItems || flyRallyPointController.containsItems)) {
if (promptForMissionRemove && (_missionController.containsItems || _geoFenceController.containsItems || _rallyPointController.containsItems)) {
root.showDialog(removeMissionDialogComponent, qsTr("Flight complete"), showDialogDefaultWidth, StandardButton.No | StandardButton.Yes)
}
promptForMissionRemove = false
......@@ -169,9 +167,9 @@ QGCView {
message: qsTr("Do you want to remove the mission from the vehicle?")
function accept() {
flyMissionController.removeAllFromVehicle()
flyGeoFenceController.removeAllFromVehicle()
flyRallyPointController.removeAllFromVehicle()
_missionController.removeAllFromVehicle()
_geoFenceController.removeAllFromVehicle()
_rallyPointController.removeAllFromVehicle()
hideDialog()
}
......@@ -214,9 +212,7 @@ QGCView {
FlightDisplayViewMap {
id: _flightMap
anchors.fill: parent
missionController: flyMissionController
geoFenceController: flyGeoFenceController
rallyPointController: flyRallyPointController
planMasterController: masterController
guidedActionsController: _guidedController
flightWidgets: flightDisplayViewWidgets
rightPanelWidth: ScreenTools.defaultFontPixelHeight * 9
......@@ -320,7 +316,7 @@ QGCView {
anchors.bottom: parent.bottom
qgcView: root
useLightColors: isBackgroundDark
missionController: _flightMap.missionController
missionController: _missionController
visible: singleVehicleView.checked
}
......@@ -511,7 +507,7 @@ QGCView {
GuidedActionsController {
id: guidedActionsController
missionController: flyMissionController
missionController: _missionController
confirmDialog: guidedActionConfirm
z: _flightVideoPipControl.z + 1
......
......@@ -34,9 +34,7 @@ FlightMap {
property alias scaleState: mapScale.state
// The following properties must be set by the consumer
property var missionController
property var geoFenceController
property var rallyPointController
property var planMasterController
property var guidedActionsController
property var flightWidgets
property var rightPanelWidth
......@@ -44,6 +42,10 @@ FlightMap {
property rect centerViewport: Qt.rect(0, 0, width, height)
property var _planMasterController: planMasterController
property var _missionController: _planMasterController.missionController
property var _geoFenceController: _planMasterController.geoFenceController
property var _rallyPointController: _planMasterController.rallyPointController
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate()
property var _gotoHereCoordinate: QtPositioning.coordinate()
......@@ -132,10 +134,10 @@ FlightMap {
QGCMapPalette { id: mapPal; lightColors: isSatelliteMap }
Connections {
target: missionController
target: _missionController
onNewItemsFromVehicle: {
var visualItems = missionController.visualItems
var visualItems = _missionController.visualItems
if (visualItems && visualItems.count != 1) {
mapFitFunctions.fitMapViewportToMissionItems()
firstVehiclePositionReceived = true
......@@ -151,9 +153,7 @@ FlightMap {
id: mapFitFunctions
map: _flightMap
usePlannedHomePosition: false
mapMissionController: missionController
mapGeoFenceController: geoFenceController
mapRallyPointController: rallyPointController
planMasterController: _planMasterController
property real leftToolWidth: toolStrip.x + toolStrip.width
}
......@@ -188,7 +188,7 @@ FlightMap {
// Add the mission item visuals to the map
Repeater {
model: _mainIsMap ? missionController.visualItems : 0
model: _mainIsMap ? _missionController.visualItems : 0
delegate: MissionItemMapVisual {
map: flightMap
......@@ -198,12 +198,12 @@ FlightMap {
// Add lines between waypoints
MissionLineView {
model: _mainIsMap ? missionController.waypointLines : 0
model: _mainIsMap ? _missionController.waypointLines : 0
}
GeoFenceMapVisuals {
map: flightMap
myGeoFenceController: geoFenceController
myGeoFenceController: _geoFenceController
interactive: false
planView: false
homePosition: _activeVehicle && _activeVehicle.homePosition.isValid ? _activeVehicle.homePosition : undefined
......@@ -211,7 +211,7 @@ FlightMap {
// Rally points on map
MapItemView {
model: rallyPointController.points
model: _rallyPointController.points
delegate: MapQuickItem {
id: itemIndicator
......@@ -243,7 +243,7 @@ FlightMap {
// Camera points
MapItemView {
model: missionController.cameraPoints
model: _missionController.cameraPoints
delegate: CameraTriggerIndicator {
coordinate: object.coordinate
......
......@@ -16,9 +16,11 @@ import QGroundControl 1.0
Item {
property var map
property bool usePlannedHomePosition ///< true: planned home position used for calculations, false: vehicle home position use for calculations
property var mapGeoFenceController
property var mapMissionController
property var mapRallyPointController
property var planMasterController
property var _missionController: planMasterController.missionController
property var _geoFenceController: planMasterController.geoFenceController
property var _rallyPointController: planMasterController.rallyPointController
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
......@@ -26,7 +28,7 @@ Item {
var homePosition = QtPositioning.coordinate()
var activeVehicle = QGroundControl.multiVehicleManager.activeVehicle
if (usePlannedHomePosition) {
homePosition = mapMissionController.visualItems.get(0).coordinate
homePosition = _missionController.visualItems.get(0).coordinate
} else if (activeVehicle) {
homePosition = activeVehicle.homePosition
}
......@@ -92,8 +94,8 @@ Item {
if (homePosition.isValid) {
coordList.push(homePosition)
}
for (var i=1; i<mapMissionController.visualItems.count; i++) {
var missionItem = mapMissionController.visualItems.get(i)
for (var i=1; i<_missionController.visualItems.count; i++) {
var missionItem = _missionController.visualItems.get(i)
if (missionItem.specifiesCoordinate && !missionItem.isStandaloneCoordinate) {
coordList.push(missionItem.coordinate)
}
......@@ -101,7 +103,7 @@ Item {
}
function fitMapViewportToMissionItems() {
if (!mapMissionController.visualItems) {
if (!_missionController.visualItems) {
// Being called prior to controller.start
return
}
......@@ -112,16 +114,16 @@ Item {
function addFenceItemCoordsForFit(coordList) {
var homePosition = fitHomePosition()
if (homePosition.isValid && mapGeoFenceController.circleEnabled) {
if (homePosition.isValid && _geoFenceController.circleEnabled) {
var azimuthList = [ 0, 180, 90, 270 ]
for (var i=0; i<azimuthList.length; i++) {
var edgeCoordinate = homePosition.atDistanceAndAzimuth(mapGeoFenceController.circleRadius, azimuthList[i])
var edgeCoordinate = homePosition.atDistanceAndAzimuth(_geoFenceController.circleRadius, azimuthList[i])
coordList.push(edgeCoordinate)
}
}
if (mapGeoFenceController.polygonEnabled && mapGeoFenceController.mapPolygon.path.count > 2) {
for (var i=0; i<mapGeoFenceController.mapPolygon.path.count; i++) {
coordList.push(mapGeoFenceController.mapPolygon.path[i])
if (_geoFenceController.polygonEnabled && _geoFenceController.mapPolygon.path.count > 2) {
for (var i=0; i<_geoFenceController.mapPolygon.path.count; i++) {
coordList.push(_geoFenceController.mapPolygon.path[i])
}
}
}
......@@ -133,8 +135,8 @@ Item {
}
function addRallyItemCoordsForFit(coordList) {
for (var i=0; i<mapRallyPointController.points.count; i++) {
coordList.push(mapRallyPointController.points.get(i).coordinate)
for (var i=0; i<_rallyPointController.points.count; i++) {
coordList.push(_rallyPointController.points.get(i).coordinate)
}
}
......@@ -145,7 +147,7 @@ Item {
}
function fitMapViewportToAllItems() {
if (!mapMissionController.visualItems) {
if (!_missionController.visualItems) {
// Being called prior to controller.start
return
}
......
......@@ -125,7 +125,7 @@ bool JsonHelper::parseEnum(const QJsonObject& jsonObject, QStringList& enumStrin
return true;
}
bool JsonHelper::isJsonFile(const QByteArray& bytes, QJsonDocument& jsonDoc)
bool JsonHelper::isJsonFile(const QByteArray& bytes, QJsonDocument& jsonDoc, QString& errorString)
{
QJsonParseError error;
......@@ -192,6 +192,15 @@ bool JsonHelper::validateQGCJsonFile(const QJsonObject& jsonObject,
return true;
}
void JsonHelper::saveQGCJsonFileHeader(QJsonObject& jsonObject,
const QString& fileType,
int version)
{
jsonObject[jsonGroundStationKey] = jsonGroundStationValue;
jsonObject[jsonFileTypeKey] = fileType;
jsonObject[jsonVersionKey] = version;
}
bool JsonHelper::loadGeoCoordinateArray(const QJsonValue& jsonValue,
bool altitudeRequired,
QVariantList& rgVarPoints,
......
......@@ -20,9 +20,15 @@ class JsonHelper
{
public:
/// Determines is the specified data is a json file
/// @param jsonDoc Returned json document if json file
/// @return true: file is json, false: file is not json
static bool isJsonFile(const QByteArray& bytes, QJsonDocument& jsonDoc);
static bool isJsonFile(const QByteArray& bytes, ///< json bytes
QJsonDocument& jsonDoc, ///< returned json document
QString& errorString); ///< error on parse failure
/// Saves the standard file header the json object
static void saveQGCJsonFileHeader(QJsonObject& jsonObject, ///< root json object
const QString& fileType, ///< file type for file
int version); ///< version number for file
/// Validates the standard parts of a QGC json file:
/// jsonFileTypeKey - Required and checked to be equal to expectedFileType
......
......@@ -89,13 +89,15 @@ void GeoFenceController::_signalAll(void)
emit dirtyChanged(dirty());
}
void GeoFenceController::_activeVehicleBeingRemoved(void)
void GeoFenceController::activeVehicleBeingRemoved(void)
{
_activeVehicle->geoFenceManager()->disconnect(this);
_activeVehicle = NULL;
}
void GeoFenceController::_activeVehicleSet(void)
void GeoFenceController::activeVehicleSet(Vehicle* vehicle)
{
_activeVehicle = vehicle;
GeoFenceManager* geoFenceManager = _activeVehicle->geoFenceManager();
connect(geoFenceManager, &GeoFenceManager::breachReturnSupportedChanged, this, &GeoFenceController::breachReturnSupportedChanged);
connect(geoFenceManager, &GeoFenceManager::circleEnabledChanged, this, &GeoFenceController::circleEnabledChanged);
......@@ -112,97 +114,40 @@ void GeoFenceController::_activeVehicleSet(void)
_signalAll();
}
bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorString)
bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
{
QJsonObject json = jsonDoc.object();
QString errorStr;
QString errorMessage = tr("GeoFence: %1");
int fileVersion;
if (!JsonHelper::validateQGCJsonFile(json,
_jsonFileTypeValue, // expected file type
1, // minimum supported version
1, // maximum supported version
fileVersion,
errorString)) {
if (json.contains(_jsonBreachReturnKey) &&
!JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorStr)) {
errorString = errorMessage.arg(errorStr);
return false;
}
if (!_activeVehicle->parameterManager()->loadFromJson(json, false /* required */, errorString)) {
return false;
}
if (json.contains(_jsonBreachReturnKey)
&& !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) {
return false;
}
if (!_mapPolygon.loadFromJson(json, true, errorString)) {
if (!_mapPolygon.loadFromJson(json, true, errorStr)) {
errorString = errorMessage.arg(errorStr);
return false;
}
_mapPolygon.setDirty(false);
return true;
}
void GeoFenceController::loadFromFile(const QString& filename)
{
QString errorString;
if (filename.isEmpty()) {
return;
}
QFile file(filename);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
errorString = file.errorString() + QStringLiteral(" ") + filename;
} else {
QJsonDocument jsonDoc;
QByteArray bytes = file.readAll();
_loadJsonFile(jsonDoc, errorString);
}
if (!errorString.isEmpty()) {
qgcApp()->showMessage(errorString);
}
setDirty(false);
_signalAll();
setDirty(true);
return true;
}
void GeoFenceController::saveToFile(const QString& filename)
void GeoFenceController::save(QJsonObject& json)
{
if (filename.isEmpty()) {
return;
}
QString fenceFilename = filename;
if (!QFileInfo(filename).fileName().contains(".")) {
fenceFilename += QString(".%1").arg(AppSettings::fenceFileExtension);
}
QFile file(fenceFilename);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
qgcApp()->showMessage(file.errorString());
} else {
QJsonObject fenceFileObject; // top level json object
fenceFileObject[JsonHelper::jsonFileTypeKey] = _jsonFileTypeValue;
fenceFileObject[JsonHelper::jsonVersionKey] = 1;
fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue;
json[JsonHelper::jsonVersionKey] = 1;
if (_breachReturnPoint.isValid()) {
QJsonValue jsonBreachReturn;
JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn);
fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn;
_mapPolygon.saveToJson(fenceFileObject);
QJsonDocument saveDoc(fenceFileObject);
file.write(saveDoc.toJson());
json[_jsonBreachReturnKey] = jsonBreachReturn;
}
setDirty(false);
_mapPolygon.saveToJson(json);
}
void GeoFenceController::removeAll(void)
......@@ -323,11 +268,6 @@ void GeoFenceController::_loadComplete(const QGeoCoordinate& breachReturn, const
emit loadComplete();
}
QString GeoFenceController::fileExtension(void) const
{
return AppSettings::fenceFileExtension;
}
bool GeoFenceController::containsItems(void) const
{
return _mapPolygon.count() > 2;
......
......@@ -46,18 +46,18 @@ public:
void start (bool editMode) final;
void startStaticActiveVehicle (Vehicle* vehicle) final;
void save (QJsonObject& json) final;
bool load (const QJsonObject& json, QString& errorString) final;
void loadFromVehicle (void) final;
void sendToVehicle (void) final;
void loadFromFile (const QString& filename) final;
void saveToFile (const QString& filename) final;
void removeAll (void) final;
void removeAllFromVehicle (void) final;
bool syncInProgress (void) const final;
bool dirty (void) const final;
void setDirty (bool dirty) final;
bool containsItems (void) const final;
QString fileExtension(void) const final;
void activeVehicleBeingRemoved (void) final;
void activeVehicleSet (Vehicle* vehicle) final;
bool circleEnabled (void) const;
Fact* circleRadiusFact (void) const;
......@@ -95,10 +95,6 @@ private slots:
private:
void _init(void);
void _signalAll(void);
bool _loadJsonFile(QJsonDocument& jsonDoc, QString& errorString);
void _activeVehicleBeingRemoved(void) final;
void _activeVehicleSet(void) final;
bool _dirty;
QGCMapPolygon _mapPolygon;
......
......@@ -339,39 +339,6 @@ void MissionController::removeAll(void)
}
}
bool MissionController::_loadJsonMissionFile(Vehicle* vehicle, const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString)
{
QJsonParseError jsonParseError;
QJsonDocument jsonDoc(QJsonDocument::fromJson(bytes, &jsonParseError));
if (jsonParseError.error != QJsonParseError::NoError) {
errorString = jsonParseError.errorString();
return false;
}
QJsonObject json = jsonDoc.object();
// V1 file format has no file type key and version key is string. Convert to new format.
if (!json.contains(JsonHelper::jsonFileTypeKey)) {
json[JsonHelper::jsonFileTypeKey] = _jsonFileTypeValue;
}
int fileVersion;
if (!JsonHelper::validateQGCJsonFile(json,
_jsonFileTypeValue, // expected file type
1, // minimum supported version
2, // maximum supported version
fileVersion,
errorString)) {
return false;
}
if (fileVersion == 1) {
return _loadJsonMissionFileV1(vehicle, json, visualItems, errorString);
} else {
return _loadJsonMissionFileV2(vehicle, json, visualItems, errorString);
}
}
bool MissionController::_loadJsonMissionFileV1(Vehicle* vehicle, const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
{
// Validate root object keys
......@@ -612,6 +579,32 @@ bool MissionController::_loadJsonMissionFileV2(Vehicle* vehicle, const QJsonObje
return true;
}
#if 0
bool MissionController::_loadItemsFromJson(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
{
// V1 file format has no file type key and version key is string. Convert to new format.
if (!json.contains(JsonHelper::jsonFileTypeKey)) {
json[JsonHelper::jsonFileTypeKey] = _jsonFileTypeValue;
}
int fileVersion;
if (!JsonHelper::validateQGCJsonFile(json,
_jsonFileTypeValue, // expected file type
1, // minimum supported version
2, // maximum supported version
fileVersion,
errorString)) {
return false;
}
if (fileVersion == 1) {
return _loadJsonMissionFileV1(_activeVehicle, json, visualItems, errorString);
} else {
return _loadJsonMissionFileV2(_activeVehicle, json, visualItems, errorString);
}
}
#endif
bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
{
bool addPlannedHomePosition = false;
......@@ -662,12 +655,15 @@ bool MissionController::_loadTextMissionFile(Vehicle* vehicle, QTextStream& stre
return true;
}
void MissionController::loadFromFile(const QString& filename)
bool MissionController::load(const QJsonObject& json, QString& errorString)
{
QmlObjectListModel* newVisualItems = NULL;
QString errorStr;
QString errorMessage = tr("Mission: %1");
QmlObjectListModel* newVisualItems = new QmlObjectListModel(this);
if (!loadItemsFromFile(_activeVehicle, filename, &newVisualItems)) {
return;
if (!_loadJsonMissionFileV2(_activeVehicle, json, newVisualItems, errorStr)) {
errorString = errorMessage.arg(errorStr);
return false;
}
if (_visualItems) {
......@@ -690,67 +686,13 @@ void MissionController::loadFromFile(const QString& filename)
// Needs a sync to vehicle
setDirty(true);
}
}
bool MissionController::loadItemsFromFile(Vehicle* vehicle, const QString& filename, QmlObjectListModel** visualItems)
{
*visualItems = NULL;
QString errorString;
if (filename.isEmpty()) {
return false;
}
*visualItems = new QmlObjectListModel();
QFile file(filename);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
errorString = file.errorString() + QStringLiteral(" ") + filename;
} else {
QByteArray bytes = file.readAll();
QTextStream stream(&bytes);
QString firstLine = stream.readLine();
if (firstLine.contains(QRegExp("QGC.*WPL"))) {
stream.seek(0);
_loadTextMissionFile(vehicle, stream, *visualItems, errorString);
} else {
_loadJsonMissionFile(vehicle, bytes, *visualItems, errorString);
}
}
if (!errorString.isEmpty()) {
(*visualItems)->deleteLater();
qgcApp()->showMessage(errorString);
return false;
}
return true;
}
void MissionController::saveToFile(const QString& filename)
void MissionController::save(QJsonObject& json)
{
if (filename.isEmpty()) {
return;
}
QString missionFilename = filename;
if (!QFileInfo(filename).fileName().contains(".")) {
missionFilename += QString(".%1").arg(AppSettings::missionFileExtension);
}
QFile file(missionFilename);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
qgcApp()->showMessage(tr("Mission save %1 : %2").arg(filename).arg(file.errorString()));
} else {
QJsonObject missionFileObject; // top level json object
missionFileObject[JsonHelper::jsonVersionKey] = _missionFileVersion;
missionFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue;
json[JsonHelper::jsonVersionKey] = _missionFileVersion;
// Mission settings
......@@ -761,11 +703,11 @@ void MissionController::saveToFile(const QString& filename)
}
QJsonValue coordinateValue;
JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
missionFileObject[_jsonPlannedHomePositionKey] = coordinateValue;
missionFileObject[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
missionFileObject[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
missionFileObject[_jsonCruiseSpeedKey] = _activeVehicle->defaultCruiseSpeed();
missionFileObject[_jsonHoverSpeedKey] = _activeVehicle->defaultHoverSpeed();
json[_jsonPlannedHomePositionKey] = coordinateValue;
json[_jsonFirmwareTypeKey] = _activeVehicle->firmwareType();
json[_jsonVehicleTypeKey] = _activeVehicle->vehicleType();
json[_jsonCruiseSpeedKey] = _activeVehicle->defaultCruiseSpeed();
json[_jsonHoverSpeedKey] = _activeVehicle->defaultHoverSpeed();
// Save the visual items
......@@ -791,16 +733,7 @@ void MissionController::saveToFile(const QString& filename)
}
}
missionFileObject[_jsonItemsKey] = rgJsonMissionItems;
QJsonDocument saveDoc(missionFileObject);
file.write(saveDoc.toJson());
}
// If we are connected to a real vehicle, don't clear dirty bit on saving to file since vehicle is still out of date
if (_activeVehicle->isOfflineEditingVehicle()) {
_visualItems->setDirty(false);
}
json[_jsonItemsKey] = rgJsonMissionItems;
}
void MissionController::_calcPrevWaypointValues(double homeAlt, VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
......@@ -1320,7 +1253,7 @@ void MissionController::_itemCommandChanged(void)
_recalcWaypointLines();
}
void MissionController::_activeVehicleBeingRemoved(void)
void MissionController::activeVehicleBeingRemoved(void)
{
qCDebug(MissionControllerLog) << "MissionController::_activeVehicleBeingRemoved";
......@@ -1337,10 +1270,14 @@ void MissionController::_activeVehicleBeingRemoved(void)
// We always remove all items on vehicle change. This leaves a user model hole:
// If the user has unsaved changes in the Plan view they will lose them
removeAll();
_activeVehicle = NULL;
}
void MissionController::_activeVehicleSet(void)
void MissionController::activeVehicleSet(Vehicle* activeVehicle)
{