Browse Source

Add Home Position Manager support to Mission Editor

Also:
- Remove unused code
QGC4.4
Don Gagne 10 years ago
parent
commit
143bb616f7
  1. 185
      src/HomePositionManager.cc
  2. 120
      src/HomePositionManager.h
  3. 295
      src/MissionEditor/MissionEditor.qml
  4. 4
      src/QmlControls/QmlObjectListModel.cc
  5. 1
      src/QmlControls/QmlObjectListModel.h
  6. 1
      src/comm/QGCFlightGearLink.cc
  7. 5
      src/comm/QGCXPlaneLink.cc
  8. 3
      src/uas/UAS.cc
  9. 1
      src/ui/MainWindow.cc

185
src/HomePositionManager.cc

@ -40,24 +40,47 @@
IMPLEMENT_QGC_SINGLETON(HomePositionManager, HomePositionManager) IMPLEMENT_QGC_SINGLETON(HomePositionManager, HomePositionManager)
HomePositionManager::HomePositionManager(QObject* parent) : const char* HomePositionManager::_settingsGroup = "HomePositionManager";
QObject(parent), const char* HomePositionManager::_latitudeKey = "Latitude";
homeLat(47.3769), const char* HomePositionManager::_longitudeKey = "Longitude";
homeLon(8.549444), const char* HomePositionManager::_altitudeKey = "Altitude";
homeAlt(470.0),
homeFrame(MAV_FRAME_GLOBAL) HomePositionManager::HomePositionManager(QObject* parent)
: QObject(parent)
, homeLat(47.3769)
, homeLon(8.549444)
, homeAlt(470.0)
{ {
loadSettings(); _loadSettings();
} }
HomePositionManager::~HomePositionManager() HomePositionManager::~HomePositionManager()
{ {
storeSettings();
} }
void HomePositionManager::storeSettings() void HomePositionManager::_storeSettings(void)
{ {
QSettings settings; QSettings settings;
settings.remove(_settingsGroup);
settings.beginGroup(_settingsGroup);
for (int i=0; i<_homePositions.count(); i++) {
HomePosition* homePos = qobject_cast<HomePosition*>(_homePositions[i]);
qDebug() << "Saving" << homePos->name();
settings.beginGroup(homePos->name());
settings.setValue(_latitudeKey, homePos->coordinate().latitude());
settings.setValue(_longitudeKey, homePos->coordinate().longitude());
settings.setValue(_altitudeKey, homePos->coordinate().altitude());
settings.endGroup();
}
settings.endGroup();
// Deprecated settings for old editor
settings.beginGroup("QGC_UASMANAGER"); settings.beginGroup("QGC_UASMANAGER");
settings.setValue("HOMELAT", homeLat); settings.setValue("HOMELAT", homeLat);
settings.setValue("HOMELON", homeLon); settings.setValue("HOMELON", homeLon);
@ -65,9 +88,36 @@ void HomePositionManager::storeSettings()
settings.endGroup(); settings.endGroup();
} }
void HomePositionManager::loadSettings() void HomePositionManager::_loadSettings(void)
{ {
QSettings settings; QSettings settings;
_homePositions.clear();
settings.beginGroup(_settingsGroup);
foreach(QString name, settings.childGroups()) {
QGeoCoordinate coordinate;
qDebug() << "Load setting" << name;
settings.beginGroup(name);
coordinate.setLatitude(settings.value(_latitudeKey).toDouble());
coordinate.setLongitude(settings.value(_longitudeKey).toDouble());
coordinate.setAltitude(settings.value(_altitudeKey).toDouble());
settings.endGroup();
_homePositions.append(new HomePosition(name, coordinate, this));
}
settings.endGroup();
if (_homePositions.count() == 0) {
_homePositions.append(new HomePosition("ETH Campus", QGeoCoordinate(47.3769, 8.549444, 470.0)));
}
// Deprecated settings for old editor
settings.beginGroup("QGC_UASMANAGER"); settings.beginGroup("QGC_UASMANAGER");
bool changed = setHomePosition(settings.value("HOMELAT", homeLat).toDouble(), bool changed = setHomePosition(settings.value("HOMELAT", homeLat).toDouble(),
settings.value("HOMELON", homeLon).toDouble(), settings.value("HOMELON", homeLon).toDouble(),
@ -97,9 +147,6 @@ bool HomePositionManager::setHomePosition(double lat, double lon, double alt)
if (fabs(homeLon - lon) > 1e-7) changed = true; if (fabs(homeLon - lon) > 1e-7) changed = true;
if (fabs(homeAlt - alt) > 0.5f) changed = true; if (fabs(homeAlt - alt) > 0.5f) changed = true;
// Initialize conversion reference in any case
initReference(lat, lon, alt);
if (changed) if (changed)
{ {
homeLat = lat; homeLat = lat;
@ -125,75 +172,81 @@ bool HomePositionManager::setHomePositionAndNotify(double lat, double lon, doubl
return changed; return changed;
} }
void HomePositionManager::initReference(const double & latitude, const double & longitude, const double & altitude) void HomePositionManager::updateHomePosition(const QString& name, const QGeoCoordinate& coordinate)
{ {
Eigen::Matrix3d R; HomePosition * homePos = NULL;
double s_long, s_lat, c_long, c_lat;
sincos(latitude * DEG2RAD, &s_lat, &c_lat); for (int i=0; i<_homePositions.count(); i++) {
sincos(longitude * DEG2RAD, &s_long, &c_long); homePos = qobject_cast<HomePosition*>(_homePositions[i]);
if (homePos->name() == name) {
R(0, 0) = -s_long; break;
R(0, 1) = c_long; }
R(0, 2) = 0; homePos = NULL;
}
R(1, 0) = -s_lat * c_long;
R(1, 1) = -s_lat * s_long; if (homePos == NULL) {
R(1, 2) = c_lat; HomePosition* homePos = new HomePosition(name, coordinate, this);
_homePositions.append(homePos);
R(2, 0) = c_lat * c_long; } else {
R(2, 1) = c_lat * s_long; homePos->setName(name);
R(2, 2) = s_lat; homePos->setCoordinate(coordinate);
}
ecef_ref_orientation_ = Eigen::Quaterniond(R);
_storeSettings();
ecef_ref_point_ = wgs84ToEcef(latitude, longitude, altitude);
} }
Eigen::Vector3d HomePositionManager::wgs84ToEcef(const double & latitude, const double & longitude, const double & altitude) void HomePositionManager::deleteHomePosition(const QString& name)
{ {
const double a = 6378137.0; // semi-major axis // Don't allow delete of last position
const double e_sq = 6.69437999014e-3; // first eccentricity squared if (_homePositions.count() == 1) {
return;
double s_long, s_lat, c_long, c_lat; }
sincos(latitude * DEG2RAD, &s_lat, &c_lat);
sincos(longitude * DEG2RAD, &s_long, &c_long); qDebug() << "Attempting delete" << name;
const double N = a / sqrt(1 - e_sq * s_lat * s_lat); for (int i=0; i<_homePositions.count(); i++) {
if (qobject_cast<HomePosition*>(_homePositions[i])->name() == name) {
Eigen::Vector3d ecef; qDebug() << "Deleting" << name;
_homePositions.removeAt(i);
ecef[0] = (N + altitude) * c_lat * c_long; break;
ecef[1] = (N + altitude) * c_lat * s_long; }
ecef[2] = (N * (1 - e_sq) + altitude) * s_lat; }
_storeSettings();
}
return ecef; HomePosition::HomePosition(const QString& name, const QGeoCoordinate& coordinate, QObject* parent)
: QObject(parent)
, _coordinate(coordinate)
{
setObjectName(name);
} }
Eigen::Vector3d HomePositionManager::ecefToEnu(const Eigen::Vector3d & ecef) HomePosition::~HomePosition()
{ {
return ecef_ref_orientation_ * (ecef - ecef_ref_point_);
} }
void HomePositionManager::wgs84ToEnu(const double& lat, const double& lon, const double& alt, double* east, double* north, double* up) QString HomePosition::name(void)
{ {
Eigen::Vector3d ecef = wgs84ToEcef(lat, lon, alt); return objectName();
Eigen::Vector3d enu = ecefToEnu(ecef);
*east = enu.x();
*north = enu.y();
*up = enu.z();
} }
void HomePositionManager::enuToWgs84(const double& x, const double& y, const double& z, double* lat, double* lon, double* alt) void HomePosition::setName(const QString& name)
{ {
*lat=homeLat+y/MEAN_EARTH_DIAMETER*360./PI; setObjectName(name);
*lon=homeLon+x/MEAN_EARTH_DIAMETER*360./PI/cos(homeLat*UMR); HomePositionManager::instance()->_storeSettings();
*alt=homeAlt+z; emit nameChanged(name);
} }
void HomePositionManager::nedToWgs84(const double& x, const double& y, const double& z, double* lat, double* lon, double* alt) QGeoCoordinate HomePosition::coordinate(void)
{ {
*lat=homeLat+x/MEAN_EARTH_DIAMETER*360./PI; return _coordinate;
*lon=homeLon+y/MEAN_EARTH_DIAMETER*360./PI/cos(homeLat*UMR);
*alt=homeAlt-z;
} }
void HomePosition::setCoordinate(const QGeoCoordinate& coordinate)
{
_coordinate = coordinate;
HomePositionManager::instance()->_storeSettings();
emit coordinateChanged(coordinate);
}

120
src/HomePositionManager.h

@ -21,21 +21,41 @@ This file is part of the QGROUNDCONTROL project
======================================================================*/ ======================================================================*/
#ifndef _UASMANAGER_H_ #ifndef HomePositionManager_H
#define _UASMANAGER_H_ #define HomePositionManager_H
#include "UASInterface.h" #include "QGCSingleton.h"
#include "QmlObjectListModel.h"
#include <QList>
#include <QMutex>
#include <Eigen/Eigen> #include <QGeoCoordinate>
#include "QGCGeo.h" class HomePosition : public QObject
#include "QGCSingleton.h" {
Q_OBJECT
public:
HomePosition(const QString& name, const QGeoCoordinate& coordinate, QObject* parent = NULL);
~HomePosition();
Q_PROPERTY(QString name READ name WRITE setName NOTIFY nameChanged)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
// Property accessors
QString name(void);
void setName(const QString& name);
QGeoCoordinate coordinate(void);
void setCoordinate(const QGeoCoordinate& coordinate);
signals:
void nameChanged(const QString& name);
void coordinateChanged(const QGeoCoordinate& coordinate);
private:
QGeoCoordinate _coordinate;
};
/// Manages an offline home position as well as performance coordinate transformations
/// around a home position.
class HomePositionManager : public QObject class HomePositionManager : public QObject
{ {
Q_OBJECT Q_OBJECT
@ -43,6 +63,40 @@ class HomePositionManager : public QObject
DECLARE_QGC_SINGLETON(HomePositionManager, HomePositionManager) DECLARE_QGC_SINGLETON(HomePositionManager, HomePositionManager)
public: public:
Q_PROPERTY(QmlObjectListModel* homePositions READ homePositions CONSTANT)
/// If name is not already a home position a new one will be added, otherwise the existing
/// home position will be updated
Q_INVOKABLE void updateHomePosition(const QString& name, const QGeoCoordinate& coordinate);
Q_INVOKABLE void deleteHomePosition(const QString& name);
// Property accesors
QmlObjectListModel* homePositions(void) { return &_homePositions; }
// Should only be called by HomePosition
void _storeSettings(void);
private:
/// @brief All access to HomePositionManager singleton is through HomePositionManager::instance
HomePositionManager(QObject* parent = NULL);
~HomePositionManager();
void _loadSettings(void);
QmlObjectListModel _homePositions;
static const char* _settingsGroup;
static const char* _latitudeKey;
static const char* _longitudeKey;
static const char* _altitudeKey;
// Everything below is deprecated and will be removed once old Map code is removed
public:
// Deprecated methods
/** @brief Get home position latitude */ /** @brief Get home position latitude */
double getHomeLatitude() const { double getHomeLatitude() const {
return homeLat; return homeLat;
@ -56,24 +110,10 @@ public:
return homeAlt; return homeAlt;
} }
/** @brief Get the home position coordinate frame */
int getHomeFrame() const
{
return homeFrame;
}
/** @brief Convert WGS84 coordinates to earth centric frame */
Eigen::Vector3d wgs84ToEcef(const double & latitude, const double & longitude, const double & altitude);
/** @brief Convert earth centric frame to EAST-NORTH-UP frame (x-y-z directions */
Eigen::Vector3d ecefToEnu(const Eigen::Vector3d & ecef);
/** @brief Convert WGS84 lat/lon coordinates to carthesian coordinates with home position as origin */
void wgs84ToEnu(const double& lat, const double& lon, const double& alt, double* east, double* north, double* up);
/** @brief Convert x,y,z coordinates to lat / lon / alt coordinates in east-north-up frame */
void enuToWgs84(const double& x, const double& y, const double& z, double* lat, double* lon, double* alt);
/** @brief Convert x,y,z coordinates to lat / lon / alt coordinates in north-east-down frame */
void nedToWgs84(const double& x, const double& y, const double& z, double* lat, double* lon, double* alt);
public slots: public slots:
// Deprecated methods
/** @brief Set the current home position, but do not change it on the UAVs */ /** @brief Set the current home position, but do not change it on the UAVs */
bool setHomePosition(double lat, double lon, double alt); bool setHomePosition(double lat, double lon, double alt);
@ -81,11 +121,6 @@ public slots:
bool setHomePositionAndNotify(double lat, double lon, double alt); bool setHomePositionAndNotify(double lat, double lon, double alt);
/** @brief Load settings */
void loadSettings();
/** @brief Store settings */
void storeSettings();
signals: signals:
/** @brief Current home position changed */ /** @brief Current home position changed */
void homePositionChanged(double lat, double lon, double alt); void homePositionChanged(double lat, double lon, double alt);
@ -94,23 +129,6 @@ protected:
double homeLat; double homeLat;
double homeLon; double homeLon;
double homeAlt; double homeAlt;
int homeFrame;
Eigen::Quaterniond ecef_ref_orientation_;
Eigen::Vector3d ecef_ref_point_;
void initReference(const double & latitude, const double & longitude, const double & altitude);
private:
/// @brief All access to HomePositionManager singleton is through HomePositionManager::instance
HomePositionManager(QObject* parent = NULL);
~HomePositionManager();
public:
/* Need to align struct pointer to prevent a memory assertion:
* See http://eigen.tuxfamily.org/dox-devel/TopicUnalignedArrayAssert.html
* for details
*/
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
}; };
#endif // _UASMANAGER_H_ #endif

295
src/MissionEditor/MissionEditor.qml

@ -27,6 +27,7 @@ import QtQuick.Dialogs 1.2
import QtLocation 5.3 import QtLocation 5.3
import QtPositioning 5.3 import QtPositioning 5.3
import QGroundControl 1.0
import QGroundControl.FlightMap 1.0 import QGroundControl.FlightMap 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
@ -37,14 +38,18 @@ import QGroundControl.Palette 1.0
QGCView { QGCView {
viewPanel: panel viewPanel: panel
readonly property real _defaultLatitude: 37.803784
readonly property real _defaultLongitude: -122.462276
readonly property int _decimalPlaces: 7 readonly property int _decimalPlaces: 7
readonly property real _horizontalMargin: ScreenTools.defaultFontPixelWidth / 2 readonly property real _horizontalMargin: ScreenTools.defaultFontPixelWidth / 2
readonly property real _verticalMargin: ScreenTools.defaultFontPixelHeight / 2 readonly property real _verticalMargin: ScreenTools.defaultFontPixelHeight / 2
readonly property var _activeVehicle: multiVehicleManager.activeVehicle readonly property var _activeVehicle: multiVehicleManager.activeVehicle
readonly property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 16
property var _missionItems: controller.missionItems property var _missionItems: controller.missionItems
property bool _showHomePositionManager: false
property var _homePositionManager: QGroundControl.homePositionManager
property string _homePositionName: _homePositionManager.homePositions.get(0).name
property var _homePositionCoordinate: _homePositionManager.homePositions.get(0).coordinate
QGCPalette { id: _qgcPal; colorGroupEnabled: enabled } QGCPalette { id: _qgcPal; colorGroupEnabled: enabled }
@ -68,8 +73,8 @@ QGCView {
anchors.top: parent.top anchors.top: parent.top
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
mapName: "MissionEditor" mapName: "MissionEditor"
latitude: _defaultLatitude latitude: _homePositionCoordinate.latitude
longitude: _defaultLongitude longitude: _homePositionCoordinate.longitude
QGCLabel { QGCLabel {
anchors.right: parent.right anchors.right: parent.right
@ -83,12 +88,21 @@ QGCView {
var coordinate = editorMap.toCoordinate(Qt.point(mouse.x, mouse.y)) var coordinate = editorMap.toCoordinate(Qt.point(mouse.x, mouse.y))
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces) coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces) coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = 0 coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
var index = controller.addMissionItem(coordinate) if (_showHomePositionManager) {
setCurrentItem(index) _homePositionCoordinate = coordinate
} else {
var index = controller.addMissionItem(coordinate)
setCurrentItem(index)
}
} }
} }
MissionItemIndicator {
label: "H"
coordinate: _homePositionCoordinate
}
// Add the mission items to the map // Add the mission items to the map
MapItemView { MapItemView {
model: controller.missionItems model: controller.missionItems
@ -141,6 +155,16 @@ QGCView {
id: toolMenu id: toolMenu
MenuItem { MenuItem {
text: "Manage Home Position"
checkable: true
checked: _showHomePositionManager
onTriggered: _showHomePositionManager = checked
}
MenuSeparator { }
MenuItem {
text: "Get mission items from vehicle" text: "Get mission items from vehicle"
enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress
@ -184,63 +208,234 @@ QGCView {
} }
} }
// Mission item list // Mission Item Editor
ListView { Item {
id: missionItemSummaryList
anchors.topMargin: _verticalMargin anchors.topMargin: _verticalMargin
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
anchors.top: toolsButton.bottom anchors.top: toolsButton.bottom
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
spacing: _verticalMargin visible: !_showHomePositionManager
orientation: ListView.Vertical
model: controller.canEdit ? controller.missionItems : 0 ListView {
id: missionItemSummaryList
property real _maxItemHeight: 0 anchors.fill: parent
spacing: _verticalMargin
delegate: orientation: ListView.Vertical
MissionItemEditor { model: controller.canEdit ? controller.missionItems : 0
missionItem: object
width: parent.width property real _maxItemHeight: 0
onClicked: setCurrentItem(object.sequenceNumber) delegate:
MissionItemEditor {
onRemove: { missionItem: object
var newCurrentItem = object.sequenceNumber - 1 width: parent.width
controller.removeMissionItem(object.sequenceNumber)
if (_missionItems.count) { onClicked: setCurrentItem(object.sequenceNumber)
newCurrentItem = Math.min(_missionItems.count - 1, newCurrentItem)
setCurrentItem(newCurrentItem) onRemove: {
var newCurrentItem = object.sequenceNumber - 1
controller.removeMissionItem(object.sequenceNumber)
if (_missionItems.count) {
newCurrentItem = Math.min(_missionItems.count - 1, newCurrentItem)
setCurrentItem(newCurrentItem)
}
} }
onMoveUp: controller.moveUp(object.sequenceNumber)
onMoveDown: controller.moveDown(object.sequenceNumber)
} }
} // ListView
onMoveUp: controller.moveUp(object.sequenceNumber) QGCLabel {
onMoveDown: controller.moveDown(object.sequenceNumber) anchors.fill: parent
} visible: controller.missionItems.count == 0
} // ListView wrapMode: Text.WordWrap
text: "Click in the map to add Mission Items"
}
QGCLabel { QGCLabel {
anchors.topMargin: _verticalMargin anchors.fill: parent
anchors.left: parent.left visible: !controller.canEdit
anchors.right: parent.right wrapMode: Text.WordWrap
anchors.top: toolsButton.bottom text: "The set of mission items you have loaded cannot be edited by QGroundControl. " +
anchors.bottom: parent.bottom "You will only be able to save these to a file, or send them to a vehicle."
visible: controller.missionItems.count == 0 }
wrapMode: Text.WordWrap } // Item - Mission Item editor
text: "Click in the map to add Mission Items"
}
QGCLabel { // Home Position Manager
Item {
anchors.topMargin: _verticalMargin anchors.topMargin: _verticalMargin
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
anchors.top: toolsButton.bottom anchors.top: toolsButton.bottom
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
visible: !controller.canEdit visible: _showHomePositionManager
wrapMode: Text.WordWrap
text: "The set of mission items you have loaded cannot be edited by QGroundControl. " + Column {
"You will only be able to save these to a file, or send them to a vehicle." anchors.fill: parent
}
QGCLabel {
font.pixelSize: ScreenTools.mediumFontPixelSize
text: "Home Position Manager"
}
Item {
width: 10
height: ScreenTools.defaultFontPixelHeight
}
QGCLabel {
text: "Select home position to use:"
}
QGCComboBox {
id: homePosCombo
width: parent.width
textRole: "text"
model: _homePositionManager.homePositions
onCurrentIndexChanged: {
if (currentIndex != -1) {
var homePos = _homePositionManager.homePositions.get(currentIndex)
_homePositionName = homePos.name
_homePositionCoordinate = homePos.coordinate
}
}
}
Item {
width: 10
height: ScreenTools.defaultFontPixelHeight
}
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: "To add a new home position, click in the Map to set the position. Then give it a name and click Add."
}
Item {
width: 10
height: ScreenTools.defaultFontPixelHeight / 3
}
Item {
width: parent.width
height: nameField.height
QGCLabel {
anchors.baseline: nameField.baseline
text: "Name:"
}
QGCTextField {
id: nameField
anchors.right: parent.right
width: _editFieldWidth
text: _homePositionName
}
}
Item {
width: 10
height: ScreenTools.defaultFontPixelHeight / 3
}
Item {
width: parent.width
height: latitudeField.height
QGCLabel {
anchors.baseline: latitudeField.baseline
text: "Lat:"
}
QGCTextField {
id: latitudeField
anchors.right: parent.right
width: _editFieldWidth
text: _homePositionCoordinate.latitude
}
}
Item {
width: 10
height: ScreenTools.defaultFontPixelHeight / 3
}
Item {
width: parent.width
height: longitudeField.height
QGCLabel {
anchors.baseline: longitudeField.baseline
text: "Lon:"
}
QGCTextField {
id: longitudeField
anchors.right: parent.right
width: _editFieldWidth
text: _homePositionCoordinate.longitude
}
}
Item {
width: 10
height: ScreenTools.defaultFontPixelHeight / 3
}
Item {
width: parent.width
height: altitudeField.height
QGCLabel {
anchors.baseline: altitudeField.baseline
text: "Alt:"
}
QGCTextField {
id: altitudeField
anchors.right: parent.right
width: _editFieldWidth
text: _homePositionCoordinate.altitude
}
}
Item {
width: 10
height: ScreenTools.defaultFontPixelHeight
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
QGCButton {
text: "Add/Update"
onClicked: {
_homePositionManager.updateHomePosition(nameField.text, QtPositioning.coordinate(latitudeField.text, longitudeField.text, altitudeField.text))
homePosCombo.currentIndex = homePosCombo.find(nameField.text)
}
}
QGCButton {
text: "Delete"
onClicked: {
homePosCombo.currentIndex = -1
_homePositionManager.deleteHomePosition(nameField.text)
homePosCombo.currentIndex = 0
var homePos = _homePositionManager.homePositions.get(0)
_homePositionName = homePos.name
_homePositionCoordinate = homePos.coordinate
}
}
}
} // Column
} // Item - Home Position Manager
} // Item } // Item
} // Rectangle - mission item list } // Rectangle - mission item list
} // Item - split view container } // Item - split view container

4
src/QmlControls/QmlObjectListModel.cc

@ -29,6 +29,7 @@
#include <QDebug> #include <QDebug>
const int QmlObjectListModel::ObjectRole = Qt::UserRole; const int QmlObjectListModel::ObjectRole = Qt::UserRole;
const int QmlObjectListModel::TextRole = Qt::UserRole + 1;
QmlObjectListModel::QmlObjectListModel(QObject* parent) QmlObjectListModel::QmlObjectListModel(QObject* parent)
: QAbstractListModel(parent) : QAbstractListModel(parent)
@ -60,6 +61,8 @@ QVariant QmlObjectListModel::data(const QModelIndex &index, int role) const
if (role == ObjectRole) { if (role == ObjectRole) {
return QVariant::fromValue(_objectList[index.row()]); return QVariant::fromValue(_objectList[index.row()]);
} else if (role == TextRole) {
return QVariant::fromValue(_objectList[index.row()]->objectName());
} else { } else {
return QVariant(); return QVariant();
} }
@ -70,6 +73,7 @@ QHash<int, QByteArray> QmlObjectListModel::roleNames(void) const
QHash<int, QByteArray> hash; QHash<int, QByteArray> hash;
hash[ObjectRole] = "object"; hash[ObjectRole] = "object";
hash[TextRole] = "text";
return hash; return hash;
} }

