Commit d0d6cc42 authored by Don Gagne's avatar Don Gagne

More MissionEditor work

- New MissionManager
- Plumb MissionManager through MissionEditor
- Mission Editor supports get/set
parent 830d7dee
...@@ -145,6 +145,7 @@ INCLUDEPATH += \ ...@@ -145,6 +145,7 @@ INCLUDEPATH += \
src/Joystick \ src/Joystick \
src/lib/qmapcontrol \ src/lib/qmapcontrol \
src/MissionEditor \ src/MissionEditor \
src/MissionManager \
src/QmlControls \ src/QmlControls \
src/uas \ src/uas \
src/ui \ src/ui \
...@@ -246,6 +247,7 @@ HEADERS += \ ...@@ -246,6 +247,7 @@ HEADERS += \
src/LogCompressor.h \ src/LogCompressor.h \
src/MG.h \ src/MG.h \
src/MissionEditor/MissionEditor.h \ src/MissionEditor/MissionEditor.h \
src/MissionManager/MissionManager.h \
src/QGC.h \ src/QGC.h \
src/QGCApplication.h \ src/QGCApplication.h \
src/QGCComboBox.h \ src/QGCComboBox.h \
...@@ -384,6 +386,7 @@ SOURCES += \ ...@@ -384,6 +386,7 @@ SOURCES += \
src/LogCompressor.cc \ src/LogCompressor.cc \
src/main.cc \ src/main.cc \
src/MissionEditor/MissionEditor.cc \ src/MissionEditor/MissionEditor.cc \
src/MissionManager/MissionManager.cc \
src/QGC.cc \ src/QGC.cc \
src/QGCApplication.cc \ src/QGCApplication.cc \
src/QGCComboBox.cc \ src/QGCComboBox.cc \
......
...@@ -34,7 +34,7 @@ import QGroundControl.Controllers 1.0 ...@@ -34,7 +34,7 @@ import QGroundControl.Controllers 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
QGCView { QGCView {
id: rootQGCView id: qgcView
viewPanel: panel viewPanel: panel
QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled } QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled }
......
...@@ -53,7 +53,6 @@ Map { ...@@ -53,7 +53,6 @@ Map {
property real lon: (longitude >= -180 && longitude <= 180) ? longitude : 0 property real lon: (longitude >= -180 && longitude <= 180) ? longitude : 0
property real lat: (latitude >= -90 && latitude <= 90) ? latitude : 0 property real lat: (latitude >= -90 && latitude <= 90) ? latitude : 0
anchors.fill: parent
zoomLevel: 18 zoomLevel: 18
center: QtPositioning.coordinate(lat, lon) center: QtPositioning.coordinate(lat, lon)
gesture.flickDeceleration: 3000 gesture.flickDeceleration: 3000
......
...@@ -23,6 +23,8 @@ This file is part of the QGROUNDCONTROL project ...@@ -23,6 +23,8 @@ This file is part of the QGROUNDCONTROL project
#include "MissionEditor.h" #include "MissionEditor.h"
#include "ScreenToolsController.h" #include "ScreenToolsController.h"
#include "MultiVehicleManager.h"
#include "MissionManager.h"
#include <QQmlContext> #include <QQmlContext>
#include <QQmlEngine> #include <QQmlEngine>
...@@ -32,6 +34,7 @@ const char* MissionEditor::_settingsGroup = "MissionEditor"; ...@@ -32,6 +34,7 @@ const char* MissionEditor::_settingsGroup = "MissionEditor";
MissionEditor::MissionEditor(QWidget *parent) MissionEditor::MissionEditor(QWidget *parent)
: QGCQmlWidgetHolder(parent) : QGCQmlWidgetHolder(parent)
, _missionItems(NULL)
{ {
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
// Get rid of layout default margins // Get rid of layout default margins
...@@ -44,6 +47,15 @@ MissionEditor::MissionEditor(QWidget *parent) ...@@ -44,6 +47,15 @@ MissionEditor::MissionEditor(QWidget *parent)
setMinimumHeight(33 * ScreenToolsController::defaultFontPixelSize_s()); setMinimumHeight(33 * ScreenToolsController::defaultFontPixelSize_s());
#endif #endif
Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
if (activeVehicle) {
MissionManager* missionManager = activeVehicle->missionManager();
connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionEditor::_newMissionItemsAvailable);
_newMissionItemsAvailable();
} else {
_missionItems = new QmlObjectListModel(this);
}
setContextPropertyObject("controller", this); setContextPropertyObject("controller", this);
setSource(QUrl::fromUserInput("qrc:/qml/MissionEditor.qml")); setSource(QUrl::fromUserInput("qrc:/qml/MissionEditor.qml"));
...@@ -53,6 +65,34 @@ MissionEditor::~MissionEditor() ...@@ -53,6 +65,34 @@ MissionEditor::~MissionEditor()
{ {
} }
void MissionEditor::_newMissionItemsAvailable(void)
{
if (_missionItems) {
_missionItems->deleteLater();
}
_missionItems = MultiVehicleManager::instance()->activeVehicle()->missionManager()->copyMissionItems();
emit missionItemsChanged();
}
void MissionEditor::getMissionItems(void)
{
Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
if (activeVehicle) {
activeVehicle->missionManager()->requestMissionItems();
}
}
void MissionEditor::setMissionItems(void)
{
Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
if (activeVehicle) {
activeVehicle->missionManager()->writeMissionItems(*_missionItems);
}
}
void MissionEditor::saveSetting(const QString &name, const QString& value) void MissionEditor::saveSetting(const QString &name, const QString& value)
{ {
QSettings settings; QSettings settings;
...@@ -73,10 +113,10 @@ QString MissionEditor::loadSetting(const QString &name, const QString& defaultVa ...@@ -73,10 +113,10 @@ QString MissionEditor::loadSetting(const QString &name, const QString& defaultVa
void MissionEditor::addMissionItem(QGeoCoordinate coordinate) void MissionEditor::addMissionItem(QGeoCoordinate coordinate)
{ {
MissionItem * newItem = new MissionItem(this, _missionItems.count(), coordinate); MissionItem * newItem = new MissionItem(this, _missionItems->count(), coordinate);
if (_missionItems.count() == 0) { if (_missionItems->count() == 0) {
newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF); newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
} }
qDebug() << "MissionItem" << newItem->coordinate(); qDebug() << "MissionItem" << newItem->coordinate();
_missionItems.append(newItem); _missionItems->append(newItem);
} }
...@@ -35,19 +35,27 @@ public: ...@@ -35,19 +35,27 @@ public:
MissionEditor(QWidget* parent = NULL); MissionEditor(QWidget* parent = NULL);
~MissionEditor(); ~MissionEditor();
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItemsModel CONSTANT) Q_PROPERTY(QmlObjectListModel* missionItems READ missionItemsModel NOTIFY missionItemsChanged)
Q_INVOKABLE void addMissionItem(QGeoCoordinate coordinate); Q_INVOKABLE void addMissionItem(QGeoCoordinate coordinate);
Q_INVOKABLE void getMissionItems(void);
Q_INVOKABLE void setMissionItems(void);
Q_INVOKABLE void saveSetting (const QString &key, const QString& value); Q_INVOKABLE void saveSetting (const QString &key, const QString& value);
Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue); Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue);
// Property accessors // Property accessors
QmlObjectListModel* missionItemsModel(void) { return &_missionItems; } QmlObjectListModel* missionItemsModel(void) { return _missionItems; }
signals:
void missionItemsChanged(void);
private slots:
void _newMissionItemsAvailable();
private: private:
QmlObjectListModel _missionItems; QmlObjectListModel* _missionItems;
static const char* _settingsGroup; static const char* _settingsGroup;
}; };
......
...@@ -34,82 +34,147 @@ import QGroundControl.Palette 1.0 ...@@ -34,82 +34,147 @@ import QGroundControl.Palette 1.0
/// Mission Editor /// Mission Editor
Item { QGCView {
// For some reason we can't have FlightMap as the top level control. If you do that it doesn't draw. viewPanel: panel
// So we have an Item at the top to work around that.
readonly property real _defaultLatitude: 37.803784 readonly property real _defaultLatitude: 37.803784
readonly property real _defaultLongitude: -122.462276 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 _verticalMargin: ScreenTools.defaultFontPixelHeight / 2
readonly property var _activeVehicle: multiVehicleManager.activeVehicle
FlightMap { QGCPalette { id: _qgcPal; colorGroupEnabled: enabled }
id: editorMap
anchors.fill: parent
mapName: "MissionEditor"
latitude: _defaultLatitude
longitude: _defaultLongitude
QGCLabel { text: "WIP: Non functional"; font.pixelSize: ScreenTools.largeFontPixelSize }
QGCViewPanel {
id: panel
anchors.fill: parent
MouseArea { Item {
anchors.fill: parent anchors.fill: parent
onClicked: { FlightMap {
var coordinate = editorMap.toCoordinate(Qt.point(mouse.x, mouse.y)) id: editorMap
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces) anchors.left: parent.left
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces) anchors.right: missionItemView.left
coordinate.altitude = 0 anchors.top: parent.top
controller.addMissionItem(coordinate) anchors.bottom: parent.bottom
} mapName: "MissionEditor"
} latitude: _defaultLatitude
longitude: _defaultLongitude
// Add the mission items to the map
MapItemView { QGCLabel {
model: controller.missionItems anchors.right: parent.right
text: "WIP: Danger, do not fly with this!"; font.pixelSize: ScreenTools.largeFontPixelSize }
delegate:
MissionItemIndicator {
label: object.sequenceNumber MouseArea {
isCurrentItem: object.isCurrentItem anchors.fill: parent
coordinate: object.coordinate
onClicked: {
Component.onCompleted: console.log("Indicator", object.coordinate) var coordinate = editorMap.toCoordinate(Qt.point(mouse.x, mouse.y))
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = 0
controller.addMissionItem(coordinate)
}
} }
}
// Add the mission items to the map
// Mission item list MapItemView {
ListView { model: controller.missionItems
id: missionItemSummaryList
anchors.margins: ScreenTools.defaultFontPixelHeight delegate:
anchors.top: parent.top MissionItemIndicator {
anchors.bottom: editorMap.mapWidgets.top label: object.sequenceNumber
anchors.right: parent.right isCurrentItem: object.isCurrentItem
width: ScreenTools.defaultFontPixelWidth * 30 coordinate: object.coordinate
spacing: ScreenTools.defaultFontPixelHeight / 2
orientation: ListView.Vertical Component.onCompleted: console.log("Indicator", object.coordinate)
model: controller.missionItems }
}
property real _maxItemHeight: 0
Column {
delegate: id: controlWidgets
MissionItemEditor { anchors.margins: ScreenTools.defaultFontPixelWidth
missionItem: object anchors.right: parent.left
anchors.bottom: parent.top
spacing: ScreenTools.defaultFontPixelWidth / 2
QGCButton {
id: addMode
text: "+"
checkable: true
}
} }
} } // FlightMap
Column { Rectangle {
id: controlWidgets id: missionItemView
anchors.margins: ScreenTools.defaultFontPixelWidth anchors.right: parent.right
anchors.right: parent.left anchors.top: parent.top
anchors.bottom: parent.top anchors.bottom: parent.bottom
spacing: ScreenTools.defaultFontPixelWidth / 2 width: ScreenTools.defaultFontPixelWidth * 30
color: _qgcPal.window
QGCButton {
id: addMode Item {
text: "+" anchors.margins: _verticalMargin
checkable: true anchors.fill: parent
}
} QGCButton {
} id: toolsButton
} text: "Tools"
menu : toolMenu
Menu {
id: toolMenu
MenuItem {
text: "Get mission items from vehicle"
enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress
onTriggered: controller.getMissionItems()
}
MenuItem {
text: "Send mission items to vehicle"
enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress
onTriggered: controller.setMissionItems()
}
MenuItem {
text: "Load mission items from disk"
}
MenuItem {
text: "Save mission items to disk"
}
}
}
// Mission item list
ListView {
id: missionItemSummaryList
anchors.topMargin: _verticalMargin
anchors.left: parent.left
anchors.right: parent.right
anchors.top: toolsButton.bottom
anchors.bottom: parent.bottom
spacing: _verticalMargin
orientation: ListView.Vertical
model: controller.missionItems
property real _maxItemHeight: 0
delegate:
MissionItemEditor {
missionItem: object
width: parent.width
}
} // ListView
} // Item
} // Rectangle - mission item list
} // Item - split view container
} // QGCViewPanel
} // QGCVIew
This diff is collapsed.
...@@ -69,6 +69,7 @@ public: ...@@ -69,6 +69,7 @@ public:
Q_PROPERTY(QStringList valueStrings READ valueStrings NOTIFY valueStringsChanged) Q_PROPERTY(QStringList valueStrings READ valueStrings NOTIFY valueStringsChanged)
Q_PROPERTY(int commandByIndex READ commandByIndex WRITE setCommandByIndex NOTIFY commandChanged) Q_PROPERTY(int commandByIndex READ commandByIndex WRITE setCommandByIndex NOTIFY commandChanged)
Q_PROPERTY(QmlObjectListModel* facts READ facts NOTIFY commandChanged) Q_PROPERTY(QmlObjectListModel* facts READ facts NOTIFY commandChanged)
Q_PROPERTY(int factCount READ factCount NOTIFY commandChanged)
Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged) Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged)
// Property accesors // Property accesors
...@@ -90,13 +91,14 @@ public: ...@@ -90,13 +91,14 @@ public:
int commandByIndex(void); int commandByIndex(void);
void setCommandByIndex(int index); void setCommandByIndex(int index);
MavlinkQmlSingleton::Qml_MAV_CMD command(void) { return (MavlinkQmlSingleton::Qml_MAV_CMD)getAction(); }; MavlinkQmlSingleton::Qml_MAV_CMD command(void) { return (MavlinkQmlSingleton::Qml_MAV_CMD)_command; };
void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) { setAction(command); } void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) { setAction(command); }
QStringList valueLabels(void); QStringList valueLabels(void);
QStringList valueStrings(void); QStringList valueStrings(void);
QmlObjectListModel* facts(void); QmlObjectListModel* facts(void);
int factCount(void);
double yawDegrees(void) const; double yawDegrees(void) const;
void setYawDegrees(double yaw); void setYawDegrees(double yaw);
...@@ -122,57 +124,56 @@ public: ...@@ -122,57 +124,56 @@ public:
double yawRadians(void) const; double yawRadians(void) const;
void setYawRadians(double yaw); void setYawRadians(double yaw);
bool getAutoContinue() const { bool autoContinue() const {
return _autocontinue; return _autocontinue;
} }
double loiterOrbitRadius() const { double loiterOrbitRadius() const {
return _loiterOrbitRadiusFact->value().toDouble(); return _loiterOrbitRadiusFact->value().toDouble();
} }
double getAcceptanceRadius() const { double acceptanceRadius() const {
return getParam2(); return param2();
} }
double getHoldTime() const { double holdTime() const {
return getParam1(); return param1();
} }
double getParam1() const { double param1() const {
return _param1Fact->value().toDouble(); return _param1Fact->value().toDouble();
} }
double getParam2() const { double param2() const {
return _param2Fact->value().toDouble(); return _param2Fact->value().toDouble();
} }
double getParam3() const { double param3() const {
return loiterOrbitRadius(); return loiterOrbitRadius();
} }
double getParam4() const { double param4() const {
return yawRadians(); return yawRadians();
} }
double getParam5() const { double param5() const {
return latitude(); return latitude();
} }
double getParam6() const { double param6() const {
return longitude(); return longitude();
} }
double getParam7() const { double param7() const {
return altitude(); return altitude();
} }
// MAV_FRAME // MAV_FRAME
int getFrame() const { int frame() const {
return _frame; return _frame;
} }
// MAV_CMD // MAV_CMD
int getAction() const { int command() const {
return _action; return _command;
} }
/** @brief Returns true if x, y, z contain reasonable navigation data */ /** @brief Returns true if x, y, z contain reasonable navigation data */
bool isNavigationType(); bool isNavigationType();
/** @brief Get the time this waypoint was reached */ /** @brief Get the time this waypoint was reached */
quint64 getReachedTime() const { return _reachedTime; } quint64 reachedTime() const { return _reachedTime; }
void save(QTextStream &saveStream); void save(QTextStream &saveStream);
bool load(QTextStream &loadStream); bool load(QTextStream &loadStream);
signals: signals:
void sequenceNumberChanged(int sequenceNumber); void sequenceNumberChanged(int sequenceNumber);
void specifiesCoordinateChanged(bool specifiesCoordinate); void specifiesCoordinateChanged(bool specifiesCoordinate);
...@@ -224,13 +225,13 @@ private: ...@@ -224,13 +225,13 @@ private:
const char* name; const char* name;
} MavCmd2Name_t; } MavCmd2Name_t;
int _sequenceNumber; int _sequenceNumber;
QGeoCoordinate _coordinate; QGeoCoordinate _coordinate;
int _frame; int _frame;
int _action; MavlinkQmlSingleton::Qml_MAV_CMD _command;
bool _autocontinue; bool _autocontinue;
bool _isCurrentItem; bool _isCurrentItem;
quint64 _reachedTime; quint64 _reachedTime;
Fact* _yawRadiansFact; Fact* _yawRadiansFact;
Fact* _loiterOrbitRadiusFact; Fact* _loiterOrbitRadiusFact;
......
This diff is collapsed.
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 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 MissionManager_H
#define MissionManager_H
#include <QObject>
#include <QLoggingCategory>
#include <QThread>
#include <QMutex>
#include <QTimer>
#include "QmlObjectListModel.h"
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
class Vehicle;
Q_DECLARE_LOGGING_CATEGORY(MissionManagerLog)
class MissionManager : public QThread
{
Q_OBJECT
public:
/// @param uas Uas which this set of facts is associated with
MissionManager(Vehicle* vehicle);
~MissionManager();
Q_PROPERTY(bool inProgress READ inProgress CONSTANT)
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems CONSTANT)
// Property accessors
bool inProgress(void) { return _retryAck != AckNone; }
QmlObjectListModel* missionItems(void) { return &_missionItems; }
void requestMissionItems(void);
/// Writes the specified set of mission items to the vehicle
void writeMissionItems(const QmlObjectListModel& missionItems);
/// Returns a copy of the current set of mission items. Caller is responsible for
/// freeing returned object.
QmlObjectListModel* copyMissionItems(void);
signals:
void newMissionItemsAvailable(void);
void _requestMissionItemsOnThread(void);
void _writeMissionItemsOnThread(void);
private slots:
void _mavlinkMessageReceived(const mavlink_message_t& message);
void _ackTimeout(void);
private:
typedef enum {
AckNone, ///< State machine is idle
AckMissionCount, ///< MISSION_COUNT message expected
AckMissionItem, ///< MISSION_ITEM expected
AckMissionRequest, ///< MISSION_REQUEST is expected, or MISSION_ACK to end sequence
} AckType_t;
void _startAckTimeout(AckType_t ack, const mavlink_message_t& message);
bool _stopAckTimeout(AckType_t expectedAck);
void _sendTransactionComplete(void);
void _handleMissionCount(const mavlink_message_t& message);
void _handleMissionItem(const mavlink_message_t& message);
void _handleMissionRequest(const mavlink_message_t& message);
void _handleMissionAck(const mavlink_message_t& message);
void _requestNextMissionItem(int sequenceNumber);
void _clearMissionItems(void);
void _requestMissionItems(void);
void _writeMissionItems(void);
// Overrides from QThread
void run(void);
private:
Vehicle* _vehicle;
int _cMissionItems; ///< Mission items on vehicle
QTimer* _ackTimeoutTimer;
AckType_t _retryAck;
mavlink_message_t _retryMessage;
int _retryCount;
int _expectedSequenceNumber;
QMutex _dataMutex;
QmlObjectListModel _missionItems;
static const int _ackTimeoutMilliseconds= 1000;
static const int _maxRetryCount = 5;
};
#endif
\ No newline at end of file
...@@ -79,6 +79,7 @@ ...@@ -79,6 +79,7 @@
#include "MavlinkQmlSingleton.h" #include "MavlinkQmlSingleton.h"
#include "JoystickManager.h" #include "JoystickManager.h"
#include "QmlObjectListModel.h" #include "QmlObjectListModel.h"
#include "MissionManager.h"
#ifndef __ios__ #ifndef __ios__
#include "SerialLink.h" #include "SerialLink.h"
...@@ -294,6 +295,7 @@ void QGCApplication::_initCommon(void) ...@@ -294,6 +295,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterUncreatableType<VehicleComponent> ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Can only reference, cannot create"); qmlRegisterUncreatableType<VehicleComponent> ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Can only reference, cannot create");
qmlRegisterUncreatableType<Vehicle> ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Can only reference, cannot create"); qmlRegisterUncreatableType<Vehicle> ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Can only reference, cannot create");
qmlRegisterUncreatableType<MissionItem> ("QGroundControl.Vehicle", 1, 0, "MissionItem", "Can only reference, cannot create"); qmlRegisterUncreatableType<MissionItem> ("QGroundControl.Vehicle", 1, 0, "MissionItem", "Can only reference, cannot create");
qmlRegisterUncreatableType<MissionManager> ("QGroundControl.Vehicle", 1, 0, "MissionManager", "Can only reference, cannot create");
qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only"); qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only");
qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only"); qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only");
qmlRegisterUncreatableType<QmlObjectListModel> ("QGroundControl", 1, 0, "QmlObjectListModel", "Reference only"); qmlRegisterUncreatableType<QmlObjectListModel> ("QGroundControl", 1, 0, "QmlObjectListModel", "Reference only");
......
This diff is collapsed.
...@@ -112,7 +112,12 @@ bool QmlObjectListModel::removeRows(int position, int rows, const QModelIndex& p ...@@ -112,7 +112,12 @@ bool QmlObjectListModel::removeRows(int position, int rows, const QModelIndex& p
return true; return true;
} }
QObject*& QmlObjectListModel::operator[](int index) QObject* QmlObjectListModel::operator[](int index)
{
return _objectList[index];
}
const QObject* QmlObjectListModel::operator[](int index) const
{ {
return _objectList[index]; return _objectList[index];
} }
...@@ -135,7 +140,7 @@ void QmlObjectListModel::append(QObject* object) ...@@ -135,7 +140,7 @@ void QmlObjectListModel::append(QObject* object)
insertRows(_objectList.count() - 1, 1); insertRows(_objectList.count() - 1, 1);
} }
int QmlObjectListModel::count(void) int QmlObjectListModel::count(void) const
{ {
return rowCount(); return rowCount();
} }
......
...@@ -38,11 +38,12 @@ public: ...@@ -38,11 +38,12 @@ public:
Q_PROPERTY(int count READ count NOTIFY countChanged) Q_PROPERTY(int count READ count NOTIFY countChanged)
int count(void); int count(void) const;
void append(QObject* object); void append(QObject* object);
void clear(void); void clear(void);
void removeAt(int i); void removeAt(int i);
QObject*& operator[](int i); QObject* operator[](int i);
const QObject* operator[](int i) const;
// Overrides from QAbstractListModel // Overrides from QAbstractListModel
virtual int rowCount(const QModelIndex & parent = QModelIndex()) const; virtual int rowCount(const QModelIndex & parent = QModelIndex()) const;
......
...@@ -30,6 +30,7 @@ ...@@ -30,6 +30,7 @@
#include "UASMessageHandler.h" #include "UASMessageHandler.h"
#include "UAS.h" #include "UAS.h"
#include "JoystickManager.h" #include "JoystickManager.h"
#include "MissionManager.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog") QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
...@@ -151,6 +152,10 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType) ...@@ -151,6 +152,10 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType)
_waypointViewOnlyListChanged(); _waypointViewOnlyListChanged();
_loadSettings(); _loadSettings();
if (qgcApp()->useNewMissionEditor()) {
_missionManager = new MissionManager(this);
}
} }
Vehicle::~Vehicle() Vehicle::~Vehicle()
...@@ -187,7 +192,7 @@ Vehicle::~Vehicle() ...@@ -187,7 +192,7 @@ Vehicle::~Vehicle()
void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message) void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message)
{ {
if (message.sysid != _id) { if (message.sysid != _id && message.sysid != 0) {
return; return;
} }
...@@ -195,6 +200,8 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes ...@@ -195,6 +200,8 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
_addLink(link); _addLink(link);
} }
emit mavlinkMessageReceived(message);
_uas->receiveMessage(message); _uas->receiveMessage(message);
} }
......
...@@ -41,6 +41,7 @@ class UASInterface; ...@@ -41,6 +41,7 @@ class UASInterface;
class FirmwarePlugin; class FirmwarePlugin;
class AutoPilotPlugin; class AutoPilotPlugin;
class UASWaypointManager; class UASWaypointManager;
class MissionManager;
Q_DECLARE_LOGGING_CATEGORY(VehicleLog) Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
...@@ -55,7 +56,8 @@ public: ...@@ -55,7 +56,8 @@ public:
Q_PROPERTY(int id READ id CONSTANT) Q_PROPERTY(int id READ id CONSTANT)
Q_PROPERTY(AutoPilotPlugin* autopilot MEMBER _autopilotPlugin CONSTANT) Q_PROPERTY(AutoPilotPlugin* autopilot MEMBER _autopilotPlugin CONSTANT)
Q_PROPERTY(QGeoCoordinate coordinate MEMBER _geoCoordinate NOTIFY coordinateChanged) Q_PROPERTY(QGeoCoordinate coordinate MEMBER _geoCoordinate NOTIFY coordinateChanged)
Q_PROPERTY(MissionManager* missionManager MEMBER _missionManager CONSTANT)
Q_INVOKABLE QString getMavIconColor(); Q_INVOKABLE QString getMavIconColor();
...@@ -147,6 +149,8 @@ public: ...@@ -147,6 +149,8 @@ public:
int manualControlReservedButtonCount(void); int manualControlReservedButtonCount(void);
MissionManager* missionManager(void) { return _missionManager; }
typedef enum { typedef enum {
MessageNone, MessageNone,
MessageNormal, MessageNormal,
...@@ -213,6 +217,7 @@ signals: ...@@ -213,6 +217,7 @@ signals:
void joystickModeChanged(int mode); void joystickModeChanged(int mode);
void joystickEnabledChanged(bool enabled); void joystickEnabledChanged(bool enabled);
void activeChanged(bool active); void activeChanged(bool active);
void mavlinkMessageReceived(const mavlink_message_t& message);
/// Used internally to move sendMessage call to main thread /// Used internally to move sendMessage call to main thread
void _sendMessageOnThread(mavlink_message_t message); void _sendMessageOnThread(mavlink_message_t message);
...@@ -351,6 +356,7 @@ private: ...@@ -351,6 +356,7 @@ private:
UASWaypointManager* _wpm; UASWaypointManager* _wpm;
int _updateCount; int _updateCount;
MissionManager* _missionManager;
QmlObjectListModel _missionItems; QmlObjectListModel _missionItems;
static const char* _settingsGroup; static const char* _settingsGroup;
......
This diff is collapsed.
...@@ -485,7 +485,6 @@ protected: //COMMENTS FOR TEST UNIT ...@@ -485,7 +485,6 @@ protected: //COMMENTS FOR TEST UNIT
double airSpeed; ///< Airspeed double airSpeed; ///< Airspeed
double groundSpeed; ///< Groundspeed double groundSpeed; ///< Groundspeed
double bearingToWaypoint; ///< Bearing to next waypoint double bearingToWaypoint; ///< Bearing to next waypoint
UASWaypointManager waypointManager;
FileManager fileManager; FileManager fileManager;
/// ATTITUDE /// ATTITUDE
...@@ -552,7 +551,7 @@ public: ...@@ -552,7 +551,7 @@ public:
/** @brief Get reference to the waypoint manager **/ /** @brief Get reference to the waypoint manager **/
UASWaypointManager* getWaypointManager() { UASWaypointManager* getWaypointManager() {
return &waypointManager; return _waypointManager;
} }
virtual FileManager* getFileManager() { virtual FileManager* getFileManager() {
...@@ -985,7 +984,8 @@ private: ...@@ -985,7 +984,8 @@ private:
void _say(const QString& text, int severity = 6); void _say(const QString& text, int severity = 6);
private: private:
Vehicle* _vehicle; UASWaypointManager* _waypointManager;
Vehicle* _vehicle;
}; };
......
...@@ -114,7 +114,7 @@ void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x, ...@@ -114,7 +114,7 @@ void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x,
{ {
Q_UNUSED(mav); Q_UNUSED(mav);
Q_UNUSED(time); Q_UNUSED(time);
if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_NED || currentWaypointEditable->getFrame() == MAV_FRAME_LOCAL_ENU)) if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->frame() == MAV_FRAME_LOCAL_NED || currentWaypointEditable->frame() == MAV_FRAME_LOCAL_ENU))
{ {
double xdiff = x-currentWaypointEditable->x(); double xdiff = x-currentWaypointEditable->x();
double ydiff = y-currentWaypointEditable->y(); double ydiff = y-currentWaypointEditable->y();
...@@ -132,7 +132,7 @@ void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double l ...@@ -132,7 +132,7 @@ void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double l
Q_UNUSED(altWGS84); Q_UNUSED(altWGS84);
Q_UNUSED(lon); Q_UNUSED(lon);
Q_UNUSED(lat); Q_UNUSED(lat);
if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL || currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) if (waypointsEditable.count() > 0 && !currentWaypointEditable.isNull() && (currentWaypointEditable->frame() == MAV_FRAME_GLOBAL || currentWaypointEditable->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT))
{ {
// TODO FIXME Calculate distance // TODO FIXME Calculate distance
double dist = 0; double dist = 0;
...@@ -250,7 +250,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_ ...@@ -250,7 +250,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
emit updateStatusString(tr("MissionItem ID mismatch, rejecting waypoint")); emit updateStatusString(tr("MissionItem ID mismatch, rejecting waypoint"));
} }
} else if (systemId == current_partner_systemid } else if (systemId == current_partner_systemid
&& wp->seq < waypointsViewOnly.size() && waypointsViewOnly[wp->seq]->getAction()) { && wp->seq < waypointsViewOnly.size() && waypointsViewOnly[wp->seq]->command()) {
// accept single sent waypoints because they can contain updates about remaining DO_JUMP repetitions // accept single sent waypoints because they can contain updates about remaining DO_JUMP repetitions
// but only update view only side // but only update view only side
MissionItem *lwp_vo = new MissionItem(NULL, MissionItem *lwp_vo = new MissionItem(NULL,
...@@ -677,7 +677,7 @@ const QList<MissionItem *> UASWaypointManager::getGlobalFrameWaypointList() ...@@ -677,7 +677,7 @@ const QList<MissionItem *> UASWaypointManager::getGlobalFrameWaypointList()
QList<MissionItem*> wps; QList<MissionItem*> wps;
foreach (MissionItem* wp, waypointsEditable) foreach (MissionItem* wp, waypointsEditable)
{ {
if (wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) if (wp->frame() == MAV_FRAME_GLOBAL || wp->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{ {
wps.append(wp); wps.append(wp);
} }
...@@ -693,7 +693,7 @@ const QList<MissionItem *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointL ...@@ -693,7 +693,7 @@ const QList<MissionItem *> UASWaypointManager::getGlobalFrameAndNavTypeWaypointL
QList<MissionItem*> wps; QList<MissionItem*> wps;
foreach (MissionItem* wp, waypointsEditable) foreach (MissionItem* wp, waypointsEditable)
{ {
if ((wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType()) if ((wp->frame() == MAV_FRAME_GLOBAL || wp->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType())
{ {
wps.append(wp); wps.append(wp);
} }
...@@ -728,7 +728,7 @@ int UASWaypointManager::getGlobalFrameIndexOf(MissionItem* wp) ...@@ -728,7 +728,7 @@ int UASWaypointManager::getGlobalFrameIndexOf(MissionItem* wp)
// counting only those in global frame // counting only those in global frame
int i = 0; int i = 0;
foreach (MissionItem* p, waypointsEditable) { foreach (MissionItem* p, waypointsEditable) {
if (p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) if (p->frame() == MAV_FRAME_GLOBAL || wp->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{ {
if (p == wp) if (p == wp)
{ {
...@@ -747,7 +747,7 @@ int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(MissionItem* wp) ...@@ -747,7 +747,7 @@ int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(MissionItem* wp)
// counting only those in global frame // counting only those in global frame
int i = 0; int i = 0;
foreach (MissionItem* p, waypointsEditable) { foreach (MissionItem* p, waypointsEditable) {
if ((p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType()) if ((p->frame() == MAV_FRAME_GLOBAL || wp->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
{ {
if (p == wp) if (p == wp)
{ {
...@@ -787,7 +787,7 @@ int UASWaypointManager::getGlobalFrameCount() ...@@ -787,7 +787,7 @@ int UASWaypointManager::getGlobalFrameCount()
int i = 0; int i = 0;
foreach (MissionItem* p, waypointsEditable) foreach (MissionItem* p, waypointsEditable)
{ {
if (p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) if (p->frame() == MAV_FRAME_GLOBAL || p->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{ {
i++; i++;
} }
...@@ -802,7 +802,7 @@ int UASWaypointManager::getGlobalFrameAndNavTypeCount() ...@@ -802,7 +802,7 @@ int UASWaypointManager::getGlobalFrameAndNavTypeCount()
// counting only those in global frame // counting only those in global frame
int i = 0; int i = 0;
foreach (MissionItem* p, waypointsEditable) { foreach (MissionItem* p, waypointsEditable) {
if ((p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType()) if ((p->frame() == MAV_FRAME_GLOBAL || p->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType())
{ {
i++; i++;
} }
...@@ -832,7 +832,7 @@ int UASWaypointManager::getLocalFrameCount() ...@@ -832,7 +832,7 @@ int UASWaypointManager::getLocalFrameCount()
int i = 0; int i = 0;
foreach (MissionItem* p, waypointsEditable) foreach (MissionItem* p, waypointsEditable)
{ {
if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU) if (p->frame() == MAV_FRAME_LOCAL_NED || p->frame() == MAV_FRAME_LOCAL_ENU)
{ {
i++; i++;
} }
...@@ -848,7 +848,7 @@ int UASWaypointManager::getLocalFrameIndexOf(MissionItem* wp) ...@@ -848,7 +848,7 @@ int UASWaypointManager::getLocalFrameIndexOf(MissionItem* wp)
int i = 0; int i = 0;
foreach (MissionItem* p, waypointsEditable) foreach (MissionItem* p, waypointsEditable)
{ {
if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU) if (p->frame() == MAV_FRAME_LOCAL_NED || p->frame() == MAV_FRAME_LOCAL_ENU)
{ {
if (p == wp) if (p == wp)
{ {
...@@ -868,7 +868,7 @@ int UASWaypointManager::getMissionFrameIndexOf(MissionItem* wp) ...@@ -868,7 +868,7 @@ int UASWaypointManager::getMissionFrameIndexOf(MissionItem* wp)
int i = 0; int i = 0;
foreach (MissionItem* p, waypointsEditable) foreach (MissionItem* p, waypointsEditable)
{ {
if (p->getFrame() == MAV_FRAME_MISSION) if (p->frame() == MAV_FRAME_MISSION)
{ {
if (p == wp) if (p == wp)
{ {
...@@ -941,12 +941,12 @@ void UASWaypointManager::goToWaypoint(MissionItem *wp) ...@@ -941,12 +941,12 @@ void UASWaypointManager::goToWaypoint(MissionItem *wp)
mission.autocontinue = 0; mission.autocontinue = 0;
mission.current = 2; //2 for guided mode mission.current = 2; //2 for guided mode
mission.param1 = wp->getParam1(); mission.param1 = wp->param1();
mission.param2 = wp->getParam2(); mission.param2 = wp->param2();
mission.param3 = wp->getParam3(); mission.param3 = wp->param3();
mission.param4 = wp->getParam4(); mission.param4 = wp->param4();
mission.frame = wp->getFrame(); mission.frame = wp->frame();
mission.command = wp->getAction(); mission.command = wp->command();
mission.seq = 0; // don't read out the sequence number of the waypoint class mission.seq = 0; // don't read out the sequence number of the waypoint class
mission.x = wp->x(); mission.x = wp->x();
mission.y = wp->y(); mission.y = wp->y();
...@@ -992,14 +992,14 @@ void UASWaypointManager::writeWaypoints() ...@@ -992,14 +992,14 @@ void UASWaypointManager::writeWaypoints()
memset(cur_d, 0, sizeof(mavlink_mission_item_t)); //initialize with zeros memset(cur_d, 0, sizeof(mavlink_mission_item_t)); //initialize with zeros
const MissionItem *cur_s = waypointsEditable.at(i); const MissionItem *cur_s = waypointsEditable.at(i);
cur_d->autocontinue = cur_s->getAutoContinue(); cur_d->autocontinue = cur_s->autoContinue();
cur_d->current = cur_s->isCurrentItem() & noCurrent; //make sure only one current waypoint is selected, the first selected will be chosen cur_d->current = cur_s->isCurrentItem() & noCurrent; //make sure only one current waypoint is selected, the first selected will be chosen
cur_d->param1 = cur_s->getParam1(); cur_d->param1 = cur_s->param1();
cur_d->param2 = cur_s->getParam2(); cur_d->param2 = cur_s->param2();
cur_d->param3 = cur_s->getParam3(); cur_d->param3 = cur_s->param3();
cur_d->param4 = cur_s->getParam4(); cur_d->param4 = cur_s->param4();
cur_d->frame = cur_s->getFrame(); cur_d->frame = cur_s->frame();
cur_d->command = cur_s->getAction(); cur_d->command = cur_s->command();
cur_d->seq = i; // don't read out the sequence number of the waypoint class cur_d->seq = i; // don't read out the sequence number of the waypoint class
cur_d->x = cur_s->x(); cur_d->x = cur_s->x();
cur_d->y = cur_s->y(); cur_d->y = cur_s->y();
...@@ -1163,7 +1163,7 @@ float UASWaypointManager::getAltitudeRecommendation() ...@@ -1163,7 +1163,7 @@ float UASWaypointManager::getAltitudeRecommendation()
int UASWaypointManager::getFrameRecommendation() int UASWaypointManager::getFrameRecommendation()
{ {
if (waypointsEditable.count() > 0) { if (waypointsEditable.count() > 0) {
return static_cast<int>(waypointsEditable.last()->getFrame()); return static_cast<int>(waypointsEditable.last()->frame());
} else { } else {
return MAV_FRAME_GLOBAL; return MAV_FRAME_GLOBAL;
} }
...@@ -1173,7 +1173,7 @@ float UASWaypointManager::getAcceptanceRadiusRecommendation() ...@@ -1173,7 +1173,7 @@ float UASWaypointManager::getAcceptanceRadiusRecommendation()
{ {
if (waypointsEditable.count() > 0) if (waypointsEditable.count() > 0)
{ {
return waypointsEditable.last()->getAcceptanceRadius(); return waypointsEditable.last()->acceptanceRadius();
} }
else else
{ {
......
...@@ -1312,7 +1312,7 @@ void HSIDisplay::drawWaypoint(QPainter& painter, const QColor& color, float widt ...@@ -1312,7 +1312,7 @@ void HSIDisplay::drawWaypoint(QPainter& painter, const QColor& color, float widt
poly.replace(3, QPointF(p.x() - waypointSize/2.0f, p.y())); poly.replace(3, QPointF(p.x() - waypointSize/2.0f, p.y()));
float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f)); float radius = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
float acceptRadius = w->getAcceptanceRadius(); float acceptRadius = w->acceptanceRadius();
double yawDiff = w->yawRadians()/180.0*M_PI-yaw; double yawDiff = w->yawRadians()/180.0*M_PI-yaw;
// Draw background // Draw background
...@@ -1353,7 +1353,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter) ...@@ -1353,7 +1353,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
const MissionItem *w = list.at(i); const MissionItem *w = list.at(i);
QPointF in; QPointF in;
// Use local coordinates as-is. // Use local coordinates as-is.
int frameRef = w->getFrame(); int frameRef = w->frame();
if (frameRef == MAV_FRAME_LOCAL_NED) if (frameRef == MAV_FRAME_LOCAL_NED)
{ {
in = QPointF(w->x(), w->y()); in = QPointF(w->x(), w->y());
......
...@@ -93,13 +93,13 @@ WaypointEditableView::WaypointEditableView(MissionItem* wp, QWidget* parent) : ...@@ -93,13 +93,13 @@ WaypointEditableView::WaypointEditableView(MissionItem* wp, QWidget* parent) :
connect(m_ui->selectedBox, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int))); connect(m_ui->selectedBox, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int)));
// Initialize view correctly // Initialize view correctly
int actionID = wp->getAction(); int actionID = wp->command();
initializeActionView(actionID); initializeActionView(actionID);
updateValues(); updateValues();
updateActionView(actionID); updateActionView(actionID);
// Check for mission frame // Check for mission frame
if (wp->getFrame() == MAV_FRAME_MISSION) if (wp->frame() == MAV_FRAME_MISSION)
{ {
m_ui->comboBox_action->setCurrentIndex(m_ui->comboBox_action->count()-1); m_ui->comboBox_action->setCurrentIndex(m_ui->comboBox_action->count()-1);
} }
...@@ -417,14 +417,14 @@ void WaypointEditableView::updateValues() ...@@ -417,14 +417,14 @@ void WaypointEditableView::updateValues()
// update frame // update frame
MAV_FRAME frame = (MAV_FRAME)wp->getFrame(); MAV_FRAME frame = (MAV_FRAME)wp->frame();
int frame_index = m_ui->comboBox_frame->findData(frame); int frame_index = m_ui->comboBox_frame->findData(frame);
if (m_ui->comboBox_frame->currentIndex() != frame_index) { if (m_ui->comboBox_frame->currentIndex() != frame_index) {
m_ui->comboBox_frame->setCurrentIndex(frame_index); m_ui->comboBox_frame->setCurrentIndex(frame_index);
} }
// Update action // Update action
MAV_CMD action = (MAV_CMD)wp->getAction(); MAV_CMD action = (MAV_CMD)wp->command();
int action_index = m_ui->comboBox_action->findData(action); int action_index = m_ui->comboBox_action->findData(action);
if (m_ui->comboBox_action->currentIndex() != action_index) if (m_ui->comboBox_action->currentIndex() != action_index)
{ {
...@@ -440,15 +440,15 @@ void WaypointEditableView::updateValues() ...@@ -440,15 +440,15 @@ void WaypointEditableView::updateValues()
} }
} }
emit commandBroadcast(wp->getAction()); emit commandBroadcast(wp->command());
emit frameBroadcast((MAV_FRAME)wp->getFrame()); emit frameBroadcast((MAV_FRAME)wp->frame());
emit param1Broadcast(wp->getParam1()); emit param1Broadcast(wp->param1());
emit param2Broadcast(wp->getParam2()); emit param2Broadcast(wp->param2());
emit param3Broadcast(wp->getParam3()); emit param3Broadcast(wp->param3());
emit param4Broadcast(wp->getParam4()); emit param4Broadcast(wp->param4());
emit param5Broadcast(wp->getParam5()); emit param5Broadcast(wp->param5());
emit param6Broadcast(wp->getParam6()); emit param6Broadcast(wp->param6());
emit param7Broadcast(wp->getParam7()); emit param7Broadcast(wp->param7());
if (m_ui->selectedBox->isChecked() != wp->isCurrentItem()) if (m_ui->selectedBox->isChecked() != wp->isCurrentItem())
...@@ -458,9 +458,9 @@ void WaypointEditableView::updateValues() ...@@ -458,9 +458,9 @@ void WaypointEditableView::updateValues()
m_ui->selectedBox->setChecked(wp->isCurrentItem()); m_ui->selectedBox->setChecked(wp->isCurrentItem());
m_ui->selectedBox->blockSignals(false); m_ui->selectedBox->blockSignals(false);
} }
if (m_ui->autoContinue->isChecked() != wp->getAutoContinue()) if (m_ui->autoContinue->isChecked() != wp->autoContinue())
{ {
m_ui->autoContinue->setChecked(wp->getAutoContinue()); m_ui->autoContinue->setChecked(wp->autoContinue());
} }
m_ui->idLabel->setText(QString::number(wp->sequenceNumber())); m_ui->idLabel->setText(QString::number(wp->sequenceNumber()));
......
...@@ -268,7 +268,7 @@ void WaypointList::addEditable(bool onCurrentPosition) ...@@ -268,7 +268,7 @@ void WaypointList::addEditable(bool onCurrentPosition)
MissionItem *last = waypoints.last(); MissionItem *last = waypoints.last();
wp = WPM->createWaypoint(); wp = WPM->createWaypoint();
// wp->blockSignals(true); // wp->blockSignals(true);
MAV_FRAME frame = (MAV_FRAME)last->getFrame(); MAV_FRAME frame = (MAV_FRAME)last->frame();
wp->setFrame(frame); wp->setFrame(frame);
if (frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_RELATIVE_ALT) if (frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_RELATIVE_ALT)
{ {
...@@ -280,13 +280,13 @@ void WaypointList::addEditable(bool onCurrentPosition) ...@@ -280,13 +280,13 @@ void WaypointList::addEditable(bool onCurrentPosition)
wp->setY(last->y()); wp->setY(last->y());
wp->setZ(last->z()); wp->setZ(last->z());
} }
wp->setParam1(last->getParam1()); wp->setParam1(last->param1());
wp->setParam2(last->getParam2()); wp->setParam2(last->param2());
wp->setParam3(last->getParam3()); wp->setParam3(last->param3());
wp->setParam4(last->getParam4()); wp->setParam4(last->param4());
wp->setAutocontinue(last->getAutoContinue()); wp->setAutocontinue(last->autoContinue());
// wp->blockSignals(false); // wp->blockSignals(false);
wp->setAction(last->getAction()); wp->setAction(last->command());
// WPM->addWaypointEditable(wp); // WPM->addWaypointEditable(wp);
} }
else else
......
This diff is collapsed.
...@@ -678,7 +678,7 @@ void QGCMapWidget::updateWaypoint(int uas, MissionItem* wp) ...@@ -678,7 +678,7 @@ void QGCMapWidget::updateWaypoint(int uas, MissionItem* wp)
if (currWPManager) if (currWPManager)
{ {
// Only accept waypoints in global coordinate frame // Only accept waypoints in global coordinate frame
if (((wp->getFrame() == MAV_FRAME_GLOBAL) || (wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType()) if (((wp->frame() == MAV_FRAME_GLOBAL) || (wp->frame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) && wp->isNavigationType())
{ {
// We're good, this is a global waypoint // We're good, this is a global waypoint
......
...@@ -98,11 +98,11 @@ QRectF Waypoint2DIcon::boundingRect() const ...@@ -98,11 +98,11 @@ QRectF Waypoint2DIcon::boundingRect() const
internals::PointLatLng coord = (internals::PointLatLng)Coord(); internals::PointLatLng coord = (internals::PointLatLng)Coord();
if (!waypoint.isNull()) { if (!waypoint.isNull()) {
if (showAcceptanceRadius && (waypoint->getAction() == (int)MAV_CMD_NAV_WAYPOINT)) if (showAcceptanceRadius && (waypoint->command() == (int)MAV_CMD_NAV_WAYPOINT))
{ {
acceptance = map->metersToPixels(waypoint->getAcceptanceRadius(), coord); acceptance = map->metersToPixels(waypoint->acceptanceRadius(), coord);
} }
if (((waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TURNS))) if (((waypoint->command() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->command() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->command() == (int)MAV_CMD_NAV_LOITER_TURNS)))
{ {
loiter = map->metersToPixels(waypoint->loiterOrbitRadius(), coord); loiter = map->metersToPixels(waypoint->loiterOrbitRadius(), coord);
} }
...@@ -159,12 +159,12 @@ void Waypoint2DIcon::drawIcon() ...@@ -159,12 +159,12 @@ void Waypoint2DIcon::drawIcon()
// or it is a waypoint, but not one where direction has no meaning // or it is a waypoint, but not one where direction has no meaning
// then draw the heading indicator // then draw the heading indicator
if (waypoint.isNull() || (waypoint && ( if (waypoint.isNull() || (waypoint && (
(waypoint->getAction() != (int)MAV_CMD_NAV_TAKEOFF) && (waypoint->command() != (int)MAV_CMD_NAV_TAKEOFF) &&
(waypoint->getAction() != (int)MAV_CMD_NAV_LAND) && (waypoint->command() != (int)MAV_CMD_NAV_LAND) &&
(waypoint->getAction() != (int)MAV_CMD_NAV_LOITER_UNLIM) && (waypoint->command() != (int)MAV_CMD_NAV_LOITER_UNLIM) &&
(waypoint->getAction() != (int)MAV_CMD_NAV_LOITER_TIME) && (waypoint->command() != (int)MAV_CMD_NAV_LOITER_TIME) &&
(waypoint->getAction() != (int)MAV_CMD_NAV_LOITER_TURNS) && (waypoint->command() != (int)MAV_CMD_NAV_LOITER_TURNS) &&
(waypoint->getAction() != (int)MAV_CMD_NAV_RETURN_TO_LAUNCH) (waypoint->command() != (int)MAV_CMD_NAV_RETURN_TO_LAUNCH)
))) )))
{ {
painter.setPen(pen1); painter.setPen(pen1);
...@@ -173,7 +173,7 @@ void Waypoint2DIcon::drawIcon() ...@@ -173,7 +173,7 @@ void Waypoint2DIcon::drawIcon()
painter.drawLine(p.x(), p.y(), p.x()+sin(Heading()/180.0f*M_PI) * rad, p.y()-cos(Heading()/180.0f*M_PI) * rad); painter.drawLine(p.x(), p.y(), p.x()+sin(Heading()/180.0f*M_PI) * rad, p.y()-cos(Heading()/180.0f*M_PI) * rad);
} }
if (((!waypoint.isNull())) && (waypoint->getAction() == (int)MAV_CMD_NAV_TAKEOFF)) if (((!waypoint.isNull())) && (waypoint->command() == (int)MAV_CMD_NAV_TAKEOFF))
{ {
// Takeoff waypoint // Takeoff waypoint
int width = picture.width()-penWidth; int width = picture.width()-penWidth;
...@@ -189,7 +189,7 @@ void Waypoint2DIcon::drawIcon() ...@@ -189,7 +189,7 @@ void Waypoint2DIcon::drawIcon()
painter.setPen(pen2); painter.setPen(pen2);
painter.drawRect(width*0.3, height*0.3f, width*0.6f, height*0.6f); painter.drawRect(width*0.3, height*0.3f, width*0.6f, height*0.6f);
} }
else if (((!waypoint.isNull())) && (waypoint->getAction() == (int)MAV_CMD_NAV_LAND)) else if (((!waypoint.isNull())) && (waypoint->command() == (int)MAV_CMD_NAV_LAND))
{ {
// Landing waypoint // Landing waypoint
int width = (picture.width())/2-penWidth; int width = (picture.width())/2-penWidth;
...@@ -201,7 +201,7 @@ void Waypoint2DIcon::drawIcon() ...@@ -201,7 +201,7 @@ void Waypoint2DIcon::drawIcon()
painter.drawEllipse(p, width, height); painter.drawEllipse(p, width, height);
painter.drawLine(p.x()-width/2, p.y()-height/2, 2*width, 2*height); painter.drawLine(p.x()-width/2, p.y()-height/2, 2*width, 2*height);
} }
else if (((!waypoint.isNull())) && ((waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TURNS))) else if (((!waypoint.isNull())) && ((waypoint->command() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->command() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->command() == (int)MAV_CMD_NAV_LOITER_TURNS)))
{ {
// Loiter waypoint // Loiter waypoint
int width = (picture.width()-penWidth)/2; int width = (picture.width()-penWidth)/2;
...@@ -213,7 +213,7 @@ void Waypoint2DIcon::drawIcon() ...@@ -213,7 +213,7 @@ void Waypoint2DIcon::drawIcon()
painter.drawEllipse(p, width, height); painter.drawEllipse(p, width, height);
painter.drawPoint(p); painter.drawPoint(p);
} }
else if (((!waypoint.isNull())) && (waypoint->getAction() == (int)MAV_CMD_NAV_RETURN_TO_LAUNCH)) else if (((!waypoint.isNull())) && (waypoint->command() == (int)MAV_CMD_NAV_RETURN_TO_LAUNCH))
{ {
// Return to launch waypoint // Return to launch waypoint
int width = picture.width()-penWidth; int width = picture.width()-penWidth;
...@@ -286,13 +286,13 @@ void Waypoint2DIcon::paint(QPainter *painter, const QStyleOptionGraphicsItem *op ...@@ -286,13 +286,13 @@ void Waypoint2DIcon::paint(QPainter *painter, const QStyleOptionGraphicsItem *op
penBlack.setWidth(4); penBlack.setWidth(4);
pen.setColor(color); pen.setColor(color);
if ((!waypoint.isNull()) && (waypoint->getAction() == (int)MAV_CMD_NAV_WAYPOINT) && showAcceptanceRadius) if ((!waypoint.isNull()) && (waypoint->command() == (int)MAV_CMD_NAV_WAYPOINT) && showAcceptanceRadius)
{ {
QPen redPen = QPen(pen); QPen redPen = QPen(pen);
redPen.setColor(Qt::yellow); redPen.setColor(Qt::yellow);
redPen.setWidth(1); redPen.setWidth(1);
painter->setPen(redPen); painter->setPen(redPen);
const int acceptance = map->metersToPixels(waypoint->getAcceptanceRadius(), Coord()); const int acceptance = map->metersToPixels(waypoint->acceptanceRadius(), Coord());
if (acceptance > 0) { if (acceptance > 0) {
painter->setPen(penBlack); painter->setPen(penBlack);
painter->drawEllipse(QPointF(0, 0), acceptance, acceptance); painter->drawEllipse(QPointF(0, 0), acceptance, acceptance);
...@@ -300,7 +300,7 @@ void Waypoint2DIcon::paint(QPainter *painter, const QStyleOptionGraphicsItem *op ...@@ -300,7 +300,7 @@ void Waypoint2DIcon::paint(QPainter *painter, const QStyleOptionGraphicsItem *op
painter->drawEllipse(QPointF(0, 0), acceptance, acceptance); painter->drawEllipse(QPointF(0, 0), acceptance, acceptance);
} }
} }
if ((!waypoint.isNull()) && ((waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->getAction() == (int)MAV_CMD_NAV_LOITER_TURNS))) if ((!waypoint.isNull()) && ((waypoint->command() == (int)MAV_CMD_NAV_LOITER_UNLIM) || (waypoint->command() == (int)MAV_CMD_NAV_LOITER_TIME) || (waypoint->command() == (int)MAV_CMD_NAV_LOITER_TURNS)))
{ {
QPen penDash(color); QPen penDash(color);
penDash.setWidth(1); penDash.setWidth(1);
......
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