Commit 520d63a3 authored by Don Gagne's avatar Don Gagne

Mission items now show summary

Plus lots of other cleanup
parent 1c20beb5
...@@ -258,6 +258,7 @@ HEADERS += \ ...@@ -258,6 +258,7 @@ HEADERS += \
src/QGCQuickWidget.h \ src/QGCQuickWidget.h \
src/QGCSingleton.h \ src/QGCSingleton.h \
src/QGCTemporaryFile.h \ src/QGCTemporaryFile.h \
src/QmlControls/MavlinkQmlSingleton.h \
src/QmlControls/ParameterEditorController.h \ src/QmlControls/ParameterEditorController.h \
src/QmlControls/ScreenToolsController.h \ src/QmlControls/ScreenToolsController.h \
src/SerialPortIds.h \ src/SerialPortIds.h \
...@@ -336,7 +337,7 @@ HEADERS += \ ...@@ -336,7 +337,7 @@ HEADERS += \
src/ViewWidgets/CustomCommandWidgetController.h \ src/ViewWidgets/CustomCommandWidgetController.h \
src/ViewWidgets/ParameterEditorWidget.h \ src/ViewWidgets/ParameterEditorWidget.h \
src/ViewWidgets/ViewWidgetController.h \ src/ViewWidgets/ViewWidgetController.h \
src/Waypoint.h \ src/MissionItem.h \
src/AutoPilotPlugins/PX4/PX4AirframeLoader.h src/AutoPilotPlugins/PX4/PX4AirframeLoader.h
!iOSBuild { !iOSBuild {
...@@ -467,7 +468,7 @@ SOURCES += \ ...@@ -467,7 +468,7 @@ SOURCES += \
src/ViewWidgets/CustomCommandWidgetController.cc \ src/ViewWidgets/CustomCommandWidgetController.cc \
src/ViewWidgets/ParameterEditorWidget.cc \ src/ViewWidgets/ParameterEditorWidget.cc \
src/ViewWidgets/ViewWidgetController.cc \ src/ViewWidgets/ViewWidgetController.cc \
src/Waypoint.cc \ src/MissionItem.cc \
src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc
!iOSBuild { !iOSBuild {
......
...@@ -37,6 +37,7 @@ import QGroundControl.FlightMap 1.0 ...@@ -37,6 +37,7 @@ import QGroundControl.FlightMap 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.MultiVehicleManager 1.0 import QGroundControl.MultiVehicleManager 1.0
import QGroundControl.Vehicle 1.0 import QGroundControl.Vehicle 1.0
import QGroundControl.Mavlink 1.0
Item { Item {
id: root id: root
...@@ -227,7 +228,12 @@ Item { ...@@ -227,7 +228,12 @@ Item {
function addMissionItem(missionItem, index) { function addMissionItem(missionItem, index) {
if (!showMissionItems) { 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 return
} }
...@@ -250,7 +256,7 @@ Item { ...@@ -250,7 +256,7 @@ Item {
function removeMissionItem(missionItem) { function removeMissionItem(missionItem) {
if (!showMissionItems) { if (!showMissionItems) {
console.warning("Shouldn't be called with showMissionItems=false") console.warn("Shouldn't be called with showMissionItems=false")
return return
} }
...@@ -275,7 +281,6 @@ Item { ...@@ -275,7 +281,6 @@ Item {
var vehicle = multiVehicleManager.activeVehicle var vehicle = multiVehicleManager.activeVehicle
if (!vehicle) { if (!vehicle) {
console.warning("Why no active vehicle?")
return return
} }
...@@ -382,7 +387,6 @@ Item { ...@@ -382,7 +387,6 @@ Item {
MissionItemSummary { MissionItemSummary {
missionItem: modelData missionItem: modelData
missionItemIndex: index + 1
} }
} }
} }
......
This diff is collapsed.
/*===================================================================== /*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit #ifndef MissionItem_H
#define MissionItem_H
(c) 2009 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
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 <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Waypoint class
*
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
#ifndef WAYPOINT_H
#define WAYPOINT_H
#include <QObject> #include <QObject>
#include <QString> #include <QString>
...@@ -41,12 +32,13 @@ This file is part of the PIXHAWK project ...@@ -41,12 +32,13 @@ This file is part of the PIXHAWK project
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "QGC.h" #include "QGC.h"
#include "MavlinkQmlSingleton.h"
class Waypoint : public QObject class MissionItem : public QObject
{ {
Q_OBJECT Q_OBJECT
public: public:
Waypoint( MissionItem(
QObject *parent = 0, QObject *parent = 0,
quint16 id = 0, quint16 id = 0,
double x = 0.0, double x = 0.0,
...@@ -62,18 +54,24 @@ public: ...@@ -62,18 +54,24 @@ public:
int action = MAV_CMD_NAV_WAYPOINT, int action = MAV_CMD_NAV_WAYPOINT,
const QString& description=QString("")); const QString& description=QString(""));
Waypoint(const Waypoint& other); MissionItem(const MissionItem& other);
~Waypoint(); ~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(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 longitude READ longitude NOTIFY longitudeChanged)
Q_PROPERTY(double latitude READ latitude NOTIFY latitudeChanged) Q_PROPERTY(double latitude READ latitude NOTIFY latitudeChanged)
Q_PROPERTY(double altitude READ altitude NOTIFY altitudeChanged) Q_PROPERTY(double altitude READ altitude NOTIFY altitudeChanged)
Q_PROPERTY(quint16 id READ id CONSTANT) 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 latitude() { return _x; }
double longitude() { return _y; } double longitude() { return _y; }
...@@ -167,9 +165,17 @@ public: ...@@ -167,9 +165,17 @@ public:
void save(QTextStream &saveStream); void save(QTextStream &saveStream);
bool load(QTextStream &loadStream); bool load(QTextStream &loadStream);
bool hasCoordinate(void);
QGeoCoordinate coordinate(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: protected:
quint16 _id; quint16 _id;
double _x; double _x;
...@@ -229,15 +235,22 @@ public: ...@@ -229,15 +235,22 @@ public:
signals: signals:
/** @brief Announces a change to the waypoint data */ /** @brief Announces a change to the waypoint data */
void changed(Waypoint* wp); void changed(MissionItem* wp);
void latitudeChanged (); void latitudeChanged ();
void longitudeChanged (); void longitudeChanged ();
void altitudeChanged (); void altitudeChanged ();
void hasCoordinateChanged(bool hasCoordinate);
void coordinateChanged(void); 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
...@@ -88,6 +88,7 @@ G_END_DECLS ...@@ -88,6 +88,7 @@ G_END_DECLS
#include "Generic/GenericFirmwarePlugin.h" #include "Generic/GenericFirmwarePlugin.h"
#include "PX4/PX4FirmwarePlugin.h" #include "PX4/PX4FirmwarePlugin.h"
#include "Vehicle.h" #include "Vehicle.h"
#include "MavlinkQmlSingleton.h"
#ifdef QGC_RTLAB_ENABLED #ifdef QGC_RTLAB_ENABLED
#include "OpalLink.h" #include "OpalLink.h"
...@@ -109,11 +110,8 @@ const char* QGCApplication::_savedFileParameterDirectoryName = "SavedParameters" ...@@ -109,11 +110,8 @@ const char* QGCApplication::_savedFileParameterDirectoryName = "SavedParameters"
const char* QGCApplication::_darkStyleFile = ":/res/styles/style-dark.css"; const char* QGCApplication::_darkStyleFile = ":/res/styles/style-dark.css";
const char* QGCApplication::_lightStyleFile = ":/res/styles/style-light.css"; const char* QGCApplication::_lightStyleFile = ":/res/styles/style-light.css";
/**
* @brief ScreenTools creation callback // Qml Singleton factories
*
* This is called by the QtQuick engine for creating the singleton
**/
static QObject* screenToolsControllerSingletonFactory(QQmlEngine*, QJSEngine*) static QObject* screenToolsControllerSingletonFactory(QQmlEngine*, QJSEngine*)
{ {
...@@ -121,6 +119,11 @@ static QObject* screenToolsControllerSingletonFactory(QQmlEngine*, QJSEngine*) ...@@ -121,6 +119,11 @@ static QObject* screenToolsControllerSingletonFactory(QQmlEngine*, QJSEngine*)
return screenToolsController; return screenToolsController;
} }
static QObject* mavlinkQmlSingletonFactory(QQmlEngine*, QJSEngine*)
{
return new MavlinkQmlSingleton;
}
#if defined(QGC_GST_STREAMING) #if defined(QGC_GST_STREAMING)
#ifdef Q_OS_MAC #ifdef Q_OS_MAC
#ifndef __ios__ #ifndef __ios__
...@@ -339,11 +342,12 @@ void QGCApplication::_initCommon(void) ...@@ -339,11 +342,12 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<FirmwareUpgradeController>("QGroundControl.Controllers", 1, 0, "FirmwareUpgradeController"); qmlRegisterType<FirmwareUpgradeController>("QGroundControl.Controllers", 1, 0, "FirmwareUpgradeController");
#endif #endif
//-- Create QML Singleton Interfaces // Register Qml Singletons
qmlRegisterSingletonType<ScreenToolsController>("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory); qmlRegisterSingletonType<ScreenToolsController> ("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory);
qmlRegisterSingletonType<MavlinkQmlSingleton> ("QGroundControl.Mavlink", 1, 0, "Mavlink", mavlinkQmlSingletonFactory);
//-- Register Waypoint Interface //-- Register MissionItem Interface
qmlRegisterInterface<Waypoint>("Waypoint"); qmlRegisterInterface<MissionItem>("MissionItem");
// Show user an upgrade message if the settings version has been bumped up // Show user an upgrade message if the settings version has been bumped up
bool settingsUpgraded = false; bool settingsUpgraded = false;
if (settings.contains(_settingsVersionKey)) { if (settings.contains(_settingsVersionKey)) {
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
...@@ -7,28 +7,65 @@ import QGroundControl.ScreenTools 1.0 ...@@ -7,28 +7,65 @@ import QGroundControl.ScreenTools 1.0
/// Mission item summary display control /// Mission item summary display control
Rectangle { Rectangle {
property var missionItem ///< Mission Item object property var missionItem ///< Mission Item object
property int missionItemIndex ///< Index for this item
width: ScreenTools.defaultFontPixelWidth * 15 width: ScreenTools.defaultFontPixelWidth * 15
height: ScreenTools.defaultFontPixelWidth * 3 height: valueColumn.height + radius
border.width: 2 border.width: 2
border.color: "white" border.color: "white"
color: "white" color: "white"
opacity: 0.75 opacity: 0.75
radius: ScreenTools.defaultFontPixelWidth 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 { MissionItemIndexLabel {
anchors.top: parent.top anchors.top: parent.top
anchors.right: parent.right 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
}
}
} }
} }
...@@ -126,7 +126,7 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType) ...@@ -126,7 +126,7 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType)
connect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &Vehicle::_updateCurrentWaypoint); connect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &Vehicle::_updateCurrentWaypoint);
connect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &Vehicle::_updateWaypointDistance); connect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &Vehicle::_updateWaypointDistance);
connect(_wpm, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(_waypointViewOnlyListChanged(void))); 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); _wpm->readWaypoints(true);
} }
UAS* pUas = dynamic_cast<UAS*>(_mav); UAS* pUas = dynamic_cast<UAS*>(_mav);
...@@ -162,7 +162,7 @@ Vehicle::~Vehicle() ...@@ -162,7 +162,7 @@ Vehicle::~Vehicle()
disconnect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &Vehicle::_updateCurrentWaypoint); disconnect(_wpm, &UASWaypointManager::currentWaypointChanged, this, &Vehicle::_updateCurrentWaypoint);
disconnect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &Vehicle::_updateWaypointDistance); disconnect(_wpm, &UASWaypointManager::waypointDistanceChanged, this, &Vehicle::_updateWaypointDistance);
disconnect(_wpm, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(_waypointViewOnlyListChanged(void))); 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<UAS*>(_mav); UAS* pUas = dynamic_cast<UAS*>(_mav);
if(pUas) { if(pUas) {
...@@ -688,7 +688,7 @@ void Vehicle::_updateCurrentWaypoint(quint16 id) ...@@ -688,7 +688,7 @@ void Vehicle::_updateCurrentWaypoint(quint16 id)
} }
} }
void Vehicle::_updateWaypointViewOnly(int, Waypoint* /*wp*/) void Vehicle::_updateWaypointViewOnly(int, MissionItem* /*wp*/)
{ {
/* /*
bool changed = false; bool changed = false;
...@@ -708,11 +708,11 @@ void Vehicle::_updateWaypointViewOnly(int, Waypoint* /*wp*/) ...@@ -708,11 +708,11 @@ void Vehicle::_updateWaypointViewOnly(int, Waypoint* /*wp*/)
void Vehicle::_waypointViewOnlyListChanged() void Vehicle::_waypointViewOnlyListChanged()
{ {
if(_wpm) { if(_wpm) {
const QList<Waypoint*> &waypoints = _wpm->getWaypointViewOnlyList(); const QList<MissionItem*> &waypoints = _wpm->getWaypointViewOnlyList();
_waypoints.clear(); _waypoints.clear();
for(int i = 0; i < waypoints.count(); i++) { for(int i = 0; i < waypoints.count(); i++) {
Waypoint* wp = waypoints[i]; MissionItem* wp = waypoints[i];
_waypoints.append(new Waypoint(*wp)); _waypoints.append(new MissionItem(*wp));
} }
emit missionItemsChanged(); emit missionItemsChanged();
/* /*
......
...@@ -88,8 +88,8 @@ public: ...@@ -88,8 +88,8 @@ public:
Q_PROPERTY(uint16_t currentWaypoint READ currentWaypoint NOTIFY currentWaypointChanged) Q_PROPERTY(uint16_t currentWaypoint READ currentWaypoint NOTIFY currentWaypointChanged)
Q_PROPERTY(unsigned int heartbeatTimeout READ heartbeatTimeout NOTIFY heartbeatTimeoutChanged) Q_PROPERTY(unsigned int heartbeatTimeout READ heartbeatTimeout NOTIFY heartbeatTimeoutChanged)
//-- Waypoint management //-- MissionItem management
Q_PROPERTY(QQmlListProperty<Waypoint> missionItems READ missionItems NOTIFY missionItemsChanged) Q_PROPERTY(QQmlListProperty<MissionItem> missionItems READ missionItems NOTIFY missionItemsChanged)
// Property accesors // Property accesors
int id(void) { return _id; } int id(void) { return _id; }
...@@ -162,7 +162,7 @@ public: ...@@ -162,7 +162,7 @@ public:
uint16_t currentWaypoint () { return _currentWaypoint; } uint16_t currentWaypoint () { return _currentWaypoint; }
unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; } unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; }
QQmlListProperty<Waypoint> missionItems() {return QQmlListProperty<Waypoint>(this, _waypoints); } QQmlListProperty<MissionItem> missionItems() {return QQmlListProperty<MissionItem>(this, _waypoints); }
public slots: public slots:
void setLatitude(double latitude); void setLatitude(double latitude);
...@@ -235,7 +235,7 @@ private slots: ...@@ -235,7 +235,7 @@ private slots:
void _updateWaypointDistance (double distance); void _updateWaypointDistance (double distance);
void _setSatelliteCount (double val, QString name); void _setSatelliteCount (double val, QString name);
void _setSatLoc (UASInterface* uas, int fix); void _setSatLoc (UASInterface* uas, int fix);
void _updateWaypointViewOnly (int uas, Waypoint* wp); void _updateWaypointViewOnly (int uas, MissionItem* wp);
void _waypointViewOnlyListChanged (); void _waypointViewOnlyListChanged ();
private: private:
...@@ -301,6 +301,6 @@ private: ...@@ -301,6 +301,6 @@ private:
int _satelliteLock; int _satelliteLock;
UASWaypointManager* _wpm; UASWaypointManager* _wpm;
int _updateCount; int _updateCount;
QList<Waypoint*>_waypoints; QList<MissionItem*>_waypoints;
}; };
#endif #endif
This diff is collapsed.
...@@ -832,7 +832,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t* ...@@ -832,7 +832,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
mavlink_command_long_t action; mavlink_command_long_t action;
mavlink_msg_command_long_decode(msg, &action); mavlink_msg_command_long_decode(msg, &action);
if(action.target_system == systemid) { 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) { // switch (action.action) {
// case MAV_ACTION_LAUNCH: // case MAV_ACTION_LAUNCH:
// if (verbose) std::cerr << "Launch received" << std::endl; // if (verbose) std::cerr << "Launch received" << std::endl;
...@@ -1129,7 +1129,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t* ...@@ -1129,7 +1129,7 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
} }
default: { default: {
if (debug) qDebug("Waypoint: received message of unknown type\n"); if (debug) qDebug("MissionItem: received message of unknown type\n");
break; break;
} }
} }
......
...@@ -751,7 +751,7 @@ public slots: ...@@ -751,7 +751,7 @@ public slots:
/** @brief Launches the system **/ /** @brief Launches the system **/
void launch(); void launch();
/** @brief Write this waypoint to the list of waypoints */ /** @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 */ /** @brief Set currently active waypoint */
//void setWaypointActive(int id); FIXME tbd //void setWaypointActive(int id); FIXME tbd
/** @brief Order the robot to return home **/ /** @brief Order the robot to return home **/
......
...@@ -265,7 +265,7 @@ public slots: ...@@ -265,7 +265,7 @@ public slots:
/** @brief Launches the system/Liftof **/ /** @brief Launches the system/Liftof **/
virtual void launch() = 0; virtual void launch() = 0;
/** @brief Set a new waypoint **/ /** @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 */ /** @brief Set this waypoint as next waypoint to fly to */
//virtual void setWaypointActive(int wp) = 0; //virtual void setWaypointActive(int wp) = 0;
/** @brief Order the robot to return home / to land on the runway **/ /** @brief Order the robot to return home / to land on the runway **/
......
This diff is collapsed.
...@@ -36,7 +36,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -36,7 +36,7 @@ This file is part of the QGROUNDCONTROL project
#include <QList> #include <QList>
#include <QTimer> #include <QTimer>
#include <QPointer> #include <QPointer>
#include "Waypoint.h" #include "MissionItem.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
class UAS; class UAS;
...@@ -71,7 +71,7 @@ public: ...@@ -71,7 +71,7 @@ public:
~UASWaypointManager(); ~UASWaypointManager();
bool guidedModeSupported(); bool guidedModeSupported();
void goToWaypoint(Waypoint *wp); void goToWaypoint(MissionItem *wp);
/** @name Received message handlers */ /** @name Received message handlers */
/*@{*/ /*@{*/
void handleWaypointCount(quint8 systemId, quint8 compId, quint16 count); ///< Handles received waypoint count messages void handleWaypointCount(quint8 systemId, quint8 compId, quint16 count); ///< Handles received waypoint count messages
...@@ -92,23 +92,23 @@ public: ...@@ -92,23 +92,23 @@ public:
int setCurrentEditable(quint16 seq); ///< Changes the current waypoint in edit tab int setCurrentEditable(quint16 seq); ///< Changes the current waypoint in edit tab
/*@}*/ /*@}*/
/** @name Waypoint list operations */ /** @name MissionItem list operations */
/*@{*/ /*@{*/
const QList<Waypoint *> &getWaypointEditableList(void) { const QList<MissionItem *> &getWaypointEditableList(void) {
return waypointsEditable; ///< Returns a const reference to the waypoint list. return waypointsEditable; ///< Returns a const reference to the waypoint list.
} }
const QList<Waypoint *> &getWaypointViewOnlyList(void) { const QList<MissionItem *> &getWaypointViewOnlyList(void) {
return waypointsViewOnly; ///< Returns a const reference to the waypoint list. return waypointsViewOnly; ///< Returns a const reference to the waypoint list.
} }
const QList<Waypoint *> getGlobalFrameWaypointList(); ///< Returns a global waypoint list const QList<MissionItem *> getGlobalFrameWaypointList(); ///< Returns a global waypoint list
const QList<Waypoint *> getGlobalFrameAndNavTypeWaypointList(); ///< Returns a global waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out. const QList<MissionItem *> getGlobalFrameAndNavTypeWaypointList(); ///< Returns a global waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out.
const QList<Waypoint *> getNavTypeWaypointList(); ///< Returns a waypoint list containing only waypoints suitable for navigation. Actions and other mission items are filtered out. const QList<MissionItem *> 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 getIndexOf(MissionItem* 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 getGlobalFrameIndexOf(MissionItem* 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 getGlobalFrameAndNavTypeIndexOf(MissionItem* 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 getNavTypeIndexOf(MissionItem* 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 getLocalFrameIndexOf(MissionItem* 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 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 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 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 int getNavTypeCount(); ///< Get the count of global waypoints in navigation mode in the list
...@@ -135,17 +135,17 @@ private: ...@@ -135,17 +135,17 @@ private:
public slots: public slots:
void timeout(); ///< Called by the timer if a response times out. Handles send retries. 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 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(Waypoint *wp); ///< adds a new waypoint to the end of the view-only 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
Waypoint* createWaypoint(bool enforceFirstActive=true); ///< Creates a waypoint MissionItem* createWaypoint(bool enforceFirstActive=true); ///< Creates a waypoint
int removeWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage 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 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 saveWaypoints(const QString &saveFile); ///< saves the local waypoint list to saveFile
void loadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile void loadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile
void notifyOfChangeEditable(Waypoint* wp); ///< Notifies manager to changes to an editable waypoint void notifyOfChangeEditable(MissionItem* 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 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 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); void handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double altAMSL, double altWGS84, quint64 time);
...@@ -153,10 +153,10 @@ public slots: ...@@ -153,10 +153,10 @@ public slots:
signals: signals:
void waypointEditableListChanged(void); ///< emits signal that the list of editable waypoints has been changed 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 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(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 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 currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number
void updateStatusString(const QString &); ///< emits the current status string void updateStatusString(const QString &); ///< emits the current status string
void waypointDistanceChanged(double distance); ///< Distance to next waypoint changed (in meters) void waypointDistanceChanged(double distance); ///< Distance to next waypoint changed (in meters)
...@@ -182,9 +182,9 @@ private: ...@@ -182,9 +182,9 @@ private:
quint8 current_partner_compid; ///< The current protocol communication target component 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. 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<Waypoint *> waypointsViewOnly; ///< local copy of current waypoint list on MAV QList<MissionItem *> waypointsViewOnly; ///< local copy of current waypoint list on MAV
QList<Waypoint *> waypointsEditable; ///< local editable waypoint list QList<MissionItem *> waypointsEditable; ///< local editable waypoint list
QPointer<Waypoint> currentWaypointEditable; ///< The currently used waypoint QPointer<MissionItem> currentWaypointEditable; ///< The currently used waypoint
QList<mavlink_mission_item_t *> waypoint_buffer; ///< buffer for waypoints during communication QList<mavlink_mission_item_t *> waypoint_buffer; ///< buffer for waypoints during communication
QTimer protocol_timer; ///< Timer to catch timeouts QTimer protocol_timer; ///< Timer to catch timeouts
QTimer _updateWPlist_timer; ///< update WP list if modified by another instance onboard QTimer _updateWPlist_timer; ///< update WP list if modified by another instance onboard
......
...@@ -41,7 +41,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -41,7 +41,7 @@ This file is part of the QGROUNDCONTROL project
#include "HomePositionManager.h" #include "HomePositionManager.h"
#include "HSIDisplay.h" #include "HSIDisplay.h"
#include "QGC.h" #include "QGC.h"
#include "Waypoint.h" #include "MissionItem.h"
#include "UASWaypointManager.h" #include "UASWaypointManager.h"
#include <qmath.h> #include <qmath.h>
#include "MAV2DIcon.h" #include "MAV2DIcon.h"
...@@ -1291,7 +1291,7 @@ void HSIDisplay::drawSetpointXYZYaw(float x, float y, float z, float yaw, const ...@@ -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); painter.setBrush(Qt::NoBrush);
...@@ -1334,7 +1334,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter) ...@@ -1334,7 +1334,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
if (uas) if (uas)
{ {
// Grab all waypoints. // Grab all waypoints.
const QList<Waypoint*>& list = uas->getWaypointManager()->getWaypointEditableList(); const QList<MissionItem*>& list = uas->getWaypointManager()->getWaypointEditableList();
const int numWaypoints = list.size(); const int numWaypoints = list.size();
// Do not work on empty lists // Do not work on empty lists
...@@ -1349,7 +1349,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter) ...@@ -1349,7 +1349,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
QPointF lastWaypoint; QPointF lastWaypoint;
for (int i = 0; i < numWaypoints; i++) for (int i = 0; i < numWaypoints; i++)
{ {
const Waypoint *w = list.at(i); const MissionItem *w = list.at(i);
QPointF in; QPointF in;
// Use local coordinates as-is. // Use local coordinates as-is.
int frameRef = w->getFrame(); int frameRef = w->getFrame();
......
...@@ -200,7 +200,7 @@ protected slots: ...@@ -200,7 +200,7 @@ protected slots:
/** @brief Draw waypoints of this system */ /** @brief Draw waypoints of this system */
void drawWaypoints(QPainter& painter); void drawWaypoints(QPainter& painter);
/** @brief Draw one waypoint */ /** @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 */ /** @brief Draw the limiting safety area */
void drawSafetyArea(const QPointF &topLeft, const QPointF &bottomRight, const QColor &color, QPainter &painter); void drawSafetyArea(const QPointF &topLeft, const QPointF &bottomRight, const QColor &color, QPainter &painter);
/** @brief Receive mouse clicks */ /** @brief Receive mouse clicks */
......
...@@ -441,14 +441,6 @@ void MainWindow::_buildPlanView(void) ...@@ -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) void MainWindow::_buildFlightView(void)
{ {
if (!_flightView) { if (!_flightView) {
...@@ -725,7 +717,6 @@ void MainWindow::connectCommonActions() ...@@ -725,7 +717,6 @@ void MainWindow::connectCommonActions()
perspectives->addAction(_ui.actionSimulationView); perspectives->addAction(_ui.actionSimulationView);
perspectives->addAction(_ui.actionPlan); perspectives->addAction(_ui.actionPlan);
perspectives->addAction(_ui.actionSetup); perspectives->addAction(_ui.actionSetup);
perspectives->addAction(_ui.actionExperimentalPlanView);
perspectives->setExclusive(true); perspectives->setExclusive(true);
// Mark the right one as selected // Mark the right one as selected
...@@ -749,11 +740,6 @@ void MainWindow::connectCommonActions() ...@@ -749,11 +740,6 @@ void MainWindow::connectCommonActions()
_ui.actionPlan->setChecked(true); _ui.actionPlan->setChecked(true);
_ui.actionPlan->activate(QAction::Trigger); _ui.actionPlan->activate(QAction::Trigger);
} }
if (_currentView == VIEW_EXPERIMENTAL_PLAN)
{
_ui.actionExperimentalPlanView->setChecked(true);
_ui.actionExperimentalPlanView->activate(QAction::Trigger);
}
if (_currentView == VIEW_SETUP) if (_currentView == VIEW_SETUP)
{ {
_ui.actionSetup->setChecked(true); _ui.actionSetup->setChecked(true);
...@@ -772,7 +758,6 @@ void MainWindow::connectCommonActions() ...@@ -772,7 +758,6 @@ void MainWindow::connectCommonActions()
connect(_ui.actionSimulationView, SIGNAL(triggered()), this, SLOT(loadSimulationView())); connect(_ui.actionSimulationView, SIGNAL(triggered()), this, SLOT(loadSimulationView()));
connect(_ui.actionAnalyze, SIGNAL(triggered()), this, SLOT(loadAnalyzeView())); connect(_ui.actionAnalyze, SIGNAL(triggered()), this, SLOT(loadAnalyzeView()));
connect(_ui.actionPlan, SIGNAL(triggered()), this, SLOT(loadPlanView())); connect(_ui.actionPlan, SIGNAL(triggered()), this, SLOT(loadPlanView()));
connect(_ui.actionExperimentalPlanView, SIGNAL(triggered()), this, SLOT(loadOldPlanView()));
// Help Actions // Help Actions
connect(_ui.actionOnline_Documentation, SIGNAL(triggered()), this, SLOT(showHelp())); connect(_ui.actionOnline_Documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
...@@ -926,12 +911,6 @@ void MainWindow::_loadCurrentViewState(void) ...@@ -926,12 +911,6 @@ void MainWindow::_loadCurrentViewState(void)
defaultWidgets = "WAYPOINT_LIST_DOCKWIDGET"; defaultWidgets = "WAYPOINT_LIST_DOCKWIDGET";
break; break;
case VIEW_EXPERIMENTAL_PLAN:
_buildExperimentalPlanView();
centerView = _experimentalPlanView;
defaultWidgets.clear();
break;
case VIEW_SIMULATION: case VIEW_SIMULATION:
_buildSimView(); _buildSimView();
centerView = _simView; centerView = _simView;
...@@ -1034,17 +1013,6 @@ void MainWindow::loadPlanView() ...@@ -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() void MainWindow::loadSetupView()
{ {
if (_currentView != VIEW_SETUP) if (_currentView != VIEW_SETUP)
......
...@@ -143,8 +143,6 @@ public slots: ...@@ -143,8 +143,6 @@ public slots:
void loadAnalyzeView(); void loadAnalyzeView();
/** @brief Load New (QtQuick) Map View (Mission) */ /** @brief Load New (QtQuick) Map View (Mission) */
void loadPlanView(); void loadPlanView();
/** @brief Load Old (Qt Widget) Map View (Mission) */
void loadOldPlanView();
/** @brief Manage Links */ /** @brief Manage Links */
void manageLinks(); void manageLinks();
...@@ -215,7 +213,6 @@ protected: ...@@ -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_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_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_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; } VIEW_SECTIONS;
/** @brief Catch window resize events */ /** @brief Catch window resize events */
...@@ -293,7 +290,6 @@ private: ...@@ -293,7 +290,6 @@ private:
// Center widgets // Center widgets
QPointer<QWidget> _planView; QPointer<QWidget> _planView;
QPointer<QWidget> _experimentalPlanView;
QPointer<QWidget> _flightView; QPointer<QWidget> _flightView;
QPointer<QWidget> _setupView; QPointer<QWidget> _setupView;
QPointer<QWidget> _analyzeView; QPointer<QWidget> _analyzeView;
...@@ -322,7 +318,6 @@ private: ...@@ -322,7 +318,6 @@ private:
QMap<QDockWidget*, QAction*> _mapDockWidget2Action; QMap<QDockWidget*, QAction*> _mapDockWidget2Action;
void _buildPlanView(void); void _buildPlanView(void);
void _buildExperimentalPlanView(void);
void _buildFlightView(void); void _buildFlightView(void);
void _buildSetupView(void); void _buildSetupView(void);
void _buildAnalyzeView(void); void _buildAnalyzeView(void);
......
...@@ -243,11 +243,6 @@ ...@@ -243,11 +243,6 @@
<string>Show Status Bar</string> <string>Show Status Bar</string>
</property> </property>
</action> </action>
<action name="actionExperimentalPlanView">
<property name="text">
<string>Experimental Plan View</string>
</property>
</action>
</widget> </widget>
<layoutdefault spacing="6" margin="11"/> <layoutdefault spacing="6" margin="11"/>
<resources> <resources>
......
...@@ -36,7 +36,7 @@ ...@@ -36,7 +36,7 @@
#include "mission/QGCMissionOther.h" #include "mission/QGCMissionOther.h"
WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : WaypointEditableView::WaypointEditableView(MissionItem* wp, QWidget* parent) :
QWidget(parent), QWidget(parent),
wp(wp), wp(wp),
viewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_DEFAULT), viewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_DEFAULT),
...@@ -67,7 +67,7 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : ...@@ -67,7 +67,7 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
// add actions // 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: 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 Unlim."),MAV_CMD_NAV_LOITER_UNLIM);
m_ui->comboBox_action->addItem(tr("NAV: Loiter Time"),MAV_CMD_NAV_LOITER_TIME); m_ui->comboBox_action->addItem(tr("NAV: Loiter Time"),MAV_CMD_NAV_LOITER_TIME);
......
...@@ -34,7 +34,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -34,7 +34,7 @@ This file is part of the QGROUNDCONTROL project
#define WAYPOINTEDITABLEVIEW_H #define WAYPOINTEDITABLEVIEW_H
#include <QWidget> #include <QWidget>
#include "Waypoint.h" #include "MissionItem.h"
#include <iostream> #include <iostream>
enum QGC_WAYPOINTEDITABLEVIEW_MODE { enum QGC_WAYPOINTEDITABLEVIEW_MODE {
...@@ -65,7 +65,7 @@ class WaypointEditableView : public QWidget ...@@ -65,7 +65,7 @@ class WaypointEditableView : public QWidget
Q_OBJECT Q_OBJECT
Q_DISABLE_COPY(WaypointEditableView) Q_DISABLE_COPY(WaypointEditableView)
public: public:
explicit WaypointEditableView(Waypoint* wp, QWidget* parent); explicit WaypointEditableView(MissionItem* wp, QWidget* parent);
virtual ~WaypointEditableView(); virtual ~WaypointEditableView();
public: public:
...@@ -75,7 +75,7 @@ public slots: ...@@ -75,7 +75,7 @@ public slots:
void moveUp(); void moveUp();
void moveDown(); void moveDown();
void remove(); void remove();
/** @brief Waypoint matching this widget has been deleted */ /** @brief MissionItem matching this widget has been deleted */
void deleted(QObject* waypoint); void deleted(QObject* waypoint);
void changedAutoContinue(int); void changedAutoContinue(int);
void changedFrame(int state); void changedFrame(int state);
...@@ -99,7 +99,7 @@ protected slots: ...@@ -99,7 +99,7 @@ protected slots:
protected: protected:
virtual void changeEvent(QEvent *e); virtual void changeEvent(QEvent *e);
virtual void paintEvent(QPaintEvent *); virtual void paintEvent(QPaintEvent *);
Waypoint* wp; MissionItem* wp;
QGC_WAYPOINTEDITABLEVIEW_MODE viewMode; QGC_WAYPOINTEDITABLEVIEW_MODE viewMode;
// Widgets for every mission element // Widgets for every mission element
QGCMissionNavWaypoint* MissionNavWaypointWidget; QGCMissionNavWaypoint* MissionNavWaypointWidget;
...@@ -121,9 +121,9 @@ private: ...@@ -121,9 +121,9 @@ private:
Ui::WaypointEditableView *m_ui; Ui::WaypointEditableView *m_ui;
signals: signals:
void moveUpWaypoint(Waypoint*); void moveUpWaypoint(MissionItem*);
void moveDownWaypoint(Waypoint*); void moveDownWaypoint(MissionItem*);
void removeWaypoint(Waypoint*); void removeWaypoint(MissionItem*);
void changeCurrentWaypoint(quint16); void changeCurrentWaypoint(quint16);
void setYaw(double); void setYaw(double);
......
This diff is collapsed.
...@@ -38,7 +38,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -38,7 +38,7 @@ This file is part of the QGROUNDCONTROL project
#include <QMap> #include <QMap>
#include <QVBoxLayout> #include <QVBoxLayout>
#include <QTimer> #include <QTimer>
#include "Waypoint.h" #include "MissionItem.h"
#include "UASInterface.h" #include "UASInterface.h"
#include "WaypointEditableView.h" #include "WaypointEditableView.h"
#include "WaypointViewOnlyView.h" #include "WaypointViewOnlyView.h"
...@@ -62,7 +62,7 @@ public slots: ...@@ -62,7 +62,7 @@ public slots:
void setUAS(UASInterface* uas); void setUAS(UASInterface* uas);
//Waypoint list operations //MissionItem list operations
/** @brief Save the local waypoint list to a file */ /** @brief Save the local waypoint list to a file */
void saveWaypoints(); void saveWaypoints();
/** @brief Load a waypoint list from a file */ /** @brief Load a waypoint list from a file */
...@@ -91,9 +91,9 @@ public slots: ...@@ -91,9 +91,9 @@ public slots:
/** @brief Current waypoint on UAV was changed, update view-tab */ /** @brief Current waypoint on UAV was changed, update view-tab */
void currentWaypointViewOnlyChanged(quint16 seq); void currentWaypointViewOnlyChanged(quint16 seq);
/** @brief The waypoint manager informs that one editable waypoint was changed */ /** @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 */ /** @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 */ /** @brief The waypoint manager informs that the editable waypoint list was changed */
void waypointEditableListChanged(void); void waypointEditableListChanged(void);
/** @brief The waypoint manager informs that the waypoint list on the MAV was changed */ /** @brief The waypoint manager informs that the waypoint list on the MAV was changed */
...@@ -104,12 +104,12 @@ public slots: ...@@ -104,12 +104,12 @@ public slots:
void clearWPWidget(); void clearWPWidget();
//void changeWPPositionBySpinBox(Waypoint* wp); //void changeWPPositionBySpinBox(MissionItem* wp);
// Waypoint operations // MissionItem operations
void moveUp(Waypoint* wp); void moveUp(MissionItem* wp);
void moveDown(Waypoint* wp); void moveDown(MissionItem* wp);
void removeWaypoint(Waypoint* wp); void removeWaypoint(MissionItem* wp);
// void setIsLoadFileWP(); // void setIsLoadFileWP();
// void setIsReadGlobalWP(bool value); // void setIsReadGlobalWP(bool value);
...@@ -125,8 +125,8 @@ protected: ...@@ -125,8 +125,8 @@ protected:
virtual void changeEvent(QEvent *e); virtual void changeEvent(QEvent *e);
protected: protected:
QMap<Waypoint*, WaypointEditableView*> wpEditableViews; QMap<MissionItem*, WaypointEditableView*> wpEditableViews;
QMap<Waypoint*, WaypointViewOnlyView*> wpViewOnlyViews; QMap<MissionItem*, WaypointViewOnlyView*> wpViewOnlyViews;
QVBoxLayout* viewOnlyListLayout; QVBoxLayout* viewOnlyListLayout;
QVBoxLayout* editableListLayout; QVBoxLayout* editableListLayout;
UASInterface* uas; UASInterface* uas;
......
...@@ -4,7 +4,7 @@ ...@@ -4,7 +4,7 @@
#include "WaypointViewOnlyView.h" #include "WaypointViewOnlyView.h"
#include "ui_WaypointViewOnlyView.h" #include "ui_WaypointViewOnlyView.h"
WaypointViewOnlyView::WaypointViewOnlyView(Waypoint* wp, QWidget *parent) : WaypointViewOnlyView::WaypointViewOnlyView(MissionItem* wp, QWidget *parent) :
QWidget(parent), QWidget(parent),
wp(wp), wp(wp),
m_ui(new Ui::WaypointViewOnlyView) m_ui(new Ui::WaypointViewOnlyView)
......
...@@ -2,7 +2,7 @@ ...@@ -2,7 +2,7 @@
#define WAYPOINTVIEWONLYVIEW_H #define WAYPOINTVIEWONLYVIEW_H
#include <QWidget> #include <QWidget>
#include "Waypoint.h" #include "MissionItem.h"
#include <iostream> #include <iostream>
namespace Ui { namespace Ui {
...@@ -14,7 +14,7 @@ class WaypointViewOnlyView : public QWidget ...@@ -14,7 +14,7 @@ class WaypointViewOnlyView : public QWidget
Q_OBJECT Q_OBJECT
public: public:
explicit WaypointViewOnlyView(Waypoint* wp, QWidget *parent = 0); explicit WaypointViewOnlyView(MissionItem* wp, QWidget *parent = 0);
~WaypointViewOnlyView(); ~WaypointViewOnlyView();
public slots: public slots:
...@@ -28,7 +28,7 @@ signals: ...@@ -28,7 +28,7 @@ signals:
void changeAutoContinue(quint16, bool); void changeAutoContinue(quint16, bool);
protected: protected:
Waypoint* wp; MissionItem* wp;
virtual void changeEvent(QEvent *e); virtual void changeEvent(QEvent *e);
virtual void paintEvent(QPaintEvent *); virtual void paintEvent(QPaintEvent *);
......
...@@ -28,10 +28,10 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) : ...@@ -28,10 +28,10 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) :
waypointLines.insert(0, new QGraphicsItemGroup(map)); waypointLines.insert(0, new QGraphicsItemGroup(map));
connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int))); 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(waypointCreated(MissionItem*)), currWPManager, SLOT(addWaypointEditable(MissionItem*)));
connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*))); connect(this, SIGNAL(waypointChanged(MissionItem*)), currWPManager, SLOT(notifyOfChangeEditable(MissionItem*)));
offlineMode = true; offlineMode = true;
// Widget is inactive until shown // Widget is inactive until shown
...@@ -87,7 +87,7 @@ void QGCMapWidget::guidedActionTriggered() ...@@ -87,7 +87,7 @@ void QGCMapWidget::guidedActionTriggered()
// Create new waypoint and send it to the WPManager to send out. // Create new waypoint and send it to the WPManager to send out.
internals::PointLatLng pos = map->FromLocalToLatLng(contextMousePressPos.x(), contextMousePressPos.y()); internals::PointLatLng pos = map->FromLocalToLatLng(contextMousePressPos.x(), contextMousePressPos.y());
qDebug() << "Guided action requested. Lat:" << pos.Lat() << "Lon:" << pos.Lng(); qDebug() << "Guided action requested. Lat:" << pos.Lat() << "Lon:" << pos.Lng();
Waypoint wp; MissionItem wp;
wp.setLatitude(pos.Lat()); wp.setLatitude(pos.Lat());
wp.setLongitude(pos.Lng()); wp.setLongitude(pos.Lng());
wp.setAltitude(defaultGuidedAlt); wp.setAltitude(defaultGuidedAlt);
...@@ -323,7 +323,7 @@ void QGCMapWidget::mouseDoubleClickEvent(QMouseEvent* event) ...@@ -323,7 +323,7 @@ void QGCMapWidget::mouseDoubleClickEvent(QMouseEvent* event)
{ {
// Create new waypoint // Create new waypoint
internals::PointLatLng pos = map->FromLocalToLatLng(event->pos().x(), event->pos().y()); internals::PointLatLng pos = map->FromLocalToLatLng(event->pos().x(), event->pos().y());
Waypoint* wp = currWPManager->createWaypoint(); MissionItem* wp = currWPManager->createWaypoint();
wp->setLatitude(pos.Lat()); wp->setLatitude(pos.Lat());
wp->setLongitude(pos.Lng()); wp->setLongitude(pos.Lng());
wp->setFrame((MAV_FRAME)currWPManager->getFrameRecommendation()); wp->setFrame((MAV_FRAME)currWPManager->getFrameRecommendation());
...@@ -364,9 +364,9 @@ void QGCMapWidget::_activeVehicleChanged(Vehicle* vehicle) ...@@ -364,9 +364,9 @@ void QGCMapWidget::_activeVehicleChanged(Vehicle* vehicle)
{ {
// Disconnect the waypoint manager / data storage from the UI // Disconnect the waypoint manager / data storage from the UI
disconnect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int))); disconnect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)));
disconnect(currWPManager, SIGNAL(waypointEditableChanged(int, Waypoint*)), this, SLOT(updateWaypoint(int,Waypoint*))); disconnect(currWPManager, SIGNAL(waypointEditableChanged(int, MissionItem*)), this, SLOT(updateWaypoint(int,MissionItem*)));
disconnect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*))); disconnect(this, SIGNAL(waypointCreated(MissionItem*)), currWPManager, SLOT(addWaypointEditable(MissionItem*)));
disconnect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*))); disconnect(this, SIGNAL(waypointChanged(MissionItem*)), currWPManager, SLOT(notifyOfChangeEditable(MissionItem*)));
} }
// Attach the new waypoint manager if a new UAS was selected. Otherwise, indicate // Attach the new waypoint manager if a new UAS was selected. Otherwise, indicate
...@@ -383,9 +383,9 @@ void QGCMapWidget::_activeVehicleChanged(Vehicle* vehicle) ...@@ -383,9 +383,9 @@ void QGCMapWidget::_activeVehicleChanged(Vehicle* vehicle)
// Connect the waypoint manager / data storage to the UI // Connect the waypoint manager / data storage to the UI
connect(currWPManager, SIGNAL(waypointEditableListChanged(int)), this, SLOT(updateWaypointList(int)), Qt::UniqueConnection); 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(currWPManager, SIGNAL(waypointEditableChanged(int, MissionItem*)), this, SLOT(updateWaypoint(int,MissionItem*)), Qt::UniqueConnection);
connect(this, SIGNAL(waypointCreated(Waypoint*)), currWPManager, SLOT(addWaypointEditable(Waypoint*)), Qt::UniqueConnection); connect(this, SIGNAL(waypointCreated(MissionItem*)), currWPManager, SLOT(addWaypointEditable(MissionItem*)), Qt::UniqueConnection);
connect(this, SIGNAL(waypointChanged(Waypoint*)), currWPManager, SLOT(notifyOfChangeEditable(Waypoint*)), Qt::UniqueConnection); connect(this, SIGNAL(waypointChanged(MissionItem*)), currWPManager, SLOT(notifyOfChangeEditable(MissionItem*)), Qt::UniqueConnection);
if (!mapPositionInitialized) { if (!mapPositionInitialized) {
internals::PointLatLng pos_lat_lon = internals::PointLatLng(_uas->getLatitude(), _uas->getLongitude()); internals::PointLatLng pos_lat_lon = internals::PointLatLng(_uas->getLatitude(), _uas->getLongitude());
...@@ -627,7 +627,7 @@ void QGCMapWidget::cacheVisibleRegion() ...@@ -627,7 +627,7 @@ void QGCMapWidget::cacheVisibleRegion()
void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint) void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
{ {
// Block circle updates // Block circle updates
Waypoint* wp = iconsToWaypoints.value(waypoint, NULL); MissionItem* wp = iconsToWaypoints.value(waypoint, NULL);
// Delete UI element if wp doesn't exist // Delete UI element if wp doesn't exist
if (!wp) if (!wp)
...@@ -665,7 +665,7 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint) ...@@ -665,7 +665,7 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
* This function is called if a a single waypoint is updated and * This function is called if a a single waypoint is updated and
* also if the whole list changes. * 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"; //qDebug() << __FILE__ << __LINE__ << "UPDATING WP FUNCTION CALLED";
// Source of the event was in this widget, do nothing // Source of the event was in this widget, do nothing
...@@ -710,8 +710,8 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) ...@@ -710,8 +710,8 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
if (wpindex > 0) if (wpindex > 0)
{ {
// Get predecessor of this WP // Get predecessor of this WP
QList<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList(); QList<MissionItem* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
Waypoint* wp1 = wps.at(wpindex-1); MissionItem* wp1 = wps.at(wpindex-1);
mapcontrol::WayPointItem* prevIcon = waypointsToIcons.value(wp1, NULL); mapcontrol::WayPointItem* prevIcon = waypointsToIcons.value(wp1, NULL);
// If we got a valid graphics item, continue // If we got a valid graphics item, continue
if (prevIcon) if (prevIcon)
...@@ -729,7 +729,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) ...@@ -729,7 +729,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
} }
else 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); mapcontrol::WayPointItem* icon = waypointsToIcons.value(wp);
// Make sure we don't die on a null pointer // Make sure we don't die on a null pointer
// this should never happen, just a precaution // this should never happen, just a precaution
...@@ -747,7 +747,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp) ...@@ -747,7 +747,7 @@ void QGCMapWidget::updateWaypoint(int uas, Waypoint* wp)
} }
else 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->SetCoord(internals::PointLatLng(wp->getLatitude(), wp->getLongitude()));
icon->SetAltitude(wp->getAltitude()); icon->SetAltitude(wp->getAltitude());
icon->SetHeading(wp->getYaw()); icon->SetHeading(wp->getYaw());
...@@ -804,8 +804,8 @@ void QGCMapWidget::updateWaypointList(int uas) ...@@ -804,8 +804,8 @@ void QGCMapWidget::updateWaypointList(int uas)
// Delete first all old waypoints // Delete first all old waypoints
// this is suboptimal (quadratic, but wps should stay in the sub-100 range anyway) // this is suboptimal (quadratic, but wps should stay in the sub-100 range anyway)
QList<Waypoint* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList(); QList<MissionItem* > wps = currWPManager->getGlobalFrameAndNavTypeWaypointList();
foreach (Waypoint* wp, waypointsToIcons.keys()) foreach (MissionItem* wp, waypointsToIcons.keys())
{ {
if (!wps.contains(wp)) if (!wps.contains(wp))
{ {
...@@ -818,14 +818,14 @@ void QGCMapWidget::updateWaypointList(int uas) ...@@ -818,14 +818,14 @@ void QGCMapWidget::updateWaypointList(int uas)
} }
// Update all existing waypoints // Update all existing waypoints
foreach (Waypoint* wp, waypointsToIcons.keys()) foreach (MissionItem* wp, waypointsToIcons.keys())
{ {
// Update remaining waypoints // Update remaining waypoints
updateWaypoint(uas, wp); updateWaypoint(uas, wp);
} }
// Update all potentially new waypoints // Update all potentially new waypoints
foreach (Waypoint* wp, wps) foreach (MissionItem* wp, wps)
{ {
qDebug() << "UPDATING NEW WP" << wp->getId(); qDebug() << "UPDATING NEW WP" << wp->getId();
// Update / add only if new // Update / add only if new
...@@ -834,7 +834,7 @@ void QGCMapWidget::updateWaypointList(int uas) ...@@ -834,7 +834,7 @@ void QGCMapWidget::updateWaypointList(int uas)
// Add line element if this is NOT the first waypoint // Add line element if this is NOT the first waypoint
mapcontrol::WayPointItem* prevIcon = NULL; mapcontrol::WayPointItem* prevIcon = NULL;
foreach (Waypoint* wp, wps) foreach (MissionItem* wp, wps)
{ {
mapcontrol::WayPointItem* currIcon = waypointsToIcons.value(wp, NULL); mapcontrol::WayPointItem* currIcon = waypointsToIcons.value(wp, NULL);
// Do not work on first waypoint, but only increment counter // Do not work on first waypoint, but only increment counter
......
...@@ -14,7 +14,7 @@ ...@@ -14,7 +14,7 @@
class UASInterface; class UASInterface;
class UASWaypointManager; class UASWaypointManager;
class Waypoint; class MissionItem;
typedef mapcontrol::WayPointItem WayPointItem; typedef mapcontrol::WayPointItem WayPointItem;
/** /**
...@@ -43,8 +43,8 @@ public: ...@@ -43,8 +43,8 @@ public:
signals: signals:
void homePositionChanged(double latitude, double longitude, double altitude); void homePositionChanged(double latitude, double longitude, double altitude);
/** @brief Signal for newly created map waypoints */ /** @brief Signal for newly created map waypoints */
void waypointCreated(Waypoint* wp); void waypointCreated(MissionItem* wp);
void waypointChanged(Waypoint* wp); void waypointChanged(MissionItem* wp);
public slots: public slots:
/** @brief Action triggered when guided action is selected from the context menu */ /** @brief Action triggered when guided action is selected from the context menu */
...@@ -68,7 +68,7 @@ public slots: ...@@ -68,7 +68,7 @@ public slots:
/** @brief Jump to the home position on the map */ /** @brief Jump to the home position on the map */
void goHome(); void goHome();
/** @brief Update this waypoint for this UAS */ /** @brief Update this waypoint for this UAS */
void updateWaypoint(int uas, Waypoint* wp); void updateWaypoint(int uas, MissionItem* wp);
/** @brief Update the whole waypoint */ /** @brief Update the whole waypoint */
void updateWaypointList(int uas); void updateWaypointList(int uas);
/** @brief Update the home position on the map */ /** @brief Update the home position on the map */
...@@ -149,9 +149,9 @@ protected: ...@@ -149,9 +149,9 @@ protected:
UASWaypointManager* currWPManager; ///< The current waypoint manager UASWaypointManager* currWPManager; ///< The current waypoint manager
bool offlineMode; bool offlineMode;
QMap<Waypoint* , mapcontrol::WayPointItem*> waypointsToIcons; QMap<MissionItem* , mapcontrol::WayPointItem*> waypointsToIcons;
QMap<mapcontrol::WayPointItem*, Waypoint*> iconsToWaypoints; QMap<mapcontrol::WayPointItem*, MissionItem*> iconsToWaypoints;
Waypoint* firingWaypointChange; MissionItem* firingWaypointChange;
QTimer updateTimer; QTimer updateTimer;
float maxUpdateInterval; float maxUpdateInterval;
enum editMode { enum editMode {
......
...@@ -24,7 +24,7 @@ Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMa ...@@ -24,7 +24,7 @@ Waypoint2DIcon::Waypoint2DIcon(mapcontrol::MapGraphicItem* map, mapcontrol::OPMa
drawIcon(); 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), : mapcontrol::WayPointItem(internals::PointLatLng(wp->getLatitude(), wp->getLongitude()), wp->getAltitude(), wp->getDescription(), map),
parent(parent), parent(parent),
waypoint(wp), waypoint(wp),
......
...@@ -3,7 +3,7 @@ ...@@ -3,7 +3,7 @@
#include <QGraphicsItem> #include <QGraphicsItem>
#include "Waypoint.h" #include "MissionItem.h"
#include "opmapcontrol.h" #include "opmapcontrol.h"
class Waypoint2DIcon : public mapcontrol::WayPointItem class Waypoint2DIcon : public mapcontrol::WayPointItem
...@@ -19,10 +19,10 @@ public: ...@@ -19,10 +19,10 @@ public:
/** /**
* *
* @param wp Waypoint * @param wp MissionItem
* @param radius the radius of the circle * @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(); virtual ~Waypoint2DIcon();
...@@ -42,7 +42,7 @@ public: ...@@ -42,7 +42,7 @@ public:
protected: protected:
mapcontrol::OPMapWidget* parent; ///< Parent widget mapcontrol::OPMapWidget* parent; ///< Parent widget
QPointer<Waypoint> waypoint; ///< Waypoint data container this icon represents QPointer<MissionItem> waypoint; ///< MissionItem data container this icon represents
int radius; ///< Radius / diameter of the icon in pixels int radius; ///< Radius / diameter of the icon in pixels
bool showAcceptanceRadius; bool showAcceptanceRadius;
bool showOrbit; bool showOrbit;
......
...@@ -101,7 +101,7 @@ Rectangle { ...@@ -101,7 +101,7 @@ Rectangle {
} }
} }
//---------------------------------------------------------------------------------------- //----------------------------------------------------------------------------------------
// Waypoint Editor // MissionItem Editor
QGCWaypointEditor { QGCWaypointEditor {
id: waypointEditor id: waypointEditor
Layout.minimumWidth: 200 Layout.minimumWidth: 200
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment