Commit 5c465846 authored by Don Gagne's avatar Don Gagne

Initial ArduPilot Rally Point support

parent 265b3dcc
......@@ -293,7 +293,6 @@ HEADERS += \
src/MissionManager/ComplexMissionItem.h \
src/MissionManager/GeoFenceController.h \
src/MissionManager/GeoFenceManager.h \
src/MissionManager/QGCMapPolygon.h \
src/MissionManager/MissionCommandList.h \
src/MissionManager/MissionCommandTree.h \
src/MissionManager/MissionCommandUIInfo.h \
......@@ -301,6 +300,10 @@ HEADERS += \
src/MissionManager/MissionItem.h \
src/MissionManager/MissionManager.h \
src/MissionManager/PlanElementController.h \
src/MissionManager/QGCMapPolygon.h \
src/MissionManager/RallyPoint.h \
src/MissionManager/RallyPointController.h \
src/MissionManager/RallyPointManager.h \
src/MissionManager/SimpleMissionItem.h \
src/MissionManager/SurveyMissionItem.h \
src/MissionManager/VisualMissionItem.h \
......@@ -457,7 +460,6 @@ SOURCES += \
src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/GeoFenceController.cc \
src/MissionManager/GeoFenceManager.cc \
src/MissionManager/QGCMapPolygon.cc \
src/MissionManager/MissionCommandList.cc \
src/MissionManager/MissionCommandTree.cc \
src/MissionManager/MissionCommandUIInfo.cc \
......@@ -465,6 +467,10 @@ SOURCES += \
src/MissionManager/MissionItem.cc \
src/MissionManager/MissionManager.cc \
src/MissionManager/PlanElementController.cc \
src/MissionManager/QGCMapPolygon.cc \
src/MissionManager/RallyPoint.cc \
src/MissionManager/RallyPointController.cc \
src/MissionManager/RallyPointManager.cc \
src/MissionManager/SimpleMissionItem.cc \
src/MissionManager/SurveyMissionItem.cc \
src/MissionManager/VisualMissionItem.cc \
......@@ -696,6 +702,7 @@ HEADERS+= \
src/FirmwarePlugin/APM/APMFirmwarePlugin.h \
src/FirmwarePlugin/APM/APMGeoFenceManager.h \
src/FirmwarePlugin/APM/APMParameterMetaData.h \
src/FirmwarePlugin/APM/APMRallyPointManager.h \
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h \
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h \
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h \
......@@ -757,6 +764,7 @@ SOURCES += \
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc \
src/FirmwarePlugin/APM/APMGeoFenceManager.cc \
src/FirmwarePlugin/APM/APMParameterMetaData.cc \
src/FirmwarePlugin/APM/APMRallyPointManager.cc \
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc \
src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc \
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc \
......
......@@ -55,7 +55,7 @@
<file alias="QGroundControl/Controls/JoystickThumbPad.qml">src/QmlControls/JoystickThumbPad.qml</file>
<file alias="QGroundControl/Controls/MainToolBar.qml">src/ui/toolbar/MainToolBar.qml</file>
<file alias="QGroundControl/Controls/MainToolBarIndicators.qml">src/ui/toolbar/MainToolBarIndicators.qml</file>
<file alias="QGroundControl/Controls/MissionItemEditor.qml">src/QmlControls/MissionItemEditor.qml</file>
<file alias="QGroundControl/Controls/MissionItemEditor.qml">src/MissionEditor/MissionItemEditor.qml</file>
<file alias="QGroundControl/Controls/MissionItemIndexLabel.qml">src/QmlControls/MissionItemIndexLabel.qml</file>
<file alias="QGroundControl/Controls/MissionItemStatus.qml">src/MissionEditor/MissionItemStatus.qml</file>
<file alias="QGroundControl/Controls/MissionCommandDialog.qml">src/QmlControls/MissionCommandDialog.qml</file>
......@@ -63,6 +63,7 @@
<file alias="QGroundControl/Controls/ModeSwitchDisplay.qml">src/QmlControls/ModeSwitchDisplay.qml</file>
<file alias="QGroundControl/Controls/ParameterEditor.qml">src/QmlControls/ParameterEditor.qml</file>
<file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file>
<file alias="QGroundControl/Controls/RallyPointItemEditor.qml">src/MissionEditor/RallyPointItemEditor.qml</file>
<file alias="QGroundControl/Controls/RCChannelMonitor.qml">src/QmlControls/RCChannelMonitor.qml</file>
<file alias="QGroundControl/Controls/QGCButton.qml">src/QmlControls/QGCButton.qml</file>
<file alias="QGroundControl/Controls/QGCCheckBox.qml">src/QmlControls/QGCCheckBox.qml</file>
......@@ -83,6 +84,7 @@
<file alias="QGroundControl/Controls/QGCViewDialog.qml">src/QmlControls/QGCViewDialog.qml</file>
<file alias="QGroundControl/Controls/QGCViewMessage.qml">src/QmlControls/QGCViewMessage.qml</file>
<file alias="QGroundControl/Controls/QGCViewPanel.qml">src/QmlControls/QGCViewPanel.qml</file>
<file alias="QGroundControl/Controls/RallyPointEditorHeader.qml">src/MissionEditor/RallyPointEditorHeader.qml</file>
<file alias="QGroundControl/Controls/RoundButton.qml">src/QmlControls/RoundButton.qml</file>
<file alias="QGroundControl/Controls/SetupPage.qml">src/AutoPilotPlugins/Common/SetupPage.qml</file>
<file alias="QGroundControl/Controls/SignalStrength.qml">src/ui/toolbar/SignalStrength.qml</file>
......@@ -190,5 +192,6 @@
<file alias="Vehicle/WindFact.json">src/Vehicle/WindFact.json</file>
<file alias="Vehicle/VibrationFact.json">src/Vehicle/VibrationFact.json</file>
<file alias="QGroundControlQmlGlobal.json">src/QmlControls/QGroundControlQmlGlobal.json</file>
<file alias="RallyPoint.json">src/MissionManager/RallyPoint.json</file>
</qresource>
</RCC>
......@@ -18,6 +18,7 @@
#include "QGCLoggingCategory.h"
#include "APMParameterMetaData.h"
#include "APMGeoFenceManager.h"
#include "APMRallyPointManager.h"
#include <QAbstractSocket>
......@@ -93,6 +94,7 @@ public:
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
QObject* loadParameterMetaData (const QString& metaDataFile);
GeoFenceManager* newGeoFenceManager (Vehicle* vehicle) { return new APMGeoFenceManager(vehicle); }
RallyPointManager* newRallyPointManager (Vehicle* vehicle) { return new APMRallyPointManager(vehicle); }
QString getParameterMetaDataFile(Vehicle* vehicle);
......
......@@ -99,6 +99,7 @@ void APMGeoFenceManager::loadFromVehicle(void)
return;
}
_breachReturnPoint = QGeoCoordinate();
_polygon.clear();
if (!_geoFenceSupported()) {
......@@ -112,7 +113,8 @@ void APMGeoFenceManager::loadFromVehicle(void)
int minFencePoints = 6;
qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::loadFromVehicle" << cFencePoints;
if (cFencePoints == 0) {
// No fence, no more work to do, fence data has already been cleared
// No fence
emit loadComplete(_breachReturnPoint, _polygon);
return;
}
if (cFencePoints < 0 || (cFencePoints > 0 && cFencePoints < minFencePoints)) {
......@@ -142,6 +144,8 @@ void APMGeoFenceManager::_mavlinkMessageReceived(const mavlink_message_t& messag
if (fencePoint.idx != _currentFencePoint) {
// FIXME: Protocol out of whack
_readTransactionInProgress = false;
emit inProgressChanged(inProgress());
qCWarning(GeoFenceManagerLog) << "Indices out of sync" << fencePoint.idx << _currentFencePoint;
return;
}
......@@ -159,8 +163,10 @@ void APMGeoFenceManager::_mavlinkMessageReceived(const mavlink_message_t& messag
_requestFencePoint(++_currentFencePoint);
} else {
// We've finished collecting fence points
qCDebug(GeoFenceManagerLog) << "Fence point load complete";
_readTransactionInProgress = false;
emit loadComplete(_breachReturnPoint, _polygon);
emit inProgressChanged(inProgress());
}
}
}
......
/****************************************************************************
*
* (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;
}
/****************************************************************************
*
* (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
......@@ -18,6 +18,7 @@
#include "VehicleComponent.h"
#include "AutoPilotPlugin.h"
#include "GeoFenceManager.h"
#include "RallyPointManager.h"
#include <QList>
#include <QString>
......@@ -209,14 +210,15 @@ public:
/// @return true: X confiuration, false: Plus configuration
virtual bool multiRotorXConfig(Vehicle* vehicle) { Q_UNUSED(vehicle); return false; }
/// Returns a newly create geofence manager for this vehicle. Returns NULL if this vehicle
/// does not support geofence. You should make sense to check vehicle capabilites for geofence
/// support.
/// Returns a newly created geofence manager for this vehicle.
virtual GeoFenceManager* newGeoFenceManager(Vehicle* vehicle) { return new GeoFenceManager(vehicle); }
/// Returns the parameter which holds the fence circle radius if supported.
virtual QString geoFenceRadiusParam(Vehicle* vehicle) { Q_UNUSED(vehicle); return QString(); }
/// Returns a newly created rally point manager for this vehicle.
virtual RallyPointManager* newRallyPointManager(Vehicle* vehicle) { return new RallyPointManager(vehicle); }
/// Return the resource file which contains the set of params loaded for offline editing.
virtual QString offlineEditingParamFile(Vehicle* vehicle) { Q_UNUSED(vehicle); return QString(); }
};
......
......@@ -63,6 +63,11 @@ FlightMap {
Component.onCompleted: start(false /* editMode */)
}
RallyPointController {
id: rallyPointController
Component.onCompleted: start(false /* editMode */)
}
// Add trajectory points to the map
MapItemView {
model: _mainIsMap ? _activeVehicle ? _activeVehicle.trajectoryPoints : 0 : 0
......@@ -126,6 +131,23 @@ FlightMap {
z: QGroundControl.zOrderMapItems
}
// Rally points on map
MapItemView {
model: rallyPointController.points
delegate: MapQuickItem {
id: itemIndicator
anchorPoint: Qt.point(sourceItem.width / 2, sourceItem.height / 2)
coordinate: object.coordinate
z: QGroundControl.zOrderMapItems
sourceItem: MissionItemIndexLabel {
id: itemIndexLabel
label: qsTr("R", "rally point map item label")
}
}
}
// GoTo here waypoint
MapQuickItem {
coordinate: _gotoHereCoordinate
......@@ -135,8 +157,8 @@ FlightMap {
anchorPoint.y: sourceItem.height / 2
sourceItem: MissionItemIndexLabel {
isCurrentItem: true
label: qsTr("G", "Goto here waypoint") // second string is translator's hint.
checked: true
label: qsTr("G", "Goto here waypoint") // second string is translator's hint.
}
}
......
......@@ -29,10 +29,10 @@ MapQuickItem {
sourceItem:
MissionItemIndexLabel {
id: _label
isCurrentItem: _isCurrentItem
label: missionItem ? missionItem.abbreviation : ""
onClicked: _item.clicked()
id: _label
checked: _isCurrentItem
label: missionItem ? missionItem.abbreviation : ""
onClicked: _item.clicked()
property bool _isCurrentItem: missionItem ? missionItem.isCurrentItem : false
}
......
......@@ -43,9 +43,9 @@ MapItemView {
model: object.childItems
delegate: MissionItemIndexLabel {
label: object.abbreviation
isCurrentItem: object.isCurrentItem
z: 2
label: object.abbreviation
checked: object.isCurrentItem
z: 2
}
}
}
......
......@@ -12,6 +12,9 @@
#include <QJsonArray>
#include <QJsonParseError>
#include <QObject>
#include <QRegularExpression>
#include <QRegularExpressionMatch>
const char* JsonHelper::_enumStringsJsonKey = "enumStrings";
const char* JsonHelper::_enumValuesJsonKey = "enumValues";
......@@ -34,30 +37,33 @@ bool JsonHelper::validateRequiredKeys(const QJsonObject& jsonObject, const QStri
}
if (missingKeys.count() != 0) {
errorString = QString("The following required keys are missing: %1").arg(missingKeys);
errorString = QObject::tr("The following required keys are missing: %1").arg(missingKeys);
return false;
}
return true;
}
bool JsonHelper::toQGeoCoordinate(const QJsonValue& jsonValue, QGeoCoordinate& coordinate, bool altitudeRequired, QString& errorString)
bool JsonHelper::loadGeoCoordinate(const QJsonValue& jsonValue,
bool altitudeRequired,
QGeoCoordinate& coordinate,
QString& errorString)
{
if (!jsonValue.isArray()) {
errorString = QStringLiteral("JSon value for coordinate is not array");
errorString = QObject::tr("value for coordinate is not array");
return false;
}
QJsonArray coordinateArray = jsonValue.toArray();
int requiredCount = altitudeRequired ? 3 : 2;
if (coordinateArray.count() != requiredCount) {
errorString = QString("Coordinate array must contain %1 values").arg(requiredCount);
errorString = QObject::tr("Coordinate array must contain %1 values").arg(requiredCount);
return false;
}
foreach(const QJsonValue& jsonValue, coordinateArray) {
if (jsonValue.type() != QJsonValue::Double) {
errorString = QString("Coordinate array may only contain double values, found: %1").arg(jsonValue.type());
errorString = QObject::tr("Coordinate array may only contain double values, found: %1").arg(jsonValue.type());
return false;
}
}
......@@ -68,14 +74,16 @@ bool JsonHelper::toQGeoCoordinate(const QJsonValue& jsonValue, QGeoCoordinate& c
}
if (!coordinate.isValid()) {
errorString = QString("Coordinate is invalid: %1").arg(coordinate.toString());
errorString = QObject::tr("Coordinate is invalid: %1").arg(coordinate.toString());
return false;
}
return true;
}
void JsonHelper::writeQGeoCoordinate(QJsonValue& jsonValue, const QGeoCoordinate& coordinate, bool writeAltitude)
void JsonHelper::saveGeoCoordinate(const QGeoCoordinate& coordinate,
bool writeAltitude,
QJsonValue& jsonValue)
{
QJsonArray coordinateArray;
......@@ -92,7 +100,7 @@ bool JsonHelper::validateKeyTypes(const QJsonObject& jsonObject, const QStringLi
for (int i=0; i<keys.count(); i++) {
if (jsonObject.contains(keys[i])) {
if (jsonObject.value(keys[i]).type() != types[i]) {
errorString = QString("Incorrect type key:type:expected %1 %2 %3").arg(keys[i]).arg(jsonObject.value(keys[i]).type()).arg(types[i]);
errorString = QObject::tr("Incorrect type key:type:expected %1 %2 %3").arg(keys[i]).arg(jsonObject.value(keys[i]).type()).arg(types[i]);
return false;
}
}
......@@ -107,7 +115,7 @@ bool JsonHelper::parseEnum(const QJsonObject& jsonObject, QStringList& enumStrin
enumValues = jsonObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts);
if (enumStrings.count() != enumValues.count()) {
errorString = QString("enum strings/values count mismatch strings:values %1:%2").arg(enumStrings.count()).arg(enumValues.count());
errorString = QObject::tr("enum strings/values count mismatch strings:values %1:%2").arg(enumStrings.count()).arg(enumValues.count());
return false;
}
......@@ -130,3 +138,127 @@ bool JsonHelper::isJsonFile(const QByteArray& bytes, QJsonDocument& jsonDoc)
return true;
}
bool JsonHelper::validateQGCJsonFile(const QJsonObject& jsonObject,
const QString& expectedFileType,
int supportedMajorVersion,
int supportedMinorVersion,
int& fileMajorVersion,
int& fileMinorVersion,
QString& errorString)
{
// Check for required keys
QStringList requiredKeys = { jsonVersionKey, jsonFileTypeKey };
if (!validateRequiredKeys(jsonObject, requiredKeys, errorString)) {
return false;
}
// Validate base key types
QList<QJsonValue::Type> typeList = { QJsonValue::String, QJsonValue::String };
if (!validateKeyTypes(jsonObject, requiredKeys, typeList, errorString)) {
return false;
}
// Make sure file type is correct
QString fileTypeValue = jsonObject[jsonFileTypeKey].toString();
if (fileTypeValue != expectedFileType) {
errorString = QObject::tr("Incorrect file type key expected:%1 actual:%2").arg(expectedFileType).arg(fileTypeValue);
return false;
}
// Parse and validate version
QString incorrectVersionFormatErrorString = QObject::tr("Incorrectly formatted version value");
QRegularExpression versionRegExp("(\\d+).(\\d+)");
QRegularExpressionMatch match = versionRegExp.match(jsonObject[jsonVersionKey].toString());
if (!match.hasMatch()) {
errorString = incorrectVersionFormatErrorString;
return false;
}
QStringList versionParts = match.capturedTexts();
if (versionParts.count() != 3) {
errorString = incorrectVersionFormatErrorString;
return false;
}
fileMajorVersion = versionParts[0].toInt();
fileMinorVersion = versionParts[0].toInt();
if (fileMajorVersion > supportedMajorVersion || (fileMajorVersion == supportedMajorVersion && fileMinorVersion > supportedMinorVersion)) {
errorString = QObject::tr("File version (%1.%2) is larger than current supported version (%3.%4)").arg(fileMajorVersion).arg(fileMinorVersion).arg(supportedMajorVersion).arg(supportedMinorVersion);
return false;
}
return true;
}
bool JsonHelper::loadGeoCoordinateArray(const QJsonValue& jsonValue,
bool altitudeRequired,
QVariantList& rgVarPoints,
QString& errorString)
{
if (!jsonValue.isArray()) {
errorString = QObject::tr("value for coordinate array is not array");
return false;
}
QJsonArray rgJsonPoints = jsonValue.toArray();
rgVarPoints.clear();
for (int i=0; i<rgJsonPoints.count(); i++) {
QGeoCoordinate coordinate;
if (!JsonHelper::loadGeoCoordinate(rgJsonPoints[i], altitudeRequired, coordinate, errorString)) {
return false;
}
rgVarPoints.append(QVariant::fromValue(coordinate));
}
return true;
}
bool JsonHelper::loadGeoCoordinateArray(const QJsonValue& jsonValue,
bool altitudeRequired,
QList<QGeoCoordinate>& rgPoints,
QString& errorString)
{
QVariantList rgVarPoints;
if (!loadGeoCoordinateArray(jsonValue, altitudeRequired, rgVarPoints, errorString)) {
return false;
}
rgPoints.clear();
for (int i=0; i<rgVarPoints.count(); i++) {
rgPoints.append(rgVarPoints[i].value<QGeoCoordinate>());
}
return true;
}
void JsonHelper::saveGeoCoordinateArray(const QVariantList& rgVarPoints,
bool writeAltitude,
QJsonValue& jsonValue)
{
QJsonArray rgJsonPoints;
// Add all points to the array
for (int i=0; i<rgVarPoints.count(); i++) {
QJsonValue jsonPoint;
JsonHelper::saveGeoCoordinate(rgVarPoints[i].value<QGeoCoordinate>(), writeAltitude, jsonPoint);
rgJsonPoints.append(jsonPoint);
}
jsonValue = rgJsonPoints;
}
void JsonHelper::saveGeoCoordinateArray(const QList<QGeoCoordinate>& rgPoints,
bool writeAltitude,
QJsonValue& jsonValue)
{
QVariantList rgVarPoints;
for (int i=0; i<rgPoints.count(); i++) {
rgVarPoints.append(QVariant::fromValue(rgPoints[i]));
}
return saveGeoCoordinateArray(rgVarPoints, writeAltitude, jsonValue);
}
......@@ -11,6 +11,7 @@
#define JsonHelper_H
#include <QJsonObject>
#include <QVariantList>
#include <QGeoCoordinate>
class JsonHelper
......@@ -21,12 +22,54 @@ public:
/// @return true: file is json, false: file is not json
static bool isJsonFile(const QByteArray& bytes, QJsonDocument& jsonDoc);
/// Validates the standard parts of a QGC json file:
/// jsonFileTypeKey - Required and checked to be equal to expectedFileType
/// jsonVersionKey - Required and checked to be below supportedMajorVersion, supportedMinorVersion
/// @return false: validation failed
static bool validateQGCJsonFile(const QJsonObject& jsonObject, ///< top level json object in file
const QString& expectedFileType, ///< correct file type for file
int supportedMajorVersion, ///< maximum supported major version
int supportedMinorVersion, ///< maximum supported minor version
int &fileMajorVersion, ///< returned file major version
int &fileMinorVersion, ///< returned file minor version
QString& errorString); ///< returned error string if validation fails
static bool validateRequiredKeys(const QJsonObject& jsonObject, const QStringList& keys, QString& errorString);
static bool validateKeyTypes(const QJsonObject& jsonObject, const QStringList& keys, const QList<QJsonValue::Type>& types, QString& errorString);
static bool toQGeoCoordinate(const QJsonValue& jsonValue, QGeoCoordinate& coordinate, bool altitudeRequired, QString& errorString);
/// Loads a QGeoCoordinate
/// @return false: validation failed
static bool loadGeoCoordinate(const QJsonValue& jsonValue, ///< json value to load from
bool altitudeRequired, ///< true: altitude must be specified
QGeoCoordinate& coordinate, ///< returned QGeoCordinate
QString& errorString); ///< returned error string if load failure
/// Saves a QGeoCoordinate
static void saveGeoCoordinate(const QGeoCoordinate& coordinate, ///< QGeoCoordinate to save
bool writeAltitude, ///< true: write altitude to json
QJsonValue& jsonValue); ///< json value to save to
/// Loads a list of QGeoCoordinates from a json array
/// @return false: validation failed
static bool loadGeoCoordinateArray(const QJsonValue& jsonValue, ///< json value which contains points
bool altitudeRequired, ///< true: altitude field must be specified
QVariantList& rgVarPoints, ///< returned points
QString& errorString); ///< returned error string if load failure
static bool loadGeoCoordinateArray(const QJsonValue& jsonValue, ///< json value which contains points
bool altitudeRequired, ///< true: altitude field must be specified
QList<QGeoCoordinate>& rgPoints, ///< returned points
QString& errorString); ///< returned error string if load failure
/// Saves a list of QGeoCoordinates to a json array
static void saveGeoCoordinateArray(const QVariantList& rgVarPoints, ///< points to save
bool writeAltitude, ///< true: write altitide value
QJsonValue& jsonValue); ///< json value to save to
static void saveGeoCoordinateArray(const QList<QGeoCoordinate>& rgPoints, ///< points to save
bool writeAltitude, ///< true: write altitide value
QJsonValue& jsonValue); ///< json value to save to
static bool parseEnum(const QJsonObject& jsonObject, QStringList& enumStrings, QStringList& enumValues, QString& errorString);
static void writeQGeoCoordinate(QJsonValue& jsonValue, const QGeoCoordinate& coordinate, bool writeAltitude);
static const char* jsonVersionKey;
static const char* jsonGroundStationKey;
......