1
src/QmlControls/QmlObjectListModel.h

@ -65,6 +65,7 @@ private:
QList<QObject*> _objectList; QList<QObject*> _objectList;
static const int ObjectRole; static const int ObjectRole;
static const int TextRole;
}; };
#endif #endif

1
src/comm/QGCFlightGearLink.cc

@ -38,6 +38,7 @@ This file is part of the QGROUNDCONTROL project
#include <QMessageBox> #include <QMessageBox>
#include <iostream> #include <iostream>
#include <Eigen/Eigen>
#include "QGCFlightGearLink.h" #include "QGCFlightGearLink.h"
#include "QGC.h" #include "QGC.h"

5
src/comm/QGCXPlaneLink.cc

@ -33,10 +33,13 @@ This file is part of the QGROUNDCONTROL project
#include <QDebug> #include <QDebug>
#include <QMutexLocker> #include <QMutexLocker>
#include <QNetworkInterface> #include <QNetworkInterface>
#include <QHostInfo>
#include <iostream> #include <iostream>
#include <Eigen/Eigen>
#include "QGCXPlaneLink.h" #include "QGCXPlaneLink.h"
#include "QGC.h" #include "QGC.h"
#include <QHostInfo>
#include "UAS.h" #include "UAS.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"

3
src/uas/UAS.cc

@ -2784,9 +2784,8 @@ void UAS::home()
double latitude = HomePositionManager::instance()->getHomeLatitude(); double latitude = HomePositionManager::instance()->getHomeLatitude();
double longitude = HomePositionManager::instance()->getHomeLongitude(); double longitude = HomePositionManager::instance()->getHomeLongitude();
double altitude = HomePositionManager::instance()->getHomeAltitude(); double altitude = HomePositionManager::instance()->getHomeAltitude();
int frame = HomePositionManager::instance()->getHomeFrame();
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, frame, 0, latitude, longitude, altitude); mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, MAV_FRAME_GLOBAL, 0, latitude, longitude, altitude);
_vehicle->sendMessage(msg); _vehicle->sendMessage(msg);
} }

1
src/ui/MainWindow.cc

@ -609,7 +609,6 @@ void MainWindow::closeEvent(QCloseEvent *event)
_storeCurrentViewState(); _storeCurrentViewState();
storeSettings(); storeSettings();
HomePositionManager::instance()->storeSettings();
event->accept(); event->accept();
} }

Loading…
Cancel
Save