Commit 17641797 authored by dogmaphobic's avatar dogmaphobic

Merge remote-tracking branch 'MavLink/master'

* MavLink/master:
  Support V110 (APM) and V120 (PX4) formats
  Fit map viewport to mission items
  Add support for mission item insert
  Add support for mission item insert
  Warn about joystick on APM stack

Conflicts:
	src/FlightDisplay/FlightDisplayView.qml
parents a4c19e72 8890d874
......@@ -91,6 +91,53 @@ QGCView {
}
}
function loadFromVehicle() {
controller.getMissionItems()
}
function loadFromFile() {
controller.loadMissionFromFile()
fitViewportToMissionItems()
}
function normalizeLat(lat) {
// Normalize latitude to range: 0 to 180, S to N
return lat + 90.0
}
function normalizeLon(lon) {
// Normalize longitude to range: 0 to 360, W to E
return lon + 180.0
}
/// Fix the map viewport to the current mission items. We don't fit the home position in this process.
function fitViewportToMissionItems() {
if (_missionItems.count <= 1) {
return
}
var missionItem = _missionItems.get(1)
var north = normalizeLat(missionItem.coordinate.latitude)
var south = north
var east = normalizeLon(missionItem.coordinate.longitude)
var west = east
for (var i=2; i<_missionItems.count; i++) {
missionItem = _missionItems.get(i)
var lat = normalizeLat(missionItem.coordinate.latitude)
var lon = normalizeLon(missionItem.coordinate.longitude)
north = Math.max(north, lat)
south = Math.min(south, lat)
east = Math.max(east, lon)
west = Math.min(west, lon)
}
editorMap.visibleRegion = QtPositioning.rectangle(QtPositioning.coordinate(north - 90.0, west - 180.0), QtPositioning.coordinate(south - 90.0, east - 180.0))
}
MissionController {
id: controller
......@@ -107,6 +154,7 @@ QGCView {
*/
onMissionItemsChanged: itemDragger.clearItem()
onNewItemsFromVehicle: fitViewportToMissionItems()
}
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
......@@ -200,7 +248,7 @@ QGCView {
if (false /*homePositionManagerButton.checked*/) {
//offlineHomePosition = coordinate
} else if (addMissionItemsButton.checked) {
var index = controller.addMissionItem(coordinate)
var index = controller.insertMissionItem(coordinate, controller.missionItems.count)
setCurrentItem(index)
} else {
editorMap.zoomLevel = editorMap.maxZoomLevel - 2
......@@ -261,11 +309,11 @@ QGCView {
// Add the mission items to the map
MapItemView {
model: controller.missionItems
delegate: delegateComponent
delegate: missionItemComponent
}
Component {
id: delegateComponent
id: missionItemComponent
MissionItemIndicator {
id: itemIndicator
......@@ -288,10 +336,6 @@ QGCView {
} else {
itemDragger.clearItem()
}
// Move to the new position
editorMap.latitude = object.coordinate.latitude
editorMap.longitude = object.coordinate.longitude
}
}
}
......@@ -374,6 +418,11 @@ QGCView {
itemDragger.clearItem()
controller.removeAllMissionItems()
}
onInsert: {
controller.insertMissionItem(editorMap.center, i)
setCurrentItem(i)
}
}
} // ListView
} // Item - Mission Item editor
......@@ -549,7 +598,7 @@ QGCView {
function accept() {
hideDialog()
controller.getMissionItems()
loadFromVehicle()
}
}
}
......@@ -563,7 +612,7 @@ QGCView {
function accept() {
hideDialog()
controller.loadMissionFromFile()
loadFromFile()
}
}
}
......@@ -606,7 +655,7 @@ QGCView {
if (syncNeeded) {
_root.showDialog(syncLoadFromVehicleOverwrite, "Mission overwrite", _root.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel)
} else {
controller.getMissionItems()
loadFromVehicle()
}
}
}
......@@ -633,7 +682,7 @@ QGCView {
if (syncNeeded) {
_root.showDialog(syncLoadFromFileOverwrite, "Mission overwrite", _root.showDialogDefaultWidth, StandardButton.Yes | StandardButton.Cancel)
} else {
controller.loadMissionFromFile()
loadFromFile()
}
}
}
......
......@@ -130,12 +130,13 @@ void MissionController::_setupMissionItems(bool loadFromVehicle, bool forceLoad)
if (!missionManager || !loadFromVehicle || missionManager->inProgress()) {
_missionItems = new QmlObjectListModel(this);
qCDebug(MissionControllerLog) << "creating empty set";
_initAllMissionItems();
} else {
_missionItems = missionManager->copyMissionItems();
qCDebug(MissionControllerLog) << "loading from vehicle count"<< _missionItems->count();
_initAllMissionItems();
emit newItemsFromVehicle();
}
_initAllMissionItems();
}
void MissionController::getMissionItems(void)
......@@ -158,7 +159,7 @@ void MissionController::sendMissionItems(void)
}
}
int MissionController::addMissionItem(QGeoCoordinate coordinate)
int MissionController::insertMissionItem(QGeoCoordinate coordinate, int i)
{
MissionItem * newItem = new MissionItem(this);
newItem->setSequenceNumber(_missionItems->count());
......@@ -179,7 +180,7 @@ int MissionController::addMissionItem(QGeoCoordinate coordinate)
newItem->setParam7(lastValue);
}
}
_missionItems->append(newItem);
_missionItems->insert(i, newItem);
_recalcAll();
......@@ -222,6 +223,7 @@ void MissionController::loadMissionFromFile(void)
#ifndef __mobile__
QString errorString;
QString filename = QGCFileDialog::getOpenFileName(NULL, "Select Mission File to load");
bool versionAPM = false;
if (filename.isEmpty()) {
return;
......@@ -244,9 +246,17 @@ void MissionController::loadMissionFromFile(void)
const QStringList& version = in.readLine().split(" ");
if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120")) {
errorString = "The mission file is not compatible with the current version of QGroundControl.";
} else {
bool versionOk = false;
if (version.size() == 3 && version[0] == "QGC" && version[1] == "WPL") {
if (version[2] == "120") {
versionOk = true;
} else if (version[2] == "110") {
versionOk = true;
versionAPM = true;
}
}
if (versionOk) {
while (!in.atEnd()) {
MissionItem* item = new MissionItem();
......@@ -257,12 +267,19 @@ void MissionController::loadMissionFromFile(void)
break;
}
}
} else {
errorString = "The mission file is not compatible with this version of QGroundControl.";
}
}
if (!errorString.isEmpty()) {
if (errorString.isEmpty()) {
if (versionAPM) {
// Remove fake home position from APM files
_missionItems->removeAt(0);
}
} else {
_missionItems->clear();
qgcApp()->showMessage(errorString);
}
_initAllMissionItems();
......@@ -272,7 +289,6 @@ void MissionController::loadMissionFromFile(void)
void MissionController::saveMissionToFile(void)
{
#ifndef __mobile__
QString errorString;
QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to");
if (filename.isEmpty()) {
......@@ -282,7 +298,7 @@ void MissionController::saveMissionToFile(void)
QFile file(filename);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
errorString = file.errorString();
qgcApp()->showMessage(file.errorString());
} else {
QTextStream out(&file);
......
......@@ -46,8 +46,7 @@ public:
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 start(bool editMode);
Q_INVOKABLE void getMissionItems(void);
Q_INVOKABLE void sendMissionItems(void);
Q_INVOKABLE void loadMissionFromFile(void);
......@@ -55,6 +54,9 @@ public:
Q_INVOKABLE void removeMissionItem(int index);
Q_INVOKABLE void removeAllMissionItems(void);
/// @param i: index to insert at
Q_INVOKABLE int insertMissionItem(QGeoCoordinate coordinate, int i);
// Property accessors
QmlObjectListModel* missionItems(void);
......@@ -70,6 +72,7 @@ signals:
void liveHomePositionAvailableChanged(bool homePositionAvailable);
void liveHomePositionChanged(const QGeoCoordinate& homePosition);
void autoSyncChanged(bool autoSync);
void newItemsFromVehicle(void);
private slots:
void _newMissionItemsAvailableFromVehicle();
......
......@@ -176,7 +176,7 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QGeoCoordinate coordinate(37.803784, -122.462276);
_missionController->addMissionItem(coordinate);
_missionController->insertMissionItem(coordinate, _missionController->missionItems()->count());
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true);
......@@ -223,7 +223,7 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp
_missionController = new MissionController();
Q_CHECK_PTR(_missionController);
_missionController->start(true /* editMode */);
_missionController->addMissionItem(QGeoCoordinate(37.803784, -122.462276));
_missionController->insertMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->missionItems()->count());
// Go online to empty vehicle
MissionControllerManagerTest::_initForFirmwareType(firmwareType);
......
......@@ -21,6 +21,7 @@ Rectangle {
signal clicked
signal remove
signal removeAll
signal insert(int i)
height: innerItem.height + (_margin * 3)
color: missionItem.isCurrentItem ? qgcPal.buttonHighlight : qgcPal.windowShade
......@@ -87,6 +88,11 @@ Rectangle {
Menu {
id: hamburgerMenu
MenuItem {
text: "Insert"
onTriggered: insert(missionItem.sequenceNumber)
}
MenuItem {
text: "Delete"
onTriggered: remove()
......
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