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 += \
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 {
......
......@@ -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
}
}
}
......
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
(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
#ifndef MissionItem_H
#define MissionItem_H
#include <QObject>
#include <QString>
......@@ -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
......@@ -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<FirmwareUpgradeController>("QGroundControl.Controllers", 1, 0, "FirmwareUpgradeController");
#endif
//-- Create QML Singleton Interfaces
qmlRegisterSingletonType<ScreenToolsController>("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory);
// Register Qml Singletons
qmlRegisterSingletonType<ScreenToolsController> ("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory);
qmlRegisterSingletonType<MavlinkQmlSingleton> ("QGroundControl.Mavlink", 1, 0, "Mavlink", mavlinkQmlSingletonFactory);
//-- Register Waypoint Interface
qmlRegisterInterface<Waypoint>("Waypoint");
//-- Register MissionItem Interface
qmlRegisterInterface<MissionItem>("MissionItem");
// Show user an upgrade message if the settings version has been bumped up
bool settingsUpgraded = false;
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
/// 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
}
}
}
}
......@@ -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<UAS*>(_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<UAS*>(_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<Waypoint*> &waypoints = _wpm->getWaypointViewOnlyList();
const QList<MissionItem*> &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();
/*
......
......@@ -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<Waypoint> missionItems READ missionItems NOTIFY missionItemsChanged)
//-- MissionItem management
Q_PROPERTY(QQmlListProperty<MissionItem> 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<Waypoint> missionItems() {return QQmlListProperty<Waypoint>(this, _waypoints); }
QQmlListProperty<MissionItem> missionItems() {return QQmlListProperty<MissionItem>(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<Waypoint*>_waypoints;
QList<MissionItem*>_waypoints;
};
#endif
This diff is collapsed.
......@@ -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;
}
}
......
......@@ -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 **/
......
......@@ -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 **/
......
This diff is collapsed.
......@@ -36,7 +36,7 @@ This file is part of the QGROUNDCONTROL project
#include <QList>
#include <QTimer>
#include <QPointer>
#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<Waypoint *> &getWaypointEditableList(void) {
const QList<MissionItem *> &getWaypointEditableList(void) {
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.
}
const QList<Waypoint *> 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<Waypoint *> 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<MissionItem *> getGlobalFrameWaypointList(); ///< Returns a global waypoint list
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<MissionItem *> 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<Waypoint *> waypointsViewOnly; ///< local copy of current waypoint list on MAV
QList<Waypoint *> waypointsEditable; ///< local editable waypoint list
QPointer<Waypoint> currentWaypointEditable; ///< The currently used waypoint
QList<MissionItem *> waypointsViewOnly; ///< local copy of current waypoint list on MAV
QList<MissionItem *> waypointsEditable; ///< local editable waypoint list
QPointer<MissionItem> currentWaypointEditable; ///< The currently used waypoint
QList<mavlink_mission_item_t *> 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
......
......@@ -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 <qmath.h>
#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<Waypoint*>& list = uas->getWaypointManager()->getWaypointEditableList();
const QList<MissionItem*>& 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();
......
......@@ -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 */
......
......@@ -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)
......
......@@ -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<QWidget> _planView;
QPointer<QWidget> _experimentalPlanView;
QPointer<QWidget> _flightView;
QPointer<QWidget> _setupView;
QPointer<QWidget> _analyzeView;
......@@ -322,7 +318,6 @@ private:
QMap<QDockWidget*, QAction*> _mapDockWidget2Action;