diff --git a/QGCApplication.pro b/QGCApplication.pro index de414f3d5941329f17f12c4718edef0533d88b4b..e3de2ee522f3ece14e0005b9b158d6841cb00d79 100644 --- a/QGCApplication.pro +++ b/QGCApplication.pro @@ -258,6 +258,7 @@ HEADERS += \ src/QGCQuickWidget.h \ src/QGCSingleton.h \ src/QGCTemporaryFile.h \ + src/QmlControls/MavlinkQmlSingleton.h \ src/QmlControls/ParameterEditorController.h \ src/QmlControls/ScreenToolsController.h \ src/SerialPortIds.h \ @@ -336,7 +337,7 @@ HEADERS += \ src/ViewWidgets/CustomCommandWidgetController.h \ src/ViewWidgets/ParameterEditorWidget.h \ src/ViewWidgets/ViewWidgetController.h \ - src/Waypoint.h \ + src/MissionItem.h \ src/AutoPilotPlugins/PX4/PX4AirframeLoader.h !iOSBuild { @@ -467,7 +468,7 @@ SOURCES += \ src/ViewWidgets/CustomCommandWidgetController.cc \ src/ViewWidgets/ParameterEditorWidget.cc \ src/ViewWidgets/ViewWidgetController.cc \ - src/Waypoint.cc \ + src/MissionItem.cc \ src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc !iOSBuild { diff --git a/src/FlightMap/FlightMap.qml b/src/FlightMap/FlightMap.qml index 202a8db97df7997ead749fef7dbc6dbe1eec3003..a32c4ee91426224222017648ee0ac140df754fd7 100644 --- a/src/FlightMap/FlightMap.qml +++ b/src/FlightMap/FlightMap.qml @@ -37,6 +37,7 @@ import QGroundControl.FlightMap 1.0 import QGroundControl.ScreenTools 1.0 import QGroundControl.MultiVehicleManager 1.0 import QGroundControl.Vehicle 1.0 +import QGroundControl.Mavlink 1.0 Item { id: root @@ -227,7 +228,12 @@ Item { function addMissionItem(missionItem, index) { if (!showMissionItems) { - console.warning("Shouldn't be called with showMissionItems=false") + console.warn("Shouldn't be called with showMissionItems=false") + return + } + + if (!missionItem.hasCoordinate) { + // Item has no map position associated with it return } @@ -250,7 +256,7 @@ Item { function removeMissionItem(missionItem) { if (!showMissionItems) { - console.warning("Shouldn't be called with showMissionItems=false") + console.warn("Shouldn't be called with showMissionItems=false") return } @@ -275,7 +281,6 @@ Item { var vehicle = multiVehicleManager.activeVehicle if (!vehicle) { - console.warning("Why no active vehicle?") return } @@ -382,7 +387,6 @@ Item { MissionItemSummary { missionItem: modelData - missionItemIndex: index + 1 } } } diff --git a/src/MissionItem.cc b/src/MissionItem.cc new file mode 100644 index 0000000000000000000000000000000000000000..d613a8244d6fedda0058588167fac3a96fb1b42b --- /dev/null +++ b/src/MissionItem.cc @@ -0,0 +1,540 @@ +/*=================================================================== +QGroundControl Open Source Ground Control Station + +(c) 2009, 2010 QGROUNDCONTROL PROJECT + +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 . + +======================================================================*/ + +/** + * @file + * @brief MissionItem class + * + * @author Benjamin Knecht + * @author Petri Tanskanen + * + */ + +#include +#include + +#include "MissionItem.h" + +MissionItem::MissionItem( + QObject *parent, + quint16 id, + double x, + double y, + double z, + double param1, + double param2, + double param3, + double param4, + bool autocontinue, + bool current, + int frame, + int action, + const QString& description + ) + : QObject(parent) + , _id(id) + , _x(x) + , _y(y) + , _z(z) + , _yaw(param4) + , _frame(frame) + , _action(action) + , _autocontinue(autocontinue) + , _current(current) + , _orbit(param3) + , _param1(param1) + , _param2(param2) + , _name(QString("WP%1").arg(id, 2, 10, QChar('0'))) + , _description(description) + , _reachedTime(0) +{ + connect(this, &MissionItem::latitudeChanged, this, &MissionItem::coordinateChanged); + connect(this, &MissionItem::longitudeChanged, this, &MissionItem::coordinateChanged); +} + +MissionItem::MissionItem(const MissionItem& other) + : QObject(NULL) +{ + *this = other; +} + +MissionItem::~MissionItem() +{ +} + +const MissionItem& MissionItem::operator=(const MissionItem& other) +{ + _id = other.getId(); + _x = other.getX(); + _y = other.getY(); + _z = other.getZ(); + _yaw = other.getYaw(); + _frame = other.getFrame(); + _action = other.getAction(); + _autocontinue = other.getAutoContinue(); + _current = other.getCurrent(); + _orbit = other.getParam3(); + _param1 = other.getParam1(); + _param2 = other.getParam2(); + _name = other.getName(); + _description = other.getDescription(); + _reachedTime = other.getReachedTime(); + return *this; +} + +bool MissionItem::isNavigationType() +{ + return (_action < MAV_CMD_NAV_LAST); +} + +void MissionItem::save(QTextStream &saveStream) +{ + QString position("%1\t%2\t%3"); + position = position.arg(_x, 0, 'g', 18); + position = position.arg(_y, 0, 'g', 18); + position = position.arg(_z, 0, 'g', 18); + QString parameters("%1\t%2\t%3\t%4"); + parameters = parameters.arg(_param1, 0, 'g', 18).arg(_param2, 0, 'g', 18).arg(_orbit, 0, 'g', 18).arg(_yaw, 0, 'g', 18); + // FORMAT: + // as documented here: http://qgroundcontrol.org/waypoint_protocol + saveStream << this->getId() << "\t" << this->getCurrent() << "\t" << this->getFrame() << "\t" << this->getAction() << "\t" << parameters << "\t" << position << "\t" << this->getAutoContinue() << "\r\n"; //"\t" << this->getDescription() << "\r\n"; +} + +bool MissionItem::load(QTextStream &loadStream) +{ + const QStringList &wpParams = loadStream.readLine().split("\t"); + if (wpParams.size() == 12) { + _id = wpParams[0].toInt(); + _current = (wpParams[1].toInt() == 1 ? true : false); + _frame = (MAV_FRAME) wpParams[2].toInt(); + _action = (MAV_CMD) wpParams[3].toInt(); + _param1 = wpParams[4].toDouble(); + _param2 = wpParams[5].toDouble(); + _orbit = wpParams[6].toDouble(); + _yaw = wpParams[7].toDouble(); + _x = wpParams[8].toDouble(); + _y = wpParams[9].toDouble(); + _z = wpParams[10].toDouble(); + _autocontinue = (wpParams[11].toInt() == 1 ? true : false); + //_description = wpParams[12]; + return true; + } + return false; +} + + +void MissionItem::setId(quint16 id) +{ + _id = id; + _name = QString("WP%1").arg(id, 2, 10, QChar('0')); + emit changed(this); +} + +void MissionItem::setX(double x) +{ + if (!isinf(x) && !isnan(x) && ((_frame == MAV_FRAME_LOCAL_NED) || (_frame == MAV_FRAME_LOCAL_ENU))) + { + _x = x; + emit changed(this); + } +} + +void MissionItem::setY(double y) +{ + if (!isinf(y) && !isnan(y) && ((_frame == MAV_FRAME_LOCAL_NED) || (_frame == MAV_FRAME_LOCAL_ENU))) + { + _y = y; + emit changed(this); + } +} + +void MissionItem::setZ(double z) +{ + if (!isinf(z) && !isnan(z) && ((_frame == MAV_FRAME_LOCAL_NED) || (_frame == MAV_FRAME_LOCAL_ENU))) + { + _z = z; + emit changed(this); + } +} + +void MissionItem::setLatitude(double lat) +{ + if (_x != lat && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT))) + { + _x = lat; + emit changed(this); + emit coordinateChanged(); + } +} + +void MissionItem::setLongitude(double lon) +{ + if (_y != lon && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT))) + { + _y = lon; + emit changed(this); + emit coordinateChanged(); + } +} + +void MissionItem::setAltitude(double altitude) +{ + if (_z != altitude && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT))) + { + _z = altitude; + emit changed(this); + emit valueStringsChanged(valueStrings()); + emit coordinateChanged(); + } +} + +void MissionItem::setYaw(int yaw) +{ + if (_yaw != yaw) + { + _yaw = yaw; + emit changed(this); + emit valueStringsChanged(valueStrings()); + } +} + +void MissionItem::setYaw(double yaw) +{ + if (_yaw != yaw) + { + _yaw = yaw; + emit changed(this); + emit valueStringsChanged(valueStrings()); + } +} + +void MissionItem::setAction(int /*MAV_CMD*/ action) +{ + if (_action != action) { + _action = action; + + // Flick defaults according to WP type + + if (_action == MAV_CMD_NAV_TAKEOFF) { + // We default to 15 degrees minimum takeoff pitch + _param1 = 15.0; + } + + emit changed(this); + emit commandNameChanged(commandName()); + emit commandChanged((MavlinkQmlSingleton::Qml_MAV_CMD)_action); + emit hasCoordinateChanged(hasCoordinate()); + emit valueLabelsChanged(valueLabels()); + emit valueStringsChanged(valueStrings()); + } +} + +void MissionItem::setFrame(int /*MAV_FRAME*/ frame) +{ + if (_frame != frame) { + _frame = frame; + emit changed(this); + } +} + +void MissionItem::setAutocontinue(bool autoContinue) +{ + if (_autocontinue != autoContinue) { + _autocontinue = autoContinue; + emit changed(this); + } +} + +void MissionItem::setCurrent(bool current) +{ + if (_current != current) + { + _current = current; + // The current waypoint index is handled by the list + // and not part of the individual waypoint update state + } +} + +void MissionItem::setAcceptanceRadius(double radius) +{ + if (_param2 != radius) + { + _param2 = radius; + emit changed(this); + emit valueStringsChanged(valueStrings()); + } +} + +void MissionItem::setParam1(double param1) +{ + //// // qDebug() << "SENDER:" << QObject::sender(); + //// // qDebug() << "PARAM1 SET REQ:" << param1; + if (_param1 != param1) + { + _param1 = param1; + emit changed(this); + emit valueStringsChanged(valueStrings()); + } +} + +void MissionItem::setParam2(double param2) +{ + if (_param2 != param2) + { + _param2 = param2; + emit valueStringsChanged(valueStrings()); + emit changed(this); + } +} + +void MissionItem::setParam3(double param3) +{ + if (_orbit != param3) { + _orbit = param3; + emit valueStringsChanged(valueStrings()); + emit changed(this); + } +} + +void MissionItem::setParam4(double param4) +{ + if (_yaw != param4) { + _yaw = param4; + emit changed(this); + emit valueStringsChanged(valueStrings()); + } +} + +void MissionItem::setParam5(double param5) +{ + if (_x != param5) { + _x = param5; + emit changed(this); + emit valueStringsChanged(valueStrings()); + } +} + +void MissionItem::setParam6(double param6) +{ + if (_y != param6) { + _y = param6; + emit changed(this); + emit valueStringsChanged(valueStrings()); + } +} + +void MissionItem::setParam7(double param7) +{ + if (_z != param7) { + _z = param7; + emit valueStringsChanged(valueStrings()); + emit changed(this); + } +} + +void MissionItem::setLoiterOrbit(double orbit) +{ + if (_orbit != orbit) { + _orbit = orbit; + emit valueStringsChanged(valueStrings()); + emit changed(this); + } +} + +void MissionItem::setHoldTime(int holdTime) +{ + if (_param1 != holdTime) { + _param1 = holdTime; + emit valueStringsChanged(valueStrings()); + emit changed(this); + } +} + +void MissionItem::setHoldTime(double holdTime) +{ + if (_param1 != holdTime) { + _param1 = holdTime; + emit changed(this); + emit valueStringsChanged(valueStrings()); + } +} + +void MissionItem::setTurns(int turns) +{ + if (_param1 != turns) { + _param1 = turns; + emit changed(this); + emit valueStringsChanged(valueStrings()); + } +} + +bool MissionItem::hasCoordinate(void) +{ + switch (_action) { + case MAV_CMD_NAV_WAYPOINT: + case MAV_CMD_NAV_LOITER_UNLIM: + case MAV_CMD_NAV_LOITER_TURNS: + case MAV_CMD_NAV_LOITER_TIME: + case MAV_CMD_NAV_LAND: + case MAV_CMD_NAV_TAKEOFF: + return true; + default: + return false; + } +} + +QGeoCoordinate MissionItem::coordinate(void) +{ + return QGeoCoordinate(_x, _y); +} + +QString MissionItem::commandName(void) +{ + QString type; + + switch (_action) { + case MAV_CMD_NAV_WAYPOINT: + type = "Waypoint"; + break; + case MAV_CMD_NAV_LOITER_UNLIM: + case MAV_CMD_NAV_LOITER_TURNS: + case MAV_CMD_NAV_LOITER_TIME: + type = "Loiter"; + break; + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + type = "Return Home"; + break; + case MAV_CMD_NAV_LAND: + type = "Land"; + break; + case MAV_CMD_NAV_TAKEOFF: + type = "Takeoff"; + break; + case MAV_CMD_CONDITION_DELAY: + type = "Delay"; + break; + case MAV_CMD_DO_JUMP: + type = "Jump To Command"; + break; + default: + type = QString("Unknown (%1)").arg(_action); + break; + } + + return type; +} + +QStringList MissionItem::valueLabels(void) +{ + QStringList labels; + + switch (_action) { + case MAV_CMD_NAV_WAYPOINT: + if (getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) { + labels << "Alt (rel):"; + } else { + labels << "Alt:"; + } + labels << "Heading:" << "Radius:" << "Hold:"; + break; + case MAV_CMD_NAV_LOITER_UNLIM: + labels << "Heading:" << "Radius:"; + break; + case MAV_CMD_NAV_LOITER_TURNS: + labels << "Heading:" << "Radius:"<< "Turns:"; + break; + case MAV_CMD_NAV_LOITER_TIME: + labels << "Heading:" << "Radius:" << "Seconds:"; + break; + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + break; + case MAV_CMD_NAV_LAND: + if (getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) { + labels << "Alt (rel):"; + } else { + labels << "Alt:"; + } + labels << "Heading:"; + break; + case MAV_CMD_NAV_TAKEOFF: + if (getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) { + labels << "Alt (rel):"; + } else { + labels << "Alt:"; + } + labels << "Heading:" << "Pitch:"; + break; + case MAV_CMD_CONDITION_DELAY: + labels << "Seconds:"; + break; + case MAV_CMD_DO_JUMP: + labels << "Jump to:" << "Repeat:"; + break; + default: + break; + } + + return labels; +} + +QString MissionItem::_oneDecimalString(double value) +{ + return QString("%1").arg(value, 0 /* min field width */, 'f' /* format */, 1 /* precision */); +} + +QStringList MissionItem::valueStrings(void) +{ + QStringList list; + + switch (_action) { + case MAV_CMD_NAV_WAYPOINT: + list << _oneDecimalString(_z) << _oneDecimalString(_yaw * (180.0 / M_PI)) << _oneDecimalString(_param2) << _oneDecimalString(_param1); + break; + case MAV_CMD_NAV_LOITER_UNLIM: + list << _oneDecimalString(_yaw * (180.0 / M_PI)) << _oneDecimalString(_orbit); + break; + case MAV_CMD_NAV_LOITER_TURNS: + list << _oneDecimalString(_yaw * (180.0 / M_PI)) << _oneDecimalString(_orbit) << _oneDecimalString(_turns); + break; + case MAV_CMD_NAV_LOITER_TIME: + list << _oneDecimalString(_yaw * (180.0 / M_PI)) << _oneDecimalString(_orbit) << _oneDecimalString(_param1); + break; + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + break; + case MAV_CMD_NAV_LAND: + list << _oneDecimalString(_z) << _oneDecimalString(_yaw * (180.0 / M_PI)); + break; + case MAV_CMD_NAV_TAKEOFF: + list << _oneDecimalString(_z) << _oneDecimalString(_yaw * (180.0 / M_PI)) << _oneDecimalString(_param1); + break; + case MAV_CMD_CONDITION_DELAY: + list << _oneDecimalString(_param1); + break; + case MAV_CMD_DO_JUMP: + list << _oneDecimalString(_param1) << _oneDecimalString(_param2); + break; + default: + break; + } + + return list; +} \ No newline at end of file diff --git a/src/Waypoint.h b/src/MissionItem.h similarity index 68% rename from src/Waypoint.h rename to src/MissionItem.h index 9683b0b22b4ea18d080bae4036baab916805ae83..ba2574b90e3738005e53db41b3500652fe9a2bd0 100644 --- a/src/Waypoint.h +++ b/src/MissionItem.h @@ -1,37 +1,28 @@ /*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2014 QGROUNDCONTROL PROJECT + + 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 . + + ======================================================================*/ -PIXHAWK Micro Air Vehicle Flying Robotics Toolkit - -(c) 2009 PIXHAWK PROJECT - -This file is part of the PIXHAWK project - - PIXHAWK 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. - - PIXHAWK 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 PIXHAWK. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Waypoint class - * - * @author Benjamin Knecht - * @author Petri Tanskanen - * - */ - -#ifndef WAYPOINT_H -#define WAYPOINT_H +#ifndef MissionItem_H +#define MissionItem_H #include #include @@ -41,12 +32,13 @@ This file is part of the PIXHAWK project #include "QGCMAVLink.h" #include "QGC.h" +#include "MavlinkQmlSingleton.h" -class Waypoint : public QObject +class MissionItem : public QObject { Q_OBJECT public: - Waypoint( + MissionItem( QObject *parent = 0, quint16 id = 0, double x = 0.0, @@ -62,18 +54,24 @@ public: int action = MAV_CMD_NAV_WAYPOINT, const QString& description=QString("")); - Waypoint(const Waypoint& other); - ~Waypoint(); + MissionItem(const MissionItem& other); + ~MissionItem(); - const Waypoint& operator=(const Waypoint& other); + const MissionItem& operator=(const MissionItem& other); + Q_PROPERTY(bool hasCoordinate READ hasCoordinate NOTIFY hasCoordinateChanged) Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged) - Q_PROPERTY(QString type READ type NOTIFY typeChanged) + + Q_PROPERTY(QString commandName READ commandName NOTIFY commandNameChanged) + Q_PROPERTY(MavlinkQmlSingleton::Qml_MAV_CMD command READ command WRITE setCommand NOTIFY commandChanged) Q_PROPERTY(double longitude READ longitude NOTIFY longitudeChanged) Q_PROPERTY(double latitude READ latitude NOTIFY latitudeChanged) Q_PROPERTY(double altitude READ altitude NOTIFY altitudeChanged) Q_PROPERTY(quint16 id READ id CONSTANT) + + Q_PROPERTY(QStringList valueLabels READ valueLabels NOTIFY commandChanged) + Q_PROPERTY(QStringList valueStrings READ valueStrings NOTIFY valueStringsChanged) double latitude() { return _x; } double longitude() { return _y; } @@ -167,9 +165,17 @@ public: void save(QTextStream &saveStream); bool load(QTextStream &loadStream); + bool hasCoordinate(void); QGeoCoordinate coordinate(void); - QString type(void); + + QString commandName(void); + MavlinkQmlSingleton::Qml_MAV_CMD command(void) { return (MavlinkQmlSingleton::Qml_MAV_CMD)getAction(); }; + void setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command) { setAction(command); } + + QStringList valueLabels(void); + QStringList valueStrings(void); + protected: quint16 _id; double _x; @@ -229,15 +235,22 @@ public: signals: /** @brief Announces a change to the waypoint data */ - void changed(Waypoint* wp); + void changed(MissionItem* wp); void latitudeChanged (); void longitudeChanged (); void altitudeChanged (); + void hasCoordinateChanged(bool hasCoordinate); void coordinateChanged(void); - void typeChanged(QString type); + void commandNameChanged(QString type); + void commandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command); + void valueLabelsChanged(QStringList valueLabels); + void valueStringsChanged(QStringList valueStrings); + +private: + QString _oneDecimalString(double value); }; -QML_DECLARE_TYPE(Waypoint) +QML_DECLARE_TYPE(MissionItem) -#endif // WAYPOINT_H +#endif diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index b263313b16c4e404e1f2b3a5fb3aa0c65ea398f6..48615b08811eb8d5cfe90b1c326c4f5e63158070 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -88,6 +88,7 @@ G_END_DECLS #include "Generic/GenericFirmwarePlugin.h" #include "PX4/PX4FirmwarePlugin.h" #include "Vehicle.h" +#include "MavlinkQmlSingleton.h" #ifdef QGC_RTLAB_ENABLED #include "OpalLink.h" @@ -109,11 +110,8 @@ const char* QGCApplication::_savedFileParameterDirectoryName = "SavedParameters" const char* QGCApplication::_darkStyleFile = ":/res/styles/style-dark.css"; const char* QGCApplication::_lightStyleFile = ":/res/styles/style-light.css"; -/** - * @brief ScreenTools creation callback - * - * This is called by the QtQuick engine for creating the singleton - **/ + +// Qml Singleton factories static QObject* screenToolsControllerSingletonFactory(QQmlEngine*, QJSEngine*) { @@ -121,6 +119,11 @@ static QObject* screenToolsControllerSingletonFactory(QQmlEngine*, QJSEngine*) return screenToolsController; } +static QObject* mavlinkQmlSingletonFactory(QQmlEngine*, QJSEngine*) +{ + return new MavlinkQmlSingleton; +} + #if defined(QGC_GST_STREAMING) #ifdef Q_OS_MAC #ifndef __ios__ @@ -339,11 +342,12 @@ void QGCApplication::_initCommon(void) qmlRegisterType("QGroundControl.Controllers", 1, 0, "FirmwareUpgradeController"); #endif - //-- Create QML Singleton Interfaces - qmlRegisterSingletonType("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory); + // Register Qml Singletons + qmlRegisterSingletonType ("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory); + qmlRegisterSingletonType ("QGroundControl.Mavlink", 1, 0, "Mavlink", mavlinkQmlSingletonFactory); - //-- Register Waypoint Interface - qmlRegisterInterface("Waypoint"); + //-- Register MissionItem Interface + qmlRegisterInterface("MissionItem"); // Show user an upgrade message if the settings version has been bumped up bool settingsUpgraded = false; if (settings.contains(_settingsVersionKey)) { diff --git a/src/QmlControls/MavManager.cc b/src/QmlControls/MavManager.cc deleted file mode 100644 index abd0d08ed4a8d469aca5b26c727fc9dcf2192c08..0000000000000000000000000000000000000000 --- a/src/QmlControls/MavManager.cc +++ /dev/null @@ -1,727 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2015 QGROUNDCONTROL PROJECT - -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 . - -======================================================================*/ - -/** - * @file - * @brief QGC Mav Manager (QML Bindings) - * @author Gus Grubba - */ - -#include "UAS.h" -#include "MainWindow.h" -#include "MultiVehicleManager.h" -#include "Waypoint.h" -#include "MavManager.h" -#include "UASMessageHandler.h" - -#define UPDATE_TIMER 50 -#define DEFAULT_LAT 38.965767f -#define DEFAULT_LON -120.083923f - -MavManager::MavManager(QObject *parent) - : QObject(parent) - , _mav(NULL) - , _currentMessageCount(0) - , _messageCount(0) - , _currentErrorCount(0) - , _currentWarningCount(0) - , _currentNormalCount(0) - , _currentMessageType(MessageNone) - , _roll(0.0f) - , _pitch(0.0f) - , _heading(0.0f) - , _altitudeAMSL(0.0f) - , _altitudeWGS84(0.0f) - , _altitudeRelative(0.0f) - , _groundSpeed(0.0f) - , _airSpeed(0.0f) - , _climbRate(0.0f) - , _navigationAltitudeError(0.0f) - , _navigationSpeedError(0.0f) - , _navigationCrosstrackError(0.0f) - , _navigationTargetBearing(0.0f) - , _latitude(DEFAULT_LAT) - , _longitude(DEFAULT_LON) - , _refreshTimer(new QTimer(this)) - , _batteryVoltage(0.0) - , _batteryPercent(0.0) - , _batteryConsumed(-1.0) - , _systemArmed(false) - , _currentHeartbeatTimeout(0) - , _waypointDistance(0.0) - , _currentWaypoint(0) - , _satelliteCount(-1) - , _satelliteLock(0) - , _wpm(NULL) - , _updateCount(0) -{ - // Connect with UAS signal - _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle()); - connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &MavManager::_activeVehicleChanged); - - // Refresh timer - connect(_refreshTimer, SIGNAL(timeout()), this, SLOT(_checkUpdate())); - _refreshTimer->setInterval(UPDATE_TIMER); - _refreshTimer->start(UPDATE_TIMER); - emit heartbeatTimeoutChanged(); -} - -MavManager::~MavManager() -{ - _refreshTimer->stop(); -} - -void MavManager::saveSetting(const QString &name, const QString& value) -{ - QSettings settings; - settings.setValue(name, value); -} - -QString MavManager::loadSetting(const QString &name, const QString& defaultValue) -{ - QSettings settings; - return settings.value(name, defaultValue).toString(); -} - -void MavManager::_activeVehicleChanged(Vehicle* vehicle) -{ - // Disconnect the previous one (if any) - if (_mav) { - // Stop listening for system messages - disconnect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &MavManager::_handleTextMessage); - // Disconnect any previously connected active MAV - disconnect(_mav, SIGNAL(attitudeChanged (UASInterface*, double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64))); - disconnect(_mav, SIGNAL(attitudeChanged (UASInterface*, int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64))); - disconnect(_mav, SIGNAL(speedChanged (UASInterface*, double, double, quint64)), this, SLOT(_updateSpeed(UASInterface*, double, double, quint64))); - disconnect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64))); - disconnect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double))); - disconnect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*,QString,QString))); - disconnect(_mav, SIGNAL(armingChanged (bool)), this, SLOT(_updateArmingState(bool))); - disconnect(_mav, &UASInterface::NavigationControllerDataChanged, this, &MavManager::_updateNavigationControllerData); - disconnect(_mav, &UASInterface::heartbeatTimeout, this, &MavManager::_heartbeatTimeout); - disconnect(_mav, &UASInterface::batteryChanged, this, &MavManager::_updateBatteryRemaining); - disconnect(_mav, &UASInterface::batteryConsumedChanged, this, &MavManager::_updateBatteryConsumedChanged); - disconnect(_mav, &UASInterface::modeChanged, this, &MavManager::_updateMode); - disconnect(_mav, &UASInterface::nameChanged, this, &MavManager::_updateName); - disconnect(_mav, &UASInterface::systemTypeSet, this, &MavManager::_setSystemType); - disconnect(_mav, &UASInterface::localizationChanged, this, &MavManager::_setSatLoc); - if (_wpm) { - disconnect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &MavManager::_updateCurrentWaypoint); - disconnect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &MavManager::_updateWaypointDistance); - disconnect(_wpm, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(_waypointViewOnlyListChanged(void))); - disconnect(_wpm, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)), this, SLOT(_updateWaypointViewOnly(int,Waypoint*))); - } - UAS* pUas = dynamic_cast(_mav); - if(pUas) { - disconnect(pUas, &UAS::satelliteCountChanged, this, &MavManager::_setSatelliteCount); - } - _mav = NULL; - _satelliteCount = -1; - emit mavPresentChanged(); - emit satelliteCountChanged(); - } - - _mav = NULL; - - if (vehicle) { - _mav = vehicle->uas(); - // Reset satellite count (no GPS) - _satelliteCount = -1; - emit satelliteCountChanged(); - // Reset connection lost (if any) - _currentHeartbeatTimeout = 0; - emit heartbeatTimeoutChanged(); - // Listen for system messages - connect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &MavManager::_handleTextMessage); - // Now connect the new UAS - connect(_mav, SIGNAL(attitudeChanged (UASInterface*,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64))); - connect(_mav, SIGNAL(attitudeChanged (UASInterface*,int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64))); - connect(_mav, SIGNAL(speedChanged (UASInterface*, double, double, quint64)), this, SLOT(_updateSpeed(UASInterface*, double, double, quint64))); - connect(_mav, SIGNAL(altitudeChanged (UASInterface*, double, double, double, double, quint64)), this, SLOT(_updateAltitude(UASInterface*, double, double, double, double, quint64))); - connect(_mav, SIGNAL(navigationControllerErrorsChanged (UASInterface*, double, double, double)), this, SLOT(_updateNavigationControllerErrors(UASInterface*, double, double, double))); - connect(_mav, SIGNAL(statusChanged (UASInterface*,QString,QString)), this, SLOT(_updateState(UASInterface*, QString,QString))); - connect(_mav, SIGNAL(armingChanged (bool)), this, SLOT(_updateArmingState(bool))); - connect(_mav, &UASInterface::NavigationControllerDataChanged, this, &MavManager::_updateNavigationControllerData); - connect(_mav, &UASInterface::heartbeatTimeout, this, &MavManager::_heartbeatTimeout); - connect(_mav, &UASInterface::batteryChanged, this, &MavManager::_updateBatteryRemaining); - connect(_mav, &UASInterface::batteryConsumedChanged, this, &MavManager::_updateBatteryConsumedChanged); - connect(_mav, &UASInterface::modeChanged, this, &MavManager::_updateMode); - connect(_mav, &UASInterface::nameChanged, this, &MavManager::_updateName); - connect(_mav, &UASInterface::systemTypeSet, this, &MavManager::_setSystemType); - connect(_mav, &UASInterface::localizationChanged, this, &MavManager::_setSatLoc); - _wpm = _mav->getWaypointManager(); - if (_wpm) { - connect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &MavManager::_updateCurrentWaypoint); - connect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &MavManager::_updateWaypointDistance); - connect(_wpm, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(_waypointViewOnlyListChanged(void))); - connect(_wpm, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)),this, SLOT(_updateWaypointViewOnly(int,Waypoint*))); - _wpm->readWaypoints(true); - } - UAS* pUas = dynamic_cast(_mav); - if(pUas) { - _setSatelliteCount(pUas->getSatelliteCount(), QString("")); - connect(pUas, &UAS::satelliteCountChanged, this, &MavManager::_setSatelliteCount); - } - _setSystemType(_mav, _mav->getSystemType()); - _updateArmingState(_mav->isArmed()); - } - emit mavPresentChanged(); -} - -void MavManager::_updateAttitude(UASInterface*, double roll, double pitch, double yaw, quint64) -{ - if (isinf(roll)) { - _roll = std::numeric_limits::quiet_NaN(); - } else { - float rolldeg = _oneDecimal(roll * (180.0 / M_PI)); - if (fabs(roll - rolldeg) > 1.0) { - _roll = rolldeg; - if(_refreshTimer->isActive()) { - emit rollChanged(); - } - } - if(_roll != rolldeg) { - _roll = rolldeg; - _addChange(ROLL_CHANGED); - } - } - if (isinf(pitch)) { - _pitch = std::numeric_limits::quiet_NaN(); - } else { - float pitchdeg = _oneDecimal(pitch * (180.0 / M_PI)); - if (fabs(pitch - pitchdeg) > 1.0) { - _pitch = pitchdeg; - if(_refreshTimer->isActive()) { - emit pitchChanged(); - } - } - if(_pitch != pitchdeg) { - _pitch = pitchdeg; - _addChange(PITCH_CHANGED); - } - } - if (isinf(yaw)) { - _heading = std::numeric_limits::quiet_NaN(); - } else { - yaw = _oneDecimal(yaw * (180.0 / M_PI)); - if (yaw < 0) yaw += 360; - if (fabs(_heading - yaw) > 1.0) { - _heading = yaw; - if(_refreshTimer->isActive()) { - emit headingChanged(); - } - } - if(_heading != yaw) { - _heading = yaw; - _addChange(HEADING_CHANGED); - } - } -} - -void MavManager::_updateAttitude(UASInterface* uas, int, double roll, double pitch, double yaw, quint64 timestamp) -{ - _updateAttitude(uas, roll, pitch, yaw, timestamp); -} - -void MavManager::_updateSpeed(UASInterface*, double groundSpeed, double airSpeed, quint64) -{ - groundSpeed = _oneDecimal(groundSpeed); - if (fabs(_groundSpeed - groundSpeed) > 0.5) { - _groundSpeed = groundSpeed; - if(_refreshTimer->isActive()) { - emit groundSpeedChanged(); - } - } - airSpeed = _oneDecimal(airSpeed); - if (fabs(_airSpeed - airSpeed) > 1.0) { - _airSpeed = airSpeed; - if(_refreshTimer->isActive()) { - emit airSpeedChanged(); - } - } - if(_groundSpeed != groundSpeed) { - _groundSpeed = groundSpeed; - _addChange(GROUNDSPEED_CHANGED); - } - if(_airSpeed != airSpeed) { - _airSpeed = airSpeed; - _addChange(AIRSPEED_CHANGED); - } -} - -void MavManager::_updateAltitude(UASInterface*, double altitudeAMSL, double altitudeWGS84, double altitudeRelative, double climbRate, quint64) { - altitudeAMSL = _oneDecimal(altitudeAMSL); - if (fabs(_altitudeAMSL - altitudeAMSL) > 0.5) { - _altitudeAMSL = altitudeAMSL; - if(_refreshTimer->isActive()) { - emit altitudeAMSLChanged(); - } - } - altitudeWGS84 = _oneDecimal(altitudeWGS84); - if (fabs(_altitudeWGS84 - altitudeWGS84) > 0.5) { - _altitudeWGS84 = altitudeWGS84; - if(_refreshTimer->isActive()) { - emit altitudeWGS84Changed(); - } - } - altitudeRelative = _oneDecimal(altitudeRelative); - if (fabs(_altitudeRelative - altitudeRelative) > 0.5) { - _altitudeRelative = altitudeRelative; - if(_refreshTimer->isActive()) { - emit altitudeRelativeChanged(); - } - } - climbRate = _oneDecimal(climbRate); - if (fabs(_climbRate - climbRate) > 0.5) { - _climbRate = climbRate; - if(_refreshTimer->isActive()) { - emit climbRateChanged(); - } - } - if(_altitudeAMSL != altitudeAMSL) { - _altitudeAMSL = altitudeAMSL; - _addChange(ALTITUDEAMSL_CHANGED); - } - if(_altitudeWGS84 != altitudeWGS84) { - _altitudeWGS84 = altitudeWGS84; - _addChange(ALTITUDEWGS84_CHANGED); - } - if(_altitudeRelative != altitudeRelative) { - _altitudeRelative = altitudeRelative; - _addChange(ALTITUDERELATIVE_CHANGED); - } - if(_climbRate != climbRate) { - _climbRate = climbRate; - _addChange(CLIMBRATE_CHANGED); - } -} - -void MavManager::_updateNavigationControllerErrors(UASInterface*, double altitudeError, double speedError, double xtrackError) { - _navigationAltitudeError = altitudeError; - _navigationSpeedError = speedError; - _navigationCrosstrackError = xtrackError; -} - -void MavManager::_updateNavigationControllerData(UASInterface *uas, float, float, float, float targetBearing, float) { - if (_mav == uas) { - _navigationTargetBearing = targetBearing; - } -} - -/* - * Internal - */ - -bool MavManager::_isAirplane() { - if (_mav) - return _mav->isAirplane(); - return false; -} - -void MavManager::_addChange(int id) -{ - if(!_changes.contains(id)) { - _changes.append(id); - } -} - -float MavManager::_oneDecimal(float value) -{ - int i = (value * 10); - return (float)i / 10.0; -} - -void MavManager::_checkUpdate() -{ - // Update current location - if(_mav) { - if(_latitude != _mav->getLatitude()) { - _latitude = _mav->getLatitude(); - emit latitudeChanged(); - } - if(_longitude != _mav->getLongitude()) { - _longitude = _mav->getLongitude(); - emit longitudeChanged(); - } - } - // The timer rate is 20Hz for the coordinates above. These below we only check - // twice a second. - if(++_updateCount > 9) { - _updateCount = 0; - // Check for changes - // Significant changes, that is, whole number changes, are updated immediatelly. - // For every message however, we set a flag for what changed and this timer updates - // them to bring everything up-to-date. This prevents an avalanche of UI updates. - foreach(int i, _changes) { - switch (i) { - case ROLL_CHANGED: - emit rollChanged(); - break; - case PITCH_CHANGED: - emit pitchChanged(); - break; - case HEADING_CHANGED: - emit headingChanged(); - break; - case GROUNDSPEED_CHANGED: - emit groundSpeedChanged(); - break; - case AIRSPEED_CHANGED: - emit airSpeedChanged(); - break; - case CLIMBRATE_CHANGED: - emit climbRateChanged(); - break; - case ALTITUDERELATIVE_CHANGED: - emit altitudeRelativeChanged(); - break; - case ALTITUDEWGS84_CHANGED: - emit altitudeWGS84Changed(); - break; - case ALTITUDEAMSL_CHANGED: - emit altitudeAMSLChanged(); - break; - default: - break; - } - } - _changes.clear(); - } -} - -QString MavManager::getMavIconColor() -{ - // TODO: Not using because not only the colors are ghastly, it doesn't respect dark/light palette - if(_mav) - return _mav->getColor().name(); - else - return QString("black"); -} - -void MavManager::_updateArmingState(bool armed) -{ - if(_systemArmed != armed) { - _systemArmed = armed; - emit systemArmedChanged(); - } -} - -void MavManager::_updateBatteryRemaining(UASInterface*, double voltage, double, double percent, int) -{ - - if(percent < 0.0) { - percent = 0.0; - } - if(voltage < 0.0) { - voltage = 0.0; - } - if (_batteryVoltage != voltage) { - _batteryVoltage = voltage; - emit batteryVoltageChanged(); - } - if (_batteryPercent != percent) { - _batteryPercent = percent; - emit batteryPercentChanged(); - } -} - -void MavManager::_updateBatteryConsumedChanged(UASInterface*, double current_consumed) -{ - if(_batteryConsumed != current_consumed) { - _batteryConsumed = current_consumed; - emit batteryConsumedChanged(); - } -} - - -void MavManager::_updateState(UASInterface*, QString name, QString) -{ - if (_currentState != name) { - _currentState = name; - emit currentStateChanged(); - } -} - -void MavManager::_updateMode(int, QString name, QString) -{ - if (name.size()) { - QString shortMode = name; - shortMode = shortMode.replace("D|", ""); - shortMode = shortMode.replace("A|", ""); - if (_currentMode != shortMode) { - _currentMode = shortMode; - emit currentModeChanged(); - } - } -} - -void MavManager::_updateName(const QString& name) -{ - if (_systemName != name) { - _systemName = name; - emit systemNameChanged(); - } -} - -/** - * The current system type is represented through the system icon. - * - * @param uas Source system, has to be the same as this->uas - * @param systemType type ID, following the MAVLink system type conventions - * @see http://pixhawk.ethz.ch/software/mavlink - */ -void MavManager::_setSystemType(UASInterface*, unsigned int systemType) -{ - _systemPixmap = "qrc:/res/mavs/"; - switch (systemType) { - case MAV_TYPE_GENERIC: - _systemPixmap += "Generic"; - break; - case MAV_TYPE_FIXED_WING: - _systemPixmap += "FixedWing"; - break; - case MAV_TYPE_QUADROTOR: - _systemPixmap += "QuadRotor"; - break; - case MAV_TYPE_COAXIAL: - _systemPixmap += "Coaxial"; - break; - case MAV_TYPE_HELICOPTER: - _systemPixmap += "Helicopter"; - break; - case MAV_TYPE_ANTENNA_TRACKER: - _systemPixmap += "AntennaTracker"; - break; - case MAV_TYPE_GCS: - _systemPixmap += "Groundstation"; - break; - case MAV_TYPE_AIRSHIP: - _systemPixmap += "Airship"; - break; - case MAV_TYPE_FREE_BALLOON: - _systemPixmap += "FreeBalloon"; - break; - case MAV_TYPE_ROCKET: - _systemPixmap += "Rocket"; - break; - case MAV_TYPE_GROUND_ROVER: - _systemPixmap += "GroundRover"; - break; - case MAV_TYPE_SURFACE_BOAT: - _systemPixmap += "SurfaceBoat"; - break; - case MAV_TYPE_SUBMARINE: - _systemPixmap += "Submarine"; - break; - case MAV_TYPE_HEXAROTOR: - _systemPixmap += "HexaRotor"; - break; - case MAV_TYPE_OCTOROTOR: - _systemPixmap += "OctoRotor"; - break; - case MAV_TYPE_TRICOPTER: - _systemPixmap += "TriCopter"; - break; - case MAV_TYPE_FLAPPING_WING: - _systemPixmap += "FlappingWing"; - break; - case MAV_TYPE_KITE: - _systemPixmap += "Kite"; - break; - default: - _systemPixmap += "Unknown"; - break; - } - emit systemPixmapChanged(); -} - -void MavManager::_heartbeatTimeout(bool timeout, unsigned int ms) -{ - unsigned int elapsed = ms; - if (!timeout) - { - elapsed = 0; - } - if(elapsed != _currentHeartbeatTimeout) { - _currentHeartbeatTimeout = elapsed; - emit heartbeatTimeoutChanged(); - } -} - -void MavManager::_setSatelliteCount(double val, QString) -{ - // I'm assuming that a negative value or over 99 means there is no GPS - if(val < 0.0) val = -1.0; - if(val > 99.0) val = -1.0; - if(_satelliteCount != (int)val) { - _satelliteCount = (int)val; - emit satelliteCountChanged(); - } -} - -void MavManager::_setSatLoc(UASInterface*, int fix) -{ - // fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D lock, 3: 3D lock - if(_satelliteLock != fix) { - _satelliteLock = fix; - emit satelliteLockChanged(); - } -} - -void MavManager::_updateWaypointDistance(double distance) -{ - if (_waypointDistance != distance) { - _waypointDistance = distance; - emit waypointDistanceChanged(); - } -} - -void MavManager::_updateCurrentWaypoint(quint16 id) -{ - if (_currentWaypoint != id) { - _currentWaypoint = id; - emit currentWaypointChanged(); - } -} - -void MavManager::_updateWaypointViewOnly(int, Waypoint* /*wp*/) -{ - /* - bool changed = false; - for(int i = 0; i < _waypoints.count(); i++) { - if(_waypoints[i].getId() == wp->getId()) { - _waypoints[i] = *wp; - changed = true; - break; - } - } - if(changed) { - emit waypointListChanged(); - } - */ -} - -void MavManager::_waypointViewOnlyListChanged() -{ - if(_wpm) { - const QList &waypoints = _wpm->getWaypointViewOnlyList(); - _waypoints.clear(); - for(int i = 0; i < waypoints.count(); i++) { - Waypoint* wp = waypoints[i]; - _waypoints.append(new Waypoint(*wp)); - } - emit waypointsChanged(); - /* - if(_longitude == DEFAULT_LON && _latitude == DEFAULT_LAT && _waypoints.length()) { - _longitude = _waypoints[0]->getLongitude(); - _latitude = _waypoints[0]->getLatitude(); - emit longitudeChanged(); - emit latitudeChanged(); - } - */ - } -} - -void MavManager::_handleTextMessage(int newCount) -{ - // Reset? - if(!newCount) { - _currentMessageCount = 0; - _currentNormalCount = 0; - _currentWarningCount = 0; - _currentErrorCount = 0; - _messageCount = 0; - _currentMessageType = MessageNone; - emit newMessageCountChanged(); - emit messageTypeChanged(); - emit messageCountChanged(); - return; - } - - UASMessageHandler* pMh = UASMessageHandler::instance(); - Q_ASSERT(pMh); - MessageType_t type = newCount ? _currentMessageType : MessageNone; - int errorCount = _currentErrorCount; - int warnCount = _currentWarningCount; - int normalCount = _currentNormalCount; - //-- Add current message counts - errorCount += pMh->getErrorCount(); - warnCount += pMh->getWarningCount(); - normalCount += pMh->getNormalCount(); - //-- See if we have a higher level - if(errorCount != _currentErrorCount) { - _currentErrorCount = errorCount; - type = MessageError; - } - if(warnCount != _currentWarningCount) { - _currentWarningCount = warnCount; - if(_currentMessageType != MessageError) { - type = MessageWarning; - } - } - if(normalCount != _currentNormalCount) { - _currentNormalCount = normalCount; - if(_currentMessageType != MessageError && _currentMessageType != MessageWarning) { - type = MessageNormal; - } - } - int count = _currentErrorCount + _currentWarningCount + _currentNormalCount; - if(count != _currentMessageCount) { - _currentMessageCount = count; - // Display current total new messages count - emit newMessageCountChanged(); - } - if(type != _currentMessageType) { - _currentMessageType = type; - // Update message level - emit messageTypeChanged(); - } - // Update message count (all messages) - if(newCount != _messageCount) { - _messageCount = newCount; - emit messageCountChanged(); - } - QString errMsg = pMh->getLatestError(); - if(errMsg != _latestError) { - _latestError = errMsg; - emit latestErrorChanged(); - } -} - -void MavManager::resetMessages() -{ - // Reset Counts - int count = _currentMessageCount; - MessageType_t type = _currentMessageType; - _currentErrorCount = 0; - _currentWarningCount = 0; - _currentNormalCount = 0; - _currentMessageCount = 0; - _currentMessageType = MessageNone; - if(count != _currentMessageCount) { - emit newMessageCountChanged(); - } - if(type != _currentMessageType) { - emit messageTypeChanged(); - } -} diff --git a/src/QmlControls/MavManager.h b/src/QmlControls/MavManager.h deleted file mode 100644 index 171b79f29e7c6fdaf06ea7d7e0326f8cd26efa06..0000000000000000000000000000000000000000 --- a/src/QmlControls/MavManager.h +++ /dev/null @@ -1,254 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2015 QGROUNDCONTROL PROJECT - -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 . - -======================================================================*/ - -/** - * @file - * @brief QGC Mav Manager (QML Bindings) - * @author Gus Grubba - */ - -#ifndef MAVMANAGER_H -#define MAVMANAGER_H - -#include -#include -#include - -#include "Waypoint.h" -#include "Vehicle.h" - -class UASInterface; -class UASWaypointManager; - -class MavManager : public QObject -{ - Q_OBJECT - Q_ENUMS(MessageType_t) -public: - explicit MavManager(QObject *parent = 0); - ~MavManager(); - - typedef enum { - MessageNone, - MessageNormal, - MessageWarning, - MessageError - } MessageType_t; - - enum { - ROLL_CHANGED, - PITCH_CHANGED, - HEADING_CHANGED, - GROUNDSPEED_CHANGED, - AIRSPEED_CHANGED, - CLIMBRATE_CHANGED, - ALTITUDERELATIVE_CHANGED, - ALTITUDEWGS84_CHANGED, - ALTITUDEAMSL_CHANGED - }; - - // Called when the message drop-down is invoked to clear current count - void resetMessages(); - - Q_INVOKABLE QString getMavIconColor(); - Q_INVOKABLE void saveSetting (const QString &key, const QString& value); - Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue); - - //-- System Messages - Q_PROPERTY(MessageType_t messageType READ messageType NOTIFY messageTypeChanged) - Q_PROPERTY(int newMessageCount READ newMessageCount NOTIFY newMessageCountChanged) - Q_PROPERTY(int messageCount READ messageCount NOTIFY messageCountChanged) - Q_PROPERTY(QString latestError READ latestError NOTIFY latestErrorChanged) - //-- UAV Stats - Q_PROPERTY(float roll READ roll NOTIFY rollChanged) - Q_PROPERTY(float pitch READ pitch NOTIFY pitchChanged) - Q_PROPERTY(float heading READ heading NOTIFY headingChanged) - Q_PROPERTY(float groundSpeed READ groundSpeed NOTIFY groundSpeedChanged) - Q_PROPERTY(float airSpeed READ airSpeed NOTIFY airSpeedChanged) - Q_PROPERTY(float climbRate READ climbRate NOTIFY climbRateChanged) - Q_PROPERTY(float altitudeRelative READ altitudeRelative NOTIFY altitudeRelativeChanged) - Q_PROPERTY(float altitudeWGS84 READ altitudeWGS84 NOTIFY altitudeWGS84Changed) - Q_PROPERTY(float altitudeAMSL READ altitudeAMSL NOTIFY altitudeAMSLChanged) - Q_PROPERTY(float latitude READ latitude NOTIFY latitudeChanged) - Q_PROPERTY(float longitude READ longitude NOTIFY longitudeChanged) - Q_PROPERTY(bool mavPresent READ mavPresent NOTIFY mavPresentChanged) - Q_PROPERTY(double batteryVoltage READ batteryVoltage NOTIFY batteryVoltageChanged) - Q_PROPERTY(double batteryPercent READ batteryPercent NOTIFY batteryPercentChanged) - Q_PROPERTY(double batteryConsumed READ batteryConsumed NOTIFY batteryConsumedChanged) - Q_PROPERTY(bool systemArmed READ systemArmed NOTIFY systemArmedChanged) - Q_PROPERTY(QString currentMode READ currentMode NOTIFY currentModeChanged) - Q_PROPERTY(QString systemPixmap READ systemPixmap NOTIFY systemPixmapChanged) - Q_PROPERTY(int satelliteCount READ satelliteCount NOTIFY satelliteCountChanged) - Q_PROPERTY(QString currentState READ currentState NOTIFY currentStateChanged) - Q_PROPERTY(QString systemName READ systemName NOTIFY systemNameChanged) - Q_PROPERTY(int satelliteLock READ satelliteLock NOTIFY satelliteLockChanged) - Q_PROPERTY(double waypointDistance READ waypointDistance NOTIFY waypointDistanceChanged) - Q_PROPERTY(uint16_t currentWaypoint READ currentWaypoint NOTIFY currentWaypointChanged) - Q_PROPERTY(unsigned int heartbeatTimeout READ heartbeatTimeout NOTIFY heartbeatTimeoutChanged) - //-- Waypoint management - Q_PROPERTY(QQmlListProperty waypoints READ waypoints NOTIFY waypointsChanged) - - MessageType_t messageType () { return _currentMessageType; } - int newMessageCount () { return _currentMessageCount; } - int messageCount () { return _messageCount; } - QString latestError () { return _latestError; } - float roll () { return _roll; } - float pitch () { return _pitch; } - float heading () { return _heading; } - float groundSpeed () { return _groundSpeed; } - float airSpeed () { return _airSpeed; } - float climbRate () { return _climbRate; } - float altitudeRelative () { return _altitudeRelative; } - float altitudeWGS84 () { return _altitudeWGS84; } - float altitudeAMSL () { return _altitudeAMSL; } - float latitude () { return _latitude; } - float longitude () { return _longitude; } - bool mavPresent () { return _mav != NULL; } - int satelliteCount () { return _satelliteCount; } - double batteryVoltage () { return _batteryVoltage; } - double batteryPercent () { return _batteryPercent; } - double batteryConsumed () { return _batteryConsumed; } - bool systemArmed () { return _systemArmed; } - QString currentMode () { return _currentMode; } - QString systemPixmap () { return _systemPixmap; } - QString currentState () { return _currentState; } - QString systemName () { return _systemName; } - int satelliteLock () { return _satelliteLock; } - double waypointDistance () { return _waypointDistance; } - uint16_t currentWaypoint () { return _currentWaypoint; } - unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; } - - QQmlListProperty waypoints() {return QQmlListProperty(this, _waypoints); } - -signals: - void messageTypeChanged (); - void newMessageCountChanged (); - void messageCountChanged (); - void latestErrorChanged (); - void rollChanged (); - void pitchChanged (); - void headingChanged (); - void groundSpeedChanged (); - void airSpeedChanged (); - void climbRateChanged (); - void altitudeRelativeChanged(); - void altitudeWGS84Changed (); - void altitudeAMSLChanged (); - void latitudeChanged (); - void longitudeChanged (); - void mavPresentChanged (); - void batteryVoltageChanged (); - void batteryPercentChanged (); - void batteryConsumedChanged (); - void systemArmedChanged (); - void heartbeatTimeoutChanged(); - void currentModeChanged (); - void currentConfigChanged (); - void systemPixmapChanged (); - void satelliteCountChanged (); - void currentStateChanged (); - void systemNameChanged (); - void satelliteLockChanged (); - void waypointDistanceChanged(); - void currentWaypointChanged (); - void waypointsChanged (); - -private slots: - void _activeVehicleChanged(Vehicle* vehicle); - void _handleTextMessage (int newCount); - /** @brief Attitude from main autopilot / system state */ - void _updateAttitude (UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp); - /** @brief Attitude from one specific component / redundant autopilot */ - void _updateAttitude (UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp); - /** @brief Speed */ - void _updateSpeed (UASInterface* uas, double _groundSpeed, double _airSpeed, quint64 timestamp); - /** @brief Altitude */ - void _updateAltitude (UASInterface* uas, double _altitudeAMSL, double _altitudeWGS84, double _altitudeRelative, double _climbRate, quint64 timestamp); - void _updateNavigationControllerErrors (UASInterface* uas, double altitudeError, double speedError, double xtrackError); - void _updateNavigationControllerData (UASInterface *uas, float navRoll, float navPitch, float navBearing, float targetBearing, float targetDistance); - void _checkUpdate (); - void _updateBatteryRemaining (UASInterface*, double voltage, double, double percent, int); - void _updateBatteryConsumedChanged (UASInterface*, double current_consumed); - void _updateArmingState (bool armed); - void _updateState (UASInterface* system, QString name, QString description); - void _updateMode (int system, QString name, QString description); - void _updateName (const QString& name); - void _setSystemType (UASInterface* uas, unsigned int systemType); - void _heartbeatTimeout (bool timeout, unsigned int ms); - void _updateCurrentWaypoint (quint16 id); - void _updateWaypointDistance (double distance); - void _setSatelliteCount (double val, QString name); - void _setSatLoc (UASInterface* uas, int fix); - void _updateWaypointViewOnly (int uas, Waypoint* wp); - void _waypointViewOnlyListChanged (); - -private: - bool _isAirplane (); - void _addChange (int id); - float _oneDecimal (float value); - -private: - UASInterface* _mav; - int _currentMessageCount; - int _messageCount; - int _currentErrorCount; - int _currentWarningCount; - int _currentNormalCount; - MessageType_t _currentMessageType; - QString _latestError; - float _roll; - float _pitch; - float _heading; - float _altitudeAMSL; - float _altitudeWGS84; - float _altitudeRelative; - float _groundSpeed; - float _airSpeed; - float _climbRate; - float _navigationAltitudeError; - float _navigationSpeedError; - float _navigationCrosstrackError; - float _navigationTargetBearing; - float _latitude; - float _longitude; - QTimer* _refreshTimer; - QList _changes; - double _batteryVoltage; - double _batteryPercent; - double _batteryConsumed; - bool _systemArmed; - QString _currentState; - QString _currentMode; - QString _systemName; - QString _systemPixmap; - unsigned int _currentHeartbeatTimeout; - double _waypointDistance; - quint16 _currentWaypoint; - int _satelliteCount; - int _satelliteLock; - UASWaypointManager* _wpm; - int _updateCount; - QList_waypoints; -}; - -#endif // MAVMANAGER_H diff --git a/src/QmlControls/MavlinkQmlSingleton.h b/src/QmlControls/MavlinkQmlSingleton.h new file mode 100644 index 0000000000000000000000000000000000000000..74bc9d65d307ebeb33b6c606e94cfb4e99e7c962 --- /dev/null +++ b/src/QmlControls/MavlinkQmlSingleton.h @@ -0,0 +1,120 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +(c) 2009, 2015 QGROUNDCONTROL PROJECT + +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 . + +======================================================================*/ + +#ifndef MavlinkQmlSingleton_H +#define MavlinkQmlSingleton_H + +#include + +class MavlinkQmlSingleton : public QObject +{ + Q_OBJECT + Q_ENUMS(Qml_MAV_CMD) + +public: + // Couldn't figure a way to get MAV_CMD enum out to Qml so I had to copy it. Sigh! + + typedef enum { + MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate [ms^-1]| Desired yaw angle [rad]| Y-axis position [m]| X-axis position [m]| Z-axis / ground level position [m]| */ + MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]| Empty| Takeoff ascend rate [ms^-1]| Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position [m]| X-axis position [m]| Z-axis position [m]| */ + MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Empty| Empty| Empty| Empty| Empty| Empty| Desired altitude in meters| */ + MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Heading Required (0 = False)| Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_ALTITUDE_WAIT=83, /* Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. |altitude (m)| descent speed (m/s)| Wiggle Time (s)| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ + MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */ + MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ + MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ + MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ + MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable, 2=disable_floor_only)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_MOTOR_TEST=209, /* Mission command to perform motor test |motor sequence number (a number from 1 to max number of motors on the vehicle)| throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)| throttle| timeout (in seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GRIPPER=211, /* Mission command to operate EPM gripper |gripper number (a number from 1 to max number of grippers on the vehicle)| gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_AUTOTUNE_ENABLE=212, /* Enable/disable autotune |enable (1: enable, 0:disable)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */ + MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */ + MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ + MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ + MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. |1: Trigger actuator ID assignment and direction mapping.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ + MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ + MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ + MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ + MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID| */ + MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.| */ + MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */ + MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence |Duration between two consecutive pictures (in seconds)| Number of images to capture total - 0 for unlimited capture| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ + MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence |Reserved| Reserved| */ + MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved| */ + MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture |Camera ID (0 for all cameras), 1 for first, 2 for second, etc.| Frames per second| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ + MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture |Reserved| Reserved| */ + MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */ + MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| */ + MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */ + MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_DO_START_MAG_CAL=42424, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Automatically retry on failure (0=no retry, 1=retry).| Save without user input (0=require input, 1=autosave).| Delay (seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_ACCEPT_MAG_CAL=42425, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CANCEL_MAG_CAL=42426, /* Cancel a running magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_ENUM_END=42427, /* | */ + } Qml_MAV_CMD; +}; + +#endif // MavlinkQmlSingleton_H diff --git a/src/QmlControls/MissionItemSummary.qml b/src/QmlControls/MissionItemSummary.qml index 860788443abe1b69a0a45184d575b6755eb94bc3..673db7aa55ef6a75e930abea30c3e3aea6044a44 100644 --- a/src/QmlControls/MissionItemSummary.qml +++ b/src/QmlControls/MissionItemSummary.qml @@ -7,28 +7,65 @@ import QGroundControl.ScreenTools 1.0 /// Mission item summary display control Rectangle { property var missionItem ///< Mission Item object - property int missionItemIndex ///< Index for this item width: ScreenTools.defaultFontPixelWidth * 15 - height: ScreenTools.defaultFontPixelWidth * 3 + height: valueColumn.height + radius border.width: 2 border.color: "white" color: "white" opacity: 0.75 radius: ScreenTools.defaultFontPixelWidth - - QGCLabel { - anchors.margins: parent.radius / 2 - anchors.left: parent.left - anchors.top: parent.top - color: "black" - horizontalAlignment: Text.AlignTop - text: missionItem.type - } - + MissionItemIndexLabel { anchors.top: parent.top anchors.right: parent.right - missionItemIndex: parent.missionItemIndex + 1 + missionItemIndex: missionItem.id + 1 + } + + Column { + anchors.margins: parent.radius / 2 + anchors.left: parent.left + anchors.right: parent.right + anchors.top: parent.top + + QGCLabel { + color: "black" + horizontalAlignment: Text.AlignTop + font.weight: Font.Bold + text: missionItem.commandName + } + + Repeater { + model: missionItem.valueLabels + + QGCLabel { + color: "black" + text: modelData + } + } + } + + Column { + id: valueColumn + anchors.margins: parent.radius / 2 + anchors.left: parent.left + anchors.right: parent.right + anchors.top: parent.top + + QGCLabel { + font.weight: Font.Bold + text: " " + } + + Repeater { + model: missionItem.valueStrings + + QGCLabel { + width: valueColumn.width + color: "black" + text: modelData + horizontalAlignment: Text.AlignRight + } + } } } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 8d3298dfa925b62350b0e86dadba1ac0758c8759..69e4ad94a0c1ca196fe7fc352a90a141a2731a05 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -126,7 +126,7 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType) connect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &Vehicle::_updateCurrentWaypoint); connect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &Vehicle::_updateWaypointDistance); connect(_wpm, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(_waypointViewOnlyListChanged(void))); - connect(_wpm, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)),this, SLOT(_updateWaypointViewOnly(int,Waypoint*))); + connect(_wpm, SIGNAL(waypointViewOnlyChanged(int,MissionItem*)),this, SLOT(_updateWaypointViewOnly(int,MissionItem*))); _wpm->readWaypoints(true); } UAS* pUas = dynamic_cast(_mav); @@ -162,7 +162,7 @@ Vehicle::~Vehicle() disconnect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &Vehicle::_updateCurrentWaypoint); disconnect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &Vehicle::_updateWaypointDistance); disconnect(_wpm, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(_waypointViewOnlyListChanged(void))); - disconnect(_wpm, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)), this, SLOT(_updateWaypointViewOnly(int,Waypoint*))); + disconnect(_wpm, SIGNAL(waypointViewOnlyChanged(int,MissionItem*)), this, SLOT(_updateWaypointViewOnly(int,MissionItem*))); } UAS* pUas = dynamic_cast(_mav); if(pUas) { @@ -688,7 +688,7 @@ void Vehicle::_updateCurrentWaypoint(quint16 id) } } -void Vehicle::_updateWaypointViewOnly(int, Waypoint* /*wp*/) +void Vehicle::_updateWaypointViewOnly(int, MissionItem* /*wp*/) { /* bool changed = false; @@ -708,11 +708,11 @@ void Vehicle::_updateWaypointViewOnly(int, Waypoint* /*wp*/) void Vehicle::_waypointViewOnlyListChanged() { if(_wpm) { - const QList &waypoints = _wpm->getWaypointViewOnlyList(); + const QList &waypoints = _wpm->getWaypointViewOnlyList(); _waypoints.clear(); for(int i = 0; i < waypoints.count(); i++) { - Waypoint* wp = waypoints[i]; - _waypoints.append(new Waypoint(*wp)); + MissionItem* wp = waypoints[i]; + _waypoints.append(new MissionItem(*wp)); } emit missionItemsChanged(); /* diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index bd3615f853b6ad638c560549b786db27991a682e..37bcb9d81712b08dfcf1a0ef33a7d0db58a611c7 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -88,8 +88,8 @@ public: Q_PROPERTY(uint16_t currentWaypoint READ currentWaypoint NOTIFY currentWaypointChanged) Q_PROPERTY(unsigned int heartbeatTimeout READ heartbeatTimeout NOTIFY heartbeatTimeoutChanged) - //-- Waypoint management - Q_PROPERTY(QQmlListProperty missionItems READ missionItems NOTIFY missionItemsChanged) + //-- MissionItem management + Q_PROPERTY(QQmlListProperty missionItems READ missionItems NOTIFY missionItemsChanged) // Property accesors int id(void) { return _id; } @@ -162,7 +162,7 @@ public: uint16_t currentWaypoint () { return _currentWaypoint; } unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; } - QQmlListProperty missionItems() {return QQmlListProperty(this, _waypoints); } + QQmlListProperty missionItems() {return QQmlListProperty(this, _waypoints); } public slots: void setLatitude(double latitude); @@ -235,7 +235,7 @@ private slots: void _updateWaypointDistance (double distance); void _setSatelliteCount (double val, QString name); void _setSatLoc (UASInterface* uas, int fix); - void _updateWaypointViewOnly (int uas, Waypoint* wp); + void _updateWaypointViewOnly (int uas, MissionItem* wp); void _waypointViewOnlyListChanged (); private: @@ -301,6 +301,6 @@ private: int _satelliteLock; UASWaypointManager* _wpm; int _updateCount; - QList_waypoints; + QList_waypoints; }; #endif diff --git a/src/Waypoint.cc b/src/Waypoint.cc deleted file mode 100644 index eb6a44a462fcf885fa13da33a48a4135f7ce39ad..0000000000000000000000000000000000000000 --- a/src/Waypoint.cc +++ /dev/null @@ -1,475 +0,0 @@ -/*=================================================================== -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -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 . - -======================================================================*/ - -/** - * @file - * @brief Waypoint class - * - * @author Benjamin Knecht - * @author Petri Tanskanen - * - */ - -#include -#include - -#include "Waypoint.h" - -Waypoint::Waypoint( - QObject *parent, - quint16 id, - double x, - double y, - double z, - double param1, - double param2, - double param3, - double param4, - bool autocontinue, - bool current, - int frame, - int action, - const QString& description - ) - : QObject(parent) - , _id(id) - , _x(x) - , _y(y) - , _z(z) - , _yaw(param4) - , _frame(frame) - , _action(action) - , _autocontinue(autocontinue) - , _current(current) - , _orbit(param3) - , _param1(param1) - , _param2(param2) - , _name(QString("WP%1").arg(id, 2, 10, QChar('0'))) - , _description(description) - , _reachedTime(0) -{ - connect(this, &Waypoint::latitudeChanged, this, &Waypoint::coordinateChanged); - connect(this, &Waypoint::longitudeChanged, this, &Waypoint::coordinateChanged); -} - -Waypoint::Waypoint(const Waypoint& other) - : QObject(NULL) -{ - *this = other; -} - -Waypoint::~Waypoint() -{ -} - -const Waypoint& Waypoint::operator=(const Waypoint& other) -{ - _id = other.getId(); - _x = other.getX(); - _y = other.getY(); - _z = other.getZ(); - _yaw = other.getYaw(); - _frame = other.getFrame(); - _action = other.getAction(); - _autocontinue = other.getAutoContinue(); - _current = other.getCurrent(); - _orbit = other.getParam3(); - _param1 = other.getParam1(); - _param2 = other.getParam2(); - _name = other.getName(); - _description = other.getDescription(); - _reachedTime = other.getReachedTime(); - return *this; -} - -bool Waypoint::isNavigationType() -{ - return (_action < MAV_CMD_NAV_LAST); -} - -void Waypoint::save(QTextStream &saveStream) -{ - QString position("%1\t%2\t%3"); - position = position.arg(_x, 0, 'g', 18); - position = position.arg(_y, 0, 'g', 18); - position = position.arg(_z, 0, 'g', 18); - QString parameters("%1\t%2\t%3\t%4"); - parameters = parameters.arg(_param1, 0, 'g', 18).arg(_param2, 0, 'g', 18).arg(_orbit, 0, 'g', 18).arg(_yaw, 0, 'g', 18); - // FORMAT: - // as documented here: http://qgroundcontrol.org/waypoint_protocol - saveStream << this->getId() << "\t" << this->getCurrent() << "\t" << this->getFrame() << "\t" << this->getAction() << "\t" << parameters << "\t" << position << "\t" << this->getAutoContinue() << "\r\n"; //"\t" << this->getDescription() << "\r\n"; -} - -bool Waypoint::load(QTextStream &loadStream) -{ - const QStringList &wpParams = loadStream.readLine().split("\t"); - if (wpParams.size() == 12) { - _id = wpParams[0].toInt(); - _current = (wpParams[1].toInt() == 1 ? true : false); - _frame = (MAV_FRAME) wpParams[2].toInt(); - _action = (MAV_CMD) wpParams[3].toInt(); - _param1 = wpParams[4].toDouble(); - _param2 = wpParams[5].toDouble(); - _orbit = wpParams[6].toDouble(); - _yaw = wpParams[7].toDouble(); - _x = wpParams[8].toDouble(); - _y = wpParams[9].toDouble(); - _z = wpParams[10].toDouble(); - _autocontinue = (wpParams[11].toInt() == 1 ? true : false); - //_description = wpParams[12]; - return true; - } - return false; -} - - -void Waypoint::setId(quint16 id) -{ - _id = id; - _name = QString("WP%1").arg(id, 2, 10, QChar('0')); - emit changed(this); -} - -void Waypoint::setX(double x) -{ - if (!isinf(x) && !isnan(x) && ((_frame == MAV_FRAME_LOCAL_NED) || (_frame == MAV_FRAME_LOCAL_ENU))) - { - _x = x; - emit changed(this); - } -} - -void Waypoint::setY(double y) -{ - if (!isinf(y) && !isnan(y) && ((_frame == MAV_FRAME_LOCAL_NED) || (_frame == MAV_FRAME_LOCAL_ENU))) - { - _y = y; - emit changed(this); - } -} - -void Waypoint::setZ(double z) -{ - if (!isinf(z) && !isnan(z) && ((_frame == MAV_FRAME_LOCAL_NED) || (_frame == MAV_FRAME_LOCAL_ENU))) - { - _z = z; - emit changed(this); - } -} - -void Waypoint::setLatitude(double lat) -{ - if (_x != lat && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT))) - { - _x = lat; - emit changed(this); - } -} - -void Waypoint::setLongitude(double lon) -{ - if (_y != lon && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT))) - { - _y = lon; - emit changed(this); - } -} - -void Waypoint::setAltitude(double altitude) -{ - if (_z != altitude && ((_frame == MAV_FRAME_GLOBAL) || (_frame == MAV_FRAME_GLOBAL_RELATIVE_ALT))) - { - _z = altitude; - emit changed(this); - } -} - -void Waypoint::setYaw(int yaw) -{ - if (_yaw != yaw) - { - _yaw = yaw; - emit changed(this); - } -} - -void Waypoint::setYaw(double yaw) -{ - if (_yaw != yaw) - { - _yaw = yaw; - emit changed(this); - } -} - -void Waypoint::setAction(int /*MAV_CMD*/ action) -{ - if (_action != action) { - _action = action; - - // Flick defaults according to WP type - - if (_action == MAV_CMD_NAV_TAKEOFF) { - // We default to 15 degrees minimum takeoff pitch - _param1 = 15.0; - } - - emit changed(this); - emit typeChanged(type()); - } -} - -void Waypoint::setFrame(int /*MAV_FRAME*/ frame) -{ - if (_frame != frame) { - _frame = frame; - emit changed(this); - } -} - -void Waypoint::setAutocontinue(bool autoContinue) -{ - if (_autocontinue != autoContinue) { - _autocontinue = autoContinue; - emit changed(this); - } -} - -void Waypoint::setCurrent(bool current) -{ - if (_current != current) - { - _current = current; - // The current waypoint index is handled by the list - // and not part of the individual waypoint update state - } -} - -void Waypoint::setAcceptanceRadius(double radius) -{ - if (_param2 != radius) - { - _param2 = radius; - emit changed(this); - } -} - -void Waypoint::setParam1(double param1) -{ - //// // qDebug() << "SENDER:" << QObject::sender(); - //// // qDebug() << "PARAM1 SET REQ:" << param1; - if (_param1 != param1) - { - _param1 = param1; - emit changed(this); - } -} - -void Waypoint::setParam2(double param2) -{ - if (_param2 != param2) - { - _param2 = param2; - emit changed(this); - } -} - -void Waypoint::setParam3(double param3) -{ - if (_orbit != param3) { - _orbit = param3; - emit changed(this); - } -} - -void Waypoint::setParam4(double param4) -{ - if (_yaw != param4) { - _yaw = param4; - emit changed(this); - } -} - -void Waypoint::setParam5(double param5) -{ - if (_x != param5) { - _x = param5; - emit changed(this); - } -} - -void Waypoint::setParam6(double param6) -{ - if (_y != param6) { - _y = param6; - emit changed(this); - } -} - -void Waypoint::setParam7(double param7) -{ - if (_z != param7) { - _z = param7; - emit changed(this); - } -} - -void Waypoint::setLoiterOrbit(double orbit) -{ - if (_orbit != orbit) { - _orbit = orbit; - emit changed(this); - } -} - -void Waypoint::setHoldTime(int holdTime) -{ - if (_param1 != holdTime) { - _param1 = holdTime; - emit changed(this); - } -} - -void Waypoint::setHoldTime(double holdTime) -{ - if (_param1 != holdTime) { - _param1 = holdTime; - emit changed(this); - } -} - -void Waypoint::setTurns(int turns) -{ - if (_param1 != turns) { - _param1 = turns; - emit changed(this); - } -} - -QGeoCoordinate Waypoint::coordinate(void) -{ - return QGeoCoordinate(_x, _y); -} - -QString Waypoint::type(void) -{ - QString type; - - switch (_action) { - case MAV_CMD_NAV_WAYPOINT: - type = "Waypoint"; - break; - case MAV_CMD_NAV_LOITER_UNLIM: - case MAV_CMD_NAV_LOITER_TURNS: - case MAV_CMD_NAV_LOITER_TIME: - type = "Loiter"; - break; - case MAV_CMD_NAV_RETURN_TO_LAUNCH: - type = "Return To Launch"; - break; - case MAV_CMD_NAV_LAND: - type = "Land"; - break; - case MAV_CMD_NAV_TAKEOFF: - type = "Takeoff"; - break; - default: - type = QString("Unknown(%1)").arg(_action); - break; -#if 0 - // FIXME: NYI - MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate [ms^-1]| Desired yaw angle [rad]| Y-axis position [m]| X-axis position [m]| Z-axis / ground level position [m]| */ - MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]| Empty| Takeoff ascend rate [ms^-1]| Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position [m]| X-axis position [m]| Z-axis position [m]| */ - MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Empty| Empty| Empty| Empty| Empty| Empty| Desired altitude in meters| */ - MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Heading Required (0 = False)| Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_ALTITUDE_WAIT=83, /* Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. |altitude (m)| descent speed (m/s)| Wiggle Time (s)| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */ - MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ - MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ - MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ - MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable, 2=disable_floor_only)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOTOR_TEST=209, /* Mission command to perform motor test |motor sequence number (a number from 1 to max number of motors on the vehicle)| throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)| throttle| timeout (in seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_GRIPPER=211, /* Mission command to operate EPM gripper |gripper number (a number from 1 to max number of grippers on the vehicle)| gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_AUTOTUNE_ENABLE=212, /* Enable/disable autotune |enable (1: enable, 0:disable)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */ - MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */ - MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. |1: Trigger actuator ID assignment and direction mapping.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ - MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID| */ - MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.| */ - MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */ - MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence |Duration between two consecutive pictures (in seconds)| Number of images to capture total - 0 for unlimited capture| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ - MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence |Reserved| Reserved| */ - MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved| */ - MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture |Camera ID (0 for all cameras), 1 for first, 2 for second, etc.| Frames per second| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ - MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture |Reserved| Reserved| */ - MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */ - MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| */ - MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */ - MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ - MAV_CMD_DO_START_MAG_CAL=42424, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Automatically retry on failure (0=no retry, 1=retry).| Save without user input (0=require input, 1=autosave).| Delay (seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_ACCEPT_MAG_CAL=42425, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CANCEL_MAG_CAL=42426, /* Cancel a running magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */ -#endif - } - - return type; -} diff --git a/src/comm/MockLinkMissionItemHandler.cc b/src/comm/MockLinkMissionItemHandler.cc index 3591dd055a55a984b23b6c7ab3528787dcfb5c86..6e3a4abd3259698f031e04160b084e3f28f79951 100644 --- a/src/comm/MockLinkMissionItemHandler.cc +++ b/src/comm/MockLinkMissionItemHandler.cc @@ -832,7 +832,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t* mavlink_command_long_t action; mavlink_msg_command_long_decode(msg, &action); if(action.target_system == systemid) { - if (verbose) qDebug("Waypoint: received message with action %d\n", action.command); + if (verbose) qDebug("MissionItem: received message with action %d\n", action.command); // switch (action.action) { // case MAV_ACTION_LAUNCH: // if (verbose) std::cerr << "Launch received" << std::endl; @@ -1129,7 +1129,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t* } default: { - if (debug) qDebug("Waypoint: received message of unknown type\n"); + if (debug) qDebug("MissionItem: received message of unknown type\n"); break; } } diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 29c78b508ee3cefcaa323db8125943488148e0d7..977b3914e00e5019f23cc15040a460f0070749f1 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -751,7 +751,7 @@ public slots: /** @brief Launches the system **/ void launch(); /** @brief Write this waypoint to the list of waypoints */ - //void setWaypoint(Waypoint* wp); FIXME tbd + //void setWaypoint(MissionItem* wp); FIXME tbd /** @brief Set currently active waypoint */ //void setWaypointActive(int id); FIXME tbd /** @brief Order the robot to return home **/ diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 18ebcdfe6e1731391ce0f43f008098896dd7b697..6613e282cdea71a6657c29db4b90758c8da6beee 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -265,7 +265,7 @@ public slots: /** @brief Launches the system/Liftof **/ virtual void launch() = 0; /** @brief Set a new waypoint **/ - //virtual void setWaypoint(Waypoint* wp) = 0; + //virtual void setWaypoint(MissionItem* wp) = 0; /** @brief Set this waypoint as next waypoint to fly to */ //virtual void setWaypointActive(int wp) = 0; /** @brief Order the robot to return home / to land on the runway **/ diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc index 3622773040a59b5fcb59a467de86073737aa017a..548ca291628e0fee9e65f47310085924d368eb72 100644 --- a/src/uas/UASWaypointManager.cc +++ b/src/uas/UASWaypointManager.cc @@ -149,7 +149,7 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui //Clear the old edit-list before receiving the new one if (read_to_edit == true){ while(waypointsEditable.count()>0) { - Waypoint *t = waypointsEditable[0]; + MissionItem *t = waypointsEditable[0]; waypointsEditable.removeAt(0); delete t; } @@ -196,7 +196,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_ if(wp->seq == current_wp_id) { - Waypoint *lwp_vo = new Waypoint( + MissionItem *lwp_vo = new MissionItem( NULL, wp->seq, wp->x, wp->y, @@ -213,7 +213,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_ addWaypointViewOnly(lwp_vo); if (read_to_edit == true) { - Waypoint *lwp_ed = new Waypoint( + MissionItem *lwp_ed = new MissionItem( NULL, wp->seq, wp->x, @@ -252,13 +252,13 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_ } } else { - emit updateStatusString(tr("Waypoint ID mismatch, rejecting waypoint")); + emit updateStatusString(tr("MissionItem ID mismatch, rejecting waypoint")); } } else if (systemId == current_partner_systemid && wp->seq < waypointsViewOnly.size() && waypointsViewOnly[wp->seq]->getAction()) { // accept single sent waypoints because they can contain updates about remaining DO_JUMP repetitions // but only update view only side - Waypoint *lwp_vo = new Waypoint( + MissionItem *lwp_vo = new MissionItem( NULL, wp->seq, wp->x, @@ -400,7 +400,7 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m } } -void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp) +void UASWaypointManager::notifyOfChangeEditable(MissionItem* wp) { // If only one waypoint was changed, emit only WP signal if (wp != NULL) { @@ -411,7 +411,7 @@ void UASWaypointManager::notifyOfChangeEditable(Waypoint* wp) } } -void UASWaypointManager::notifyOfChangeViewOnly(Waypoint* wp) +void UASWaypointManager::notifyOfChangeViewOnly(MissionItem* wp) { if (wp != NULL) { emit waypointViewOnlyChanged(uasid, wp); @@ -463,12 +463,12 @@ int UASWaypointManager::setCurrentEditable(quint16 seq) return -1; } -void UASWaypointManager::addWaypointViewOnly(Waypoint *wp) +void UASWaypointManager::addWaypointViewOnly(MissionItem *wp) { if (wp) { waypointsViewOnly.insert(waypointsViewOnly.size(), wp); - connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeViewOnly(Waypoint*))); + connect(wp, SIGNAL(changed(MissionItem*)), this, SLOT(notifyOfChangeViewOnly(MissionItem*))); emit waypointViewOnlyListChanged(); emit waypointViewOnlyListChanged(uasid); @@ -481,13 +481,13 @@ void UASWaypointManager::addWaypointViewOnly(Waypoint *wp) * @param enforceFirstActive Enforces that the first waypoint is set as active * @see createWaypoint() is more suitable for most use cases */ -void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActive) +void UASWaypointManager::addWaypointEditable(MissionItem *wp, bool enforceFirstActive) { if (wp) { // Check if this is the first waypoint in an offline list if (waypointsEditable.count() == 0 && _vehicle == NULL) { - QGCMessageBox::critical(tr("Waypoint Manager"), _offlineEditingModeMessage); + QGCMessageBox::critical(tr("MissionItem Manager"), _offlineEditingModeMessage); } wp->setId(waypointsEditable.count()); @@ -497,7 +497,7 @@ void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActi currentWaypointEditable = wp; } waypointsEditable.insert(waypointsEditable.count(), wp); - connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*))); + connect(wp, SIGNAL(changed(MissionItem*)), this, SLOT(notifyOfChangeEditable(MissionItem*))); emit waypointEditableListChanged(); emit waypointEditableListChanged(uasid); @@ -507,14 +507,14 @@ void UASWaypointManager::addWaypointEditable(Waypoint *wp, bool enforceFirstActi /** * @param enforceFirstActive Enforces that the first waypoint is set as active */ -Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive) +MissionItem* UASWaypointManager::createWaypoint(bool enforceFirstActive) { // Check if this is the first waypoint in an offline list if (waypointsEditable.count() == 0 && _vehicle == NULL) { - QGCMessageBox::critical(tr("Waypoint Manager"), _offlineEditingModeMessage); + QGCMessageBox::critical(tr("MissionItem Manager"), _offlineEditingModeMessage); } - Waypoint* wp = new Waypoint(); + MissionItem* wp = new MissionItem(); wp->setId(waypointsEditable.count()); wp->setFrame((MAV_FRAME)getFrameRecommendation()); wp->setAltitude(getAltitudeRecommendation()); @@ -525,7 +525,7 @@ Waypoint* UASWaypointManager::createWaypoint(bool enforceFirstActive) currentWaypointEditable = wp; } waypointsEditable.append(wp); - connect(wp, SIGNAL(changed(Waypoint*)), this, SLOT(notifyOfChangeEditable(Waypoint*))); + connect(wp, SIGNAL(changed(MissionItem*)), this, SLOT(notifyOfChangeEditable(MissionItem*))); emit waypointEditableListChanged(); emit waypointEditableListChanged(uasid); @@ -536,7 +536,7 @@ int UASWaypointManager::removeWaypoint(quint16 seq) { if (seq < waypointsEditable.count()) { - Waypoint *t = waypointsEditable[seq]; + MissionItem *t = waypointsEditable[seq]; if (t->getCurrent() == true) //trying to remove the current waypoint { @@ -570,7 +570,7 @@ void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq) { if (cur_seq != new_seq && cur_seq < waypointsEditable.count() && new_seq < waypointsEditable.count()) { - Waypoint *t = waypointsEditable[cur_seq]; + MissionItem *t = waypointsEditable[cur_seq]; if (cur_seq < new_seq) { for (int i = cur_seq; i < new_seq; i++) { @@ -620,7 +620,7 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile) return; while(waypointsEditable.count()>0) { - Waypoint *t = waypointsEditable[0]; + MissionItem *t = waypointsEditable[0]; waypointsEditable.removeAt(0); delete t; } @@ -637,7 +637,7 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile) { while (!in.atEnd()) { - Waypoint *t = new Waypoint(); + MissionItem *t = new MissionItem(); if(t->load(in)) { //Use the existing function to add waypoints to the map instead of doing it manually @@ -677,13 +677,13 @@ void UASWaypointManager::clearWaypointList() } } -const QList UASWaypointManager::getGlobalFrameWaypointList() +const QList UASWaypointManager::getGlobalFrameWaypointList() { // TODO Keep this global frame list up to date // with complete waypoint list // instead of filtering on each request - QList wps; - foreach (Waypoint* wp, waypointsEditable) + QList wps; + foreach (MissionItem* wp, waypointsEditable) { if (wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) { @@ -693,13 +693,13 @@ const QList UASWaypointManager::getGlobalFrameWaypointList() return wps; } -const QList UASWaypointManager::getGlobalFrameAndNavTypeWaypointList() +const QList UASWaypointManager::getGlobalFrameAndNavTypeWaypointList() { // TODO Keep this global frame list up to date // with complete waypoint list // instead of filtering on each request - QList wps; - foreach (Waypoint* wp, waypointsEditable) + QList wps; + foreach (MissionItem* wp, waypointsEditable) { if ((wp->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && wp->isNavigationType()) { @@ -709,13 +709,13 @@ const QList UASWaypointManager::getGlobalFrameAndNavTypeWaypointList return wps; } -const QList UASWaypointManager::getNavTypeWaypointList() +const QList UASWaypointManager::getNavTypeWaypointList() { // TODO Keep this global frame list up to date // with complete waypoint list // instead of filtering on each request - QList wps; - foreach (Waypoint* wp, waypointsEditable) + QList wps; + foreach (MissionItem* wp, waypointsEditable) { if (wp->isNavigationType()) { @@ -725,17 +725,17 @@ const QList UASWaypointManager::getNavTypeWaypointList() return wps; } -int UASWaypointManager::getIndexOf(Waypoint* wp) +int UASWaypointManager::getIndexOf(MissionItem* wp) { return waypointsEditable.indexOf(wp); } -int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp) +int UASWaypointManager::getGlobalFrameIndexOf(MissionItem* wp) { // Search through all waypointsEditable, // counting only those in global frame int i = 0; - foreach (Waypoint* p, waypointsEditable) { + foreach (MissionItem* p, waypointsEditable) { if (p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) { if (p == wp) @@ -749,12 +749,12 @@ int UASWaypointManager::getGlobalFrameIndexOf(Waypoint* wp) return -1; } -int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(Waypoint* wp) +int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(MissionItem* wp) { // Search through all waypointsEditable, // counting only those in global frame int i = 0; - foreach (Waypoint* p, waypointsEditable) { + foreach (MissionItem* p, waypointsEditable) { if ((p->getFrame() == MAV_FRAME_GLOBAL || wp->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType()) { if (p == wp) @@ -768,12 +768,12 @@ int UASWaypointManager::getGlobalFrameAndNavTypeIndexOf(Waypoint* wp) return -1; } -int UASWaypointManager::getNavTypeIndexOf(Waypoint* wp) +int UASWaypointManager::getNavTypeIndexOf(MissionItem* wp) { // Search through all waypointsEditable, // counting only those in global frame int i = 0; - foreach (Waypoint* p, waypointsEditable) + foreach (MissionItem* p, waypointsEditable) { if (p->isNavigationType()) { @@ -793,7 +793,7 @@ int UASWaypointManager::getGlobalFrameCount() // Search through all waypointsEditable, // counting only those in global frame int i = 0; - foreach (Waypoint* p, waypointsEditable) + foreach (MissionItem* p, waypointsEditable) { if (p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) { @@ -809,7 +809,7 @@ int UASWaypointManager::getGlobalFrameAndNavTypeCount() // Search through all waypointsEditable, // counting only those in global frame int i = 0; - foreach (Waypoint* p, waypointsEditable) { + foreach (MissionItem* p, waypointsEditable) { if ((p->getFrame() == MAV_FRAME_GLOBAL || p->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT) && p->isNavigationType()) { i++; @@ -824,7 +824,7 @@ int UASWaypointManager::getNavTypeCount() // Search through all waypointsEditable, // counting only those in global frame int i = 0; - foreach (Waypoint* p, waypointsEditable) { + foreach (MissionItem* p, waypointsEditable) { if (p->isNavigationType()) { i++; } @@ -838,7 +838,7 @@ int UASWaypointManager::getLocalFrameCount() // Search through all waypointsEditable, // counting only those in global frame int i = 0; - foreach (Waypoint* p, waypointsEditable) + foreach (MissionItem* p, waypointsEditable) { if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU) { @@ -849,12 +849,12 @@ int UASWaypointManager::getLocalFrameCount() return i; } -int UASWaypointManager::getLocalFrameIndexOf(Waypoint* wp) +int UASWaypointManager::getLocalFrameIndexOf(MissionItem* wp) { // Search through all waypointsEditable, // counting only those in local frame int i = 0; - foreach (Waypoint* p, waypointsEditable) + foreach (MissionItem* p, waypointsEditable) { if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU) { @@ -869,12 +869,12 @@ int UASWaypointManager::getLocalFrameIndexOf(Waypoint* wp) return -1; } -int UASWaypointManager::getMissionFrameIndexOf(Waypoint* wp) +int UASWaypointManager::getMissionFrameIndexOf(MissionItem* wp) { // Search through all waypointsEditable, // counting only those in mission frame int i = 0; - foreach (Waypoint* p, waypointsEditable) + foreach (MissionItem* p, waypointsEditable) { if (p->getFrame() == MAV_FRAME_MISSION) { @@ -902,7 +902,7 @@ void UASWaypointManager::readWaypoints(bool readToEdit) //Clear the old view-list before receiving the new one while(waypointsViewOnly.size()>0) { - Waypoint *t = waypointsViewOnly[0]; + MissionItem *t = waypointsViewOnly[0]; waypointsViewOnly.removeAt(0); delete t; } @@ -911,7 +911,7 @@ void UASWaypointManager::readWaypoints(bool readToEdit) //Clear the old edit-list before receiving the new one if (read_to_edit == true){ while(waypointsEditable.count()>0) { - Waypoint *t = waypointsEditable[0]; + MissionItem *t = waypointsEditable[0]; waypointsEditable.remove(0); delete t; } @@ -938,14 +938,14 @@ bool UASWaypointManager::guidedModeSupported() return (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA); } -void UASWaypointManager::goToWaypoint(Waypoint *wp) +void UASWaypointManager::goToWaypoint(MissionItem *wp) { //Don't try to send a guided mode message to an AP that does not support it. if (_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) { mavlink_mission_item_t mission; memset(&mission, 0, sizeof(mavlink_mission_item_t)); //initialize with zeros - //const Waypoint *cur_s = waypointsEditable.at(i); + //const MissionItem *cur_s = waypointsEditable.at(i); mission.autocontinue = 0; mission.current = 2; //2 for guided mode @@ -998,7 +998,7 @@ void UASWaypointManager::writeWaypoints() waypoint_buffer.push_back(new mavlink_mission_item_t); mavlink_mission_item_t *cur_d = waypoint_buffer.back(); memset(cur_d, 0, sizeof(mavlink_mission_item_t)); //initialize with zeros - const Waypoint *cur_s = waypointsEditable.at(i); + const MissionItem *cur_s = waypointsEditable.at(i); cur_d->autocontinue = cur_s->getAutoContinue(); cur_d->current = cur_s->getCurrent() & noCurrent; //make sure only one current waypoint is selected, the first selected will be chosen diff --git a/src/uas/UASWaypointManager.h b/src/uas/UASWaypointManager.h index 5a81186f3a4a977286052e69ba02990b53c8a336..42739dc1fe891c7119db81803757e10de8ea496d 100644 --- a/src/uas/UASWaypointManager.h +++ b/src/uas/UASWaypointManager.h @@ -36,7 +36,7 @@ This file is part of the QGROUNDCONTROL project #include #include #include -#include "Waypoint.h" +#include "MissionItem.h" #include "QGCMAVLink.h" class UAS; @@ -71,7 +71,7 @@ public: ~UASWaypointManager(); bool guidedModeSupported(); - void goToWaypoint(Waypoint *wp); + void goToWaypoint(MissionItem *wp); /** @name Received message handlers */ /*@{*/ void handleWaypointCount(quint8 systemId, quint8 compId, quint16 count); ///< Handles received waypoint count messages @@ -92,23 +92,23 @@ public: int setCurrentEditable(quint16 seq); ///< Changes the current waypoint in edit tab /*@}*/ - /** @name Waypoint list operations */ + /** @name MissionItem list operations */ /*@{*/ - const QList &getWaypointEditableList(void) { + const QList &getWaypointEditableList(void) { return waypointsEditable; ///< Returns a const reference to the waypoint list. } - const QList &getWaypointViewOnlyList(void) { + const QList &getWaypointViewOnlyList(void) { return waypointsViewOnly; ///< Returns a const reference to the waypoint list. } - const QList getGlobalFrameWaypointList(); ///< Returns a global waypoint list - const QList getGlobalFrameAndNavTypeWaypointList(); ///< Returns a global waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out. - const QList getNavTypeWaypointList(); ///< Returns a waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out. - int getIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list - int getGlobalFrameIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list, counting only global waypoints - int getGlobalFrameAndNavTypeIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list, counting only global AND navigation mode waypoints - int getNavTypeIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list, counting only navigation mode waypoints - int getLocalFrameIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list, counting only local waypoints - int getMissionFrameIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list, counting only mission waypoints + const QList getGlobalFrameWaypointList(); ///< Returns a global waypoint list + const QList getGlobalFrameAndNavTypeWaypointList(); ///< Returns a global waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out. + const QList getNavTypeWaypointList(); ///< Returns a waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out. + int getIndexOf(MissionItem* wp); ///< Get the index of a waypoint in the list + int getGlobalFrameIndexOf(MissionItem* wp); ///< Get the index of a waypoint in the list, counting only global waypoints + int getGlobalFrameAndNavTypeIndexOf(MissionItem* wp); ///< Get the index of a waypoint in the list, counting only global AND navigation mode waypoints + int getNavTypeIndexOf(MissionItem* wp); ///< Get the index of a waypoint in the list, counting only navigation mode waypoints + int getLocalFrameIndexOf(MissionItem* wp); ///< Get the index of a waypoint in the list, counting only local waypoints + int getMissionFrameIndexOf(MissionItem* wp); ///< Get the index of a waypoint in the list, counting only mission waypoints int getGlobalFrameCount(); ///< Get the count of global waypoints in the list int getGlobalFrameAndNavTypeCount(); ///< Get the count of global waypoints in navigation mode in the list int getNavTypeCount(); ///< Get the count of global waypoints in navigation mode in the list @@ -135,17 +135,17 @@ private: public slots: void timeout(); ///< Called by the timer if a response times out. Handles send retries. - /** @name Waypoint list operations */ + /** @name MissionItem list operations */ /*@{*/ - void addWaypointEditable(Waypoint *wp, bool enforceFirstActive=true); ///< adds a new waypoint to the end of the editable list and changes its sequence number accordingly - void addWaypointViewOnly(Waypoint *wp); ///< adds a new waypoint to the end of the view-only list and changes its sequence number accordingly - Waypoint* createWaypoint(bool enforceFirstActive=true); ///< Creates a waypoint + void addWaypointEditable(MissionItem *wp, bool enforceFirstActive=true); ///< adds a new waypoint to the end of the editable list and changes its sequence number accordingly + void addWaypointViewOnly(MissionItem *wp); ///< adds a new waypoint to the end of the view-only list and changes its sequence number accordingly + MissionItem* createWaypoint(bool enforceFirstActive=true); ///< Creates a waypoint int removeWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage void moveWaypoint(quint16 cur_seq, quint16 new_seq); ///< locally move a waypoint from its current position cur_seq to a new position new_seq void saveWaypoints(const QString &saveFile); ///< saves the local waypoint list to saveFile void loadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile - void notifyOfChangeEditable(Waypoint* wp); ///< Notifies manager to changes to an editable waypoint - void notifyOfChangeViewOnly(Waypoint* wp); ///< Notifies manager to changes to a viewonly waypoint, e.g. some widget wants to change "current" + void notifyOfChangeEditable(MissionItem* wp); ///< Notifies manager to changes to an editable waypoint + void notifyOfChangeViewOnly(MissionItem* wp); ///< Notifies manager to changes to a viewonly waypoint, e.g. some widget wants to change "current" /*@}*/ void handleLocalPositionChanged(UASInterface* mav, double x, double y, double z, quint64 time); void handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double altAMSL, double altWGS84, quint64 time); @@ -153,10 +153,10 @@ public slots: signals: void waypointEditableListChanged(void); ///< emits signal that the list of editable waypoints has been changed void waypointEditableListChanged(int uasid); ///< emits signal that the list of editable waypoints has been changed - void waypointEditableChanged(int uasid, Waypoint* wp); ///< emits signal that a single editable waypoint has been changed + void waypointEditableChanged(int uasid, MissionItem* wp); ///< emits signal that a single editable waypoint has been changed void waypointViewOnlyListChanged(void); ///< emits signal that the list of editable waypoints has been changed void waypointViewOnlyListChanged(int uasid); ///< emits signal that the list of editable waypoints has been changed - void waypointViewOnlyChanged(int uasid, Waypoint* wp); ///< emits signal that a single editable waypoint has been changed + void waypointViewOnlyChanged(int uasid, MissionItem* wp); ///< emits signal that a single editable waypoint has been changed void currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number void updateStatusString(const QString &); ///< emits the current status string void waypointDistanceChanged(double distance); ///< Distance to next waypoint changed (in meters) @@ -182,9 +182,9 @@ private: quint8 current_partner_compid; ///< The current protocol communication target component bool read_to_edit; ///< If true, after readWaypoints() incoming waypoints will be copied both to "edit"-tab and "view"-tab. Otherwise, only to "view"-tab. - QList waypointsViewOnly; ///< local copy of current waypoint list on MAV - QList waypointsEditable; ///< local editable waypoint list - QPointer currentWaypointEditable; ///< The currently used waypoint + QList waypointsViewOnly; ///< local copy of current waypoint list on MAV + QList waypointsEditable; ///< local editable waypoint list + QPointer currentWaypointEditable; ///< The currently used waypoint QList waypoint_buffer; ///< buffer for waypoints during communication QTimer protocol_timer; ///< Timer to catch timeouts QTimer _updateWPlist_timer; ///< update WP list if modified by another instance onboard diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index 7f2b73dfe85d6eab4ac8a29e07cb4bc52fb0fcad..d0c25e21fe22040925799b529d57f9adc0577ecd 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -41,7 +41,7 @@ This file is part of the QGROUNDCONTROL project #include "HomePositionManager.h" #include "HSIDisplay.h" #include "QGC.h" -#include "Waypoint.h" +#include "MissionItem.h" #include "UASWaypointManager.h" #include #include "MAV2DIcon.h" @@ -1291,7 +1291,7 @@ void HSIDisplay::drawSetpointXYZYaw(float x, float y, float z, float yaw, const } } -void HSIDisplay::drawWaypoint(QPainter& painter, const QColor& color, float width, const Waypoint *w, const QPointF& p) +void HSIDisplay::drawWaypoint(QPainter& painter, const QColor& color, float width, const MissionItem *w, const QPointF& p) { painter.setBrush(Qt::NoBrush); @@ -1334,7 +1334,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter) if (uas) { // Grab all waypoints. - const QList& list = uas->getWaypointManager()->getWaypointEditableList(); + const QList& list = uas->getWaypointManager()->getWaypointEditableList(); const int numWaypoints = list.size(); // Do not work on empty lists @@ -1349,7 +1349,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter) QPointF lastWaypoint; for (int i = 0; i < numWaypoints; i++) { - const Waypoint *w = list.at(i); + const MissionItem *w = list.at(i); QPointF in; // Use local coordinates as-is. int frameRef = w->getFrame(); diff --git a/src/ui/HSIDisplay.h b/src/ui/HSIDisplay.h index 9080f16451b0b11bab83ed63dfe49ac8a7342013..c809c9e77107b0417a942e9f3e61fb01ea44e07f 100644 --- a/src/ui/HSIDisplay.h +++ b/src/ui/HSIDisplay.h @@ -200,7 +200,7 @@ protected slots: /** @brief Draw waypoints of this system */ void drawWaypoints(QPainter& painter); /** @brief Draw one waypoint */ - void drawWaypoint(QPainter& painter, const QColor& color, float width, const Waypoint *w, const QPointF& p); + void drawWaypoint(QPainter& painter, const QColor& color, float width, const MissionItem *w, const QPointF& p); /** @brief Draw the limiting safety area */ void drawSafetyArea(const QPointF &topLeft, const QPointF &bottomRight, const QColor &color, QPainter &painter); /** @brief Receive mouse clicks */ diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 8f9755e58fb7c386914a041e422180262f306c69..09545d01ca139b33aeee15d6ab6dff53a71aae70 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -441,14 +441,6 @@ void MainWindow::_buildPlanView(void) } } -void MainWindow::_buildExperimentalPlanView(void) -{ - if (!_experimentalPlanView) { - _experimentalPlanView = new QGCMapDisplay(this); - _experimentalPlanView->setVisible(false); - } -} - void MainWindow::_buildFlightView(void) { if (!_flightView) { @@ -725,7 +717,6 @@ void MainWindow::connectCommonActions() perspectives->addAction(_ui.actionSimulationView); perspectives->addAction(_ui.actionPlan); perspectives->addAction(_ui.actionSetup); - perspectives->addAction(_ui.actionExperimentalPlanView); perspectives->setExclusive(true); // Mark the right one as selected @@ -749,11 +740,6 @@ void MainWindow::connectCommonActions() _ui.actionPlan->setChecked(true); _ui.actionPlan->activate(QAction::Trigger); } - if (_currentView == VIEW_EXPERIMENTAL_PLAN) - { - _ui.actionExperimentalPlanView->setChecked(true); - _ui.actionExperimentalPlanView->activate(QAction::Trigger); - } if (_currentView == VIEW_SETUP) { _ui.actionSetup->setChecked(true); @@ -772,7 +758,6 @@ void MainWindow::connectCommonActions() connect(_ui.actionSimulationView, SIGNAL(triggered()), this, SLOT(loadSimulationView())); connect(_ui.actionAnalyze, SIGNAL(triggered()), this, SLOT(loadAnalyzeView())); connect(_ui.actionPlan, SIGNAL(triggered()), this, SLOT(loadPlanView())); - connect(_ui.actionExperimentalPlanView, SIGNAL(triggered()), this, SLOT(loadOldPlanView())); // Help Actions connect(_ui.actionOnline_Documentation, SIGNAL(triggered()), this, SLOT(showHelp())); @@ -926,12 +911,6 @@ void MainWindow::_loadCurrentViewState(void) defaultWidgets = "WAYPOINT_LIST_DOCKWIDGET"; break; - case VIEW_EXPERIMENTAL_PLAN: - _buildExperimentalPlanView(); - centerView = _experimentalPlanView; - defaultWidgets.clear(); - break; - case VIEW_SIMULATION: _buildSimView(); centerView = _simView; @@ -1034,17 +1013,6 @@ void MainWindow::loadPlanView() } } -void MainWindow::loadOldPlanView() -{ - if (_currentView != VIEW_EXPERIMENTAL_PLAN) - { - _storeCurrentViewState(); - _currentView = VIEW_EXPERIMENTAL_PLAN; - _ui.actionExperimentalPlanView->setChecked(true); - _loadCurrentViewState(); - } -} - void MainWindow::loadSetupView() { if (_currentView != VIEW_SETUP) diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 76e95adfeffef79f9b7e2683c5b0e2051d3bbb49..beb4286016d05d6bc791c8c86250e4ec77efdb05 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -143,8 +143,6 @@ public slots: void loadAnalyzeView(); /** @brief Load New (QtQuick) Map View (Mission) */ void loadPlanView(); - /** @brief Load Old (Qt Widget) Map View (Mission) */ - void loadOldPlanView(); /** @brief Manage Links */ void manageLinks(); @@ -215,7 +213,6 @@ protected: VIEW_SETUP, // Setup view. Used for initializing the system for operation. Includes UI for calibration, firmware updating/checking, and parameter modifcation. VIEW_UNUSED1, // Unused (don't remove, or it will screw up saved settigns indices) VIEW_UNUSED2, // Unused (don't remove, or it will screw up saved settigns indices) - VIEW_EXPERIMENTAL_PLAN, // Original (Qt Widget) Mission/Map/Plan view mode. Used for setting mission waypoints and high-level system commands. } VIEW_SECTIONS; /** @brief Catch window resize events */ @@ -293,7 +290,6 @@ private: // Center widgets QPointer _planView; - QPointer _experimentalPlanView; QPointer _flightView; QPointer _setupView; QPointer _analyzeView; @@ -322,7 +318,6 @@ private: QMap _mapDockWidget2Action; void _buildPlanView(void); - void _buildExperimentalPlanView(void); void _buildFlightView(void); void _buildSetupView(void); void _buildAnalyzeView(void); diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui index 1a74850e0a2816eb0a39faabb959ca6bd21ca899..951841bba6e9c16cccb34f73a67681c35fa9bcd8 100644 --- a/src/ui/MainWindow.ui +++ b/src/ui/MainWindow.ui @@ -243,11 +243,6 @@ Show Status Bar - - - Experimental Plan View - - diff --git a/src/ui/WaypointEditableView.cc b/src/ui/WaypointEditableView.cc index a965dbef2d760ddd783d03854e8695109e3bd229..3ceb42e05de9343534e69bae8ce99dad98d83988 100644 --- a/src/ui/WaypointEditableView.cc +++ b/src/ui/WaypointEditableView.cc @@ -36,7 +36,7 @@ #include "mission/QGCMissionOther.h" -WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : +WaypointEditableView::WaypointEditableView(MissionItem* wp, QWidget* parent) : QWidget(parent), wp(wp), viewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_DEFAULT), @@ -67,7 +67,7 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : // add actions - m_ui->comboBox_action->addItem(tr("NAV: Waypoint"),MAV_CMD_NAV_WAYPOINT); + m_ui->comboBox_action->addItem(tr("NAV: MissionItem"),MAV_CMD_NAV_WAYPOINT); m_ui->comboBox_action->addItem(tr("NAV: TakeOff"),MAV_CMD_NAV_TAKEOFF); m_ui->comboBox_action->addItem(tr("NAV: Loiter Unlim."),MAV_CMD_NAV_LOITER_UNLIM); m_ui->comboBox_action->addItem(tr("NAV: Loiter Time"),MAV_CMD_NAV_LOITER_TIME); diff --git a/src/ui/WaypointEditableView.h b/src/ui/WaypointEditableView.h index 362cc694de1f96582ee75c667bc3945d5aa0b179..efd8685e08beeaaf60aa51e8d1292e154d992711 100644 --- a/src/ui/WaypointEditableView.h +++ b/src/ui/WaypointEditableView.h @@ -34,7 +34,7 @@ This file is part of the QGROUNDCONTROL project #define WAYPOINTEDITABLEVIEW_H #include -#include "Waypoint.h" +#include "MissionItem.h" #include enum QGC_WAYPOINTEDITABLEVIEW_MODE { @@ -65,7 +65,7 @@ class WaypointEditableView : public QWidget Q_OBJECT Q_DISABLE_COPY(WaypointEditableView) public: - explicit WaypointEditableView(Waypoint* wp, QWidget* parent); + explicit WaypointEditableView(MissionItem* wp, QWidget* parent); virtual ~WaypointEditableView(); public: @@ -75,7 +75,7 @@ public slots: void moveUp(); void moveDown(); void remove(); - /** @brief Waypoint matching this widget has been deleted */ + /** @brief MissionItem matching this widget has been deleted */ void deleted(QObject* waypoint); void changedAutoContinue(int); void changedFrame(int state); @@ -99,7 +99,7 @@ protected slots: protected: virtual void changeEvent(QEvent *e); virtual void paintEvent(QPaintEvent *); - Waypoint* wp; + MissionItem* wp; QGC_WAYPOINTEDITABLEVIEW_MODE viewMode; // Widgets for every mission element QGCMissionNavWaypoint* MissionNavWaypointWidget; @@ -121,9 +121,9 @@ private: Ui::WaypointEditableView *m_ui; signals: - void moveUpWaypoint(Waypoint*); - void moveDownWaypoint(Waypoint*); - void removeWaypoint(Waypoint*); + void moveUpWaypoint(MissionItem*); + void moveDownWaypoint(MissionItem*); + void removeWaypoint(MissionItem*); void changeCurrentWaypoint(quint16); void setYaw(double); diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc index 5337c725f97b14aa3584cd82700487d793951497..c7f7a9a3b7e9ce2d5251927aebdfb2a8e716779f 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -124,9 +124,9 @@ WaypointList::WaypointList(QWidget *parent, UASWaypointManager* wpm) : /* connect slots */ connect(WPM, SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &))); connect(WPM, SIGNAL(waypointEditableListChanged(void)), this, SLOT(waypointEditableListChanged(void))); - connect(WPM, SIGNAL(waypointEditableChanged(int,Waypoint*)), this, SLOT(updateWaypointEditable(int,Waypoint*))); + connect(WPM, SIGNAL(waypointEditableChanged(int,MissionItem*)), this, SLOT(updateWaypointEditable(int,MissionItem*))); connect(WPM, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(waypointViewOnlyListChanged(void))); - connect(WPM, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)), this, SLOT(updateWaypointViewOnly(int,Waypoint*))); + connect(WPM, SIGNAL(waypointViewOnlyChanged(int,MissionItem*)), this, SLOT(updateWaypointViewOnly(int,MissionItem*))); connect(WPM, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointViewOnlyChanged(quint16))); //Even if there are no waypoints, since this is a new instance and there is an @@ -181,9 +181,9 @@ void WaypointList::setUAS(UASInterface* uas) // Disconnect everything disconnect(WPM, SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &))); disconnect(WPM, SIGNAL(waypointEditableListChanged(void)), this, SLOT(waypointEditableListChanged(void))); - disconnect(WPM, SIGNAL(waypointEditableChanged(int,Waypoint*)), this, SLOT(updateWaypointEditable(int,Waypoint*))); + disconnect(WPM, SIGNAL(waypointEditableChanged(int,MissionItem*)), this, SLOT(updateWaypointEditable(int,MissionItem*))); disconnect(WPM, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(waypointViewOnlyListChanged(void))); - disconnect(WPM, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)), this, SLOT(updateWaypointViewOnly(int,Waypoint*))); + disconnect(WPM, SIGNAL(waypointViewOnlyChanged(int,MissionItem*)), this, SLOT(updateWaypointViewOnly(int,MissionItem*))); disconnect(WPM, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointViewOnlyChanged(quint16))); disconnect(this->uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updatePosition(UASInterface*,double,double,double,quint64))); disconnect(this->uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64))); @@ -200,9 +200,9 @@ void WaypointList::setUAS(UASInterface* uas) this->uas = uas; connect(WPM, SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &))); connect(WPM, SIGNAL(waypointEditableListChanged(void)), this, SLOT(waypointEditableListChanged(void))); - connect(WPM, SIGNAL(waypointEditableChanged(int,Waypoint*)), this, SLOT(updateWaypointEditable(int,Waypoint*))); + connect(WPM, SIGNAL(waypointEditableChanged(int,MissionItem*)), this, SLOT(updateWaypointEditable(int,MissionItem*))); connect(WPM, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(waypointViewOnlyListChanged(void))); - connect(WPM, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)), this, SLOT(updateWaypointViewOnly(int,Waypoint*))); + connect(WPM, SIGNAL(waypointViewOnlyChanged(int,MissionItem*)), this, SLOT(updateWaypointViewOnly(int,MissionItem*))); connect(WPM, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointViewOnlyChanged(quint16))); connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updatePosition(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64))); @@ -259,13 +259,13 @@ void WaypointList::addEditable() void WaypointList::addEditable(bool onCurrentPosition) { - const QList &waypoints = WPM->getWaypointEditableList(); - Waypoint *wp; + const QList &waypoints = WPM->getWaypointEditableList(); + MissionItem *wp; if (waypoints.count() > 0 && !(onCurrentPosition && uas && (uas->localPositionKnown() || uas->globalPositionKnown()))) { // Create waypoint with last frame - Waypoint *last = waypoints.last(); + MissionItem *last = waypoints.last(); wp = WPM->createWaypoint(); // wp->blockSignals(true); MAV_FRAME frame = (MAV_FRAME)last->getFrame(); @@ -304,7 +304,7 @@ void WaypointList::addEditable(bool onCurrentPosition) } else { updateStatusLabel(tr("Added default GLOBAL (Relative alt.) waypoint.")); } - wp = new Waypoint(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitudeAMSL(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT); + wp = new MissionItem(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitudeAMSL(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT); WPM->addWaypointEditable(wp); } else { @@ -314,7 +314,7 @@ void WaypointList::addEditable(bool onCurrentPosition) } else { updateStatusLabel(tr("Added default GLOBAL (Relative alt.) waypoint.")); } - wp = new Waypoint(0, HomePositionManager::instance()->getHomeLatitude(), + wp = new MissionItem(0, HomePositionManager::instance()->getHomeLatitude(), HomePositionManager::instance()->getHomeLongitude(), WPM->getAltitudeRecommendation(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT); WPM->addWaypointEditable(wp); @@ -325,11 +325,11 @@ void WaypointList::addEditable(bool onCurrentPosition) if (onCurrentPosition) { updateStatusLabel(tr("Added default LOCAL (NED) waypoint.")); - wp = new Waypoint(0, uas->getLocalX(), uas->getLocalY(), uas->getLocalZ(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT); + wp = new MissionItem(0, uas->getLocalX(), uas->getLocalY(), uas->getLocalZ(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT); WPM->addWaypointEditable(wp); } else { updateStatusLabel(tr("Added default LOCAL (NED) waypoint.")); - wp = new Waypoint(0, 0, 0, -0.50, 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT); + wp = new MissionItem(0, 0, 0, -0.50, 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT); WPM->addWaypointEditable(wp); } } @@ -337,7 +337,7 @@ void WaypointList::addEditable(bool onCurrentPosition) { // MAV connected, but position unknown, add default waypoint updateStatusLabel(tr("WARNING: No position known. Adding default LOCAL (NED) waypoint")); - wp = new Waypoint(0, HomePositionManager::instance()->getHomeLatitude(), + wp = new MissionItem(0, HomePositionManager::instance()->getHomeLatitude(), HomePositionManager::instance()->getHomeLongitude(), WPM->getAltitudeRecommendation(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT); WPM->addWaypointEditable(wp); @@ -347,7 +347,7 @@ void WaypointList::addEditable(bool onCurrentPosition) { //Since no UAV available, create first default waypoint. updateStatusLabel(tr("No UAV connected. Adding default GLOBAL (NED) waypoint")); - wp = new Waypoint(0, HomePositionManager::instance()->getHomeLatitude(), + wp = new MissionItem(0, HomePositionManager::instance()->getHomeLatitude(), HomePositionManager::instance()->getHomeLongitude(), WPM->getAltitudeRecommendation(), 0, WPM->getAcceptanceRadiusRecommendation(), 0, 0,true, true, (MAV_FRAME)WPM->getFrameRecommendation(), MAV_CMD_NAV_WAYPOINT); WPM->addWaypointEditable(wp); @@ -380,7 +380,7 @@ void WaypointList::changeCurrentWaypoint(quint16 seq) void WaypointList::currentWaypointEditableChanged(quint16 seq) { WPM->setCurrentEditable(seq); - const QList waypoints = WPM->getWaypointEditableList(); + const QList waypoints = WPM->getWaypointEditableList(); if (seq < waypoints.count()) { @@ -408,7 +408,7 @@ void WaypointList::currentWaypointViewOnlyChanged(quint16 seq) // First update the edit list currentWaypointEditableChanged(seq); - const QList waypoints = WPM->getWaypointViewOnlyList(); + const QList waypoints = WPM->getWaypointViewOnlyList(); if (seq < waypoints.count()) { @@ -430,7 +430,7 @@ void WaypointList::currentWaypointViewOnlyChanged(quint16 seq) } } -void WaypointList::updateWaypointEditable(int uas, Waypoint* wp) +void WaypointList::updateWaypointEditable(int uas, MissionItem* wp) { Q_UNUSED(uas); WaypointEditableView *wpv = wpEditableViews.value(wp, NULL); @@ -440,7 +440,7 @@ void WaypointList::updateWaypointEditable(int uas, Waypoint* wp) m_ui->tabWidget->setCurrentIndex(0); // XXX magic number } -void WaypointList::updateWaypointViewOnly(int uas, Waypoint* wp) +void WaypointList::updateWaypointViewOnly(int uas, MissionItem* wp) { Q_UNUSED(uas); WaypointViewOnlyView *wpv = wpViewOnlyViews.value(wp, NULL); @@ -454,14 +454,14 @@ void WaypointList::waypointViewOnlyListChanged() { // Prevent updates to prevent visual flicker this->setUpdatesEnabled(false); - const QList &waypoints = WPM->getWaypointViewOnlyList(); + const QList &waypoints = WPM->getWaypointViewOnlyList(); if (!wpViewOnlyViews.empty()) { - QMapIterator viewIt(wpViewOnlyViews); + QMapIterator viewIt(wpViewOnlyViews); viewIt.toFront(); while(viewIt.hasNext()) { viewIt.next(); - Waypoint *cur = viewIt.key(); + MissionItem *cur = viewIt.key(); int i; for (i = 0; i < waypoints.count(); i++) { if (waypoints[i] == cur) { @@ -481,7 +481,7 @@ void WaypointList::waypointViewOnlyListChanged() // then add/update the views for each waypoint in the list for(int i = 0; i < waypoints.count(); i++) { - Waypoint *wp = waypoints[i]; + MissionItem *wp = waypoints[i]; if (!wpViewOnlyViews.contains(wp)) { WaypointViewOnlyView* wpview = new WaypointViewOnlyView(wp, this); wpViewOnlyViews.insert(wp, wpview); @@ -510,14 +510,14 @@ void WaypointList::waypointEditableListChanged() { // Prevent updates to prevent visual flicker this->setUpdatesEnabled(false); - const QList &waypoints = WPM->getWaypointEditableList(); + const QList &waypoints = WPM->getWaypointEditableList(); if (!wpEditableViews.empty()) { - QMapIterator viewIt(wpEditableViews); + QMapIterator viewIt(wpEditableViews); viewIt.toFront(); while(viewIt.hasNext()) { viewIt.next(); - Waypoint *cur = viewIt.key(); + MissionItem *cur = viewIt.key(); int i; for (i = 0; i < waypoints.count(); i++) { if (waypoints[i] == cur) { @@ -538,13 +538,13 @@ void WaypointList::waypointEditableListChanged() // then add/update the views for each waypoint in the list for(int i = 0; i < waypoints.count(); i++) { - Waypoint *wp = waypoints[i]; + MissionItem *wp = waypoints[i]; if (!wpEditableViews.contains(wp)) { WaypointEditableView* wpview = new WaypointEditableView(wp, this); wpEditableViews.insert(wp, wpview); - connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*))); - connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*))); - connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*))); + connect(wpview, SIGNAL(moveDownWaypoint(MissionItem*)), this, SLOT(moveDown(MissionItem*))); + connect(wpview, SIGNAL(moveUpWaypoint(MissionItem*)), this, SLOT(moveUp(MissionItem*))); + connect(wpview, SIGNAL(removeWaypoint(MissionItem*)), this, SLOT(removeWaypoint(MissionItem*))); //connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16))); connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(currentWaypointEditableChanged(quint16))); editableListLayout->insertWidget(i, wpview); @@ -564,9 +564,9 @@ void WaypointList::waypointEditableListChanged() } -void WaypointList::moveUp(Waypoint* wp) +void WaypointList::moveUp(MissionItem* wp) { - const QList &waypoints = WPM->getWaypointEditableList(); + const QList &waypoints = WPM->getWaypointEditableList(); //get the current position of wp in the local storage int i; @@ -581,9 +581,9 @@ void WaypointList::moveUp(Waypoint* wp) } } -void WaypointList::moveDown(Waypoint* wp) +void WaypointList::moveDown(MissionItem* wp) { - const QList &waypoints = WPM->getWaypointEditableList(); + const QList &waypoints = WPM->getWaypointEditableList(); //get the current position of wp in the local storage int i; @@ -598,7 +598,7 @@ void WaypointList::moveDown(Waypoint* wp) } } -void WaypointList::removeWaypoint(Waypoint* wp) +void WaypointList::removeWaypoint(MissionItem* wp) { WPM->removeWaypoint(wp->getId()); } @@ -620,7 +620,7 @@ void WaypointList::on_clearWPListButton_clicked() { if (uas) { emit clearPathclicked(); - const QList &waypoints = WPM->getWaypointEditableList(); + const QList &waypoints = WPM->getWaypointEditableList(); while(!waypoints.isEmpty()) { WaypointEditableView* widget = wpEditableViews.value(waypoints[0], NULL); if (widget) { @@ -633,7 +633,7 @@ void WaypointList::on_clearWPListButton_clicked() void WaypointList::clearWPWidget() { // Get list - const QList waypoints = WPM->getWaypointEditableList(); + const QList waypoints = WPM->getWaypointEditableList(); // XXX delete wps as well diff --git a/src/ui/WaypointList.h b/src/ui/WaypointList.h index 4f6fbf8223567b8b73ed36c72f27e83d815ed631..e20f23403ae97f5fa58080b69e842b7daa04d053 100644 --- a/src/ui/WaypointList.h +++ b/src/ui/WaypointList.h @@ -38,7 +38,7 @@ This file is part of the QGROUNDCONTROL project #include #include #include -#include "Waypoint.h" +#include "MissionItem.h" #include "UASInterface.h" #include "WaypointEditableView.h" #include "WaypointViewOnlyView.h" @@ -62,7 +62,7 @@ public slots: void setUAS(UASInterface* uas); - //Waypoint list operations + //MissionItem list operations /** @brief Save the local waypoint list to a file */ void saveWaypoints(); /** @brief Load a waypoint list from a file */ @@ -91,9 +91,9 @@ public slots: /** @brief Current waypoint on UAV was changed, update view-tab */ void currentWaypointViewOnlyChanged(quint16 seq); /** @brief The waypoint manager informs that one editable waypoint was changed */ - void updateWaypointEditable(int uas, Waypoint* wp); + void updateWaypointEditable(int uas, MissionItem* wp); /** @brief The waypoint manager informs that one viewonly waypoint was changed */ - void updateWaypointViewOnly(int uas, Waypoint* wp); + void updateWaypointViewOnly(int uas, MissionItem* wp); /** @brief The waypoint manager informs that the editable waypoint list was changed */ void waypointEditableListChanged(void); /** @brief The waypoint manager informs that the waypoint list on the MAV was changed */ @@ -104,12 +104,12 @@ public slots: void clearWPWidget(); - //void changeWPPositionBySpinBox(Waypoint* wp); + //void changeWPPositionBySpinBox(MissionItem* wp); - // Waypoint operations - void moveUp(Waypoint* wp); - void moveDown(Waypoint* wp); - void removeWaypoint(Waypoint* wp); + // MissionItem operations + void moveUp(MissionItem* wp); + void moveDown(MissionItem* wp); + void removeWaypoint(MissionItem* wp); // void setIsLoadFileWP(); // void setIsReadGlobalWP(bool value); @@ -125,8 +125,8 @@ protected: virtual void changeEvent(QEvent *e); protected: - QMap wpEditableViews; - QMap wpViewOnlyViews; + QMap wpEditableViews; + QMap wpViewOnlyViews; QVBoxLayout* viewOnlyListLayout; QVBoxLayout* editableListLayout; UASInterface* uas; diff --git a/src/ui/WaypointViewOnlyView.cc b/src/ui/WaypointViewOnlyView.cc index 5c4d94d402811b08b1abedea1a2bb3a29844553a..2beb63be10ead32c04498613254b4b058f8f3ff9 100644 --- a/src/ui/WaypointViewOnlyView.cc +++ b/src/ui/WaypointViewOnlyView.cc @@ -4,7 +4,7 @@ #include "WaypointViewOnlyView.h" #include "ui_WaypointViewOnlyView.h" -WaypointViewOnlyView::WaypointViewOnlyView(Waypoint* wp, QWidget *parent) : +WaypointViewOnlyView::WaypointViewOnlyView(MissionItem* wp, QWidget *parent) : QWidget(parent), wp(wp), m_ui(new Ui::WaypointViewOnlyView) diff --git a/src/ui/WaypointViewOnlyView.h b/src/ui/WaypointViewOnlyView.h index 9352475e995086c60ed49094aae25a49df2bb777..902bd4fe57d290358d77373c5004dac6b8060641 100644 --- a/src/ui/WaypointViewOnlyView.h +++ b/src/ui/WaypointViewOnlyView.h @@ -2,7 +2,7 @@ #define WAYPOINTVIEWONLYVIEW_H #include -#include "Waypoint.h" +#include "MissionItem.h" #include namespace Ui { @@ -14,7 +14,7 @@ class WaypointViewOnlyView : public QWidget Q_OBJECT public: - explicit WaypointViewOnlyView(Waypoint* wp, QWidget *parent = 0); + explicit WaypointViewOnlyView(MissionItem* wp, QWidget *parent = 0); ~WaypointViewOnlyView(); public slots: @@ -28,7 +28,7 @@ signals: void changeAutoContinue(quint16, bool); protected: - Waypoint* wp; + MissionItem* wp; virtual void changeEvent(QEvent *e); virtual void paintEvent(QPaintEvent *); diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc index 92b5347690ca1e4c8b5beb65cc6d9661948f75e3..d331fcac43f73725c169417f6efa1cb1fc0b0fc1 100644 --- a/src/ui/map/QGCMapWidget.cc +++ b/src/ui/map/QGCMapWidget.cc @@ -28,10 +28,10 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) : waypointLines.insert(0, new QGraphicsItemGroup(map)); connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int))); - connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*))); + connect(currWPManager, SIGNAL(waypointEditableChanged(int, MissionItem*)), this, SLOT(updateWaypoint(int,MissionItem*))); - connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*))); - connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*))); + connect(this, SIGNAL(waypointCreated(MissionItem*)), currWPManager, SLOT(addWaypointEditable(MissionItem*))); + connect(this, SIGNAL(waypointChanged(MissionItem*)), currWPManager, SLOT(notifyOfChangeEditable(MissionItem*))); offlineMode = true; // Widget is inactive until shown @@ -87,7 +87,7 @@ void QGCMapWidget::guidedActionTriggered() // Create new waypoint and send it to the WPManager to send out. internals::PointLatLng pos = map->FromLocalToLatLng(contextMousePressPos.x(), contextMousePressPos.y()); qDebug() << "Guided action requested. Lat:" << pos.Lat() << "Lon:" << pos.Lng(); - Waypoint wp; + MissionItem wp; wp.setLatitude(pos.Lat()); wp.setLongitude(pos.Lng()); wp.setAltitude(defaultGuidedAlt); @@ -323,7 +323,7 @@ void QGCMapWidget::mouseDoubleClickEvent(QMouseEvent* event) { // Create new waypoint internals::PointLatLng pos = map->FromLocalToLatLng(event->pos().x(), event->pos().y()); - Waypoint* wp = currWPManager->createWaypoint(); + MissionItem* wp = currWPManager->createWaypoint(); wp->setLatitude(pos.Lat()); wp->setLongitude(pos.Lng()); wp->setFrame((MAV_FRAME)currWPManager->getFrameRecommendation()); @@ -364,9 +364,9 @@ void QGCMapWidget::_activeVehicleChanged(Vehicle* vehicle) { // Disconnect the waypoint manager / data storage from the UI disconnect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int))); - disconnect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*))); - disconnect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*))); - disconnect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*))); + disconnect(currWPManager, SIGNAL(waypointEditableChanged(int, MissionItem*)), this, SLOT(updateWaypoint(int,MissionItem*))); + disconnect(this, SIGNAL(waypointCreated(MissionItem*)), currWPManager, SLOT(addWaypointEditable(MissionItem*))); + disconnect(this, SIGNAL(waypointChanged(MissionItem*)), currWPManager, SLOT(notifyOfChangeEditable(MissionItem*))); } // Attach the new waypoint manager if a new UAS was selected. Otherwise, indicate @@ -383,9 +383,9 @@ void QGCMapWidget::_activeVehicleChanged(Vehicle* vehicle) // Connect the waypoint manager / data storage to the UI connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)), Qt::UniqueConnection); - connect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*)), Qt::UniqueConnection); - connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)), Qt::UniqueConnection); - connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)), Qt::UniqueConnection); + connect(currWPManager, SIGNAL(waypointEditableChanged(int, MissionItem*)), this, SLOT(updateWaypoint(int,MissionItem*)), Qt::UniqueConnection); + connect(this, SIGNAL(waypointCreated(MissionItem*)), currWPManager, SLOT(addWaypointEditable(MissionItem*)), Qt::UniqueConnection); + connect(this, SIGNAL(waypointChanged(MissionItem*)), currWPManager, SLOT(notifyOfChangeEditable(MissionItem*)), Qt::UniqueConnection); if (!mapPositionInitialized) { internals::PointLatLng pos_lat_lon = internals::PointLatLng(_uas->getLatitude(), _uas->getLongitude()); @@ -627,7 +627,7 @@ void QGCMapWidget::cacheVisibleRegion() void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint) { // Block circle updates - Waypoint* wp = iconsToWaypoints.value(waypoint, NULL); + MissionItem* wp = iconsToWaypoints.value(waypoint, NULL); // Delete UI element if wp doesn't exist if (!wp) @@ -665,7 +665,7 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint) * This function is called if a a single waypoint is updated and * also if the whole list changes. */ -void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) +void QGCMapWidget::updateWaypoint(int uas, MissionItem* wp) { //qDebug() << __FILE__ << __LINE__ << "UPDATING WP FUNCTION CALLED"; // Source of the event was in this widget, do nothing @@ -710,8 +710,8 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) if (wpindex > 0) { // Get predecessor of this WP - QList wps = currWPManager->getGlobalFrameAndNavTypeWaypointList(); - Waypoint* wp1 = wps.at(wpindex-1); + QList wps = currWPManager->getGlobalFrameAndNavTypeWaypointList(); + MissionItem* wp1 = wps.at(wpindex-1); mapcontrol::WayPointItem* prevIcon = waypointsToIcons.value(wp1, NULL); // If we got a valid graphics item, continue if (prevIcon) @@ -729,7 +729,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) } else { - // Waypoint exists, block it's signals and update it + // MissionItem exists, block it's signals and update it mapcontrol::WayPointItem* icon = waypointsToIcons.value(wp); // Make sure we don't die on a null pointer // this should never happen, just a precaution @@ -747,7 +747,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) } else { - // Use safe standard interfaces for non Waypoint-class based wps + // Use safe standard interfaces for non MissionItem-class based wps icon->SetCoord(internals::PointLatLng(wp->getLatitude(), wp->getLongitude())); icon->SetAltitude(wp->getAltitude()); icon->SetHeading(wp->getYaw()); @@ -804,8 +804,8 @@ void QGCMapWidget::updateWaypointList(int uas) // Delete first all old waypoints // this is suboptimal (quadratic, but wps should stay in the sub-100 range anyway) - QList wps = currWPManager->getGlobalFrameAndNavTypeWaypointList(); - foreach (Waypoint* wp, waypointsToIcons.keys()) + QList wps = currWPManager->getGlobalFrameAndNavTypeWaypointList(); + foreach (MissionItem* wp, waypointsToIcons.keys()) { if (!wps.contains(wp)) { @@ -818,14 +818,14 @@ void QGCMapWidget::updateWaypointList(int uas) } // Update all existing waypoints - foreach (Waypoint* wp, waypointsToIcons.keys()) + foreach (MissionItem* wp, waypointsToIcons.keys()) { // Update remaining waypoints updateWaypoint(uas, wp); } // Update all potentially new waypoints - foreach (Waypoint* wp, wps) + foreach (MissionItem* wp, wps) { qDebug() << "UPDATING NEW WP" << wp->getId(); // Update / add only if new @@ -834,7 +834,7 @@ void QGCMapWidget::updateWaypointList(int uas) // Add line element if this is NOT the first waypoint mapcontrol::WayPointItem* prevIcon = NULL; - foreach (Waypoint* wp, wps) + foreach (MissionItem* wp, wps) { mapcontrol::WayPointItem* currIcon = waypointsToIcons.value(wp, NULL); // Do not work on first waypoint, but only increment counter diff --git a/src/ui/map/QGCMapWidget.h b/src/ui/map/QGCMapWidget.h index 6178369d5df201696427cac3b56bfa3a17653fea..d2eb547add852ff96d0997470629989a7ead7790 100644 --- a/src/ui/map/QGCMapWidget.h +++ b/src/ui/map/QGCMapWidget.h @@ -14,7 +14,7 @@ class UASInterface; class UASWaypointManager; -class Waypoint; +class MissionItem; typedef mapcontrol::WayPointItem WayPointItem; /** @@ -43,8 +43,8 @@ public: signals: void homePositionChanged(double latitude, double longitude, double altitude); /** @brief Signal for newly created map waypoints */ - void waypointCreated(Waypoint* wp); - void waypointChanged(Waypoint* wp); + void waypointCreated(MissionItem* wp); + void waypointChanged(MissionItem* wp); public slots: /** @brief Action triggered when guided action is selected from the context menu */ @@ -68,7 +68,7 @@ public slots: /** @brief Jump to the home position on the map */ void goHome(); /** @brief Update this waypoint for this UAS */ - void updateWaypoint(int uas, Waypoint* wp); + void updateWaypoint(int uas, MissionItem* wp); /** @brief Update the whole waypoint */ void updateWaypointList(int uas); /** @brief Update the home position on the map */ @@ -149,9 +149,9 @@ protected: UASWaypointManager* currWPManager; ///< The current waypoint manager bool offlineMode; - QMap waypointsToIcons; - QMap iconsToWaypoints; - Waypoint* firingWaypointChange; + QMap waypointsToIcons; + QMap iconsToWaypoints; + MissionItem* firingWaypointChange; QTimer updateTimer; float maxUpdateInterval; enum editMode { diff --git a/src/ui/map/Waypoint2DIcon.cc b/src/ui/map/Waypoint2DIcon.cc index 50204777b10f5dfa498145e2b721262eb1840845..5d416597f71b5ccff8696a440913115520b1565b 100644 --- a/src/ui/map/Waypoint2DIcon.cc +++ b/src/ui/map/Waypoint2DIcon.cc @@ -24,7 +24,7 @@ Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMa drawIcon(); } -Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, Waypoint* wp, const QColor& color, int listindex, int radius) +Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, MissionItem* wp, const QColor& color, int listindex, int radius) : mapcontrol::WayPointItem(internals::PointLatLng(wp->getLatitude(), wp->getLongitude()), wp->getAltitude(), wp->getDescription(), map), parent(parent), waypoint(wp), diff --git a/src/ui/map/Waypoint2DIcon.h b/src/ui/map/Waypoint2DIcon.h index a778368a4d1db784939ac1afe3908e84ecf8f889..66f2f2b3336045982eec7e2a5d6e71d28ffca6dc 100644 --- a/src/ui/map/Waypoint2DIcon.h +++ b/src/ui/map/Waypoint2DIcon.h @@ -3,7 +3,7 @@ #include -#include "Waypoint.h" +#include "MissionItem.h" #include "opmapcontrol.h" class Waypoint2DIcon : public mapcontrol::WayPointItem @@ -19,10 +19,10 @@ public: /** * - * @param wp Waypoint + * @param wp MissionItem * @param radius the radius of the circle */ - Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, Waypoint* wp, const QColor& color, int listindex, int radius = 31); + Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMapWidget* parent, MissionItem* wp, const QColor& color, int listindex, int radius = 31); virtual ~Waypoint2DIcon(); @@ -42,7 +42,7 @@ public: protected: mapcontrol::OPMapWidget* parent; ///< Parent widget - QPointer waypoint; ///< Waypoint data container this icon represents + QPointer waypoint; ///< MissionItem data container this icon represents int radius; ///< Radius / diameter of the icon in pixels bool showAcceptanceRadius; bool showOrbit; diff --git a/src/ui/mapdisplay/MapDisplay.qml b/src/ui/mapdisplay/MapDisplay.qml index e6b72443ea9564b73130a22de911bea41e71a60b..20526821fce444211e91b252003ca720c17fa615 100644 --- a/src/ui/mapdisplay/MapDisplay.qml +++ b/src/ui/mapdisplay/MapDisplay.qml @@ -101,7 +101,7 @@ Rectangle { } } //---------------------------------------------------------------------------------------- - // Waypoint Editor + // MissionItem Editor QGCWaypointEditor { id: waypointEditor Layout.minimumWidth: 200