Commit f0bd33ef authored by Don Gagne's avatar Don Gagne

Add support for APM Mission quirks

Also merged MissionController and MissionEditorController into single
MissionController implementation
parent 9866b603
......@@ -228,7 +228,6 @@ HEADERS += \
src/Joystick/JoystickManager.h \
src/LogCompressor.h \
src/MG.h \
src/MissionEditor/MissionEditorController.h \
src/MissionManager/MissionManager.h \
src/MissionManager/MissionController.h \
src/QGC.h \
......@@ -347,7 +346,6 @@ SOURCES += \
src/Joystick/JoystickManager.cc \
src/LogCompressor.cc \
src/main.cc \
src/MissionEditor/MissionEditorController.cc \
src/MissionManager/MissionManager.cc \
src/MissionManager/MissionController.cc \
src/QGC.cc \
......
......@@ -45,7 +45,7 @@ void FactSystemTestBase::_init(MAV_AUTOPILOT autopilot)
UnitTest::init();
MockLink* link = new MockLink();
link->setAutopilotType(autopilot);
link->setFirmwareType(autopilot);
LinkManager::instance()->_addLink(link);
LinkManager::instance()->connectLink(link);
......
......@@ -73,21 +73,26 @@ Item {
readonly property var _flightMap: flightMap
property real _roll: _activeVehicle ? (isNaN(_activeVehicle.roll) ? _defaultRoll : _activeVehicle.roll) : _defaultRoll
property real _pitch: _activeVehicle ? (isNaN(_activeVehicle.pitch) ? _defaultPitch : _activeVehicle.pitch) : _defaultPitch
property real _heading: _activeVehicle ? (isNaN(_activeVehicle.heading) ? _defaultHeading : _activeVehicle.heading) : _defaultHeading
property real _roll: _activeVehicle ? (isNaN(_activeVehicle.roll) ? _defaultRoll : _activeVehicle.roll) : _defaultRoll
property real _pitch: _activeVehicle ? (isNaN(_activeVehicle.pitch) ? _defaultPitch : _activeVehicle.pitch) : _defaultPitch
property real _heading: _activeVehicle ? (isNaN(_activeVehicle.heading) ? _defaultHeading : _activeVehicle.heading) : _defaultHeading
property var _vehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : _defaultVehicleCoordinate
property var _vehicleCoordinate: _activeVehicle ? (_activeVehicle.satelliteLock >= 2 ? _activeVehicle.coordinate : _defaultVehicleCoordinate) : _defaultVehicleCoordinate
property real _altitudeWGS84: _activeVehicle ? _activeVehicle.altitudeWGS84 : _defaultAltitudeWGS84
property real _groundSpeed: _activeVehicle ? _activeVehicle.groundSpeed : _defaultGroundSpeed
property real _airSpeed: _activeVehicle ? _activeVehicle.airSpeed : _defaultAirSpeed
property real _climbRate: _activeVehicle ? _activeVehicle.climbRate : _defaultClimbRate
property real _altitudeWGS84: _activeVehicle ? _activeVehicle.altitudeWGS84 : _defaultAltitudeWGS84
property real _groundSpeed: _activeVehicle ? _activeVehicle.groundSpeed : _defaultGroundSpeed
property real _airSpeed: _activeVehicle ? _activeVehicle.airSpeed : _defaultAirSpeed
property real _climbRate: _activeVehicle ? _activeVehicle.climbRate : _defaultClimbRate
property bool _showMap: getBool(QGroundControl.flightMapSettings.loadMapSetting(flightMap.mapName, _showMapBackgroundKey, "1"))
FlightDisplayViewController { id: _controller }
MissionController { id: _missionController }
MissionController {
id: _missionController
Component.onCompleted: start(false /* editMode */)
}
ExclusiveGroup {
id: _dropButtonsExclusiveGroup
......
......@@ -54,24 +54,27 @@ QGCView {
readonly property string _autoSyncKey: "AutoSync"
readonly property string _showHelpKey: "ShowHelp"
readonly property int _addMissionItemsButtonAutoOffTimeout: 10000
readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276)
property var _missionItems: controller.missionItems
property var _homePositionManager: QGroundControl.homePositionManager
property string _homePositionName: _homePositionManager.homePositions.get(0).name
//property var _homePositionManager: QGroundControl.homePositionManager
//property string _homePositionName: _homePositionManager.homePositions.get(0).name
//property var offlineHomePosition: _homePositionManager.homePositions.get(0).coordinate
property var liveHomePosition: controller.liveHomePosition
property var liveHomePositionAvailable: controller.liveHomePositionAvailable
//property var homePosition: offlineHomePosition // live or offline depending on state
property var homePosition: _defaultVehicleCoordinate
property bool _syncNeeded: controller.missionItems.dirty
property bool _syncInProgress: _activeVehicle ? _activeVehicle.missionManager.inProgress : false
property bool _showHelp: QGroundControl.flightMapSettings.loadBoolMapSetting(editorMap.mapName, _showHelpKey, true)
MissionEditorController {
MissionController {
id: controller
Component.onCompleted: start(true /* editMode */)
/*
FIXME: autoSync is temporarily disconnected since it's still buggy
......@@ -104,6 +107,7 @@ QGCView {
function updateHomePosition() {
if (liveHomePositionAvailable) {
homePosition = liveHomePosition
_missionItems.get(0).coordinate = liveHomePosition
_missionItems.get(0).homePositionValid = true
}
......@@ -282,8 +286,8 @@ QGCView {
}
} // Item - Mission Item editor
/*
Home Position Manager is commented out for now until a better implementation is completed
/*
Home Position Manager temporarily disbled till more work is done on it
// Home Position Manager
Rectangle {
......@@ -556,7 +560,7 @@ Home Position Manager is commented out for now until a better implementation is
}
} // Column - Online view
} // Item - Home Position Manager
*/
*/
// Help Panel
Rectangle {
......@@ -656,7 +660,7 @@ Home Position Manager is commented out for now until a better implementation is
}
/*
Home Position Manager commented until more complete implementation is done
Home Position Manager disabled
Image {
id: homePositionManagerHelpIcon
......@@ -680,7 +684,7 @@ Home Position Manager is commented out for now until a better implementation is
"When enabled, allows you to select/add/update flying field locations. " +
"You can save multiple flying field locations for use while creating missions while you are not connected to your vehicle."
}
*/
*/
Image {
id: mapCenterHelpIcon
......@@ -803,8 +807,7 @@ Home Position Manager is commented out for now until a better implementation is
}
/*
Home Position Manager commented until more complete implementation is done
Home Position manager temporarily disable
RoundButton {
id: homePositionManagerButton
anchors.margins: _margin
......
This diff is collapsed.
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef MissionEditorController_H
#define MissionEditorController_H
#include <QObject>
#include "QmlObjectListModel.h"
#include "Vehicle.h"
class MissionEditorController : public QObject
{
Q_OBJECT
public:
MissionEditorController(QObject* parent = NULL);
~MissionEditorController();
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(bool canEdit READ canEdit NOTIFY canEditChanged)
Q_PROPERTY(bool liveHomePositionAvailable READ liveHomePositionAvailable NOTIFY liveHomePositionAvailableChanged)
Q_PROPERTY(QGeoCoordinate liveHomePosition READ liveHomePosition NOTIFY liveHomePositionChanged)
Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged)
Q_INVOKABLE int addMissionItem(QGeoCoordinate coordinate);
Q_INVOKABLE void getMissionItems(void);
Q_INVOKABLE void sendMissionItems(void);
Q_INVOKABLE void loadMissionFromFile(void);
Q_INVOKABLE void saveMissionToFile(void);
Q_INVOKABLE void removeMissionItem(int index);
Q_INVOKABLE void deleteCurrentMissionItem(void);
// Property accessors
QmlObjectListModel* missionItems(void);
QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
bool canEdit(void) { return _canEdit; }
bool liveHomePositionAvailable(void) { return _liveHomePositionAvailable; }
QGeoCoordinate liveHomePosition(void) { return _liveHomePosition; }
bool autoSync(void) { return _autoSync; }
void setAutoSync(bool autoSync);
signals:
void missionItemsChanged(void);
void canEditChanged(bool canEdit);
void waypointLinesChanged(void);
void liveHomePositionAvailableChanged(bool homePositionAvailable);
void liveHomePositionChanged(const QGeoCoordinate& homePosition);
void autoSyncChanged(bool autoSync);
private slots:
void _newMissionItemsAvailable();
void _itemCoordinateChanged(const QGeoCoordinate& coordinate);
void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void _activeVehicleChanged(Vehicle* activeVehicle);
void _activeVehicleHomePositionAvailableChanged(bool homePositionAvailable);
void _activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition);
void _dirtyChanged(bool dirty);
void _inProgressChanged(bool inProgress);
private:
void _recalcSequence(void);
void _recalcWaypointLines(void);
void _recalcChildItems(void);
void _recalcAll(void);
void _initAllMissionItems(void);
void _deinitAllMissionItems(void);
void _initMissionItem(MissionItem* item);
void _deinitMissionItem(MissionItem* item);
void _autoSyncSend(void);
private:
QmlObjectListModel* _missionItems;
QmlObjectListModel _waypointLines;
bool _canEdit; ///< true: UI can edit these items, false: can't edit, can only send to vehicle or save
Vehicle* _activeVehicle;
bool _liveHomePositionAvailable;
QGeoCoordinate _liveHomePosition;
bool _autoSync;
bool _firstMissionItemSync;
bool _missionItemsRequested;
bool _queuedSend;
static const char* _settingsGroup;
};
#endif
......@@ -86,7 +86,7 @@ public:
Q_PROPERTY(QmlObjectListModel* childItems READ childItems CONSTANT)
/// true: this item is being used as a home position indicator
Q_PROPERTY(bool homePosition MEMBER _homePositionSpecialCase CONSTANT)
Q_PROPERTY(bool homePosition READ homePosition CONSTANT)
/// true: home position should be shown
Q_PROPERTY(bool homePositionValid READ homePositionValid WRITE setHomePositionValid NOTIFY homePositionValidChanged)
......@@ -131,6 +131,7 @@ public:
QmlObjectListModel* childItems(void) { return &_childItems; }
bool homePosition(void) { return _homePositionSpecialCase; }
bool homePositionValid(void) { return _homePositionValid; }
void setHomePositionValid(bool homePositionValid);
......
This diff is collapsed.
......@@ -29,37 +29,57 @@ This file is part of the QGROUNDCONTROL project
#include "QmlObjectListModel.h"
#include "Vehicle.h"
/// MissionController is a read only controller for Mission Items
class MissionController : public QObject
{
Q_OBJECT
public:
MissionController(QObject* parent = NULL);
~MissionController();
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(bool canEdit READ canEdit NOTIFY canEditChanged)
Q_PROPERTY(bool liveHomePositionAvailable READ liveHomePositionAvailable NOTIFY liveHomePositionAvailableChanged)
Q_PROPERTY(QGeoCoordinate liveHomePosition READ liveHomePosition NOTIFY liveHomePositionChanged)
Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged)
Q_INVOKABLE void start(bool editMode) ;
Q_INVOKABLE int addMissionItem(QGeoCoordinate coordinate);
Q_INVOKABLE void getMissionItems(void);
Q_INVOKABLE void sendMissionItems(void);
Q_INVOKABLE void loadMissionFromFile(void);
Q_INVOKABLE void saveMissionToFile(void);
Q_INVOKABLE void removeMissionItem(int index);
Q_INVOKABLE void deleteCurrentMissionItem(void);
/// true: home position should be shown on map, false: home position not shown on map
Q_PROPERTY(bool homePositionValid READ homePositionValid WRITE setHomePositionValid NOTIFY homePositionValidChanged)
// Property accessors
QmlObjectListModel* missionItems(void) { return _missionItems; }
QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
bool homePositionValid(void) { return _homePositionValid; }
void setHomePositionValid(bool homPositionValid);
QmlObjectListModel* missionItems(void);
QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
bool canEdit(void) { return _canEdit; }
bool liveHomePositionAvailable(void) { return _liveHomePositionAvailable; }
QGeoCoordinate liveHomePosition(void) { return _liveHomePosition; }
bool autoSync(void) { return _autoSync; }
void setAutoSync(bool autoSync);
signals:
void missionItemsChanged(void);
void canEditChanged(bool canEdit);
void waypointLinesChanged(void);
void homePositionValidChanged(bool homePositionValid);
void liveHomePositionAvailableChanged(bool homePositionAvailable);
void liveHomePositionChanged(const QGeoCoordinate& homePosition);
void autoSyncChanged(bool autoSync);
private slots:
void _newMissionItemsAvailable();
void _itemCoordinateChanged(const QGeoCoordinate& coordinate);
void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void _activeVehicleChanged(Vehicle* activeVehicle);
void _activeVehicleHomePositionAvailableChanged(bool homePositionAvailable);
void _activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition);
void _dirtyChanged(bool dirty);
void _inProgressChanged(bool inProgress);
private:
void _recalcSequence(void);
......@@ -67,12 +87,25 @@ private:
void _recalcChildItems(void);
void _recalcAll(void);
void _initAllMissionItems(void);
void _deinitAllMissionItems(void);
void _initMissionItem(MissionItem* item);
void _deinitMissionItem(MissionItem* item);
void _autoSyncSend(void);
private:
bool _editMode;
QmlObjectListModel* _missionItems;
QmlObjectListModel _waypointLines;
bool _canEdit; ///< true: UI can edit these items, false: can't edit, can only send to vehicle or save
Vehicle* _activeVehicle;
bool _homePositionValid;
bool _liveHomePositionAvailable;
QGeoCoordinate _liveHomePosition;
bool _autoSync;
bool _firstMissionItemSync;
bool _missionItemsRequested;
bool _queuedSend;
static const char* _settingsGroup;
};
#endif
......@@ -26,6 +26,7 @@
#include "MissionManager.h"
#include "Vehicle.h"
#include "FirmwarePlugin.h"
#include "MAVLinkProtocol.h"
QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")
......@@ -53,8 +54,10 @@ MissionManager::~MissionManager()
}
void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems, bool skipFirstItem)
void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
{
bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();
_retryCount = 0;
_missionItems.clear();
......@@ -65,10 +68,12 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems, b
MissionItem* item = qobject_cast<MissionItem*>(_missionItems.get(_missionItems.count() - 1));
// Editor uses 1-based sequence numbers, adjust them before going out
item->setSequenceNumber(item->sequenceNumber() - 1);
if (item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
item->setParam1((int)item->param1() - 1);
if (skipFirstItem) {
// Home is in sequence 1, remainder of items start at sequence 1
item->setSequenceNumber(item->sequenceNumber() - 1);
if (item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
item->setParam1((int)item->param1() - 1);
}
}
}
emit newMissionItemsAvailable();
......@@ -200,9 +205,9 @@ bool MissionManager::_stopAckTimeout(AckType_t expectedAck)
return success;
}
void MissionManager::_sendTransactionComplete(void)
void MissionManager::_readTransactionComplete(void)
{
qCDebug(MissionManagerLog) << "_sendTransactionComplete read sequence complete";
qCDebug(MissionManagerLog) << "_readTransactionComplete read sequence complete";
mavlink_message_t message;
mavlink_mission_ack_t missionAck;
......@@ -233,8 +238,7 @@ void MissionManager::_handleMissionCount(const mavlink_message_t& message)
qCDebug(MissionManagerLog) << "_handleMissionCount count:" << _cMissionItems;
if (_cMissionItems == 0) {
emit newMissionItemsAvailable();
emit inProgressChanged(false);
_readTransactionComplete();
} else {
_requestNextMissionItem(0);
}
......@@ -304,7 +308,7 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
int nextSequenceNumber = missionItem.seq + 1;
if (nextSequenceNumber == _cMissionItems) {
_sendTransactionComplete();
_readTransactionComplete();
} else {
_requestNextMissionItem(nextSequenceNumber);
}
......
......@@ -63,8 +63,7 @@ public:
/// Writes the specified set of mission items to the vehicle
/// @oaram missionItems Items to send to vehicle
/// @param skipFirstItem true: Don't send first item
void writeMissionItems(const QmlObjectListModel& missionItems, bool skipFirstItem);
void writeMissionItems(const QmlObjectListModel& missionItems);
/// Returns a copy of the current set of mission items. Caller is responsible for
/// freeing returned object.
......@@ -106,7 +105,7 @@ private:
void _startAckTimeout(AckType_t ack);
bool _stopAckTimeout(AckType_t expectedAck);
void _sendTransactionComplete(void);
void _readTransactionComplete(void);
void _handleMissionCount(const mavlink_message_t& message);
void _handleMissionItem(const mavlink_message_t& message);
void _handleMissionRequest(const mavlink_message_t& message);
......@@ -137,4 +136,4 @@ private:
QmlObjectListModel _missionItems;
};
#endif
\ No newline at end of file
#endif
......@@ -89,7 +89,6 @@
#include "CoordinateVector.h"
#include "MainToolBarController.h"
#include "MissionController.h"
#include "MissionEditorController.h"
#include "FlightDisplayViewController.h"
#include "VideoSurface.h"
#include "VideoReceiver.h"
......@@ -355,7 +354,6 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<ScreenToolsController> ("QGroundControl.Controllers", 1, 0, "ScreenToolsController");
qmlRegisterType<MainToolBarController> ("QGroundControl.Controllers", 1, 0, "MainToolBarController");
qmlRegisterType<MissionController> ("QGroundControl.Controllers", 1, 0, "MissionController");
qmlRegisterType<MissionEditorController> ("QGroundControl.Controllers", 1, 0, "MissionEditorController");
qmlRegisterType<FlightDisplayViewController> ("QGroundControl.Controllers", 1, 0, "FlightDisplayViewController");
#ifndef __mobile__
......
......@@ -60,7 +60,7 @@ void SetupViewTest::_clickThrough_test(void)
MockLink* link = new MockLink();
Q_CHECK_PTR(link);
link->setAutopilotType(MAV_AUTOPILOT_PX4);
link->setFirmwareType(MAV_AUTOPILOT_PX4);
LinkManager::instance()->_addLink(link);
linkMgr->connectLink(link);
......
......@@ -63,7 +63,7 @@ void MainWindowTest::_connectWindowClose_test(MAV_AUTOPILOT autopilot)
MockLink* link = new MockLink();
Q_CHECK_PTR(link);
link->setAutopilotType(autopilot);
link->setFirmwareType(autopilot);
LinkManager::instance()->_addLink(link);
linkMgr->connectLink(link);
......
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