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;
......
This diff is collapsed.
......@@ -141,7 +141,7 @@ Rectangle {
anchors.horizontalCenter: parent.horizontalCenter
y: availableHeight - (availableHeight * object.altPercent)
small: true
isCurrentItem: object.isCurrentItem
checked: object.isCurrentItem
label: object.abbreviation
visible: object.relativeAltitude ? true : (object.homePosition || graphAbsolute)
}
......
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.")
}
}
}
}
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
......@@ -92,6 +92,7 @@ void GeoFenceController::_activeVehicleSet(void)
connect(geoFenceManager, &GeoFenceManager::paramsChanged, this, &GeoFenceController::paramsChanged);
connect(geoFenceManager, &GeoFenceManager::paramLabelsChanged, this, &GeoFenceController::paramLabelsChanged);
connect(geoFenceManager, &GeoFenceManager::loadComplete, this, &GeoFenceController::_loadComplete);
connect(geoFenceManager, &GeoFenceManager::inProgressChanged, this, &GeoFenceController::syncInProgressChanged);
if (!geoFenceManager->inProgress()) {
_loadComplete(geoFenceManager->breachReturnPoint(), geoFenceManager->polygon());
......@@ -134,7 +135,7 @@ bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorStr
if (breachReturnSupported()) {
if (json.contains(_jsonBreachReturnKey)
&& !JsonHelper::toQGeoCoordinate(json[_jsonBreachReturnKey], _breachReturnPoint, false /* altitudeRequired */, errorString)) {
&& !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) {
return false;
}
} else {
......@@ -242,7 +243,7 @@ void GeoFenceController::loadFromFile(const QString& filename)
void GeoFenceController::loadFromFilePicker(void)
{
#ifndef __mobile__
QString filename = QGCFileDialog::getOpenFileName(NULL, "Select GeoFence File to load", QString(), "Mission file (*.fence);;All Files (*.*)");
QString filename = QGCFileDialog::getOpenFileName(NULL, "Select GeoFence File to load", QString(), "Fence file (*.fence);;All Files (*.*)");
if (filename.isEmpty()) {
return;
......@@ -287,7 +288,7 @@ void GeoFenceController::saveToFile(const QString& filename)
if (breachReturnSupported()) {
QJsonValue jsonBreachReturn;
JsonHelper::writeQGeoCoordinate(jsonBreachReturn, _breachReturnPoint, false /* writeAltitude */);
JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn);
fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn;
}
......@@ -433,3 +434,8 @@ void GeoFenceController::_loadComplete(const QGeoCoordinate& breachReturn, const
_setPolygonFromManager(polygon);
setDirty(false);
}
QString GeoFenceController::fileExtension(void) const
{
return QGCApplication::fenceFileExtension;
}
......@@ -52,6 +52,8 @@ public:
bool dirty (void) const final;
void setDirty (bool dirty) final;
QString fileExtension(void) const final;
bool fenceSupported (void) const;
bool circleSupported (void) const;
bool polygonSupported (void) const;
......
......@@ -102,7 +102,10 @@ void MissionCommandTree::_collapseHierarchy(Vehicle*
foreach (MAV_CMD command, cmdList->commandIds()) {
// Only add supported command to tree (MAV_CMD_NAV_LAST is used for planned home position)
if (!qgcApp()->runningUnitTests() && !vehicle->firmwarePlugin()->supportedMissionCommands().contains(command) && command != MAV_CMD_NAV_LAST) {
if (!qgcApp()->runningUnitTests()
&& !vehicle->firmwarePlugin()->supportedMissionCommands().isEmpty()
&& !vehicle->firmwarePlugin()->supportedMissionCommands().contains(command)
&& command != MAV_CMD_NAV_LAST) {
continue;
}
......
......@@ -1284,3 +1284,8 @@ void MissionController::_homeCoordinateChanged(void)
emit plannedHomePositionChanged(plannedHomePosition());
_recalcAltitudeRangeBearing();
}
QString MissionController::fileExtension(void) const
{
return QGCApplication::missionFileExtension;
}
......@@ -69,6 +69,8 @@ public:
bool dirty (void) const final;
void setDirty (bool dirty) final;
QString fileExtension(void) const final;
// Property accessors
QGeoCoordinate plannedHomePosition (void);
......
......@@ -196,7 +196,7 @@ bool MissionItem::load(const QJsonObject& json, QString& errorString)
setCommand((MAV_CMD)json[_jsonCommandKey].toInt());
QGeoCoordinate coordinate;
if (!JsonHelper::toQGeoCoordinate(json[_jsonCoordinateKey], coordinate, true /* altitudeRequired */, errorString)) {
if (!JsonHelper::loadGeoCoordinate(json[_jsonCoordinateKey], true /* altitudeRequired */, coordinate, errorString)) {
return false;
}
setParam5(coordinate.latitude());
......
......@@ -31,6 +31,10 @@ public:
/// true: unsaved/sent changes are present, false: no changes since last save/send
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
/// Returns the file extention for plan element file type.
Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT)
virtual QString fileExtension(void) const = 0;
/// Should be called immediately upon Component.onCompleted.
/// @param editMode true: controller being used in Plan view, false: controller being used in Fly view
Q_INVOKABLE virtual void start(bool editMode);
......
......@@ -142,18 +142,10 @@ void QGCMapPolygon::setPath(const QVariantList& path)
void QGCMapPolygon::saveToJson(QJsonObject& json)
{
QJsonArray rgPoints;
// Add all points to the array
for (int i=0; i<_polygonPath.count(); i++) {
QJsonValue jsonPoint;
JsonHelper::writeQGeoCoordinate(jsonPoint, (*this)[i], false /* writeAltitude */);
rgPoints.append(jsonPoint);
}
json.insert(_jsonPolygonKey, QJsonValue(rgPoints));
QJsonValue jsonValue;
JsonHelper::saveGeoCoordinateArray(_polygonPath, false /* writeAltitude*/, jsonValue);
json.insert(_jsonPolygonKey, jsonValue);
setDirty(false);
}
......@@ -170,26 +162,11 @@ bool QGCMapPolygon::loadFromJson(const QJsonObject& json, bool required, QString
return true;
}
QList<QJsonValue::Type> types;
types << QJsonValue::Array;
if (!JsonHelper::validateKeyTypes(json, QStringList(_jsonPolygonKey), types, errorString)) {
if (!JsonHelper::loadGeoCoordinateArray(json[_jsonPolygonKey], false /* altitudeRequired */, _polygonPath, errorString)) {
return false;
}
QList<QGeoCoordinate> rgPoints;
QJsonArray jsonPoints = json[_jsonPolygonKey].toArray();
for (int i=0; i<jsonPoints.count(); i++) {
QGeoCoordinate coordinate;
if (!JsonHelper::toQGeoCoordinate(jsonPoints[i], coordinate, false /* altitudeRequired */, errorString)) {
return false;
}
rgPoints.append(coordinate);
}
setPath(rgPoints);
setDirty(false);
emit pathChanged();
return true;
}
......
/****************************************************************************
*
* (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());
}
/****************************************************************************
*
* (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
[
{
"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"
}
]
/****************************************************************************
*
* (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)
{
QObject* prevPoint = _points[0];
int foundIndex = 0;
for (foundIndex=0; foundIndex<_points.count(); foundIndex++) {
prevPoint = _points[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);
}
/****************************************************************************
*
* (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
/****************************************************************************
*
* (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
}
/****************************************************************************
*
* (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
......@@ -216,7 +216,7 @@ void SurveyMissionItem::save(QJsonObject& saveObject) const
const QVariant& polyVar = _polygonPath[i];
QJsonValue jsonValue;
JsonHelper::writeQGeoCoordinate(jsonValue, polyVar.value<QGeoCoordinate>(), false /* writeAltitude */);
JsonHelper::saveGeoCoordinate(polyVar.value<QGeoCoordinate>(), false /* writeAltitude */, jsonValue);
polygonArray += jsonValue;
}
......@@ -294,7 +294,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, QString& errorStr
const QJsonValue& pointValue = polygonArray[i];
QGeoCoordinate pointCoord;
if (!JsonHelper::toQGeoCoordinate(pointValue, pointCoord, false /* altitudeRequired */, errorString)) {
if (!JsonHelper::loadGeoCoordinate(pointValue, false /* altitudeRequired */, pointCoord, errorString)) {
_clear();
return false;
}
......
......@@ -82,6 +82,8 @@
#include "CoordinateVector.h"
#include "MainToolBarController.h"
#include "MissionController.h"
#include "GeoFenceController.h"
#include "RallyPointController.h"
#include "VideoManager.h"
#include "VideoSurface.h"
#include "VideoReceiver.h"
......@@ -93,7 +95,6 @@
#include "PositionManager.h"
#include "FollowMe.h"
#include "MissionCommandTree.h"
#include "GeoFenceController.h"
#include "QGCMapPolygon.h"
#include "ParameterManager.h"
......@@ -126,6 +127,7 @@ QGCApplication* QGCApplication::_app = NULL;
const char* QGCApplication::parameterFileExtension = "params";
const char* QGCApplication::missionFileExtension = "mission";
const char* QGCApplication::fenceFileExtension = "fence";
const char* QGCApplication::rallyPointFileExtension = "rally";
const char* QGCApplication::telemetryFileExtension = "tlog";
const char* QGCApplication::_deleteAllSettingsKey = "DeleteAllSettingsNextBoot";
......@@ -400,11 +402,12 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<ScreenToolsController> ("QGroundControl.Controllers", 1, 0, "ScreenToolsController");
qmlRegisterType<MainToolBarController> ("QGroundControl.Controllers", 1, 0, "MainToolBarController");
qmlRegisterType<MissionController> ("QGroundControl.Controllers", 1, 0, "MissionController");
qmlRegisterType<GeoFenceController> ("QGroundControl.Controllers", 1, 0, "GeoFenceController");
qmlRegisterType<RallyPointController> ("QGroundControl.Controllers", 1, 0, "RallyPointController");
qmlRegisterType<ValuesWidgetController> ("QGroundControl.Controllers", 1, 0, "ValuesWidgetController");
qmlRegisterType<QGCMobileFileDialogController> ("QGroundControl.Controllers", 1, 0, "QGCMobileFileDialogController");
qmlRegisterType<RCChannelMonitorController> ("QGroundControl.Controllers", 1, 0, "RCChannelMonitorController");
qmlRegisterType<JoystickConfigController> ("QGroundControl.Controllers", 1, 0, "JoystickConfigController");
qmlRegisterType<GeoFenceController> ("QGroundControl.Controllers", 1, 0, "GeoFenceController");
#ifndef __mobile__
qmlRegisterType<ViewWidgetController> ("QGroundControl.Controllers", 1, 0, "ViewWidgetController");
qmlRegisterType<CustomCommandWidgetController> ("QGroundControl.Controllers", 1, 0, "CustomCommandWidgetController");
......
......@@ -68,6 +68,7 @@ public:
static const char* parameterFileExtension;
static const char* missionFileExtension;
static const char* fenceFileExtension;
static const char* rallyPointFileExtension;
static const char* telemetryFileExtension;
/// @brief Sets the persistent flag to delete all settings the next time QGroundControl is started.
......
......@@ -6,9 +6,11 @@ import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
Rectangle {
property alias label: _label.text
property bool isCurrentItem: false
property bool small: false
id: root
property alias label: _label.text
property bool checked: false
property bool small: false
signal clicked
......@@ -17,7 +19,7 @@ Rectangle {
radius: _width / 2
border.width: small ? 1 : 2
border.color: "white"
color: isCurrentItem ? "green" : qgcPal.mapButtonHighlight
color: checked ? "green" : qgcPal.mapButtonHighlight
property real _width: small ? ScreenTools.defaultFontPixelHeight * ScreenTools.smallFontPointRatio * 1.75 : ScreenTools.defaultFontPixelHeight * 1.75
......
......@@ -16,6 +16,8 @@ ModeSwitchDisplay 1.0 ModeSwitchDisplay.qml
MultiRotorMotorDisplay 1.0 MultiRotorMotorDisplay.qml
ParameterEditor 1.0 ParameterEditor.qml
ParameterEditorDialog 1.0 ParameterEditorDialog.qml
RallyPointEditorHeader 1.0 RallyPointEditorHeader.qml
RallyPointItemEditor 1.0 RallyPointItemEditor.qml
RCChannelMonitor 1.0 RCChannelMonitor.qml
QGCButton 1.0 QGCButton.qml
QGCCheckBox 1.0 QGCCheckBox.qml
......
......@@ -185,6 +185,7 @@ QObjectList QmlObjectListModel::swapObjectList(const QObjectList& newlist)
beginResetModel();
_objectList = newlist;
endResetModel();
emit countChanged(count());
return oldlist;
}
......
......@@ -17,6 +17,8 @@
#include "UAS.h"
#include "JoystickManager.h"
#include "MissionManager.h"
#include "GeoFenceManager.h"
#include "RallyPointManager.h"
#include "CoordinateVector.h"
#include "ParameterManager.h"
#include "QGCApplication.h"
......@@ -25,7 +27,6 @@
#include "FollowMe.h"
#include "MissionCommandTree.h"
#include "QGroundControlQmlGlobal.h"
#include "GeoFenceManager.h"
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")
......@@ -98,9 +99,11 @@ Vehicle::Vehicle(LinkInterface* link,
, _connectionLost(false)
, _connectionLostEnabled(true)
, _missionManager(NULL)
, _missionManagerInitialRequestComplete(false)
, _missionManagerInitialRequestSent(false)
, _geoFenceManager(NULL)
, _geoFenceManagerInitialRequestComplete(false)
, _geoFenceManagerInitialRequestSent(false)
, _rallyPointManager(NULL)
, _rallyPointManagerInitialRequestSent(false)
, _parameterManager(NULL)
, _armed(false)
, _base_mode(0)
......@@ -202,6 +205,10 @@ Vehicle::Vehicle(LinkInterface* link,
// GeoFenceManager needs to access ParameterManager so make sure to create after
_geoFenceManager = _firmwarePlugin->newGeoFenceManager(this);
connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
connect(_geoFenceManager, &GeoFenceManager::loadComplete, this, &Vehicle::_newGeoFenceAvailable);
_rallyPointManager = _firmwarePlugin->newRallyPointManager(this);
connect(_rallyPointManager, &RallyPointManager::error, this, &Vehicle::_rallyPointManagerError);
// Ask the vehicle for firmware version info. This must be MAV_COMP_ID_ALL since we don't know default component id yet.
......@@ -288,9 +295,11 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _connectionLost(false)
, _connectionLostEnabled(true)
, _missionManager(NULL)
, _missionManagerInitialRequestComplete(false)
, _missionManagerInitialRequestSent(false)
, _geoFenceManager(NULL)
, _geoFenceManagerInitialRequestComplete(false)
, _geoFenceManagerInitialRequestSent(false)
, _rallyPointManager(NULL)
, _rallyPointManagerInitialRequestSent(false)
, _parameterManager(NULL)
, _armed(false)
, _base_mode(0)
......@@ -335,6 +344,9 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
_geoFenceManager = _firmwarePlugin->newGeoFenceManager(this);
connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
_rallyPointManager = _firmwarePlugin->newRallyPointManager(this);
connect(_rallyPointManager, &RallyPointManager::error, this, &Vehicle::_rallyPointManagerError);
// Build FactGroup object model
_addFact(&_rollFact, _rollFactName);
......@@ -1381,7 +1393,13 @@ void Vehicle::_missionManagerError(int errorCode, const QString& errorMsg)
void Vehicle::_geoFenceManagerError(int errorCode, const QString& errorMsg)
{
Q_UNUSED(errorCode);
qgcApp()->showMessage(QString("Error during Geo-Fence communication with Vehicle: %1").arg(errorMsg));
qgcApp()->showMessage(QString("Error during GeoFence communication with Vehicle: %1").arg(errorMsg));
}
void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg)
{
Q_UNUSED(errorCode);
qgcApp()->showMessage(QString("Error during Rally Point communication with Vehicle: %1").arg(errorMsg));
}
void Vehicle::_addNewMapTrajectoryPoint(void)
......@@ -1411,8 +1429,8 @@ void Vehicle::_mapTrajectoryStop()
void Vehicle::_parametersReady(bool parametersReady)
{
if (parametersReady && !_missionManagerInitialRequestComplete) {
_missionManagerInitialRequestComplete = true;
if (parametersReady && !_missionManagerInitialRequestSent) {
_missionManagerInitialRequestSent = true;
_missionManager->requestMissionItems();
}
......@@ -1854,12 +1872,21 @@ void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
void Vehicle::_newMissionItemsAvailable(void)
{
// After the initial mission request complets we ask for the geofence
if (!_geoFenceManagerInitialRequestComplete) {
_geoFenceManagerInitialRequestComplete = true;
if (!_geoFenceManagerInitialRequestSent) {
_geoFenceManagerInitialRequestSent = true;
_geoFenceManager->loadFromVehicle();
}
}
void Vehicle::_newGeoFenceAvailable(void)
{
// After the initial mission request complets we ask for the geofence
if (!_rallyPointManagerInitialRequestSent) {
_rallyPointManagerInitialRequestSent = true;
_rallyPointManager->loadFromVehicle();
}
}
const char* VehicleGPSFactGroup::_hdopFactName = "hdop";
const char* VehicleGPSFactGroup::_vdopFactName = "vdop";
const char* VehicleGPSFactGroup::_courseOverGroundFactName = "courseOverGround";
......
......@@ -34,6 +34,7 @@ class AutoPilotPlugin;
class AutoPilotPluginManager;
class MissionManager;
class GeoFenceManager;
class RallyPointManager;
class ParameterManager;
class JoystickManager;
class UASMessage;
......@@ -448,8 +449,9 @@ public:
int manualControlReservedButtonCount(void);
MissionManager* missionManager(void) { return _missionManager; }
GeoFenceManager* geoFenceManager(void) { return _geoFenceManager; }
MissionManager* missionManager(void) { return _missionManager; }
GeoFenceManager* geoFenceManager(void) { return _geoFenceManager; }
RallyPointManager* rallyPointManager(void) { return _rallyPointManager; }
bool homePositionAvailable(void);
QGeoCoordinate homePosition(void);
......@@ -666,6 +668,7 @@ private slots:
void _connectionLostTimeout(void);
void _prearmErrorTimeout(void);
void _newMissionItemsAvailable(void);
void _newGeoFenceAvailable(void);
private:
bool _containsLink(LinkInterface* link);
......@@ -688,6 +691,7 @@ private:
void _handleHilActuatorControls(mavlink_message_t& message);
void _missionManagerError(int errorCode, const QString& errorMsg);
void _geoFenceManagerError(int errorCode, const QString& errorMsg);
void _rallyPointManagerError(int errorCode, const QString& errorMsg);
void _mapTrajectoryStart(void);
void _mapTrajectoryStop(void);
void _connectionActive(void);
......@@ -751,10 +755,13 @@ private:
QTimer _connectionLostTimer;
MissionManager* _missionManager;
bool _missionManagerInitialRequestComplete;
bool _missionManagerInitialRequestSent;
GeoFenceManager* _geoFenceManager;
bool _geoFenceManagerInitialRequestComplete;
bool _geoFenceManagerInitialRequestSent;
RallyPointManager* _rallyPointManager;
bool _rallyPointManagerInitialRequestSent;
ParameterManager* _parameterManager;
......
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