41 changed files with 1798 additions and 306 deletions
@ -0,0 +1,144 @@
@@ -0,0 +1,144 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#include "APMRallyPointManager.h" |
||||
#include "Vehicle.h" |
||||
#include "FirmwarePlugin.h" |
||||
#include "MAVLinkProtocol.h" |
||||
#include "QGCApplication.h" |
||||
#include "ParameterManager.h" |
||||
|
||||
const char* APMRallyPointManager::_rallyTotalParam = "RALLY_TOTAL"; |
||||
|
||||
APMRallyPointManager::APMRallyPointManager(Vehicle* vehicle) |
||||
: RallyPointManager(vehicle) |
||||
, _readTransactionInProgress(false) |
||||
, _writeTransactionInProgress(false) |
||||
{ |
||||
connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &APMRallyPointManager::_mavlinkMessageReceived); |
||||
} |
||||
|
||||
APMRallyPointManager::~APMRallyPointManager() |
||||
{ |
||||
|
||||
} |
||||
|
||||
void APMRallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints) |
||||
{ |
||||
if (_vehicle->isOfflineEditingVehicle()) { |
||||
return; |
||||
} |
||||
|
||||
if (_readTransactionInProgress) { |
||||
_sendError(InternalError, QStringLiteral("Rally Point write attempted while read in progress.")); |
||||
return; |
||||
} |
||||
|
||||
_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _rallyTotalParam)->setRawValue(rgPoints.count()); |
||||
|
||||
// FIXME: No validation of correct point received
|
||||
_rgPoints = rgPoints; |
||||
for (uint8_t index=0; index<_rgPoints.count(); index++) { |
||||
_sendRallyPoint(index); |
||||
} |
||||
|
||||
emit loadComplete(_rgPoints); |
||||
} |
||||
|
||||
void APMRallyPointManager::loadFromVehicle(void) |
||||
{ |
||||
if (_vehicle->isOfflineEditingVehicle() || _readTransactionInProgress) { |
||||
return; |
||||
} |
||||
|
||||
_rgPoints.clear(); |
||||
|
||||
_cReadRallyPoints = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _rallyTotalParam)->rawValue().toInt(); |
||||
qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::loadFromVehicle" << _cReadRallyPoints; |
||||
if (_cReadRallyPoints == 0) { |
||||
emit loadComplete(_rgPoints); |
||||
return; |
||||
} |
||||
|
||||
_currentRallyPoint = 0; |
||||
_readTransactionInProgress = true; |
||||
_requestRallyPoint(_currentRallyPoint); |
||||
} |
||||
|
||||
/// Called when a new mavlink message for out vehicle is received
|
||||
void APMRallyPointManager::_mavlinkMessageReceived(const mavlink_message_t& message) |
||||
{ |
||||
if (message.msgid == MAVLINK_MSG_ID_RALLY_POINT) { |
||||
mavlink_rally_point_t rallyPoint; |
||||
|
||||
mavlink_msg_rally_point_decode(&message, &rallyPoint); |
||||
qCDebug(RallyPointManagerLog) << "From vehicle rally_point: idx:lat:lng:alt" << rallyPoint.idx << rallyPoint.lat << rallyPoint.lng << rallyPoint.alt; |
||||
|
||||
if (rallyPoint.idx != _currentRallyPoint) { |
||||
// FIXME: Protocol out of whack
|
||||
_readTransactionInProgress = false; |
||||
emit inProgressChanged(inProgress()); |
||||
qCWarning(RallyPointManagerLog) << "Indices out of sync" << rallyPoint.idx << _currentRallyPoint; |
||||
return; |
||||
} |
||||
|
||||
QGeoCoordinate point((float)rallyPoint.lat / 1e7, (float)rallyPoint.lng / 1e7, rallyPoint.alt); |
||||
_rgPoints.append(point); |
||||
if (rallyPoint.idx < _cReadRallyPoints - 2) { |
||||
// Still more points to request
|
||||
_requestRallyPoint(++_currentRallyPoint); |
||||
} else { |
||||
// We've finished collecting rally points
|
||||
qCDebug(RallyPointManagerLog) << "Rally point load complete"; |
||||
_readTransactionInProgress = false; |
||||
emit loadComplete(_rgPoints); |
||||
emit inProgressChanged(inProgress()); |
||||
} |
||||
} |
||||
} |
||||
|
||||
void APMRallyPointManager::_requestRallyPoint(uint8_t pointIndex) |
||||
{ |
||||
mavlink_message_t msg; |
||||
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); |
||||
|
||||
qCDebug(RallyPointManagerLog) << "APMRallyPointManager::_requestRallyPoint" << pointIndex; |
||||
mavlink_msg_rally_fetch_point_pack(mavlink->getSystemId(), |
||||
mavlink->getComponentId(), |
||||
&msg, |
||||
_vehicle->id(), |
||||
_vehicle->defaultComponentId(), |
||||
pointIndex); |
||||
_vehicle->sendMessageOnPriorityLink(msg); |
||||
} |
||||
|
||||
void APMRallyPointManager::_sendRallyPoint(uint8_t pointIndex) |
||||
{ |
||||
mavlink_message_t msg; |
||||
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); |
||||
|
||||
QGeoCoordinate point = _rgPoints[pointIndex]; |
||||
mavlink_msg_rally_point_pack(mavlink->getSystemId(), |
||||
mavlink->getComponentId(), |
||||
&msg, |
||||
_vehicle->id(), |
||||
_vehicle->defaultComponentId(), |
||||
pointIndex, |
||||
_rgPoints.count(), |
||||
point.latitude() * 1e7, |
||||
point.longitude() * 1e7, |
||||
point.altitude(), |
||||
0, 0, 0); // break_alt, land_dir, flags
|
||||
_vehicle->sendMessageOnPriorityLink(msg); |
||||
} |
||||
|
||||
bool APMRallyPointManager::inProgress(void) const |
||||
{ |
||||
return _readTransactionInProgress || _writeTransactionInProgress; |
||||
} |
@ -0,0 +1,49 @@
@@ -0,0 +1,49 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#ifndef APMRallyPointManager_H |
||||
#define APMRallyPointManager_H |
||||
|
||||
#include "RallyPointManager.h" |
||||
#include "QGCMAVLink.h" |
||||
|
||||
class APMRallyPointManager : public RallyPointManager |
||||
{ |
||||
Q_OBJECT |
||||
|
||||
public: |
||||
APMRallyPointManager(Vehicle* vehicle); |
||||
~APMRallyPointManager(); |
||||
|
||||
// Overrides from RallyPointManager
|
||||
bool inProgress (void) const final; |
||||
void loadFromVehicle (void) final; |
||||
void sendToVehicle (const QList<QGeoCoordinate>& rgPoints) final; |
||||
bool rallyPointsSupported (void) const final { return true; } |
||||
|
||||
QString editorQml(void) const final { return QStringLiteral("qrc:/FirmwarePlugin/APM/APMRallyPointEditor.qml"); } |
||||
|
||||
private slots: |
||||
void _mavlinkMessageReceived(const mavlink_message_t& message); |
||||
|
||||
private: |
||||
void _requestRallyPoint(uint8_t pointIndex); |
||||
void _sendRallyPoint(uint8_t pointIndex); |
||||
|
||||
private: |
||||
bool _readTransactionInProgress; |
||||
bool _writeTransactionInProgress; |
||||
|
||||
uint8_t _cReadRallyPoints; |
||||
uint8_t _currentRallyPoint; |
||||
|
||||
static const char* _rallyTotalParam; |
||||
}; |
||||
|
||||
#endif |
@ -0,0 +1,68 @@
@@ -0,0 +1,68 @@
|
||||
import QtQuick 2.2 |
||||
import QtQuick.Controls 1.2 |
||||
|
||||
import QGroundControl 1.0 |
||||
import QGroundControl.ScreenTools 1.0 |
||||
import QGroundControl.Controls 1.0 |
||||
|
||||
QGCFlickable { |
||||
height: outerEditorRect.height |
||||
contentHeight: outerEditorRect.height |
||||
clip: true |
||||
|
||||
property var controller ///< RallyPointController |
||||
|
||||
readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2 |
||||
readonly property real _radius: ScreenTools.defaultFontPixelWidth / 2 |
||||
|
||||
Rectangle { |
||||
id: outerEditorRect |
||||
width: parent.width |
||||
height: innerEditorRect.y + innerEditorRect.height + (_margin * 2) |
||||
radius: _radius |
||||
color: qgcPal.buttonHighlight |
||||
|
||||
QGCLabel { |
||||
id: editorLabel |
||||
anchors.margins: _margin |
||||
anchors.left: parent.left |
||||
anchors.top: parent.top |
||||
text: qsTr("Rally Points (WIP careful!)") |
||||
color: "black" |
||||
} |
||||
|
||||
Rectangle { |
||||
id: innerEditorRect |
||||
anchors.margins: _margin |
||||
anchors.left: parent.left |
||||
anchors.right: parent.right |
||||
anchors.top: editorLabel.bottom |
||||
height: helpLabel.y + helpLabel.height + (_margin * 2) |
||||
color: qgcPal.windowShadeDark |
||||
radius: _radius |
||||
|
||||
QGCLabel { |
||||
id: infoLabel |
||||
anchors.margins: _margin |
||||
anchors.top: parent.top |
||||
anchors.left: parent.left |
||||
anchors.right: parent.right |
||||
wrapMode: Text.WordWrap |
||||
font.pointSize: ScreenTools.smallFontPointSize |
||||
text: qsTr("Rally Points provide alternate landing points when performing a Return to Launch (RTL).") |
||||
} |
||||
|
||||
QGCLabel { |
||||
id: helpLabel |
||||
anchors.margins: _margin |
||||
anchors.left: parent.left |
||||
anchors.right: parent.right |
||||
anchors.top: infoLabel.bottom |
||||
wrapMode: Text.WordWrap |
||||
text: controller.rallyPointsSupported ? |
||||
qsTr("Click in the map to add new rally points.") : |
||||
qsTr("This vehicle does not support Rally Points.") |
||||
} |
||||
} |
||||
} |
||||
} |
@ -0,0 +1,124 @@
@@ -0,0 +1,124 @@
|
||||
import QtQuick 2.2 |
||||
import QtQuick.Controls 1.2 |
||||
import QtQuick.Controls.Styles 1.2 |
||||
import QtQuick.Dialogs 1.2 |
||||
|
||||
import QGroundControl.ScreenTools 1.0 |
||||
import QGroundControl.Vehicle 1.0 |
||||
import QGroundControl.Controls 1.0 |
||||
import QGroundControl.FactControls 1.0 |
||||
import QGroundControl.Palette 1.0 |
||||
|
||||
Rectangle { |
||||
id: root |
||||
height: _currentItem ? valuesRect.y + valuesRect.height + (_margin * 2) : titleBar.y - titleBar.height + _margin |
||||
color: _currentItem ? qgcPal.buttonHighlight : qgcPal.windowShade |
||||
radius: _radius |
||||
|
||||
property var rallyPoint ///< RallyPoint object associated with editor |
||||
property var controller ///< RallyPointController |
||||
|
||||
property bool _currentItem: rallyPoint ? rallyPoint == controller.currentRallyPoint : false |
||||
property color _outerTextColor: _currentItem ? "black" : qgcPal.text |
||||
|
||||
readonly property real _editFieldWidth: Math.min(width - _margin * 2, ScreenTools.defaultFontPixelWidth * 12) |
||||
readonly property real _margin: ScreenTools.defaultFontPixelWidth / 2 |
||||
readonly property real _radius: ScreenTools.defaultFontPixelWidth / 2 |
||||
readonly property real _titleHeight: ScreenTools.defaultFontPixelHeight * 2 |
||||
|
||||
QGCPalette { id: qgcPal; colorGroupEnabled: true } |
||||
|
||||
Item { |
||||
id: titleBar |
||||
anchors.margins: _margin |
||||
anchors.top: parent.top |
||||
anchors.left: parent.left |
||||
anchors.right: parent.right |
||||
height: _titleHeight |
||||
|
||||
MissionItemIndexLabel { |
||||
id: indicator |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
anchors.left: parent.left |
||||
label: "R" |
||||
checked: true |
||||
} |
||||
|
||||
QGCLabel { |
||||
anchors.leftMargin: _margin |
||||
anchors.left: indicator.right |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
text: qsTr("Rally Point") |
||||
color: _outerTextColor |
||||
} |
||||
|
||||
Image { |
||||
id: hamburger |
||||
anchors.rightMargin: _margin |
||||
anchors.right: parent.right |
||||
anchors.verticalCenter: parent.verticalCenter |
||||
width: ScreenTools.defaultFontPixelWidth * 2 |
||||
height: width |
||||
sourceSize.height: height |
||||
source: "qrc:/qmlimages/Hamburger.svg" |
||||
|
||||
MouseArea { |
||||
anchors.fill: parent |
||||
onClicked: hamburgerMenu.popup() |
||||
|
||||
Menu { |
||||
id: hamburgerMenu |
||||
|
||||
MenuItem { |
||||
text: qsTr("Delete") |
||||
onTriggered: controller.removePoint(rallyPoint) |
||||
} |
||||
} |
||||
} |
||||
} |
||||
} // Item - titleBar |
||||
|
||||
Rectangle { |
||||
id: valuesRect |
||||
anchors.margins: _margin |
||||
anchors.left: parent.left |
||||
anchors.right: parent.right |
||||
anchors.top: titleBar.bottom |
||||
height: valuesColumn.height + (_margin * 2) |
||||
color: qgcPal.windowShadeDark |
||||
visible: _currentItem |
||||
radius: _radius |
||||
|
||||
Column { |
||||
id: valuesColumn |
||||
anchors.margins: _margin |
||||
anchors.left: parent.left |
||||
anchors.right: parent.right |
||||
anchors.top: parent.top |
||||
spacing: _margin |
||||
|
||||
Repeater { |
||||
model: rallyPoint ? rallyPoint.textFieldFacts : 0 |
||||
|
||||
Item { |
||||
width: valuesColumn.width |
||||
height: textField.height |
||||
|
||||
QGCLabel { |
||||
id: textFieldLabel |
||||
anchors.baseline: textField.baseline |
||||
text: modelData.name + ":" |
||||
} |
||||
|
||||
FactTextField { |
||||
id: textField |
||||
anchors.right: parent.right |
||||
width: _editFieldWidth |
||||
showUnits: true |
||||
fact: modelData |
||||
} |
||||
} |
||||
} // Repeater - text fields |
||||
} // Column |
||||
} // Rectangle |
||||
} // Rectangle |
@ -0,0 +1,110 @@
@@ -0,0 +1,110 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
|
||||
#include <QStringList> |
||||
#include <QDebug> |
||||
|
||||
#include "RallyPoint.h" |
||||
|
||||
const char* RallyPoint::_longitudeFactName = "Longitude"; |
||||
const char* RallyPoint::_latitudeFactName = "Latitude"; |
||||
const char* RallyPoint::_altitudeFactName = "Altitude"; |
||||
|
||||
QMap<QString, FactMetaData*> RallyPoint::_metaDataMap; |
||||
|
||||
RallyPoint::RallyPoint(const QGeoCoordinate& coordinate, QObject* parent) |
||||
: QObject(parent) |
||||
, _dirty(false) |
||||
, _longitudeFact(0, _longitudeFactName, FactMetaData::valueTypeDouble) |
||||
, _latitudeFact(0, _latitudeFactName, FactMetaData::valueTypeDouble) |
||||
, _altitudeFact(0, _altitudeFactName, FactMetaData::valueTypeDouble) |
||||
{ |
||||
setCoordinate(coordinate); |
||||
|
||||
_factSetup(); |
||||
} |
||||
|
||||
RallyPoint::RallyPoint(const RallyPoint& other, QObject* parent) |
||||
: QObject(parent) |
||||
, _dirty(false) |
||||
, _longitudeFact(0, _longitudeFactName, FactMetaData::valueTypeDouble) |
||||
, _latitudeFact(0, _latitudeFactName, FactMetaData::valueTypeDouble) |
||||
, _altitudeFact(0, _altitudeFactName, FactMetaData::valueTypeDouble) |
||||
{ |
||||
_longitudeFact.setRawValue(other._longitudeFact.rawValue()); |
||||
_latitudeFact.setRawValue(other._latitudeFact.rawValue()); |
||||
_altitudeFact.setRawValue(other._altitudeFact.rawValue()); |
||||
|
||||
_factSetup(); |
||||
} |
||||
|
||||
const RallyPoint& RallyPoint::operator=(const RallyPoint& other) |
||||
{ |
||||
_longitudeFact.setRawValue(other._longitudeFact.rawValue()); |
||||
_latitudeFact.setRawValue(other._latitudeFact.rawValue()); |
||||
_altitudeFact.setRawValue(other._altitudeFact.rawValue()); |
||||
|
||||
emit coordinateChanged(coordinate()); |
||||
|
||||
return *this; |
||||
} |
||||
|
||||
RallyPoint::~RallyPoint() |
||||
{
|
||||
|
||||
} |
||||
|
||||
void RallyPoint::_factSetup(void) |
||||
{ |
||||
if (_metaDataMap.isEmpty()) { |
||||
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/RallyPoint.json"), NULL /* metaDataParent */); |
||||
} |
||||
|
||||
_longitudeFact.setMetaData(_metaDataMap[_longitudeFactName]); |
||||
_latitudeFact.setMetaData(_metaDataMap[_latitudeFactName]); |
||||
_altitudeFact.setMetaData(_metaDataMap[_altitudeFactName]); |
||||
|
||||
_textFieldFacts.append(QVariant::fromValue(&_longitudeFact)); |
||||
_textFieldFacts.append(QVariant::fromValue(&_latitudeFact)); |
||||
_textFieldFacts.append(QVariant::fromValue(&_altitudeFact)); |
||||
|
||||
connect(&_longitudeFact, &Fact::valueChanged, this, &RallyPoint::_sendCoordinateChanged); |
||||
connect(&_latitudeFact, &Fact::valueChanged, this, &RallyPoint::_sendCoordinateChanged); |
||||
connect(&_altitudeFact, &Fact::valueChanged, this, &RallyPoint::_sendCoordinateChanged); |
||||
} |
||||
|
||||
void RallyPoint::setCoordinate(const QGeoCoordinate& coordinate) |
||||
{ |
||||
if (coordinate != this->coordinate()) { |
||||
_longitudeFact.setRawValue(coordinate.longitude()); |
||||
_latitudeFact.setRawValue(coordinate.latitude()); |
||||
_altitudeFact.setRawValue(coordinate.altitude()); |
||||
emit coordinateChanged(coordinate); |
||||
setDirty(true); |
||||
} |
||||
} |
||||
|
||||
void RallyPoint::setDirty(bool dirty) |
||||
{ |
||||
if (dirty != _dirty) { |
||||
_dirty = dirty; |
||||
emit dirtyChanged(dirty); |
||||
} |
||||
} |
||||
|
||||
QGeoCoordinate RallyPoint::coordinate(void) const |
||||
{ |
||||
return QGeoCoordinate(_latitudeFact.rawValue().toDouble(), _longitudeFact.rawValue().toDouble(), _altitudeFact.rawValue().toDouble()); |
||||
} |
||||
|
||||
void RallyPoint::_sendCoordinateChanged(void) |
||||
{ |
||||
emit coordinateChanged(coordinate()); |
||||
} |
@ -0,0 +1,66 @@
@@ -0,0 +1,66 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#ifndef RallyPoint_H |
||||
#define RallyPoint_H |
||||
|
||||
#include <QObject> |
||||
#include <QGeoCoordinate> |
||||
|
||||
#include "FactSystem.h" |
||||
|
||||
/// This class is used to encapsulate the QGeoCoordinate associated with a Rally Point into a QObject such
|
||||
/// that it can be used in a QmlObjectListMode for Qml.
|
||||
class RallyPoint : public QObject |
||||
{ |
||||
Q_OBJECT |
||||
|
||||
public: |
||||
RallyPoint(const QGeoCoordinate& coordinate, QObject* parent = NULL); |
||||
RallyPoint(const RallyPoint& other, QObject* parent = NULL); |
||||
|
||||
~RallyPoint(); |
||||
|
||||
const RallyPoint& operator=(const RallyPoint& other); |
||||
|
||||
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) |
||||
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) |
||||
Q_PROPERTY(QVariantList textFieldFacts MEMBER _textFieldFacts CONSTANT) |
||||
|
||||
QGeoCoordinate coordinate(void) const; |
||||
void setCoordinate(const QGeoCoordinate& coordinate); |
||||
|
||||
bool dirty(void) const { return _dirty; } |
||||
void setDirty(bool dirty); |
||||
|
||||
signals: |
||||
void coordinateChanged (const QGeoCoordinate& coordinate); |
||||
void dirtyChanged (bool dirty); |
||||
|
||||
private slots: |
||||
void _sendCoordinateChanged(void); |
||||
|
||||
private: |
||||
void _factSetup(void); |
||||
|
||||
bool _dirty; |
||||
Fact _longitudeFact; |
||||
Fact _latitudeFact; |
||||
Fact _altitudeFact; |
||||
|
||||
QVariantList _textFieldFacts; |
||||
|
||||
static QMap<QString, FactMetaData*> _metaDataMap; |
||||
|
||||
static const char* _longitudeFactName; |
||||
static const char* _latitudeFactName; |
||||
static const char* _altitudeFactName; |
||||
}; |
||||
|
||||
#endif |
@ -0,0 +1,21 @@
@@ -0,0 +1,21 @@
|
||||
[ |
||||
{ |
||||
"name": "Latitude", |
||||
"shortDescription": "Latitude of rally point position", |
||||
"type": "double", |
||||
"decimalPlaces": 7 |
||||
}, |
||||
{ |
||||
"name": "Longitude", |
||||
"shortDescription": "Longitude of rally point position", |
||||
"type": "double", |
||||
"decimalPlaces": 7 |
||||
}, |
||||
{ |
||||
"name": "Altitude", |
||||
"shortDescription": "Altitude of rally point position (home relative)", |
||||
"type": "double", |
||||
"decimalPlaces": 2, |
||||
"units": "m" |
||||
} |
||||
] |
@ -0,0 +1,314 @@
@@ -0,0 +1,314 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
|
||||
/// @file
|
||||
/// @author Don Gagne <don@thegagnes.com>
|
||||
|
||||
#include "RallyPointController.h" |
||||
#include "RallyPoint.h" |
||||
#include "Vehicle.h" |
||||
#include "FirmwarePlugin.h" |
||||
#include "MAVLinkProtocol.h" |
||||
#include "QGCApplication.h" |
||||
#include "ParameterManager.h" |
||||
#include "JsonHelper.h" |
||||
#include "SimpleMissionItem.h" |
||||
|
||||
#ifndef __mobile__ |
||||
#include "QGCFileDialog.h" |
||||
#endif |
||||
|
||||
#include <QJsonDocument> |
||||
#include <QJsonArray> |
||||
|
||||
QGC_LOGGING_CATEGORY(RallyPointControllerLog, "RallyPointControllerLog") |
||||
|
||||
const char* RallyPointController::_jsonFileTypeValue = "RallyPoints"; |
||||
const char* RallyPointController::_jsonPointsKey = "points"; |
||||
|
||||
RallyPointController::RallyPointController(QObject* parent) |
||||
: PlanElementController(parent) |
||||
, _dirty(false) |
||||
, _currentRallyPoint(NULL) |
||||
{ |
||||
|
||||
} |
||||
|
||||
RallyPointController::~RallyPointController() |
||||
{ |
||||
|
||||
} |
||||
|
||||
void RallyPointController::start(bool editMode) |
||||
{ |
||||
qCDebug(RallyPointControllerLog) << "start editMode" << editMode; |
||||
|
||||
PlanElementController::start(editMode); |
||||
} |
||||
|
||||
void RallyPointController::_activeVehicleBeingRemoved(void) |
||||
{ |
||||
_activeVehicle->rallyPointManager()->disconnect(this); |
||||
_points.clearAndDeleteContents(); |
||||
} |
||||
|
||||
void RallyPointController::_activeVehicleSet(void) |
||||
{ |
||||
RallyPointManager* rallyPointManager = _activeVehicle->rallyPointManager(); |
||||
connect(rallyPointManager, &RallyPointManager::loadComplete, this, &RallyPointController::_loadComplete); |
||||
connect(rallyPointManager, &RallyPointManager::inProgressChanged, this, &RallyPointController::syncInProgressChanged); |
||||
|
||||
if (!rallyPointManager->inProgress()) { |
||||
_loadComplete(rallyPointManager->points()); |
||||
} |
||||
emit rallyPointsSupportedChanged(rallyPointsSupported()); |
||||
} |
||||
|
||||
bool RallyPointController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorString) |
||||
{ |
||||
QJsonObject json = jsonDoc.object(); |
||||
|
||||
int fileMajorVersion, fileMinorVersion; |
||||
if (!JsonHelper::validateQGCJsonFile(json, _jsonFileTypeValue, 1 /* supportedMajorVersion */, 0 /* supportedMinorVersion */, fileMajorVersion, fileMinorVersion, errorString)) { |
||||
return false; |
||||
} |
||||
|
||||
// Check for required keys
|
||||
QStringList requiredKeys = { _jsonPointsKey }; |
||||
if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorString)) { |
||||
return false; |
||||
} |
||||
|
||||
// Load points
|
||||
|
||||
QList<QGeoCoordinate> rgPoints; |
||||
if (!JsonHelper::loadGeoCoordinateArray(json[_jsonPointsKey], true /* altitudeRequired */, rgPoints, errorString)) { |
||||
return false; |
||||
}
|
||||
_points.clearAndDeleteContents(); |
||||
QObjectList pointList; |
||||
for (int i=0; i<rgPoints.count(); i++) { |
||||
pointList.append(new RallyPoint(rgPoints[i], this)); |
||||
} |
||||
_points.swapObjectList(pointList); |
||||
|
||||
return true; |
||||
} |
||||
|
||||
void RallyPointController::loadFromFile(const QString& filename) |
||||
{ |
||||
QString errorString; |
||||
|
||||
if (filename.isEmpty()) { |
||||
return; |
||||
} |
||||
|
||||
QFile file(filename); |
||||
|
||||
if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) { |
||||
errorString = file.errorString(); |
||||
} else { |
||||
QJsonDocument jsonDoc; |
||||
QByteArray bytes = file.readAll(); |
||||
|
||||
if (JsonHelper::isJsonFile(bytes, jsonDoc)) { |
||||
_loadJsonFile(jsonDoc, errorString); |
||||
} else { |
||||
// FIXME: No MP file format support
|
||||
qgcApp()->showMessage("Rall Point file is in incorrect format."); |
||||
return; |
||||
} |
||||
} |
||||
|
||||
if (!errorString.isEmpty()) { |
||||
qgcApp()->showMessage(errorString); |
||||
} |
||||
|
||||
setDirty(true); |
||||
_setFirstPointCurrent(); |
||||
} |
||||
|
||||
void RallyPointController::loadFromFilePicker(void) |
||||
{ |
||||
#ifndef __mobile__ |
||||
QString filename = QGCFileDialog::getOpenFileName(NULL, "Select Rally Point File to load", QString(), "Rally point file (*.rally);;All Files (*.*)"); |
||||
|
||||
if (filename.isEmpty()) { |
||||
return; |
||||
} |
||||
loadFromFile(filename); |
||||
#endif |
||||
} |
||||
|
||||
void RallyPointController::saveToFile(const QString& filename) |
||||
{ |
||||
if (filename.isEmpty()) { |
||||
return; |
||||
} |
||||
|
||||
QString rallyFilename = filename; |
||||
if (!QFileInfo(filename).fileName().contains(".")) { |
||||
rallyFilename += QString(".%1").arg(QGCApplication::rallyPointFileExtension); |
||||
} |
||||
|
||||
QFile file(rallyFilename); |
||||
|
||||
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) { |
||||
qgcApp()->showMessage(file.errorString()); |
||||
} else { |
||||
QJsonObject jsonObject; |
||||
|
||||
jsonObject[JsonHelper::jsonFileTypeKey] = _jsonFileTypeValue; |
||||
jsonObject[JsonHelper::jsonVersionKey] = QStringLiteral("1.0"); |
||||
jsonObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue; |
||||
|
||||
QJsonArray rgPoints; |
||||
QJsonValue jsonPoint; |
||||
for (int i=0; i<_points.count(); i++) { |
||||
JsonHelper::saveGeoCoordinate(qobject_cast<RallyPoint*>(_points[i])->coordinate(), true /* writeAltitude */, jsonPoint); |
||||
rgPoints.append(jsonPoint); |
||||
} |
||||
jsonObject[_jsonPointsKey] = QJsonValue(rgPoints); |
||||
|
||||
QJsonDocument saveDoc(jsonObject); |
||||
file.write(saveDoc.toJson()); |
||||
} |
||||
|
||||
setDirty(false); |
||||
} |
||||
|
||||
void RallyPointController::saveToFilePicker(void) |
||||
{ |
||||
#ifndef __mobile__ |
||||
QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save Rally Points to", QString(), "Rally point file (*.rally);;All Files (*.*)"); |
||||
|
||||
if (filename.isEmpty()) { |
||||
return; |
||||
} |
||||
saveToFile(filename); |
||||
#endif |
||||
} |
||||
|
||||
void RallyPointController::removeAll(void) |
||||
{ |
||||
_points.clearAndDeleteContents(); |
||||
setDirty(true); |
||||
setCurrentRallyPoint(NULL); |
||||
} |
||||
|
||||
void RallyPointController::loadFromVehicle(void) |
||||
{ |
||||
if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) { |
||||
_activeVehicle->rallyPointManager()->loadFromVehicle(); |
||||
} else { |
||||
qCWarning(RallyPointControllerLog) << "RallyPointController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress(); |
||||
} |
||||
} |
||||
|
||||
void RallyPointController::sendToVehicle(void) |
||||
{ |
||||
if (!syncInProgress()) { |
||||
setDirty(false); |
||||
QList<QGeoCoordinate> rgPoints; |
||||
for (int i=0; i<_points.count(); i++) { |
||||
rgPoints.append(qobject_cast<RallyPoint*>(_points[i])->coordinate()); |
||||
} |
||||
_activeVehicle->rallyPointManager()->sendToVehicle(rgPoints); |
||||
} else { |
||||
qCWarning(RallyPointControllerLog) << "RallyPointController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress(); |
||||
} |
||||
} |
||||
|
||||
bool RallyPointController::syncInProgress(void) const |
||||
{ |
||||
return _activeVehicle->rallyPointManager()->inProgress(); |
||||
} |
||||
|
||||
void RallyPointController::setDirty(bool dirty) |
||||
{ |
||||
if (dirty != _dirty) { |
||||
_dirty = dirty; |
||||
emit dirtyChanged(dirty); |
||||
} |
||||
} |
||||
|
||||
QString RallyPointController::editorQml(void) const |
||||
{ |
||||
return _activeVehicle->rallyPointManager()->editorQml(); |
||||
} |
||||
|
||||
void RallyPointController::_loadComplete(const QList<QGeoCoordinate> rgPoints) |
||||
{ |
||||
_points.clearAndDeleteContents(); |
||||
QObjectList pointList; |
||||
for (int i=0; i<rgPoints.count(); i++) { |
||||
pointList.append(new RallyPoint(rgPoints[i], this)); |
||||
} |
||||
_points.swapObjectList(pointList); |
||||
setDirty(false); |
||||
_setFirstPointCurrent(); |
||||
} |
||||
|
||||
QString RallyPointController::fileExtension(void) const |
||||
{ |
||||
return QGCApplication::rallyPointFileExtension; |
||||
} |
||||
|
||||
void RallyPointController::addPoint(QGeoCoordinate point) |
||||
{ |
||||
double defaultAlt; |
||||
if (_points.count()) { |
||||
defaultAlt = qobject_cast<RallyPoint*>(_points[_points.count() - 1])->coordinate().altitude(); |
||||
} else { |
||||
defaultAlt = SimpleMissionItem::defaultAltitude; |
||||
} |
||||
point.setAltitude(defaultAlt); |
||||
RallyPoint* newPoint = new RallyPoint(point, this); |
||||
_points.append(newPoint); |
||||
setCurrentRallyPoint(newPoint); |
||||
setDirty(true); |
||||
} |
||||
|
||||
bool RallyPointController::rallyPointsSupported(void) const |
||||
{ |
||||
return _activeVehicle->rallyPointManager()->rallyPointsSupported(); |
||||
} |
||||
|
||||
void RallyPointController::removePoint(QObject* rallyPoint) |
||||
{ |
||||
int foundIndex = 0; |
||||
for (foundIndex=0; foundIndex<_points.count(); foundIndex++) { |
||||
if (_points[foundIndex] == rallyPoint) { |
||||
_points.removeOne(rallyPoint); |
||||
rallyPoint->deleteLater(); |
||||
} |
||||
} |
||||
|
||||
if (_points.count()) { |
||||
int newIndex = qMin(foundIndex, _points.count() - 1); |
||||
newIndex = qMax(newIndex, 0); |
||||
setCurrentRallyPoint(_points[newIndex]); |
||||
} else { |
||||
setCurrentRallyPoint(NULL); |
||||
} |
||||
} |
||||
|
||||
void RallyPointController::setCurrentRallyPoint(QObject* rallyPoint) |
||||
{ |
||||
if (_currentRallyPoint != rallyPoint) { |
||||
_currentRallyPoint = rallyPoint; |
||||
emit currentRallyPointChanged(rallyPoint); |
||||
} |
||||
} |
||||
|
||||
void RallyPointController::_setFirstPointCurrent(void) |
||||
{ |
||||
setCurrentRallyPoint(_points.count() ? _points[0] : NULL); |
||||
} |
@ -0,0 +1,83 @@
@@ -0,0 +1,83 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#ifndef RallyPointController_H |
||||
#define RallyPointController_H |
||||
|
||||
#include "PlanElementController.h" |
||||
#include "RallyPointManager.h" |
||||
#include "Vehicle.h" |
||||
#include "MultiVehicleManager.h" |
||||
#include "QGCLoggingCategory.h" |
||||
#include "QmlObjectListModel.h" |
||||
|
||||
Q_DECLARE_LOGGING_CATEGORY(RallyPointControllerLog) |
||||
|
||||
class GeoFenceManager; |
||||
|
||||
class RallyPointController : public PlanElementController |
||||
{ |
||||
Q_OBJECT |
||||
|
||||
public: |
||||
RallyPointController(QObject* parent = NULL); |
||||
~RallyPointController(); |
||||
|
||||
Q_PROPERTY(bool rallyPointsSupported READ rallyPointsSupported NOTIFY rallyPointsSupportedChanged) |
||||
Q_PROPERTY(QmlObjectListModel* points READ points CONSTANT) |
||||
Q_PROPERTY(QString editorQml READ editorQml CONSTANT) |
||||
Q_PROPERTY(QObject* currentRallyPoint READ currentRallyPoint WRITE setCurrentRallyPoint NOTIFY currentRallyPointChanged) |
||||
|
||||
Q_INVOKABLE void addPoint(QGeoCoordinate point); |
||||
Q_INVOKABLE void removePoint(QObject* rallyPoint); |
||||
|
||||
void start (bool editMode) final; |
||||
void loadFromVehicle (void) final; |
||||
void sendToVehicle (void) final; |
||||
void loadFromFilePicker (void) final; |
||||
void loadFromFile (const QString& filename) final; |
||||
void saveToFilePicker (void) final; |
||||
void saveToFile (const QString& filename) final; |
||||
void removeAll (void) final; |
||||
bool syncInProgress (void) const final; |
||||
bool dirty (void) const final { return _dirty; } |
||||
void setDirty (bool dirty) final; |
||||
|
||||
QString fileExtension(void) const final; |
||||
|
||||
bool rallyPointsSupported (void) const; |
||||
QmlObjectListModel* points (void) { return &_points; } |
||||
QString editorQml (void) const; |
||||
QObject* currentRallyPoint (void) const { return _currentRallyPoint; } |
||||
|
||||
void setCurrentRallyPoint(QObject* rallyPoint); |
||||
|
||||
signals: |
||||
void rallyPointsSupportedChanged(bool rallyPointsSupported); |
||||
void currentRallyPointChanged(QObject* rallyPoint); |
||||
|
||||
private slots: |
||||
void _loadComplete(const QList<QGeoCoordinate> rgPoints); |
||||
void _setFirstPointCurrent(void); |
||||
|
||||
private: |
||||
bool _loadJsonFile(QJsonDocument& jsonDoc, QString& errorString); |
||||
|
||||
void _activeVehicleBeingRemoved(void) final; |
||||
void _activeVehicleSet(void) final; |
||||
|
||||
bool _dirty; |
||||
QmlObjectListModel _points; |
||||
QObject* _currentRallyPoint; |
||||
|
||||
static const char* _jsonFileTypeValue; |
||||
static const char* _jsonPointsKey; |
||||
}; |
||||
|
||||
#endif |
@ -0,0 +1,44 @@
@@ -0,0 +1,44 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#include "RallyPointManager.h" |
||||
#include "Vehicle.h" |
||||
|
||||
QGC_LOGGING_CATEGORY(RallyPointManagerLog, "RallyPointManagerLog") |
||||
|
||||
RallyPointManager::RallyPointManager(Vehicle* vehicle) |
||||
: QObject(vehicle) |
||||
, _vehicle(vehicle) |
||||
{ |
||||
|
||||
} |
||||
|
||||
RallyPointManager::~RallyPointManager() |
||||
{ |
||||
|
||||
} |
||||
|
||||
void RallyPointManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg) |
||||
{ |
||||
qCDebug(RallyPointManagerLog) << "Sending error" << errorCode << errorMsg; |
||||
|
||||
emit error(errorCode, errorMsg); |
||||
} |
||||
|
||||
void RallyPointManager::loadFromVehicle(void) |
||||
{ |
||||
// No support in generic vehicle
|
||||
loadComplete(QList<QGeoCoordinate>()); |
||||
} |
||||
|
||||
void RallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints) |
||||
{ |
||||
Q_UNUSED(rgPoints); |
||||
// No support in generic vehicle
|
||||
} |
@ -0,0 +1,67 @@
@@ -0,0 +1,67 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||
* |
||||
* QGroundControl is licensed according to the terms in the file |
||||
* COPYING.md in the root of the source code directory. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
#ifndef RallyPointManager_H |
||||
#define RallyPointManager_H |
||||
|
||||
#include <QObject> |
||||
#include <QGeoCoordinate> |
||||
|
||||
#include "QGCLoggingCategory.h" |
||||
|
||||
class Vehicle; |
||||
|
||||
Q_DECLARE_LOGGING_CATEGORY(RallyPointManagerLog) |
||||
|
||||
/// This is the base class for firmware specific rally point managers. A rally point manager is responsible
|
||||
/// for communicating with the vehicle to set/get rally points.
|
||||
class RallyPointManager : public QObject |
||||
{ |
||||
Q_OBJECT |
||||
|
||||
public: |
||||
RallyPointManager(Vehicle* vehicle); |
||||
~RallyPointManager(); |
||||
|
||||
/// Returns true if the manager is currently communicating with the vehicle
|
||||
virtual bool inProgress(void) const { return false; } |
||||
|
||||
/// Load the current settings from the vehicle
|
||||
virtual void loadFromVehicle(void); |
||||
|
||||
/// Send the current settings to the vehicle
|
||||
virtual void sendToVehicle(const QList<QGeoCoordinate>& rgPoints); |
||||
|
||||
virtual bool rallyPointsSupported(void) const { return false; } |
||||
|
||||
QList<QGeoCoordinate> points(void) const { return _rgPoints; } |
||||
|
||||
virtual QString editorQml(void) const { return QStringLiteral("qrc:/FirmwarePlugin/RallyPointEditor.qml"); } |
||||
|
||||
/// Error codes returned in error signal
|
||||
typedef enum { |
||||
InternalError, |
||||
TooFewPoints, ///< Too few points for valid geofence
|
||||
TooManyPoints, ///< Too many points for valid geofence
|
||||
InvalidCircleRadius, |
||||
} ErrorCode_t; |
||||
|
||||
signals: |
||||
void loadComplete (const QList<QGeoCoordinate> rgPoints); |
||||
void inProgressChanged (bool inProgress); |
||||
void error (int errorCode, const QString& errorMsg); |
||||
|
||||
protected: |
||||
void _sendError(ErrorCode_t errorCode, const QString& errorMsg); |
||||
|
||||
Vehicle* _vehicle; |
||||
QList<QGeoCoordinate> _rgPoints; |
||||
}; |
||||
|
||||
#endif |
Loading…
Reference in new issue