Commit c240c43e authored by Don Gagne's avatar Don Gagne

Use true list models for vehicles and mission items

parent d14444a5
......@@ -261,6 +261,7 @@ HEADERS += \
src/QmlControls/MavlinkQmlSingleton.h \
src/QmlControls/ParameterEditorController.h \
src/QmlControls/ScreenToolsController.h \
src/QmlControls/QmlObjectListModel.h \
src/SerialPortIds.h \
src/uas/FileManager.h \
src/uas/UAS.h \
......@@ -393,6 +394,7 @@ SOURCES += \
src/QGCTemporaryFile.cc \
src/QmlControls/ParameterEditorController.cc \
src/QmlControls/ScreenToolsController.cc \
src/QmlControls/QmlObjectListModel.cc \
src/uas/FileManager.cc \
src/uas/UAS.cc \
src/uas/UASMessageHandler.cc \
......
This diff is collapsed.
......@@ -26,16 +26,18 @@ import QtLocation 5.3
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Vehicle 1.0
/// Marker for displaying a mission item on the map
MapQuickItem {
property int index
property var missionItem ///< Mission Item object
anchorPoint.x: sourceItem.width / 2
anchorPoint.y: sourceItem.height / 2
anchorPoint.x: sourceItem.width / 2
anchorPoint.y: sourceItem.height / 2
coordinate: missionItem.coordinate
sourceItem:
MissionItemIndexLabel {
missionItemIndex: index
missionItemIndex: missionItem.id
}
}
......@@ -21,4 +21,4 @@ QGCWaypointEditor 1.0 QGCWaypointEditor.qml
# MapQuickItems
VehicleMapItem 1.0 VehicleMapItem.qml
MissioMapItem 1.0 MissionMapItem.qml
MissionMapItem 1.0 MissionMapItem.qml
......@@ -37,6 +37,7 @@
class MissionItem : public QObject
{
Q_OBJECT
public:
MissionItem(
QObject *parent = 0,
......@@ -251,6 +252,4 @@ private:
QString _oneDecimalString(double value);
};
QML_DECLARE_TYPE(MissionItem)
#endif
......@@ -84,6 +84,7 @@ G_END_DECLS
#include "Vehicle.h"
#include "MavlinkQmlSingleton.h"
#include "JoystickManager.h"
#include "QmlObjectListModel.h"
#ifndef __ios__
#include "SerialLink.h"
......@@ -328,11 +329,13 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<QGCPalette>("QGroundControl.Palette", 1, 0, "QGCPalette");
qmlRegisterUncreatableType<AutoPilotPlugin>("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", "Can only reference, cannot create");
qmlRegisterUncreatableType<VehicleComponent>("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Can only reference, cannot create");
qmlRegisterUncreatableType<Vehicle>("QGroundControl.Vehicle", 1, 0, "Vehicle", "Can only reference, cannot create");
qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only");
qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only");
qmlRegisterUncreatableType<AutoPilotPlugin> ("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", "Can only reference, cannot create");
qmlRegisterUncreatableType<VehicleComponent> ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", "Can only reference, cannot create");
qmlRegisterUncreatableType<Vehicle> ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Can only reference, cannot create");
qmlRegisterUncreatableType<MissionItem> ("QGroundControl.Vehicle", 1, 0, "MissionItem", "Can only reference, cannot create");
qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only");
qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only");
qmlRegisterUncreatableType<QmlObjectListModel> ("QGroundControl", 1, 0, "QmlObjectListModel", "Reference only");
qmlRegisterType<ViewWidgetController> ("QGroundControl.Controllers", 1, 0, "ViewWidgetController");
qmlRegisterType<ParameterEditorController> ("QGroundControl.Controllers", 1, 0, "ParameterEditorController");
......@@ -353,8 +356,6 @@ void QGCApplication::_initCommon(void)
qmlRegisterSingletonType<ScreenToolsController> ("QGroundControl.ScreenToolsController", 1, 0, "ScreenToolsController", screenToolsControllerSingletonFactory);
qmlRegisterSingletonType<MavlinkQmlSingleton> ("QGroundControl.Mavlink", 1, 0, "Mavlink", mavlinkQmlSingletonFactory);
//-- 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)) {
......
......@@ -2,7 +2,8 @@ import QtQuick 2.2
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2
import QGroundControl.ScreenTools 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
/// Mission item summary display control
Rectangle {
......@@ -18,7 +19,7 @@ Rectangle {
MissionItemIndexLabel {
anchors.top: parent.top
anchors.right: parent.right
missionItemIndex: missionItem.id + 1
missionItemIndex: missionItem.id
}
Column {
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 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/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "QmlObjectListModel.h"
#include <QDebug>
const int QmlObjectListModel::ObjectRole = Qt::UserRole;
QmlObjectListModel::QmlObjectListModel(QObject* parent)
: QAbstractListModel(parent)
{
}
QmlObjectListModel::~QmlObjectListModel()
{
}
int QmlObjectListModel::rowCount(const QModelIndex& parent) const
{
Q_UNUSED(parent);
return _objectList.count();
}
QVariant QmlObjectListModel::data(const QModelIndex &index, int role) const
{
if (!index.isValid()) {
return QVariant();
}
if (index.row() >= _objectList.count()) {
return QVariant();
}
if (role == ObjectRole) {
return QVariant::fromValue(_objectList[index.row()]);
} else {
return QVariant();
}
}
QHash<int, QByteArray> QmlObjectListModel::roleNames(void) const
{
QHash<int, QByteArray> hash;
hash[ObjectRole] = "object";
return hash;
}
bool QmlObjectListModel::setData(const QModelIndex& index, const QVariant& value, int role)
{
if (index.isValid() && role == ObjectRole) {
_objectList.replace(index.row(), value.value<QObject*>());
emit dataChanged(index, index);
return true;
}
return false;
}
bool QmlObjectListModel::insertRows(int position, int rows, const QModelIndex& parent)
{
Q_UNUSED(parent);
beginInsertRows(QModelIndex(), position, position + rows - 1);
endInsertRows();
emit countChanged(count());
return true;
}
bool QmlObjectListModel::removeRows(int position, int rows, const QModelIndex& parent)
{
Q_UNUSED(parent);
beginRemoveRows(QModelIndex(), position, position + rows - 1);
for (int row=0; row<rows; row++) {
_objectList.removeAt(position);
}
endRemoveRows();
emit countChanged(count());
return true;
}
QObject*& QmlObjectListModel::operator[](int index)
{
return _objectList[index];
}
void QmlObjectListModel::clear(void)
{
while (rowCount()) {
removeRows(0, 1);
}
}
void QmlObjectListModel::removeAt(int i)
{
removeRows(i, 1);
}
void QmlObjectListModel::append(QObject* object)
{
_objectList += object;
insertRows(_objectList.count() - 1, 1);
}
int QmlObjectListModel::count(void)
{
return rowCount();
}
QObject* QmlObjectListModel::get(int index)
{
return _objectList[index];
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef QmlObjectListModel_H
#define QmlObjectListModel_H
#include <QAbstractListModel>
class QmlObjectListModel : public QAbstractListModel
{
Q_OBJECT
public:
QmlObjectListModel(QObject* parent = NULL);
~QmlObjectListModel();
Q_INVOKABLE QObject* get(int index);
Q_PROPERTY(int count READ count NOTIFY countChanged)
int count(void);
void append(QObject* object);
void clear(void);
void removeAt(int i);
QObject*& operator[](int i);
// Overrides from QAbstractListModel
virtual int rowCount(const QModelIndex & parent = QModelIndex()) const;
virtual QVariant data(const QModelIndex & index, int role = Qt::DisplayRole) const;
virtual QHash<int, QByteArray> roleNames(void) const;
virtual bool insertRows(int position, int rows, const QModelIndex &index = QModelIndex());
virtual bool removeRows(int position, int rows, const QModelIndex &index = QModelIndex());
virtual bool setData(const QModelIndex &index, const QVariant &value, int role = Qt::EditRole);
signals:
void countChanged(int count);
private:
QList<QObject*> _objectList;
static const int ObjectRole;
};
#endif
......@@ -49,7 +49,7 @@ MultiVehicleManager::~MultiVehicleManager()
bool MultiVehicleManager::notifyHeartbeatInfo(LinkInterface* link, int vehicleId, mavlink_heartbeat_t& heartbeat)
{
if (!_vehicleMap.contains(vehicleId) && !_ignoreVehicleIds.contains(vehicleId)) {
if (!getVehicleById(vehicleId) && !_ignoreVehicleIds.contains(vehicleId)) {
if (vehicleId == MAVLinkProtocol::instance()->getSystemId()) {
qgcApp()->showToolBarMessage(QString("Warning: A vehicle is using the same system id as QGroundControl: %1").arg(vehicleId));
}
......@@ -74,7 +74,7 @@ bool MultiVehicleManager::notifyHeartbeatInfo(LinkInterface* link, int vehicleId
connect(vehicle, &Vehicle::allLinksDisconnected, this, &MultiVehicleManager::_deleteVehiclePhase1);
connect(vehicle->autopilotPlugin(), &AutoPilotPlugin::pluginReadyChanged, this, &MultiVehicleManager::_autopilotPluginReadyChanged);
_vehicleMap[vehicleId] = vehicle;
_vehicles.append(vehicle);
emit vehicleAdded(vehicle);
......@@ -91,10 +91,10 @@ void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle)
_vehicleBeingDeleted = vehicle;
// Remove from map
bool found;
foreach(int id, _vehicleMap.keys()) {
if (_vehicleMap[id] == _vehicleBeingDeleted) {
_vehicleMap.remove(id);
bool found = false;
for (int i=0; i<_vehicles.count(); i++) {
if (_vehicles[i] == _vehicleBeingDeleted) {
_vehicles.removeAt(i);
found = true;
break;
}
......@@ -128,8 +128,8 @@ void MultiVehicleManager::_deleteVehiclePhase2 (void)
/// This means we can now clear the active vehicle property and delete the Vehicle for real.
Vehicle* newActiveVehicle = NULL;
if (_vehicleMap.count()) {
newActiveVehicle = _vehicleMap.first();
if (_vehicles.count()) {
newActiveVehicle = qobject_cast<Vehicle*>(_vehicles[0]);
}
_activeVehicle = newActiveVehicle;
......@@ -205,8 +205,8 @@ void MultiVehicleManager::_autopilotPluginReadyChanged(bool pluginReady)
void MultiVehicleManager::setHomePositionForAllVehicles(double lat, double lon, double alt)
{
foreach (Vehicle* vehicle, _vehicleMap) {
vehicle->uas()->setHomePosition(lat, lon, alt);
for (int i=0; i< _vehicles.count(); i++) {
qobject_cast<Vehicle*>(_vehicles[i])->uas()->setHomePosition(lat, lon, alt);
}
}
......@@ -222,28 +222,6 @@ UASWaypointManager* MultiVehicleManager::activeWaypointManager(void)
return _offlineWaypointManager;
}
QList<Vehicle*> MultiVehicleManager::vehicles(void)
{
QList<Vehicle*> list;
foreach (Vehicle* vehicle, _vehicleMap) {
list += vehicle;
}
return list;
}
QVariantList MultiVehicleManager::vehiclesAsVariants(void)
{
QVariantList list;
foreach (Vehicle* vehicle, _vehicleMap) {
list += QVariant::fromValue(vehicle);
}
return list;
}
void MultiVehicleManager::saveSetting(const QString &name, const QString& value)
{
QSettings settings;
......@@ -255,3 +233,26 @@ QString MultiVehicleManager::loadSetting(const QString &name, const QString& def
QSettings settings;
return settings.value(name, defaultValue).toString();
}
Vehicle* MultiVehicleManager::getVehicleById(int vehicleId)
{
for (int i=0; i< _vehicles.count(); i++) {
Vehicle* vehicle = qobject_cast<Vehicle*>(_vehicles[i]);
if (vehicle->id() == vehicleId) {
return vehicle;
}
}
return NULL;
}
QList<Vehicle*> MultiVehicleManager::vehicles(void)
{
QList<Vehicle*> list;
for (int i=0; i< _vehicles.count(); i++) {
list += qobject_cast<Vehicle*>(_vehicles[i]);
}
return list;
}
......@@ -31,6 +31,7 @@
#include "Vehicle.h"
#include "QGCMAVLink.h"
#include "UASWaypointManager.h"
#include "QmlObjectListModel.h"
class MultiVehicleManager : public QGCSingleton
{
......@@ -42,16 +43,12 @@ public:
Q_INVOKABLE void saveSetting (const QString &key, const QString& value);
Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue);
Q_PROPERTY(bool activeVehicleAvailable READ activeVehicleAvailable NOTIFY activeVehicleAvailableChanged)
Q_PROPERTY(bool parameterReadyVehicleAvailable READ parameterReadyVehicleAvailable NOTIFY parameterReadyVehicleAvailableChanged)
Q_PROPERTY(Vehicle* activeVehicle READ activeVehicle WRITE setActiveVehicle NOTIFY activeVehicleChanged)
Q_PROPERTY(QVariantList vehicles READ vehiclesAsVariants CONSTANT)
Q_PROPERTY(bool activeVehicleAvailable READ activeVehicleAvailable NOTIFY activeVehicleAvailableChanged)
Q_PROPERTY(bool parameterReadyVehicleAvailable READ parameterReadyVehicleAvailable NOTIFY parameterReadyVehicleAvailableChanged)
Q_PROPERTY(Vehicle* activeVehicle READ activeVehicle WRITE setActiveVehicle NOTIFY activeVehicleChanged)
Q_PROPERTY(QmlObjectListModel* vehicles READ vehiclesModel CONSTANT)
// Property accessors
bool activeVehicleAvailable(void) { return _activeVehicleAvailable; }
bool parameterReadyVehicleAvailable(void) { return _parameterReadyVehicleAvailable; }
Vehicle* activeVehicle(void) { return _activeVehicle; }
void setActiveVehicle(Vehicle* vehicle);
// Methods
/// Called to notify that a heartbeat was received with the specified information. MultiVehicleManager
/// will create/update Vehicles as necessary.
......@@ -61,17 +58,27 @@ public:
/// @return true: continue further processing of this message, false: disregard this message
bool notifyHeartbeatInfo(LinkInterface* link, int vehicleId, mavlink_heartbeat_t& heartbeat);
Vehicle* getVehicleById(int vehicleId) { return _vehicleMap[vehicleId]; }
Vehicle* getVehicleById(int vehicleId);
void setHomePositionForAllVehicles(double lat, double lon, double alt);
UAS* activeUas(void) { return _activeVehicle ? _activeVehicle->uas() : NULL; }
QList<Vehicle*> vehicles(void);
QVariantList vehiclesAsVariants(void);
UASWaypointManager* activeWaypointManager(void);
QList<Vehicle*> vehicles(void);
// Property accessors
bool activeVehicleAvailable(void) { return _activeVehicleAvailable; }
bool parameterReadyVehicleAvailable(void) { return _parameterReadyVehicleAvailable; }
Vehicle* activeVehicle(void) { return _activeVehicle; }
void setActiveVehicle(Vehicle* vehicle);
QmlObjectListModel* vehiclesModel(void) { return &_vehicles; }
signals:
void vehicleAdded(Vehicle* vehicle);
void vehicleRemoved(Vehicle* vehicle);
......@@ -103,7 +110,7 @@ private:
QList<int> _ignoreVehicleIds; ///< List of vehicle id for which we ignore further communication
QMap<int, Vehicle*> _vehicleMap; ///< Map of vehicles keyed by id
QmlObjectListModel _vehicles;
UASWaypointManager* _offlineWaypointManager;
};
......
......@@ -148,6 +148,8 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType)
_setSystemType(_mav, _mav->getSystemType());
_updateArmingState(_mav->isArmed());
_waypointViewOnlyListChanged();
_loadSettings();
}
......@@ -721,21 +723,14 @@ void Vehicle::_updateWaypointViewOnly(int, MissionItem* /*wp*/)
void Vehicle::_waypointViewOnlyListChanged()
{
if(_wpm) {
const QList<MissionItem*> &waypoints = _wpm->getWaypointViewOnlyList();
_waypoints.clear();
for(int i = 0; i < waypoints.count(); i++) {
MissionItem* wp = waypoints[i];
_waypoints.append(new MissionItem(*wp));
const QList<MissionItem*>& newMisionItems = _wpm->getWaypointViewOnlyList();
_missionItems.clear();
qCDebug(VehicleLog) << QString("Loading %1 mission items").arg(newMisionItems.count());
for(int i = 0; i < newMisionItems.count(); i++) {
MissionItem* itemToCopy = newMisionItems[i];
MissionItem* item = new MissionItem(*itemToCopy);
_missionItems.append(item);
}
emit missionItemsChanged();
/*
if(_longitude == DEFAULT_LON && _latitude == DEFAULT_LAT && _waypoints.length()) {
_longitude = _waypoints[0]->getLongitude();
_latitude = _waypoints[0]->getLatitude();
emit longitudeChanged();
emit latitudeChanged();
}
*/
}
}
......@@ -929,3 +924,8 @@ void Vehicle::setActive(bool active)
_startJoystick(_active);
}
QmlObjectListModel* Vehicle::missionItemsModel(void)
{
return &_missionItems;
}
......@@ -34,6 +34,7 @@
#include "LinkInterface.h"
#include "QGCMAVLink.h"
#include "MissionItem.h"
#include "QmlObjectListModel.h"
class UAS;
class UASInterface;
......@@ -92,8 +93,8 @@ public:
Q_PROPERTY(uint16_t currentWaypoint READ currentWaypoint NOTIFY currentWaypointChanged)
Q_PROPERTY(unsigned int heartbeatTimeout READ heartbeatTimeout NOTIFY heartbeatTimeoutChanged)
//-- MissionItem management
Q_PROPERTY(QQmlListProperty<MissionItem> missionItems READ missionItems NOTIFY missionItemsChanged)
Q_PROPERTY(QmlObjectListModel* missionItems READ missionItemsModel CONSTANT)
QmlObjectListModel* missionItemsModel(void);
/// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink
/// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
......@@ -202,8 +203,6 @@ public:
uint16_t currentWaypoint () { return _currentWaypoint; }
unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; }
QQmlListProperty<MissionItem> missionItems() {return QQmlListProperty<MissionItem>(this, _waypoints); }
public slots:
void setLatitude(double latitude);
void setLongitude(double longitude);
......@@ -247,7 +246,6 @@ signals:
void satelliteLockChanged ();
void waypointDistanceChanged();
void currentWaypointChanged ();
void missionItemsChanged ();
private slots:
void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
......@@ -352,7 +350,8 @@ private:
int _satelliteLock;
UASWaypointManager* _wpm;
int _updateCount;
QList<MissionItem*>_waypoints;
QmlObjectListModel _missionItems;
static const char* _settingsGroup;
static const char* _joystickModeSettingsKey;
......
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