Commit af824e20 authored by Don Gagne's avatar Don Gagne

Merge pull request #2090 from DonLakeFlyer/APMMissionSupport

APM stack mission support
parents ccef0fd9 f0bd33ef
......@@ -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);
......
......@@ -378,3 +378,9 @@ void APMFirmwarePlugin::setSupportedModes(QList<APMCustomMode> supportedModes)
{
_supportedModes = supportedModes;
}
bool APMFirmwarePlugin::sendHomePositionToVehicle(void)
{
// APM stack wants the home position sent in the first position
return true;
}
......@@ -87,7 +87,8 @@ public:
virtual int manualControlReservedButtonCount(void);
virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
protected:
/// All access to singleton is through stack specific implementation
APMFirmwarePlugin(QObject* parent = NULL);
......
......@@ -96,6 +96,14 @@ public:
/// Called when Vehicle is first created to send any necessary mavlink messages to the firmware.
virtual void initializeVehicle(Vehicle* vehicle) = 0;
/// Determines how to handle the first item of the mission item list. Internally to QGC the first item
/// is always the home position.
/// @return
/// true: Send first mission item as home position to vehicle. When vehicle has no mission items on
/// it, it may or may not return a home position back in position 0.
/// false: Do not send first item to vehicle, sequence numbers must be adjusted
virtual bool sendHomePositionToVehicle(void) = 0;
protected:
FirmwarePlugin(QObject* parent = NULL) : QGCSingleton(parent) { }
......
......@@ -110,3 +110,11 @@ void GenericFirmwarePlugin::initializeVehicle(Vehicle* vehicle)
// Generic Flight Stack is by definition "generic", so no extra work
}
bool GenericFirmwarePlugin::sendHomePositionToVehicle(void)
{
// Generic stack does not want home position sent in the first position.
// Subsequent sequence numbers must be adjusted.
// This is the mavlink spec default.
return false;
}
......@@ -46,6 +46,7 @@ public:
virtual int manualControlReservedButtonCount(void);
virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
private:
/// All access to singleton is through AutoPilotPluginManager::instance
......
......@@ -200,3 +200,10 @@ void PX4FirmwarePlugin::initializeVehicle(Vehicle* vehicle)
// PX4 Flight Stack doesn't need to do any extra work
}
bool PX4FirmwarePlugin::sendHomePositionToVehicle(void)
{
// PX4 stack does not want home position sent in the first position.
// Subsequent sequence numbers must be adjusted.
return false;
}
......@@ -46,6 +46,7 @@ public:
virtual int manualControlReservedButtonCount(void);
virtual void adjustMavlinkMessage(mavlink_message_t* message);
virtual void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void);
private:
/// All access to singleton is through AutoPilotPluginManager::instance
......
......@@ -69,21 +69,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
}
......@@ -280,8 +284,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 {
......@@ -554,7 +558,7 @@ Home Position Manager is commented out for now until a better implementation is
}
} // Column - Online view
} // Item - Home Position Manager
*/
*/
// Help Panel
Rectangle {
......@@ -654,7 +658,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
......@@ -678,7 +682,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
......@@ -801,8 +805,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
......@@ -35,8 +35,9 @@ const MissionManagerTest::TestCase_t MissionManagerTest::_rgTestCases[] = {
{ "4\t0\t3\t21\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", { 4, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_LAND, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT } },
{ "5\t0\t3\t22\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", { 5, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_NAV_TAKEOFF, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT } },
{ "6\t0\t2\t112\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", { 6, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_CONDITION_DELAY, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_MISSION } },
{ "7\t0\t2\t177\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n", { 7, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_DO_JUMP, 10.0, 20.0, 30.0, 40.0, true, false, MAV_FRAME_MISSION } },
{ "7\t0\t2\t177\t3\t20\t30\t40\t-10\t-20\t-30\t1\r\n", { 7, QGeoCoordinate(-10.0, -20.0, -30.0), MAV_CMD_DO_JUMP, 3, 20.0, 30.0, 40.0, true, false, MAV_FRAME_MISSION } },
};
const size_t MissionManagerTest::_cTestCases = sizeof(_rgTestCases)/sizeof(_rgTestCases[0]);
MissionManagerTest::MissionManagerTest(void)
: _mockLink(NULL)
......@@ -44,7 +45,7 @@ MissionManagerTest::MissionManagerTest(void)
}
void MissionManagerTest::init(void)
void MissionManagerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
{
UnitTest::init();
......@@ -53,6 +54,7 @@ void MissionManagerTest::init(void)
_mockLink = new MockLink();
Q_CHECK_PTR(_mockLink);
_mockLink->setFirmwareType(firmwareType);
LinkManager::instance()->_addLink(_mockLink);
linkMgr->connectLink(_mockLink);
......@@ -110,7 +112,7 @@ void MissionManagerTest::_checkInProgressValues(bool inProgress)
QCOMPARE(signalArgs[0].toBool(), inProgress);
}
void MissionManagerTest::_readEmptyVehicle(void)
void MissionManagerTest::_readEmptyVehicleWorker(void)
{
_missionManager->requestMissionItems();
......@@ -125,8 +127,7 @@ void MissionManagerTest::_readEmptyVehicle(void)
// inProgressChanged signal to signal completion.
_multiSpy->waitForSignalByIndex(newMissionItemsAvailableSignalIndex, _signalWaitTime);
_multiSpy->waitForSignalByIndex(inProgressChangedSignalIndex, _signalWaitTime);
QCOMPARE(_multiSpy->checkSignalByMask(newMissionItemsAvailableSignalMask | inProgressChangedSignalMask), true);
QCOMPARE(_multiSpy->checkNoSignalByMask(canEditChangedSignalMask), true);
QCOMPARE(_multiSpy->checkOnlySignalByMask(newMissionItemsAvailableSignalMask | inProgressChangedSignalMask), true);
_checkInProgressValues(false);
// Vehicle should have no items at this point
......@@ -143,7 +144,6 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
}
// Setup our test case data
const size_t cTestCases = sizeof(_rgTestCases)/sizeof(_rgTestCases[0]);
QmlObjectListModel* list = new QmlObjectListModel();
// Editor has a home position item on the front, so we do the same
......@@ -156,7 +156,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
homeItem->setSequenceNumber(0);
list->insert(0, homeItem);
for (size_t i=0; i<cTestCases; i++) {
for (size_t i=0; i<_cTestCases; i++) {
const TestCase_t* testCase = &_rgTestCases[i];
MissionItem* item = new MissionItem(list);
......@@ -175,7 +175,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
}
// Send the items to the vehicle
_missionManager->writeMissionItems(*list, true /* skipFirstItem */);
_missionManager->writeMissionItems(*list);
// writeMissionItems should emit these signals before returning:
// inProgressChanged
......@@ -197,8 +197,15 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
// Validate inProgressChanged signal value
_checkInProgressValues(false);
// We should have gotten back all mission items
QCOMPARE(_missionManager->missionItems()->count(), (int)cTestCases);
// Validate item count in mission manager
int expectedCount = (int)_cTestCases;
if (_mockLink->getFirmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
// Home position at position 0 comes from vehicle
expectedCount++;
}
QCOMPARE(_missionManager->missionItems()->count(), expectedCount);
} else {
// This should be a failed run
......@@ -260,6 +267,7 @@ void MissionManagerTest::_roundTripItems(MockLinkMissionItemHandler::FailureMode
QCOMPARE(_multiSpy->checkSignalByMask(newMissionItemsAvailableSignalMask | inProgressChangedSignalMask), true);
QCOMPARE(_multiSpy->checkNoSignalByMask(canEditChangedSignalMask), true);
_checkInProgressValues(false);
} else {
// This should be a failed run
......@@ -292,7 +300,11 @@ void MissionManagerTest::_roundTripItems(MockLinkMissionItemHandler::FailureMode
size_t cMissionItemsExpected;
if (failureMode == MockLinkMissionItemHandler::FailNone || failFirstTimeOnly == true) {
cMissionItemsExpected = sizeof(_rgTestCases)/sizeof(_rgTestCases[0]);
cMissionItemsExpected = (int)_cTestCases;
if (_mockLink->getFirmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
// Home position at position 0 comes from vehicle
cMissionItemsExpected++;
}
} else {
switch (failureMode) {
case MockLinkMissionItemHandler::FailReadRequestListNoResponse:
......@@ -315,28 +327,49 @@ void MissionManagerTest::_roundTripItems(MockLinkMissionItemHandler::FailureMode
QCOMPARE(_missionManager->missionItems()->count(), (int)cMissionItemsExpected);
QCOMPARE(_missionManager->canEdit(), true);
for (size_t i=0; i<cMissionItemsExpected; i++) {
const TestCase_t* testCase = &_rgTestCases[i];
MissionItem* actual = qobject_cast<MissionItem*>(_missionManager->missionItems()->get(i));
size_t firstActualItem = 0;
if (_mockLink->getFirmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
// First item is home position, don't validate it
firstActualItem++;
}
int testCaseIndex = 0;
for (size_t actualItemIndex=firstActualItem; actualItemIndex<cMissionItemsExpected; actualItemIndex++) {
const TestCase_t* testCase = &_rgTestCases[testCaseIndex];
int expectedSequenceNumber = testCase->expectedItem.sequenceNumber;
int expectedParam1 = (int)testCase->expectedItem.param1;
if (_mockLink->getFirmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
// Account for home position in first item
expectedSequenceNumber++;
if (testCase->expectedItem.command == MAV_CMD_DO_JUMP) {
// Expected data in test case is for PX4
expectedParam1++;
}
}
MissionItem* actual = qobject_cast<MissionItem*>(_missionManager->missionItems()->get(actualItemIndex));
qDebug() << "Test case" << i;
QCOMPARE(actual->sequenceNumber(), testCase->expectedItem.sequenceNumber);
qDebug() << "Test case" << testCaseIndex;
QCOMPARE(actual->sequenceNumber(), expectedSequenceNumber);
QCOMPARE(actual->coordinate().latitude(), testCase->expectedItem.coordinate.latitude());
QCOMPARE(actual->coordinate().longitude(), testCase->expectedItem.coordinate.longitude());
QCOMPARE(actual->coordinate().altitude(), testCase->expectedItem.coordinate.altitude());
QCOMPARE((int)actual->command(), (int)testCase->expectedItem.command);
QCOMPARE((int)actual->param1(), (int)expectedParam1);
QCOMPARE(actual->param2(), testCase->expectedItem.param2);
QCOMPARE(actual->param3(), testCase->expectedItem.param3);
QCOMPARE(actual->param4(), testCase->expectedItem.param4);
QCOMPARE(actual->autoContinue(), testCase->expectedItem.autocontinue);
QCOMPARE(actual->frame(), testCase->expectedItem.frame);
QCOMPARE(actual->param1(), testCase->expectedItem.param1);
testCaseIndex++;
}
}
void MissionManagerTest::_testWriteFailureHandling(void)
void MissionManagerTest::_testWriteFailureHandlingWorker(void)
{
/*
/// Called to send a MISSION_ACK message while the MissionManager is in idle state
......@@ -378,7 +411,7 @@ void MissionManagerTest::_testWriteFailureHandling(void)
}
}
void MissionManagerTest::_testReadFailureHandling(void)
void MissionManagerTest::_testReadFailureHandlingWorker(void)
{
/*
/// Called to send a MISSION_ACK message while the MissionManager is in idle state
......@@ -417,3 +450,40 @@ void MissionManagerTest::_testReadFailureHandling(void)
_mockLink->resetMissionItemHandler();
}
}
void MissionManagerTest::_testEmptyVehicleAPM(void)
{
_initForFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
_readEmptyVehicleWorker();
}
void MissionManagerTest::_testEmptyVehiclePX4(void)
{
_initForFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
_readEmptyVehicleWorker();
}
void MissionManagerTest::_testWriteFailureHandlingAPM(void)
{
_initForFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
_testWriteFailureHandlingWorker();
}
void MissionManagerTest::_testReadFailureHandlingAPM(void)
{
_initForFirmwareType(MAV_AUTOPILOT_ARDUPILOTMEGA);
_testReadFailureHandlingWorker();
}
void MissionManagerTest::_testWriteFailureHandlingPX4(void)
{
_initForFirmwareType(MAV_AUTOPILOT_PX4);
_testWriteFailureHandlingWorker();
}
void MissionManagerTest::_testReadFailureHandlingPX4(void)
{
_initForFirmwareType(MAV_AUTOPILOT_PX4);
_testReadFailureHandlingWorker();
}
......@@ -39,18 +39,23 @@ public:
MissionManagerTest(void);
private slots:
void init(void);
void cleanup(void);
void _testWriteFailureHandling(void);
void _testReadFailureHandling(void);
void _testEmptyVehicleAPM(void);
void _testEmptyVehiclePX4(void);
void _testWriteFailureHandlingAPM(void);
void _testReadFailureHandlingAPM(void);
void _testWriteFailureHandlingPX4(void);
void _testReadFailureHandlingPX4(void);
private:
void _initForFirmwareType(MAV_AUTOPILOT firmwareType);
void _checkInProgressValues(bool inProgress);
void _roundTripItems(MockLinkMissionItemHandler::FailureMode_t failureMode, MissionManager::ErrorCode_t errorCode, bool failFirstTimeOnly);
void _writeItems(MockLinkMissionItemHandler::FailureMode_t failureMode, MissionManager::ErrorCode_t errorCode, bool failFirstTimeOnly);
void _readEmptyVehicle(void);
void _testWriteFailureHandlingWorker(void);
void _testReadFailureHandlingWorker(void);
void _readEmptyVehicleWorker(void);
MockLink* _mockLink;
MissionManager* _missionManager;
......@@ -93,6 +98,7 @@ private:
} TestCase_t;
static const TestCase_t _rgTestCases[];
static const size_t _cTestCases;
static const int _signalWaitTime = MissionManager::_ackTimeoutMilliseconds * MissionManager::_maxRetryCount * 2;
};
......
......@@ -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__
......
......@@ -166,27 +166,9 @@ Vehicle::~Vehicle()
{
delete _missionManager;
_missionManager = NULL;
// Stop listening for system messages
disconnect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage);
// Disconnect any previously connected active MAV
disconnect(_mav, SIGNAL(attitudeChanged (UASInterface*, double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64)));
disconnect(_mav, SIGNAL(attitudeChanged (UASInterface*, int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64)));
disconnect(_mav, SIGNAL(speedChanged (UASInterface*, double, double, quint64)), this, SLOT(_updateSpeed(UASInterface*, double, double, quint64)));
disconnect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64)));
disconnect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double)));
disconnect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*,QString,QString)));
disconnect(_mav, &UASInterface::NavigationControllerDataChanged, this, &Vehicle::_updateNavigationControllerData);
disconnect(_mav, &UASInterface::heartbeatTimeout, this, &Vehicle::_heartbeatTimeout);
disconnect(_mav, &UASInterface::batteryChanged, this, &Vehicle::_updateBatteryRemaining);
disconnect(_mav, &UASInterface::batteryConsumedChanged, this, &Vehicle::_updateBatteryConsumedChanged);
disconnect(_mav, &UASInterface::nameChanged, this, &Vehicle::_updateName);
disconnect(_mav, &UASInterface::systemTypeSet, this, &Vehicle::_setSystemType);
disconnect(_mav, &UASInterface::localizationChanged, this, &Vehicle::_setSatLoc);
UAS* pUas = dynamic_cast<UAS*>(_mav);
if(pUas) {
disconnect(pUas, &UAS::satelliteCountChanged, this, &Vehicle::_setSatelliteCount);
}
delete _mav;
_mav = NULL;
}
void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message)
......
......@@ -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);
......
......@@ -84,13 +84,14 @@ MockLink::MockLink(MockConfiguration* config)
, _mavlinkStarted(false)
, _mavBaseMode(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
, _mavState(MAV_STATE_STANDBY)
, _autopilotType(MAV_AUTOPILOT_PX4)
, _firmwareType(MAV_AUTOPILOT_PX4)
, _fileServer(NULL)
, _sendStatusText(false)
, _apmSendHomePositionOnEmptyList(false)
{
_config = config;
if (_config) {
_autopilotType = config->firmwareType();
_firmwareType = config->firmwareType();
_sendStatusText = config->sendStatusText();
}
......@@ -250,7 +251,7 @@ void MockLink::_sendHeartBeat(void)
_vehicleComponentId,
&msg,
MAV_TYPE_QUADROTOR, // MAV_TYPE
_autopilotType, // MAV_AUTOPILOT
_firmwareType, // MAV_AUTOPILOT
_mavBaseMode, // MAV_MODE
_mavCustomMode, // custom mode
_mavState); // MAV_STATE
......@@ -436,7 +437,7 @@ float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
switch (paramType) {
case MAV_PARAM_TYPE_INT8:
if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
valueUnion.param_float = (unsigned char)paramVar.toChar().toLatin1();
} else {
valueUnion.param_int8 = (unsigned char)paramVar.toChar().toLatin1();
......@@ -444,7 +445,7 @@ float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
break;
case MAV_PARAM_TYPE_INT32:
if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
valueUnion.param_float = paramVar.toInt();
} else {
valueUnion.param_int32 = paramVar.toInt();
......@@ -452,7 +453,7 @@ float MockLink::_floatUnionForParam(int componentId, const QString& paramName)
break;
case MAV_PARAM_TYPE_UINT32:
if (_autopilotType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
valueUnion.param_float = paramVar.toUInt();
} else {
valueUnion.param_uint32 = paramVar.toUInt();
......
......@@ -74,9 +74,16 @@ public:
// MockLink methods
int vehicleId(void) { return _vehicleSystemId; }
MAV_AUTOPILOT getAutopilotType(void) { return _autopilotType; }
void setAutopilotType(MAV_AUTOPILOT autopilot) { _autopilotType = autopilot; }
MAV_AUTOPILOT getFirmwareType(void) { return _firmwareType; }
void setFirmwareType(MAV_AUTOPILOT autopilot) { _firmwareType = autopilot; }
void setSendStatusText(bool sendStatusText) { _sendStatusText = sendStatusText; }
/// APM stack has strange handling of the first item of the mission list. If it has no
/// onboard mission items, sometimes it sends back a home position in position 0 and
/// sometimes it doesn't. Don't ask. This option allows you to configure that behavior
/// for unit testing.
void setAPMMissionResponseMode(bool sendHomePositionOnEmptyList) { _apmSendHomePositionOnEmptyList = sendHomePositionOnEmptyList; }
void emitRemoteControlChannelRawChanged(int channel, uint16_t raw);
/// Sends the specified mavlink message to QGC
......@@ -177,11 +184,12 @@ private:
uint8_t _mavState;
MockConfiguration* _config;
MAV_AUTOPILOT _autopilotType;
MAV_AUTOPILOT _firmwareType;
MockLinkFileServer* _fileServer;
bool _sendStatusText;
bool _apmSendHomePositionOnEmptyList;
static float _vehicleLatitude;
static float _vehicleLongitude;
......
......@@ -32,6 +32,7 @@ MockLinkMissionItemHandler::MockLinkMissionItemHandler(MockLink* mockLink)
: _mockLink(mockLink)
, _missionItemResponseTimer(NULL)
, _failureMode(FailNone)
, _sendHomePositionOnEmptyList(false)
{
Q_ASSERT(mockLink);
}
......@@ -99,6 +100,11 @@ void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message
mavlink_msg_mission_request_list_decode(&msg, &request);
Q_ASSERT(request.target_system == _mockLink->vehicleId());
int itemCount = _missionItems.count();
if (itemCount == 0 && _sendHomePositionOnEmptyList) {
itemCount = 1;
}
mavlink_message_t responseMsg;
......@@ -107,7 +113,7 @@ void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message
&responseMsg, // Outgoing message
msg.sysid, // Target is original sender
msg.compid, // Target is original sender
_missionItems.count()); // Number of mission items
itemCount); // Number of mission items
_mockLink->respondWithMavlinkMessage(responseMsg);
} else {
qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList not responding due to failure mode";
......@@ -148,7 +154,16 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t&
} else {
mavlink_message_t responseMsg;
mavlink_mission_item_t item = _missionItems[request.seq];
mavlink_mission_item_t item;
if (_missionItems.count() == 0 && _sendHomePositionOnEmptyList) {
item.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
item.command = MAV_CMD_NAV_WAYPOINT;
item.current = false;
item.autocontinue = true;
item.param1 = item.param2 = item.param3 = item.param4 = item.x = item.y = item.z = 0;
} else {
item = _missionItems[request.seq];
}
mavlink_msg_mission_item_pack(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
......
......@@ -88,6 +88,8 @@ public:
/// Reset the state of the MissionItemHandler to no items, no transactions in progress.
void reset(void) { _missionItems.clear(); }
void setSendHomePositionOnEmptyList(bool sendHomePositionOnEmptyList) { _sendHomePositionOnEmptyList = sendHomePositionOnEmptyList; }
private slots:
void _missionItemResponseTimeout(void);
......@@ -112,6 +114,7 @@ private:
QTimer* _missionItemResponseTimer;
FailureMode_t _failureMode;
bool _failureFirstTimeOnly;
bool _sendHomePositionOnEmptyList;
};
#endif
......@@ -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