Commit b43ccf87 authored by Don Gagne's avatar Don Gagne

Support live home position in Mission Editor

parent 85379ce3
...@@ -38,6 +38,8 @@ MissionEditor::MissionEditor(QWidget *parent) ...@@ -38,6 +38,8 @@ MissionEditor::MissionEditor(QWidget *parent)
: QGCQmlWidgetHolder(parent) : QGCQmlWidgetHolder(parent)
, _missionItems(NULL) , _missionItems(NULL)
, _canEdit(true) , _canEdit(true)
, _activeVehicle(NULL)
, _liveHomePositionAvailable(false)
{ {
// Get rid of layout default margins // Get rid of layout default margins
QLayout* pl = layout(); QLayout* pl = layout();
...@@ -45,11 +47,16 @@ MissionEditor::MissionEditor(QWidget *parent) ...@@ -45,11 +47,16 @@ MissionEditor::MissionEditor(QWidget *parent)
pl->setContentsMargins(0,0,0,0); pl->setContentsMargins(0,0,0,0);
} }
Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle(); MultiVehicleManager* multiVehicleMgr = MultiVehicleManager::instance();
connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionEditor::_activeVehicleChanged);
Vehicle* activeVehicle = multiVehicleMgr->activeVehicle();
if (activeVehicle) { if (activeVehicle) {
MissionManager* missionManager = activeVehicle->missionManager(); MissionManager* missionManager = activeVehicle->missionManager();
connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionEditor::_newMissionItemsAvailable); connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionEditor::_newMissionItemsAvailable);
_newMissionItemsAvailable(); _newMissionItemsAvailable();
_activeVehicleChanged(activeVehicle);
} else { } else {
_missionItems = new QmlObjectListModel(this); _missionItems = new QmlObjectListModel(this);
_initAllMissionItems(); _initAllMissionItems();
...@@ -389,3 +396,34 @@ void MissionEditor::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command ...@@ -389,3 +396,34 @@ void MissionEditor::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command
_recalcChildItems(); _recalcChildItems();
_recalcWaypointLines(); _recalcWaypointLines();
} }
void MissionEditor::_activeVehicleChanged(Vehicle* activeVehicle)
{
if (_activeVehicle) {
disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionEditor::_activeVehicleHomePositionAvailableChanged);
disconnect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionEditor::_activeVehicleHomePositionChanged);
_activeVehicle = NULL;
_activeVehicleHomePositionAvailableChanged(false);
}
_activeVehicle = activeVehicle;
if (_activeVehicle) {
connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionEditor::_activeVehicleHomePositionAvailableChanged);
connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionEditor::_activeVehicleHomePositionChanged);
_activeVehicleHomePositionChanged(_activeVehicle->homePosition());
_activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
}
}
void MissionEditor::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
_liveHomePositionAvailable = homePositionAvailable;
emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
}
void MissionEditor::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
{
_liveHomePosition = homePosition;
emit liveHomePositionChanged(_liveHomePosition);
}
...@@ -26,6 +26,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -26,6 +26,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGCQmlWidgetHolder.h" #include "QGCQmlWidgetHolder.h"
#include "QmlObjectListModel.h" #include "QmlObjectListModel.h"
#include "Vehicle.h"
class MissionEditor : public QGCQmlWidgetHolder class MissionEditor : public QGCQmlWidgetHolder
{ {
...@@ -35,9 +36,11 @@ public: ...@@ -35,9 +36,11 @@ public:
MissionEditor(QWidget* parent = NULL); MissionEditor(QWidget* parent = NULL);
~MissionEditor(); ~MissionEditor();
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged) Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged) Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines NOTIFY waypointLinesChanged)
Q_PROPERTY(bool canEdit READ canEdit NOTIFY canEditChanged) 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_INVOKABLE int addMissionItem(QGeoCoordinate coordinate); Q_INVOKABLE int addMissionItem(QGeoCoordinate coordinate);
Q_INVOKABLE void getMissionItems(void); Q_INVOKABLE void getMissionItems(void);
...@@ -53,16 +56,23 @@ public: ...@@ -53,16 +56,23 @@ public:
QmlObjectListModel* missionItems(void) { return _missionItems; } QmlObjectListModel* missionItems(void) { return _missionItems; }
QmlObjectListModel* waypointLines(void) { return &_waypointLines; } QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
bool canEdit(void) { return _canEdit; } bool canEdit(void) { return _canEdit; }
bool liveHomePositionAvailable(void) { return _liveHomePositionAvailable; }
QGeoCoordinate liveHomePosition(void) { return _liveHomePosition; }
signals: signals:
void missionItemsChanged(void); void missionItemsChanged(void);
void canEditChanged(bool canEdit); void canEditChanged(bool canEdit);
void waypointLinesChanged(void); void waypointLinesChanged(void);
void liveHomePositionAvailableChanged(bool homePositionAvailable);
void liveHomePositionChanged(const QGeoCoordinate& homePosition);
private slots: private slots:
void _newMissionItemsAvailable(); void _newMissionItemsAvailable();
void _itemCoordinateChanged(const QGeoCoordinate& coordinate); void _itemCoordinateChanged(const QGeoCoordinate& coordinate);
void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command); void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
void _activeVehicleChanged(Vehicle* activeVehicle);
void _activeVehicleHomePositionAvailableChanged(bool homePositionAvailable);
void _activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition);
private: private:
void _recalcSequence(void); void _recalcSequence(void);
...@@ -78,7 +88,10 @@ private: ...@@ -78,7 +88,10 @@ private:
QmlObjectListModel* _missionItems; QmlObjectListModel* _missionItems;
QmlObjectListModel _waypointLines; QmlObjectListModel _waypointLines;
bool _canEdit; ///< true: UI can edit these items, false: can't edit, can only send to vehicle or save 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;
static const char* _settingsGroup; static const char* _settingsGroup;
}; };
......
...@@ -52,7 +52,11 @@ QGCView { ...@@ -52,7 +52,11 @@ QGCView {
property var _homePositionManager: QGroundControl.homePositionManager property var _homePositionManager: QGroundControl.homePositionManager
property string _homePositionName: _homePositionManager.homePositions.get(0).name property string _homePositionName: _homePositionManager.homePositions.get(0).name
property var homePositionCoordinate: _homePositionManager.homePositions.get(0).coordinate
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
QGCPalette { id: _qgcPal; colorGroupEnabled: enabled } QGCPalette { id: _qgcPal; colorGroupEnabled: enabled }
...@@ -76,20 +80,24 @@ QGCView { ...@@ -76,20 +80,24 @@ QGCView {
} }
} }
// Home position is mission item 0, so keep them in sync function updateHomePosition() {
onHomePositionCoordinateChanged: { homePosition = liveHomePositionAvailable ? liveHomePosition : offlineHomePosition
// Changing the coordinate will set the dirty bit, so we save and reset it // Changing the coordinate will set the dirty bit, so we save and reset it
var dirtyBit = _missionItems.dirty var dirtyBit = _missionItems.dirty
_missionItems.get(0).coordinate = homePositionCoordinate _missionItems.get(0).coordinate = homePosition
_missionItems.dirty = dirtyBit _missionItems.dirty = dirtyBit
} }
Component.onCompleted: onHomePositionCoordinateChanged Component.onCompleted: updateHomePosition()
onOfflineHomePositionChanged: updateHomePosition()
onLiveHomePositionAvailableChanged: updateHomePosition()
onLiveHomePositionChanged: updateHomePosition()
Connections { Connections {
target: controller target: controller
onMissionItemsChanged: _missionItems.get(0).coordinate = homePositionCoordinate // When the mission items change _missionsItems[0] changes as well so we need to reset it to home
onMissionItemsChanged: updateHomePosition
} }
QGCViewPanel { QGCViewPanel {
...@@ -108,8 +116,8 @@ QGCView { ...@@ -108,8 +116,8 @@ QGCView {
mapName: "MissionEditor" mapName: "MissionEditor"
Component.onCompleted: { Component.onCompleted: {
latitude = homePositionCoordinate.latitude latitude = homePosition.latitude
longitude = homePositionCoordinate.longitude longitude = homePosition.longitude
} }
MouseArea { MouseArea {
...@@ -121,7 +129,7 @@ QGCView { ...@@ -121,7 +129,7 @@ QGCView {
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces) coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces) coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
if (_showHomePositionManager) { if (_showHomePositionManager) {
homePositionCoordinate = coordinate offlineHomePosition = coordinate
} else if (_addMissionItems) { } else if (_addMissionItems) {
var index = controller.addMissionItem(coordinate) var index = controller.addMissionItem(coordinate)
setCurrentItem(index) setCurrentItem(index)
...@@ -200,7 +208,7 @@ QGCView { ...@@ -200,7 +208,7 @@ QGCView {
onClicked: { onClicked: {
centerMapButton.hideDropDown() centerMapButton.hideDropDown()
editorMap.center = QtPositioning.coordinate(homePositionCoordinate.latitude, homePositionCoordinate.longitude) editorMap.center = QtPositioning.coordinate(homePosition.latitude, homePosition.longitude)
_showHomePositionManager = true _showHomePositionManager = true
} }
} }
...@@ -229,8 +237,8 @@ QGCView { ...@@ -229,8 +237,8 @@ QGCView {
centerMapButton.hideDropDown() centerMapButton.hideDropDown()
// Begin with only the home position in the region // Begin with only the home position in the region
var region = QtPositioning.rectangle(QtPositioning.coordinate(homePositionCoordinate.latitude, _homePositionCoordinate.longitude), var region = QtPositioning.rectangle(QtPositioning.coordinate(homePosition.latitude, homePosition.longitude),
QtPositioning.coordinate(homePositionCoordinate.latitude, _homePositionCoordinate.longitude)) QtPositioning.coordinate(homePosition.latitude, homePosition.longitude))
// Now expand the region to include all mission items // Now expand the region to include all mission items
for (var i=0; i<_missionItems.count; i++) { for (var i=0; i<_missionItems.count; i++) {
...@@ -509,11 +517,12 @@ QGCView { ...@@ -509,11 +517,12 @@ QGCView {
visible: _showHomePositionManager && !_showHelpPanel visible: _showHomePositionManager && !_showHelpPanel
Column { Column {
anchors.fill: parent anchors.fill: parent
visible: !liveHomePositionAvailable
QGCLabel { QGCLabel {
font.pixelSize: ScreenTools.mediumFontPixelSize font.pixelSize: ScreenTools.mediumFontPixelSize
text: "Home Position Manager" text: "Offline Home Position Manager"
} }
Item { Item {
...@@ -522,7 +531,18 @@ QGCView { ...@@ -522,7 +531,18 @@ QGCView {
} }
QGCLabel { QGCLabel {
text: "Select home position to use:" width: parent.width
wrapMode: Text.WordWrap
text: "This is used to specify a simulated home position while you are not connected to a Vehicle."
}
Item {
width: 10
height: ScreenTools.defaultFontPixelHeight
}
QGCLabel {
text: "Select home position to use:"
} }
QGCComboBox { QGCComboBox {
...@@ -535,9 +555,9 @@ QGCView { ...@@ -535,9 +555,9 @@ QGCView {
if (currentIndex != -1) { if (currentIndex != -1) {
var homePos = _homePositionManager.homePositions.get(currentIndex) var homePos = _homePositionManager.homePositions.get(currentIndex)
_homePositionName = homePos.name _homePositionName = homePos.name
homePositionCoordinate = homePos.coordinate offlineHomePosition = homePos.coordinate
editorMap.latitude = homePositionCoordinate.latitude editorMap.latitude = offlineHomePosition.latitude
editorMap.longitude = homePositionCoordinate.longitude editorMap.longitude = offlineHomePosition.longitude
} }
} }
} }
...@@ -585,18 +605,18 @@ QGCView { ...@@ -585,18 +605,18 @@ QGCView {
Item { Item {
width: parent.width width: parent.width
height: latitudeField.height height: offlineLatitudeField.height
QGCLabel { QGCLabel {
anchors.baseline: latitudeField.baseline anchors.baseline: offlineLatitudeField.baseline
text: "Lat:" text: "Lat:"
} }
QGCTextField { QGCTextField {
id: latitudeField id: offlineLatitudeField
anchors.right: parent.right anchors.right: parent.right
width: _editFieldWidth width: _editFieldWidth
text: homePositionCoordinate.latitude text: offlineHomePosition.latitude
} }
} }
...@@ -607,18 +627,18 @@ QGCView { ...@@ -607,18 +627,18 @@ QGCView {
Item { Item {
width: parent.width width: parent.width
height: longitudeField.height height: offlineLongitudeField.height
QGCLabel { QGCLabel {
anchors.baseline: longitudeField.baseline anchors.baseline: offlineLongitudeField.baseline
text: "Lon:" text: "Lon:"
} }
QGCTextField { QGCTextField {
id: longitudeField id: offlineLongitudeField
anchors.right: parent.right anchors.right: parent.right
width: _editFieldWidth width: _editFieldWidth
text: homePositionCoordinate.longitude text: offlineHomePosition.longitude
} }
} }
...@@ -629,18 +649,18 @@ QGCView { ...@@ -629,18 +649,18 @@ QGCView {
Item { Item {
width: parent.width width: parent.width
height: altitudeField.height height: offlineAltitudeField.height
QGCLabel { QGCLabel {
anchors.baseline: altitudeField.baseline anchors.baseline: offlineAltitudeField.baseline
text: "Alt:" text: "Alt:"
} }
QGCTextField { QGCTextField {
id: altitudeField id: offlineAltitudeField
anchors.right: parent.right anchors.right: parent.right
width: _editFieldWidth width: _editFieldWidth
text: homePositionCoordinate.altitude text: offlineHomePosition.altitude
} }
} }
...@@ -656,8 +676,8 @@ QGCView { ...@@ -656,8 +676,8 @@ QGCView {
text: "Add/Update" text: "Add/Update"
onClicked: { onClicked: {
homePositionCoordinate = QtPositioning.coordinate(latitudeField.text, longitudeField.text, altitudeField.text) offlineHomePosition = QtPositioning.coordinate(latitudeField.text, longitudeField.text, altitudeField.text)
_homePositionManager.updateHomePosition(nameField.text, homePositionCoordinate) _homePositionManager.updateHomePosition(nameField.text, offlineHomePosition)
homePosCombo.currentIndex = homePosCombo.find(nameField.text) homePosCombo.currentIndex = homePosCombo.find(nameField.text)
} }
} }
...@@ -671,11 +691,88 @@ QGCView { ...@@ -671,11 +691,88 @@ QGCView {
homePosCombo.currentIndex = 0 homePosCombo.currentIndex = 0
var homePos = _homePositionManager.homePositions.get(0) var homePos = _homePositionManager.homePositions.get(0)
_homePositionName = homePos.name _homePositionName = homePos.name
homePositionCoordinate = homePos.coordinate offlineHomePosition = homePos.coordinate
} }
} }
} }
} // Column } // Column - Offline view
Column {
anchors.fill: parent
visible: liveHomePositionAvailable
QGCLabel {
font.pixelSize: ScreenTools.mediumFontPixelSize
text: "Vehicle Home Position"
}
Item {
width: 10
height: ScreenTools.defaultFontPixelHeight
}
Item {
width: parent.width
height: liveLatitudeField.height
QGCLabel {
anchors.baseline: liveLatitudeField.baseline
text: "Lat:"
}
QGCLabel {
id: liveLatitudeField
anchors.right: parent.right
width: _editFieldWidth
text: liveHomePosition.latitude
}
}
Item {
width: 10
height: ScreenTools.defaultFontPixelHeight / 3
}
Item {
width: parent.width
height: liveLongitudeField.height
QGCLabel {
anchors.baseline: liveLongitudeField.baseline
text: "Lon:"
}
QGCLabel {
id: liveLongitudeField
anchors.right: parent.right
width: _editFieldWidth
text: liveHomePosition.longitude
}
}
Item {
width: 10
height: ScreenTools.defaultFontPixelHeight / 3
}
Item {
width: parent.width
height: liveAltitudeField.height
QGCLabel {
anchors.baseline: liveAltitudeField.baseline
text: "Alt:"
}
QGCLabel {
id: liveAltitudeField
anchors.right: parent.right
width: _editFieldWidth
text: liveHomePosition.altitude
}
}
} // Column - Online view
} // Item - Home Position Manager } // Item - Home Position Manager
// Help Panel // Help Panel
......
...@@ -227,8 +227,8 @@ void Vehicle::_handleHomePosition(mavlink_message_t& message) ...@@ -227,8 +227,8 @@ void Vehicle::_handleHomePosition(mavlink_message_t& message)
_homePosition.setAltitude(homePos.altitude / 1000.0); _homePosition.setAltitude(homePos.altitude / 1000.0);
_homePositionAvailable = true; _homePositionAvailable = true;
emit homePositionAvailableChanged(true);
emit homePositionChanged(_homePosition); emit homePositionChanged(_homePosition);
emit homePositionAvailableChanged(true);
} }
void Vehicle::_handleHeartbeat(mavlink_message_t& message) void Vehicle::_handleHeartbeat(mavlink_message_t& message)
...@@ -963,10 +963,6 @@ bool Vehicle::homePositionAvailable(void) ...@@ -963,10 +963,6 @@ bool Vehicle::homePositionAvailable(void)
QGeoCoordinate Vehicle::homePosition(void) QGeoCoordinate Vehicle::homePosition(void)
{ {
if (!_homePositionAvailable) {
qWarning() << "Call to homePosition while _homePositionAvailable == false";
}
return _homePosition; return _homePosition;
} }
......
...@@ -157,6 +157,7 @@ void MockLink::_run1HzTasks(void) ...@@ -157,6 +157,7 @@ void MockLink::_run1HzTasks(void)
{ {
if (_mavlinkStarted && _connected) { if (_mavlinkStarted && _connected) {
_sendHeartBeat(); _sendHeartBeat();
_sendHomePosition();
} }
} }
...@@ -673,3 +674,25 @@ void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode ...@@ -673,3 +674,25 @@ void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode
{ {
_missionItemHandler.setMissionItemFailureMode(failureMode, firstTimeOnly); _missionItemHandler.setMissionItemFailureMode(failureMode, firstTimeOnly);
} }
void MockLink::_sendHomePosition(void)
{
mavlink_message_t msg;
float bogus[4];
bogus[0] = 0.0f;
bogus[1] = 0.0f;
bogus[2] = 0.0f;
bogus[3] = 0.0f;
mavlink_msg_home_position_pack(_vehicleSystemId,
_vehicleComponentId,
&msg,
(int32_t)(47.633033f * 1E7),
(int32_t)(-122.08794f * 1E7),
(int32_t)(2.0f * 1000),
0.0f, 0.0f, 0.0f,
&bogus[0],
0.0f, 0.0f, 0.0f);
respondWithMavlinkMessage(msg);
}
...@@ -143,6 +143,7 @@ private: ...@@ -143,6 +143,7 @@ private:
void _handleCommandLong(const mavlink_message_t& msg); void _handleCommandLong(const mavlink_message_t& msg);
float _floatUnionForParam(int componentId, const QString& paramName); float _floatUnionForParam(int componentId, const QString& paramName);
void _setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat); void _setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat);
void _sendHomePosition(void);
MockLinkMissionItemHandler _missionItemHandler; MockLinkMissionItemHandler _missionItemHandler;
......
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