Commit 8784c088 authored by DonLakeFlyer's avatar DonLakeFlyer

parent 79b05758
...@@ -33,9 +33,10 @@ Item { ...@@ -33,9 +33,10 @@ Item {
id: _root id: _root
PlanMasterController { PlanMasterController {
id: _planController id: _planController
flyView: true
Component.onCompleted: { Component.onCompleted: {
start(true /* flyView */) start()
mainWindow.planMasterControllerFlyView = _planController mainWindow.planMasterControllerFlyView = _planController
} }
} }
......
...@@ -345,6 +345,8 @@ VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordin ...@@ -345,6 +345,8 @@ VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordin
setCurrentPlanViewSeqNum(newItem->sequenceNumber(), true); setCurrentPlanViewSeqNum(newItem->sequenceNumber(), true);
} }
_firstItemAdded();
return newItem; return newItem;
} }
...@@ -383,6 +385,8 @@ VisualMissionItem* MissionController::insertTakeoffItem(QGeoCoordinate /*coordin ...@@ -383,6 +385,8 @@ VisualMissionItem* MissionController::insertTakeoffItem(QGeoCoordinate /*coordin
setCurrentPlanViewSeqNum(newItem->sequenceNumber(), true); setCurrentPlanViewSeqNum(newItem->sequenceNumber(), true);
} }
_firstItemAdded();
return newItem; return newItem;
} }
...@@ -520,6 +524,7 @@ void MissionController::_insertComplexMissionItemWorker(const QGeoCoordinate& ma ...@@ -520,6 +524,7 @@ void MissionController::_insertComplexMissionItemWorker(const QGeoCoordinate& ma
if (makeCurrentItem) { if (makeCurrentItem) {
setCurrentPlanViewSeqNum(complexItem->sequenceNumber(), true); setCurrentPlanViewSeqNum(complexItem->sequenceNumber(), true);
} }
_firstItemAdded();
} }
void MissionController::removeVisualItem(int viIndex) void MissionController::removeVisualItem(int viIndex)
...@@ -574,6 +579,10 @@ void MissionController::removeVisualItem(int viIndex) ...@@ -574,6 +579,10 @@ void MissionController::removeVisualItem(int viIndex)
setCurrentPlanViewSeqNum(_visualItems->value<VisualMissionItem*>(newVIIndex)->sequenceNumber(), true); setCurrentPlanViewSeqNum(_visualItems->value<VisualMissionItem*>(newVIIndex)->sequenceNumber(), true);
setDirty(true); setDirty(true);
if (_visualItems->count() == 1) {
_allItemsRemoved();
}
} }
void MissionController::removeAll(void) void MissionController::removeAll(void)
...@@ -588,6 +597,7 @@ void MissionController::removeAll(void) ...@@ -588,6 +597,7 @@ void MissionController::removeAll(void)
_initAllVisualItems(); _initAllVisualItems();
setDirty(true); setDirty(true);
_resetMissionFlightStatus(); _resetMissionFlightStatus();
_allItemsRemoved();
} }
} }
...@@ -708,16 +718,28 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec ...@@ -708,16 +718,28 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
qCDebug(MissionControllerLog) << "MissionController::_loadJsonMissionFileV2 itemCount:" << json[_jsonItemsKey].toArray().count(); qCDebug(MissionControllerLog) << "MissionController::_loadJsonMissionFileV2 itemCount:" << json[_jsonItemsKey].toArray().count();
// Mission Settings
AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings();
// Get the firmware/vehicle type from the plan file
MAV_AUTOPILOT planFileFirmwareType = static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt());
MAV_TYPE planFileVehicleType = static_cast<MAV_TYPE> (appSettings->offlineEditingVehicleType()->rawValue().toInt());
if (json.contains(_jsonVehicleTypeKey)) {
planFileVehicleType = static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt());
}
// Update firmware/vehicle offline settings if we aren't connect to a vehicle
if (_masterController->offline()) { if (_masterController->offline()) {
// We only update if offline since if we are online we use the online vehicle settings
appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt()))); appSettings->offlineEditingFirmwareType()->setRawValue(AppSettings::offlineEditingFirmwareTypeFromFirmwareType(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
if (json.contains(_jsonVehicleTypeKey)) { if (json.contains(_jsonVehicleTypeKey)) {
appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt()))); appSettings->offlineEditingVehicleType()->setRawValue(AppSettings::offlineEditingVehicleTypeFromVehicleType(static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt())));
} }
} }
// The controller vehicle always tracks the Plan file firmware/vehicle types so update it
_controllerVehicle->stopTrackingFirmwareVehicleTypeChanges();
_controllerVehicle->_offlineFirmwareTypeSettingChanged(planFileFirmwareType);
_controllerVehicle->_offlineVehicleTypeSettingChanged(planFileVehicleType);
if (json.contains(_jsonCruiseSpeedKey)) { if (json.contains(_jsonCruiseSpeedKey)) {
appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble()); appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
} }
...@@ -968,6 +990,12 @@ void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualI ...@@ -968,6 +990,12 @@ void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualI
MissionController::_scanForAdditionalSettings(_visualItems, _masterController); MissionController::_scanForAdditionalSettings(_visualItems, _masterController);
_initAllVisualItems(); _initAllVisualItems();
if (_visualItems->count() > 1) {
_firstItemAdded();
} else {
_allItemsRemoved();
}
} }
bool MissionController::load(const QJsonObject& json, QString& errorString) bool MissionController::load(const QJsonObject& json, QString& errorString)
...@@ -2532,3 +2560,31 @@ QString MissionController::structureScanComplexItemName(void) const ...@@ -2532,3 +2560,31 @@ QString MissionController::structureScanComplexItemName(void) const
{ {
return StructureScanComplexItem::name; return StructureScanComplexItem::name;
} }
void MissionController::_allItemsRemoved(void)
{
// When there are no mission items we track changes to firmware/vehicle type. This allows a vehicle connection
// to adjust these items.
_controllerVehicle->trackFirmwareVehicleTypeChanges();
}
void MissionController::_firstItemAdded(void)
{
// As soon as the first item is added we lock the firmware/vehicle type to current values. So if you then connect a vehicle
// it will not affect these values.
_controllerVehicle->stopTrackingFirmwareVehicleTypeChanges();
}
MissionController::SendToVehiclePreCheckState MissionController::sendToVehiclePreCheck(void)
{
if (_managerVehicle->isOfflineEditingVehicle()) {
return SendToVehiclePreCheckStateNoActiveVehicle;
}
if (_managerVehicle->armed() && _managerVehicle->flightMode() == _managerVehicle->missionFlightMode()) {
return SendToVehiclePreCheckStateActiveMission;
}
if (_controllerVehicle->firmwareType() != _managerVehicle->firmwareType() || _controllerVehicle->vehicleType() != _managerVehicle->vehicleType()) {
return SendToVehiclePreCheckStateFirwmareVehicleMismatch;
}
return SendToVehiclePreCheckStateOk;
}
...@@ -167,6 +167,16 @@ public: ...@@ -167,6 +167,16 @@ public:
/// @param sequenceNumber - index for new item, -1 to clear current item /// @param sequenceNumber - index for new item, -1 to clear current item
Q_INVOKABLE void setCurrentPlanViewSeqNum(int sequenceNumber, bool force); Q_INVOKABLE void setCurrentPlanViewSeqNum(int sequenceNumber, bool force);
enum SendToVehiclePreCheckState {
SendToVehiclePreCheckStateOk, // Ok to send plan to vehicle
SendToVehiclePreCheckStateNoActiveVehicle, // There is no active vehicle
SendToVehiclePreCheckStateFirwmareVehicleMismatch, // Firmware/Vehicle type for plan mismatch with actual vehicle
SendToVehiclePreCheckStateActiveMission, // Vehicle is currently flying a mission
};
Q_ENUM(SendToVehiclePreCheckState)
Q_INVOKABLE SendToVehiclePreCheckState sendToVehiclePreCheck(void);
/// Determines if the mission has all data needed to be saved or sent to the vehicle. /// Determines if the mission has all data needed to be saved or sent to the vehicle.
/// IMPORTANT NOTE: The return value is a VisualMissionItem::ReadForSaveState value. It is an int here to work around /// IMPORTANT NOTE: The return value is a VisualMissionItem::ReadForSaveState value. It is an int here to work around
/// a nightmare of circular header dependency problems. /// a nightmare of circular header dependency problems.
...@@ -328,6 +338,8 @@ private: ...@@ -328,6 +338,8 @@ private:
bool _isROIBeginItem (SimpleMissionItem* simpleItem); bool _isROIBeginItem (SimpleMissionItem* simpleItem);
bool _isROICancelItem (SimpleMissionItem* simpleItem); bool _isROICancelItem (SimpleMissionItem* simpleItem);
FlightPathSegment* _createFlightPathSegmentWorker (VisualItemPair& pair); FlightPathSegment* _createFlightPathSegmentWorker (VisualItemPair& pair);
void _allItemsRemoved (void);
void _firstItemAdded (void);
static double _calcDistanceToHome (VisualMissionItem* currentItem, VisualMissionItem* homeItem); static double _calcDistanceToHome (VisualMissionItem* currentItem, VisualMissionItem* homeItem);
static double _normalizeLat (double lat); static double _normalizeLat (double lat);
......
...@@ -52,13 +52,14 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType) ...@@ -52,13 +52,14 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
// Master controller pulls offline vehicle info from settings // Master controller pulls offline vehicle info from settings
qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->setRawValue(firmwareType); qgcApp()->toolbox()->settingsManager()->appSettings()->offlineEditingFirmwareType()->setRawValue(firmwareType);
_masterController = new PlanMasterController(this); _masterController = new PlanMasterController(this);
_masterController->setFlyView(false);
_missionController = _masterController->missionController(); _missionController = _masterController->missionController();
_multiSpyMissionController = new MultiSignalSpy(); _multiSpyMissionController = new MultiSignalSpy();
Q_CHECK_PTR(_multiSpyMissionController); Q_CHECK_PTR(_multiSpyMissionController);
QCOMPARE(_multiSpyMissionController->init(_missionController, _rgMissionControllerSignals, _cMissionControllerSignals), true); QCOMPARE(_multiSpyMissionController->init(_missionController, _rgMissionControllerSignals, _cMissionControllerSignals), true);
_masterController->start(false /* flyView */); _masterController->start();
// All signals should some through on start // All signals should some through on start
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(visualItemsChangedSignalMask), true); QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(visualItemsChangedSignalMask), true);
......
...@@ -39,11 +39,7 @@ const char* PlanMasterController::kJsonRallyPointsObjectKey = "rallyPoints"; ...@@ -39,11 +39,7 @@ const char* PlanMasterController::kJsonRallyPointsObjectKey = "rallyPoints";
PlanMasterController::PlanMasterController(QObject* parent) PlanMasterController::PlanMasterController(QObject* parent)
: QObject (parent) : QObject (parent)
, _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager()) , _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager())
, _controllerVehicle (new Vehicle( , _controllerVehicle (new Vehicle(Vehicle::MAV_AUTOPILOT_TRACK, Vehicle::MAV_TYPE_TRACK, qgcApp()->toolbox()->firmwarePluginManager(), this))
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) , _managerVehicle (_controllerVehicle)
, _missionController (this) , _missionController (this)
, _geoFenceController (this) , _geoFenceController (this)
...@@ -94,12 +90,11 @@ PlanMasterController::~PlanMasterController() ...@@ -94,12 +90,11 @@ PlanMasterController::~PlanMasterController()
} }
void PlanMasterController::start(bool flyView) void PlanMasterController::start(void)
{ {
_flyView = flyView; _missionController.start (_flyView);
_missionController.start(_flyView); _geoFenceController.start (_flyView);
_geoFenceController.start(_flyView); _rallyPointController.start (_flyView);
_rallyPointController.start(_flyView);
_activeVehicleChanged(_multiVehicleMgr->activeVehicle()); _activeVehicleChanged(_multiVehicleMgr->activeVehicle());
connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanMasterController::_activeVehicleChanged); connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanMasterController::_activeVehicleChanged);
......
...@@ -35,6 +35,7 @@ public: ...@@ -35,6 +35,7 @@ public:
~PlanMasterController(); ~PlanMasterController();
Q_PROPERTY(bool flyView MEMBER _flyView)
Q_PROPERTY(Vehicle* controllerVehicle READ controllerVehicle CONSTANT) ///< Offline controller vehicle 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(Vehicle* managerVehicle READ managerVehicle NOTIFY managerVehicleChanged) ///< Either active vehicle or _controllerVehicle if no active vehicle
Q_PROPERTY(MissionController* missionController READ missionController CONSTANT) Q_PROPERTY(MissionController* missionController READ missionController CONSTANT)
...@@ -53,7 +54,7 @@ public: ...@@ -53,7 +54,7 @@ public:
Q_PROPERTY(bool supportsTerrain READ supportsTerrain NOTIFY supportsTerrainChanged) Q_PROPERTY(bool supportsTerrain READ supportsTerrain NOTIFY supportsTerrainChanged)
/// Should be called immediately upon Component.onCompleted. /// Should be called immediately upon Component.onCompleted.
Q_INVOKABLE void start(bool flyView); Q_INVOKABLE void start(void);
/// Starts the controller using a single static active vehicle. Will not track global active vehicle changes. /// Starts the controller using a single static active vehicle. Will not track global active vehicle changes.
/// @param deleteWhenSendCmplete The PlanMasterController object should be deleted after the first send is completed. /// @param deleteWhenSendCmplete The PlanMasterController object should be deleted after the first send is completed.
...@@ -95,6 +96,8 @@ public: ...@@ -95,6 +96,8 @@ public:
bool isEmpty (void) const; bool isEmpty (void) const;
bool supportsTerrain (void) const { return _supportsTerrain; } bool supportsTerrain (void) const { return _supportsTerrain; }
void setFlyView(bool flyView) { _flyView = flyView; }
QJsonDocument saveToJson (); QJsonDocument saveToJson ();
Vehicle* controllerVehicle(void) { return _controllerVehicle; } Vehicle* controllerVehicle(void) { return _controllerVehicle; }
......
...@@ -27,7 +27,8 @@ void PlanMasterControllerTest::init(void) ...@@ -27,7 +27,8 @@ void PlanMasterControllerTest::init(void)
UnitTest::init(); UnitTest::init();
_masterController = new PlanMasterController(this); _masterController = new PlanMasterController(this);
_masterController->start(false /* flyView */); _masterController->setFlyView(false);
_masterController->start();
} }
void PlanMasterControllerTest::cleanup(void) void PlanMasterControllerTest::cleanup(void)
......
...@@ -22,12 +22,11 @@ Rectangle { ...@@ -22,12 +22,11 @@ Rectangle {
property var _masterControler: masterController property var _masterControler: masterController
property var _missionController: _masterControler.missionController property var _missionController: _masterControler.missionController
property var _missionVehicle: _masterControler.controllerVehicle property var _controllerVehicle: _masterControler.controllerVehicle
property bool _vehicleHasHomePosition: _missionVehicle.homePosition.isValid property bool _vehicleHasHomePosition: _controllerVehicle.homePosition.isValid
property bool _offlineEditing: _missionVehicle.isOfflineEditingVehicle property bool _enableOfflineVehicleCombos: _noMissionItemsAdded
property bool _enableOfflineVehicleCombos: _offlineEditing && _noMissionItemsAdded property bool _showCruiseSpeed: !_controllerVehicle.multiRotor
property bool _showCruiseSpeed: !_missionVehicle.multiRotor property bool _showHoverSpeed: _controllerVehicle.multiRotor || _controllerVehicle.vtol
property bool _showHoverSpeed: _missionVehicle.multiRotor || _missionVehicle.vtol
property bool _multipleFirmware: QGroundControl.supportedFirmwareCount > 2 property bool _multipleFirmware: QGroundControl.supportedFirmwareCount > 2
property bool _multipleVehicleTypes: QGroundControl.supportedVehicleCount > 1 property bool _multipleVehicleTypes: QGroundControl.supportedVehicleCount > 1
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 16 property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 16
...@@ -36,9 +35,9 @@ Rectangle { ...@@ -36,9 +35,9 @@ Rectangle {
property var _fileExtension: QGroundControl.settingsManager.appSettings.missionFileExtension property var _fileExtension: QGroundControl.settingsManager.appSettings.missionFileExtension
property var _appSettings: QGroundControl.settingsManager.appSettings property var _appSettings: QGroundControl.settingsManager.appSettings
property bool _waypointsOnlyMode: QGroundControl.corePlugin.options.missionWaypointsOnly property bool _waypointsOnlyMode: QGroundControl.corePlugin.options.missionWaypointsOnly
property bool _showCameraSection: (_waypointsOnlyMode || QGroundControl.corePlugin.showAdvancedUI) && !_missionVehicle.apmFirmware property bool _showCameraSection: (_waypointsOnlyMode || QGroundControl.corePlugin.showAdvancedUI) && !_controllerVehicle.apmFirmware
property bool _simpleMissionStart: QGroundControl.corePlugin.options.showSimpleMissionStart property bool _simpleMissionStart: QGroundControl.corePlugin.options.showSimpleMissionStart
property bool _showFlightSpeed: !_missionVehicle.vtol && !_simpleMissionStart && !_missionVehicle.apmFirmware property bool _showFlightSpeed: !_controllerVehicle.vtol && !_simpleMissionStart && !_controllerVehicle.apmFirmware
readonly property string _firmwareLabel: qsTr("Firmware") readonly property string _firmwareLabel: qsTr("Firmware")
readonly property string _vehicleLabel: qsTr("Vehicle") readonly property string _vehicleLabel: qsTr("Vehicle")
...@@ -112,7 +111,7 @@ Rectangle { ...@@ -112,7 +111,7 @@ Rectangle {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
text: qsTr("Vehicle Info") text: qsTr("Vehicle Info")
visible: _offlineEditing && !_waypointsOnlyMode visible: !_waypointsOnlyMode
checked: false checked: false
} }
...@@ -133,8 +132,11 @@ Rectangle { ...@@ -133,8 +132,11 @@ Rectangle {
fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType fact: QGroundControl.settingsManager.appSettings.offlineEditingFirmwareType
indexModel: false indexModel: false
Layout.preferredWidth: _fieldWidth Layout.preferredWidth: _fieldWidth
visible: _multipleFirmware visible: _multipleFirmware && _enableOfflineVehicleCombos
enabled: _enableOfflineVehicleCombos }
QGCLabel {
text: _controllerVehicle.firmwareTypeString
visible: _multipleFirmware && !_enableOfflineVehicleCombos
} }
QGCLabel { QGCLabel {
...@@ -146,8 +148,11 @@ Rectangle { ...@@ -146,8 +148,11 @@ Rectangle {
fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType fact: QGroundControl.settingsManager.appSettings.offlineEditingVehicleType
indexModel: false indexModel: false
Layout.preferredWidth: _fieldWidth Layout.preferredWidth: _fieldWidth
visible: _multipleVehicleTypes visible: _multipleVehicleTypes && _enableOfflineVehicleCombos
enabled: _enableOfflineVehicleCombos }
QGCLabel {
text: _controllerVehicle.vehicleTypeString
visible: _multipleVehicleTypes && !_enableOfflineVehicleCombos
} }
QGCLabel { QGCLabel {
......
...@@ -135,29 +135,16 @@ Item { ...@@ -135,29 +135,16 @@ Item {
} }
Component { Component {
id: activeMissionUploadDialogComponent id: firmwareOrVehicleMismatchUploadDialogComponent
QGCViewDialog { QGCViewMessage {
Column { message: qsTr("This Plan was created for a different firmware or vehicle type than the firmware/vehicle type of vehicle you are uploading to. " +
anchors.fill: parent "This can lead to errors or incorrect behavior. " +
spacing: ScreenTools.defaultFontPixelHeight "It is recommended to recreate the Plan for the correct firmware/vehicle type.\n\n" +
QGCLabel { "Click 'Ok' to upload the Plan anyway.")
width: parent.width
wrapMode: Text.WordWrap function accept() {
text: qsTr("Your vehicle is currently flying a mission. In order to upload a new or modified mission the current mission will be paused.") _planMasterController.sendToVehicle()
} hideDialog()
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: qsTr("After the mission is uploaded you can adjust the current waypoint and start the mission.")
}
QGCButton {
text: qsTr("Pause and Upload")
onClicked: {
activeVehicle.flightMode = activeVehicle.pauseFlightMode
_planMasterController.sendToVehicle()
hideDialog()
}
}
} }
} }
} }
...@@ -177,10 +164,11 @@ Item { ...@@ -177,10 +164,11 @@ Item {
} }
PlanMasterController { PlanMasterController {
id: _planMasterController id: _planMasterController
flyView: false
Component.onCompleted: { Component.onCompleted: {
_planMasterController.start(false /* flyView */) _planMasterController.start()
_missionController.setCurrentPlanViewSeqNum(0, true) _missionController.setCurrentPlanViewSeqNum(0, true)
mainWindow.planMasterControllerPlanView = _planMasterController mainWindow.planMasterControllerPlanView = _planMasterController
} }
...@@ -210,10 +198,16 @@ Item { ...@@ -210,10 +198,16 @@ Item {
if (!checkReadyForSaveUpload(false /* save */)) { if (!checkReadyForSaveUpload(false /* save */)) {
return return
} }
if (activeVehicle && activeVehicle.armed && activeVehicle.flightMode === activeVehicle.missionFlightMode) { switch (_missionController.sendToVehiclePreCheck()) {
mainWindow.showComponentDialog(activeMissionUploadDialogComponent, qsTr("Plan Upload"), mainWindow.showDialogDefaultWidth, StandardButton.Cancel) case MissionController.SendToVehiclePreCheckStateOk:
} else { sendToVehicle()
sendToVehicle() break
case MissionController.SendToVehiclePreCheckStateActiveMission:
mainWindow.showMessageDialog(qsTr("Send To Vehicle"), qsTr("Current mission must be paused prior to uploading a new Plan"))
break
case MissionController.SendToVehiclePreCheckStateFirwmareVehicleMismatch:
mainWindow.showComponentDialog(firmwareOrVehicleMismatchUploadDialogComponent, qsTr("Plan Upload"), mainWindow.showDialogDefaultWidth, StandardButton.Ok | StandardButton.Cancel)
break
} }
} }
......
...@@ -43,5 +43,4 @@ Item { ...@@ -43,5 +43,4 @@ Item {
hideDialog() hideDialog()
} }
} }
} }
...@@ -64,11 +64,7 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox) ...@@ -64,11 +64,7 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo); connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo);
SettingsManager* settingsManager = toolbox->settingsManager(); _offlineEditingVehicle = new Vehicle(Vehicle::MAV_AUTOPILOT_TRACK, Vehicle::MAV_TYPE_TRACK, _firmwarePluginManager, this);
_offlineEditingVehicle = new Vehicle(static_cast<MAV_AUTOPILOT>(settingsManager->appSettings()->offlineEditingFirmwareType()->rawValue().toInt()),
static_cast<MAV_TYPE>(settingsManager->appSettings()->offlineEditingVehicleType()->rawValue().toInt()),
_firmwarePluginManager,
this);
} }
void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType) void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType)
......
...@@ -430,18 +430,31 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -430,18 +430,31 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
{ {
_commonInit(); _commonInit();
// Offline editing vehicle tracks settings changes for offline editing settings if (_firmwareType == MAV_AUTOPILOT_TRACK) {
connect(_settingsManager->appSettings()->offlineEditingFirmwareType(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged); trackFirmwareVehicleTypeChanges();
connect(_settingsManager->appSettings()->offlineEditingVehicleType(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged); }
connect(_settingsManager->appSettings()->offlineEditingCruiseSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineCruiseSpeedSettingChanged); connect(_settingsManager->appSettings()->offlineEditingCruiseSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineCruiseSpeedSettingChanged);
connect(_settingsManager->appSettings()->offlineEditingHoverSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineHoverSpeedSettingChanged); connect(_settingsManager->appSettings()->offlineEditingHoverSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineHoverSpeedSettingChanged);
// This add correct terrain capability bit _offlineFirmwareTypeSettingChanged(_firmwareType); // This adds correct terrain capability bit
_offlineFirmwareTypeSettingChanged(_firmwareType);
_firmwarePlugin->initializeVehicle(this); _firmwarePlugin->initializeVehicle(this);
} }
void Vehicle::trackFirmwareVehicleTypeChanges(void)
{
connect(_settingsManager->appSettings()->offlineEditingFirmwareType(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
connect(_settingsManager->appSettings()->offlineEditingVehicleType(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
_offlineFirmwareTypeSettingChanged(_settingsManager->appSettings()->offlineEditingFirmwareType()->rawValue());
_offlineVehicleTypeSettingChanged(_settingsManager->appSettings()->offlineEditingVehicleType()->rawValue());
}
void Vehicle::stopTrackingFirmwareVehicleTypeChanges(void)
{
disconnect(_settingsManager->appSettings()->offlineEditingFirmwareType(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
disconnect(_settingsManager->appSettings()->offlineEditingVehicleType(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
}
void Vehicle::_commonInit() void Vehicle::_commonInit()
{ {
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType); _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
......
...@@ -487,6 +487,10 @@ public: ...@@ -487,6 +487,10 @@ public:
FirmwarePluginManager* firmwarePluginManager, FirmwarePluginManager* firmwarePluginManager,
JoystickManager* joystickManager); JoystickManager* joystickManager);
// Pass these into the offline constructor to create an offline vehicle which tracks the offline vehicle settings
static const MAV_AUTOPILOT MAV_AUTOPILOT_TRACK = static_cast<MAV_AUTOPILOT>(-1);
static const MAV_TYPE MAV_TYPE_TRACK = static_cast<MAV_TYPE>(-1);
// The following is used to create a disconnected Vehicle for use while offline editing. // The following is used to create a disconnected Vehicle for use while offline editing.
Vehicle(MAV_AUTOPILOT firmwareType, Vehicle(MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType, MAV_TYPE vehicleType,
...@@ -907,6 +911,10 @@ public: ...@@ -907,6 +911,10 @@ public:
/// @param sendMultiple Send multiple time to guarantee Vehicle reception /// @param sendMultiple Send multiple time to guarantee Vehicle reception
void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple = true); void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple = true);
// The follow method are used to turn on/off the tracking of settings updates for firmware/vehicle type on offline vehicles.
void trackFirmwareVehicleTypeChanges(void);
void stopTrackingFirmwareVehicleTypeChanges(void);
typedef enum { typedef enum {
MessageNone, MessageNone,
MessageNormal, MessageNormal,
...@@ -1130,7 +1138,9 @@ public: ...@@ -1130,7 +1138,9 @@ public:
void setCheckListState (CheckList cl) { _checkListState = cl; emit checkListStateChanged(); } void setCheckListState (CheckList cl) { _checkListState = cl; emit checkListStateChanged(); }
public slots: public slots:
void setVtolInFwdFlight (bool vtolInFwdFlight); void setVtolInFwdFlight (bool vtolInFwdFlight);
void _offlineFirmwareTypeSettingChanged (QVariant value); // Should only be used by MissionControler to set firmware from Plan file
void _offlineVehicleTypeSettingChanged (QVariant value); // Should only be used by MissionController to set vehicle type from Plan file
signals: signals:
void allLinksInactive (Vehicle* vehicle); void allLinksInactive (Vehicle* vehicle);
...@@ -1254,8 +1264,6 @@ private slots: ...@@ -1254,8 +1264,6 @@ private slots:
void _remoteControlRSSIChanged (uint8_t rssi); void _remoteControlRSSIChanged (uint8_t rssi);
void _handleFlightModeChanged (const QString& flightMode); void _handleFlightModeChanged (const QString& flightMode);
void _announceArmedChanged (bool armed); void _announceArmedChanged (bool armed);
void _offlineFirmwareTypeSettingChanged(QVariant value);
void _offlineVehicleTypeSettingChanged(QVariant value);
void _offlineCruiseSpeedSettingChanged(QVariant value); void _offlineCruiseSpeedSettingChanged(QVariant value);
void _offlineHoverSpeedSettingChanged(QVariant value); void _offlineHoverSpeedSettingChanged(QVariant value);
void _updateHighLatencyLink (bool sendCommand = true); void _updateHighLatencyLink (bool sendCommand = true);
......
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