Commit 537463c5 authored by Don Gagne's avatar Don Gagne

New Mavlink 2 spec GeoFence and Rally Point support

parent a11b1dbf
......@@ -509,7 +509,11 @@ HEADERS += \
src/MissionManager/MissionManager.h \
src/MissionManager/MissionSettingsItem.h \
src/MissionManager/PlanElementController.h \
src/MissionManager/PlanManager.h \
src/MissionManager/PlanMasterController.h \
src/MissionManager/QGCFenceCircle.h \
src/MissionManager/QGCFencePolygon.h \
src/MissionManager/QGCMapCircle.h \
src/MissionManager/QGCMapPolygon.h \
src/MissionManager/RallyPoint.h \
src/MissionManager/RallyPointController.h \
......@@ -689,7 +693,11 @@ SOURCES += \
src/MissionManager/MissionManager.cc \
src/MissionManager/MissionSettingsItem.cc \
src/MissionManager/PlanElementController.cc \
src/MissionManager/PlanManager.cc \
src/MissionManager/PlanMasterController.cc \
src/MissionManager/QGCFenceCircle.cc \
src/MissionManager/QGCFencePolygon.cc \
src/MissionManager/QGCMapCircle.cc \
src/MissionManager/QGCMapPolygon.cc \
src/MissionManager/RallyPoint.cc \
src/MissionManager/RallyPointController.cc \
......@@ -906,9 +914,7 @@ APMFirmwarePlugin {
src/AutoPilotPlugins/APM/APMSensorsComponentController.h \
src/AutoPilotPlugins/APM/APMTuningComponent.h \
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 \
......@@ -933,9 +939,7 @@ APMFirmwarePlugin {
src/AutoPilotPlugins/APM/APMSensorsComponentController.cc \
src/AutoPilotPlugins/APM/APMTuningComponent.cc \
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 \
......@@ -974,7 +978,6 @@ PX4FirmwarePlugin {
src/AutoPilotPlugins/PX4/SensorsComponent.h \
src/AutoPilotPlugins/PX4/SensorsComponentController.h \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4GeoFenceManager.h \
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h \
SOURCES += \
......@@ -995,7 +998,6 @@ PX4FirmwarePlugin {
src/AutoPilotPlugins/PX4/SensorsComponent.cc \
src/AutoPilotPlugins/PX4/SensorsComponentController.cc \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc \
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc \
}
......
......@@ -90,6 +90,7 @@
<file alias="QGroundControl/Controls/QGCLabel.qml">src/QmlControls/QGCLabel.qml</file>
<file alias="QGroundControl/Controls/QGCListView.qml">src/QmlControls/QGCListView.qml</file>
<file alias="QGroundControl/Controls/QGCMapLabel.qml">src/QmlControls/QGCMapLabel.qml</file>
<file alias="QGroundControl/Controls/QGCMapCircleVisuals.qml">src/MissionManager/QGCMapCircleVisuals.qml</file>
<file alias="QGroundControl/Controls/QGCMapPolygonVisuals.qml">src/MissionManager/QGCMapPolygonVisuals.qml</file>
<file alias="QGroundControl/Controls/QGCMouseArea.qml">src/QmlControls/QGCMouseArea.qml</file>
<file alias="QGroundControl/Controls/QGCMovableItem.qml">src/QmlControls/QGCMovableItem.qml</file>
......@@ -199,6 +200,7 @@
<file alias="AutoConnect.SettingsGroup.json">src/Settings/AutoConnect.SettingsGroup.json</file>
<file alias="FlightMap.SettingsGroup.json">src/Settings/FlightMap.SettingsGroup.json</file>
<file alias="Guided.SettingsGroup.json">src/Settings/Guided.SettingsGroup.json</file>
<file alias="QGCMapCircle.Facts.json">src/MissionManager/QGCMapCircle.Facts.json</file>
<file alias="RTK.SettingsGroup.json">src/Settings/RTK.SettingsGroup.json</file>
<file alias="Survey.SettingsGroup.json">src/MissionManager/Survey.SettingsGroup.json</file>
<file alias="Units.SettingsGroup.json">src/Settings/Units.SettingsGroup.json</file>
......
......@@ -17,8 +17,6 @@
#include "FirmwarePlugin.h"
#include "QGCLoggingCategory.h"
#include "APMParameterMetaData.h"
#include "APMGeoFenceManager.h"
#include "APMRallyPointManager.h"
#include <QAbstractSocket>
......@@ -93,8 +91,6 @@ public:
QString internalParameterMetaDataFile (Vehicle* vehicle) final;
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
QObject* loadParameterMetaData (const QString& metaDataFile) final;
GeoFenceManager* newGeoFenceManager (Vehicle* vehicle) final { return new APMGeoFenceManager(vehicle); }
RallyPointManager* newRallyPointManager (Vehicle* vehicle) final { return new APMRallyPointManager(vehicle); }
QString brandImageIndoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); }
QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); }
......
This diff is collapsed.
/****************************************************************************
*
* (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 APMGeoFenceManager_H
#define APMGeoFenceManager_H
#include "GeoFenceManager.h"
#include "QGCMAVLink.h"
#include "FactSystem.h"
class QmlObjectListModel;
class APMGeoFenceManager : public GeoFenceManager
{
Q_OBJECT
public:
APMGeoFenceManager(Vehicle* vehicle);
~APMGeoFenceManager();
// Overrides from GeoFenceManager
bool inProgress (void) const final;
void loadFromVehicle (void) final;
void sendToVehicle (const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon) final;
bool polygonSupported (void) const final { return _polygonSupported; }
bool polygonEnabled (void) const final { return _polygonEnabled; }
bool breachReturnSupported (void) const final { return _breachReturnSupported; }
bool circleEnabled (void) const { return _circleEnabled; }
Fact* circleRadiusFact (void) const { return _circleRadiusFact; }
QVariantList params (void) const final { return _params; }
QStringList paramLabels (void) const final { return _paramLabels; }
void removeAll (void) final;
private slots:
void _mavlinkMessageReceived (const mavlink_message_t& message);
void _parametersReady (void);
private:
void _requestFencePoint (uint8_t pointIndex);
void _sendFencePoint (uint8_t pointIndex);
void _updateEnabledFlags(void);
void _setCircleEnabled (bool circleEnabled);
void _setPolygonEnabled (bool polygonEnabled);
private:
bool _fenceSupported;
bool _circleEnabled;
bool _polygonSupported;
bool _polygonEnabled;
bool _breachReturnSupported;
bool _firstParamLoadComplete;
QVariantList _params;
QStringList _paramLabels;
bool _readTransactionInProgress;
bool _writeTransactionInProgress;
uint8_t _cReadFencePoints;
uint8_t _cWriteFencePoints;
uint8_t _currentFencePoint;
Fact* _fenceTypeFact;
Fact* _fenceEnableFact;
Fact* _circleRadiusFact;
static const char* _fenceTotalParam;
static const char* _fenceActionParam;
static const char* _fenceEnableParam;
};
#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 "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() || !rallyPointsSupported()) {
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 sendComplete(false /* error */);
}
void APMRallyPointManager::loadFromVehicle(void)
{
if (_vehicle->isOfflineEditingVehicle() || _readTransactionInProgress) {
return;
}
_rgPoints.clear();
if (!rallyPointsSupported()) {
emit loadComplete(QList<QGeoCoordinate>());
return;
}
_cReadRallyPoints = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _rallyTotalParam)->rawValue().toInt();
qCDebug(RallyPointManagerLog) << "APMRallyPointManager::loadFromVehicle - point count" << _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 - 1) {
// 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_chan(mavlink->getSystemId(),
mavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
_vehicle->id(),
_vehicle->defaultComponentId(),
pointIndex);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), 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_chan(mavlink->getSystemId(),
mavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&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->sendMessageOnLink(_vehicle->priorityLink(), msg);
}
bool APMRallyPointManager::inProgress(void) const
{
return _readTransactionInProgress || _writeTransactionInProgress;
}
bool APMRallyPointManager::rallyPointsSupported(void) const
{
return _vehicle->parameterManager()->parameterExists(_vehicle->defaultComponentId(), _rallyTotalParam);
}
void APMRallyPointManager::removeAll(void)
{
qCDebug(RallyPointManagerLog) << "APMRallyPointManager::removeAll";
QList<QGeoCoordinate> noRallyPoints;
sendToVehicle(noRallyPoints);
emit removeAllComplete(false /* error */);
}
/****************************************************************************
*
* (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;
void removeAll (void);
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
......@@ -278,12 +278,6 @@ bool ArduCopterFirmwarePlugin::multiRotorXConfig(Vehicle* vehicle)
return vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "FRAME")->rawValue().toInt() != 0;
}
QString ArduCopterFirmwarePlugin::geoFenceRadiusParam(Vehicle* vehicle)
{
Q_UNUSED(vehicle);
return QStringLiteral("FENCE_RADIUS");
}
bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const
{
if (vehicle->isOfflineEditingVehicle()) {
......
......@@ -67,7 +67,6 @@ public:
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final;
bool multiRotorCoaxialMotors (Vehicle* vehicle) final;
bool multiRotorXConfig (Vehicle* vehicle) final;
QString geoFenceRadiusParam (Vehicle* vehicle) final;
QString offlineEditingParamFile (Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Copter.OfflineEditing.params"); }
QString pauseFlightMode (void) const override { return QString("Brake"); }
QString missionFlightMode (void) const override { return QString("Auto"); }
......
......@@ -235,15 +235,6 @@ public:
/// @return true: X confiuration, false: Plus configuration
virtual bool multiRotorXConfig(Vehicle* vehicle) { Q_UNUSED(vehicle); return false; }
/// 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(); }
......
......@@ -17,7 +17,6 @@
#include "FirmwarePlugin.h"
#include "ParameterManager.h"
#include "PX4ParameterMetaData.h"
#include "PX4GeoFenceManager.h"
class PX4FirmwarePlugin : public FirmwarePlugin
{
......@@ -62,7 +61,6 @@ public:
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) override { PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
QObject* loadParameterMetaData (const QString& metaDataFile) final;
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override;
GeoFenceManager* newGeoFenceManager (Vehicle* vehicle) override { return new PX4GeoFenceManager(vehicle); }
QString offlineEditingParamFile(Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); }
QString brandImageIndoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); }
QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); }
......
/****************************************************************************
*
* (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 "PX4GeoFenceManager.h"
#include "Vehicle.h"
#include "FirmwarePlugin.h"
#include "ParameterManager.h"
PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle)
: GeoFenceManager(vehicle)
, _firstParamLoadComplete(false)
, _circleRadiusFact(NULL)
{
connect(_vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &PX4GeoFenceManager::_parametersReady);
if (_vehicle->parameterManager()->parametersReady()) {
_parametersReady();
}
}
PX4GeoFenceManager::~PX4GeoFenceManager()
{
}
void PX4GeoFenceManager::_parametersReady(void)
{
if (!_firstParamLoadComplete) {
_firstParamLoadComplete = true;
_circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("GF_MAX_HOR_DIST"));
emit circleRadiusFactChanged(_circleRadiusFact);
QStringList paramNames;
QStringList paramLabels;
paramNames << QStringLiteral("GF_ACTION") << QStringLiteral("GF_MAX_HOR_DIST") << QStringLiteral("GF_MAX_VER_DIST");
paramLabels << QStringLiteral("Breach Action:") << QStringLiteral("Radius:") << QStringLiteral("Max Altitude:");
_params.clear();
_paramLabels.clear();
for (int i=0; i<paramNames.count(); i++) {
QString paramName = paramNames[i];
if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, paramName)) {
Fact* paramFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName);
_params << QVariant::fromValue(paramFact);
_paramLabels << paramLabels[i];
}
}
emit paramsChanged(_params);
emit paramLabelsChanged(_paramLabels);
}
}
/****************************************************************************
*
* (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 PX4GeoFenceManager_H
#define PX4GeoFenceManager_H
#include "GeoFenceManager.h"
#include "QGCMAVLink.h"
#include "FactSystem.h"
class PX4GeoFenceManager : public GeoFenceManager
{
Q_OBJECT
public:
PX4GeoFenceManager(Vehicle* vehicle);
~PX4GeoFenceManager();
// Overrides from GeoFenceManager
bool circleEnabled (void) const { return true; }
Fact* circleRadiusFact (void) const { return _circleRadiusFact; }
QVariantList params (void) const final { return _params; }
QStringList paramLabels (void) const final { return _paramLabels; }
private slots:
void _parametersReady(void);
private:
bool _firstParamLoadComplete;
Fact* _circleRadiusFact;
QVariantList _params;
QStringList _paramLabels;
};
#endif
......@@ -29,6 +29,3 @@ MissionItemView 1.0 MissionItemView.qml
MissionLineView 1.0 MissionLineView.qml
PolygonEditor 1.0 PolygonEditor.qml
VehicleMapItem 1.0 VehicleMapItem.qml
# Editor controls
QGCMapPolygonControls 1.0 QGCMapPolygonControls.qml
This diff is collapsed.
......@@ -12,7 +12,8 @@
#include "PlanElementController.h"
#include "GeoFenceManager.h"
#include "QGCMapPolygon.h"
#include "QGCFencePolygon.h"
#include "QGCFenceCircle.h"
#include "Vehicle.h"
#include "MultiVehicleManager.h"
#include "QGCLoggingCategory.h"
......@@ -29,21 +30,32 @@ public:
GeoFenceController(PlanMasterController* masterController, QObject* parent = NULL);
~GeoFenceController();
Q_PROPERTY(QGCMapPolygon* mapPolygon READ mapPolygon CONSTANT)
Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged)
Q_PROPERTY(QmlObjectListModel* polygons READ polygons CONSTANT)
Q_PROPERTY(QmlObjectListModel* circles READ circles CONSTANT)
Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged)
// The following properties are reflections of properties from GeoFenceManager
Q_PROPERTY(bool circleEnabled READ circleEnabled NOTIFY circleEnabledChanged)
Q_PROPERTY(Fact* circleRadiusFact READ circleRadiusFact NOTIFY circleRadiusFactChanged)
Q_PROPERTY(bool polygonSupported READ polygonSupported NOTIFY polygonSupportedChanged)
Q_PROPERTY(bool polygonEnabled READ polygonEnabled NOTIFY polygonEnabledChanged)
Q_PROPERTY(bool breachReturnSupported READ breachReturnSupported NOTIFY breachReturnSupportedChanged)
Q_PROPERTY(QVariantList params READ params NOTIFY paramsChanged)
Q_PROPERTY(QStringList paramLabels READ paramLabels NOTIFY paramLabelsChanged)
/// Add a new inclusion polygon to the fence
/// @param topLeft - Top left coordinate or map viewport
/// @param topLeft - Bottom right left coordinate or map viewport
Q_INVOKABLE void addInclusionPolygon(QGeoCoordinate topLeft, QGeoCoordinate bottomRight);
Q_INVOKABLE void addPolygon (void) { emit addInitialFencePolygon(); }
Q_INVOKABLE void removePolygon (void) { _mapPolygon.clear(); }
/// Add a new inclusion circle to the fence
/// @param topLeft - Top left coordinate or map viewport
/// @param topLeft - Bottom right left coordinate or map viewport
Q_INVOKABLE void addInclusionCircle(QGeoCoordinate topLeft, QGeoCoordinate bottomRight);
/// Deletes the specified polygon from the polygon list
/// @param index Index of poygon to delete
Q_INVOKABLE void deletePolygon(int index);
/// Deletes the specified circle from the circle list
/// @param index Index of circle to delete
Q_INVOKABLE void deleteCircle(int index);
/// Clears the interactive bit from all fence items
Q_INVOKABLE void clearAllInteractive(void);
bool supported (void) const final;
void start (bool editMode) final;
void save (QJsonObject& json) final;
bool load (const QJsonObject& json, QString& errorString) final;
......@@ -58,15 +70,9 @@ public:
void managerVehicleChanged (Vehicle* managerVehicle) final;
bool showPlanFromManagerVehicle (void) final;
bool circleEnabled (void) const;
Fact* circleRadiusFact (void) const;
bool polygonSupported (void) const;
bool polygonEnabled (void) const;
bool breachReturnSupported (void) const;
QVariantList params (void) const;
QStringList paramLabels (void) const;
QGCMapPolygon* mapPolygon (void) { return &_mapPolygon; }
QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
QmlObjectListModel* polygons (void) { return &_polygons; }
QmlObjectListModel* circles (void) { return &_circles; }
QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
void setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint);
......@@ -74,21 +80,14 @@ signals:
void breachReturnPointChanged (QGeoCoordinate breachReturnPoint);
void editorQmlChanged (QString editorQml);
void loadComplete (void);
void addInitialFencePolygon (void);
void circleEnabledChanged (bool circleEnabled);
void circleRadiusFactChanged (Fact* circleRadiusFact);
void polygonSupportedChanged (bool polygonSupported);
void polygonEnabledChanged (bool polygonEnabled);
void breachReturnSupportedChanged (bool breachReturnSupported);
void paramsChanged (QVariantList params);
void paramLabelsChanged (QStringList paramLabels);
private slots:
void _polygonDirtyChanged(bool dirty);
void _setDirty(void);
void _setPolygonFromManager(const QList<QGeoCoordinate>& polygon);
void _setFenceFromManager(const QList<QGCFencePolygon>& polygons,
const QList<QGCFenceCircle>& circles);
void _setReturnPointFromManager(QGeoCoordinate breachReturnPoint);
void _managerLoadComplete(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon);
void _managerLoadComplete(void);
void _updateContainsItems(void);
void _managerSendComplete(bool error);
void _managerRemoveAllComplete(bool error);
......@@ -99,7 +98,8 @@ private:
GeoFenceManager* _geoFenceManager;
bool _dirty;
QGCMapPolygon _mapPolygon;
QmlObjectListModel _polygons;
QmlObjectListModel _circles;
QGeoCoordinate _breachReturnPoint;
bool _itemsRequested;
......
......@@ -10,14 +10,22 @@
#include "GeoFenceManager.h"
#include "Vehicle.h"
#include "QmlObjectListModel.h"
#include "ParameterManager.h"
#include "QGCMapPolygon.h"
#include "QGCMapCircle.h"
QGC_LOGGING_CATEGORY(GeoFenceManagerLog, "GeoFenceManagerLog")
GeoFenceManager::GeoFenceManager(Vehicle* vehicle)
: QObject(vehicle)
, _vehicle(vehicle)
: _vehicle (vehicle)
, _planManager (vehicle, MAV_MISSION_TYPE_FENCE)
, _firstParamLoadComplete (false)
{
connect(&_planManager, &PlanManager::inProgressChanged, this, &GeoFenceManager::inProgressChanged);
connect(&_planManager, &PlanManager::error, this, &GeoFenceManager::error);
connect(&_planManager, &PlanManager::removeAllComplete, this, &GeoFenceManager::removeAllComplete);
connect(&_planManager, &PlanManager::sendComplete, this, &GeoFenceManager::_sendComplete);
connect(&_planManager, &PlanManager::newMissionItemsAvailable, this, &GeoFenceManager::_planManagerLoadComplete);
}
GeoFenceManager::~GeoFenceManager()
......@@ -25,30 +33,161 @@ GeoFenceManager::~GeoFenceManager()
}
void GeoFenceManager::_sendError(ErrorCode_t errorCode, const QString& errorMsg)
bool GeoFenceManager::inProgress(void) const
{
qCDebug(GeoFenceManagerLog) << "Sending error" << errorCode << errorMsg;
emit error(errorCode, errorMsg);
return _planManager.inProgress();
}
void GeoFenceManager::loadFromVehicle(void)
{
// No geofence support in unknown vehicle
emit loadComplete(QGeoCoordinate(), QList<QGeoCoordinate>());
_planManager.loadFromVehicle();
}
void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon)
void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn,
QmlObjectListModel& polygons,
QmlObjectListModel& circles)
{
// No geofence support in unknown vehicle
Q_UNUSED(breachReturn);
Q_UNUSED(polygon);
emit sendComplete(false /* error */);
}
QList<MissionItem*> fenceItems;
_sendPolygons.clear();
_sendCircles.clear();
for (int i=0; i<polygons.count(); i++) {
_sendPolygons.append(*polygons.value<QGCFencePolygon*>(i));
}
for (int i=0; i<circles.count(); i++) {
_sendCircles.append(*circles.value<QGCFenceCircle*>(i));
}
for (int i=0; i<_sendPolygons.count(); i++) {
const QGCFencePolygon& polygon = _sendPolygons[i];
for (int j=0; j<polygon.count(); j++) {
const QGeoCoordinate& vertex = polygon.path()[j].value<QGeoCoordinate>();
MissionItem* item = new MissionItem(0,
polygon.inclusion() ? MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION : MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION,
MAV_FRAME_GLOBAL,
polygon.count(), // vertex count
0, 0, 0, // param 2-4 unused
vertex.latitude(),
vertex.longitude(),
0, // param 7 unused
false, // autocontinue
false, // isCurrentItem
this); // parent
fenceItems.append(item);
}
}
for (int i=0; i<_sendCircles.count(); i++) {
QGCFenceCircle& circle = _sendCircles[i];
MissionItem* item = new MissionItem(0,
circle.inclusion() ? MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION : MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,
MAV_FRAME_GLOBAL,
circle.radius()->rawValue().toDouble(),
0, 0, 0, // param 2-4 unused
circle.center().latitude(),
circle.center().longitude(),
0, // param 7 unused
false, // autocontinue
false, // isCurrentItem
this); // parent
fenceItems.append(item);
}
_planManager.writeMissionItems(fenceItems);
for (int i=0; i<fenceItems.count(); i++) {
fenceItems[i]->deleteLater();
}
}
void GeoFenceManager::removeAll(void)
{
// No geofence support in unknown vehicle
emit removeAllComplete(false /* error */);
_planManager.removeAll();
}
void GeoFenceManager::_sendComplete(bool error)
{
if (error) {
_polygons.clear();
_circles.clear();
} else {
_polygons = _sendPolygons;
_circles = _sendCircles;
}
_sendPolygons.clear();
_sendCircles.clear();
emit sendComplete(error);
}
void GeoFenceManager::_planManagerLoadComplete(bool removeAllRequested)
{
bool loadFailed = false;
Q_UNUSED(removeAllRequested);
_polygons.clear();
_circles.clear();
MAV_CMD expectedCommand = (MAV_CMD)0;
int expectedVertexCount = 0;
QGCFencePolygon nextPolygon(true /* inclusion */);
const QList<MissionItem*>& fenceItems = _planManager.missionItems();
for (int i=0; i<fenceItems.count(); i++) {
MissionItem* item = fenceItems[i];
MAV_CMD command = item->command();
if (command == MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION || command == MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION) {
if (nextPolygon.count() == 0) {
// Starting a new polygon
expectedVertexCount = item->param1();
expectedCommand = command;
} else if (expectedVertexCount != item->param1()){
// In the middle of a polygon, but count suddenly changed
emit error(BadPolygonItemFormat, tr("GeoFence load: Vertex count change mid-polygon - actual:expected").arg(item->param1()).arg(expectedVertexCount));
break;
} if (expectedCommand != command) {
// Command changed before last polygon was completely loaded
emit error(BadPolygonItemFormat, tr("GeoFence load: Polygon type changed before last load complete - actual:expected").arg(command).arg(expectedCommand));
break;
}
nextPolygon.appendVertex(QGeoCoordinate(item->param5(), item->param6()));
if (nextPolygon.count() == expectedVertexCount) {
// Polygon is complete
nextPolygon.setInclusion(command == MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION);
_polygons.append(nextPolygon);
nextPolygon.clear();
}
} else if (command == MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION || command == MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION) {
if (nextPolygon.count() != 0) {
// Incomplete polygon
emit error(IncompletePolygonLoad, tr("GeoFence load: Incomplete polygon loaded"));
break;
}
QGCFenceCircle circle(QGeoCoordinate(item->param5(), item->param6()), item->param1(), command == MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION /* inclusion */);
_circles.append(circle);
} else {
emit error(UnsupportedCommand, tr("GeoFence load: Unsupported command %1").arg(item->command()));
break;
}
}
if (loadFailed) {
_polygons.clear();
_circles.clear();
}
emit loadComplete();
}
bool GeoFenceManager::supported(void) const
{
return (_vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE) && (_vehicle->maxProtoVersion() >= 200);
}
......@@ -15,9 +15,13 @@
#include "QGCLoggingCategory.h"
#include "FactSystem.h"
#include "PlanManager.h"
#include "QGCFencePolygon.h"
#include "QGCFenceCircle.h"
class Vehicle;
class QmlObjectListModel;
class PlanManager;
Q_DECLARE_LOGGING_CATEGORY(GeoFenceManagerLog)
......@@ -31,80 +35,67 @@ public:
GeoFenceManager(Vehicle* vehicle);
~GeoFenceManager();
/// Returns true if GeoFence is supported by this vehicle
virtual bool supported(void) const;
/// Returns true if the manager is currently communicating with the vehicle
virtual bool inProgress(void) const { return false; }
virtual bool inProgress(void) const;
/// Load the current settings from the vehicle
/// Signals loadComplete when done
virtual void loadFromVehicle(void);
/// Send the current settings to the vehicle
/// Send the geofence settings to the vehicle
/// Signals sendComplete when done
virtual void sendToVehicle(const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon);
virtual void sendToVehicle(const QGeoCoordinate& breachReturn, ///< Breach return point
QmlObjectListModel& polygons, ///< List of QGCFencePolygons
QmlObjectListModel& circles); ///< List of QGCFenceCircles
/// Remove all fence related items from vehicle (does not affect parameters)
/// Signals removeAllComplete when done
virtual void removeAll(void);
/// Returns true if this vehicle support polygon fence
/// Signal: polygonSupportedChanged
virtual bool polygonSupported(void) const { return false; }
/// Returns true if polygon fence is currently enabled on this vehicle
/// Signal: polygonEnabledChanged
virtual bool polygonEnabled(void) const { return false; }
/// Returns true if breach return is supported by this vehicle
/// Signal: breachReturnSupportedChanged
virtual bool breachReturnSupported(void) const { return false; }
/// Returns a list of parameter facts that relate to geofence support for the vehicle
/// Signal: paramsChanged
virtual QVariantList params(void) const { return QVariantList(); }
virtual bool polygonEnabled(void) const { return true; }
/// Returns the user visible labels for the paremeters returned by params method
/// Signal: paramLabelsChanged
virtual QStringList paramLabels(void) const { return QStringList(); }
/// Returns true if circular fence is currently enabled on vehicle
/// Signal: circleEnabledChanged
virtual bool circleEnabled(void) const { return false; }
/// Returns the fact which controls the fence circle radius. NULL if not supported
/// Signal: circleRadiusFactChanged
virtual Fact* circleRadiusFact(void) const { return NULL; }
QList<QGeoCoordinate> polygon (void) const { return _polygon; }
QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
const QList<QGCFencePolygon>& polygons(void) { return _polygons; }
const QList<QGCFenceCircle>& circles(void) { return _circles; }
const QGeoCoordinate& breachReturnPoint(void) const { return _breachReturnPoint; }
/// Error codes returned in error signal
typedef enum {
InternalError,
TooFewPoints, ///< Too few points for valid geofence
TooManyPoints, ///< Too many points for valid geofence
PolygonTooFewPoints, ///< Too few points for valid fence polygon
PolygonTooManyPoints, ///< Too many points for valid fence polygon
IncompletePolygonLoad, ///< Incomplete polygon loaded
UnsupportedCommand, ///< Usupported command in mission type
BadPolygonItemFormat, ///< Error re-creating polygons from mission items
InvalidCircleRadius,
} ErrorCode_t;
signals:
void loadComplete (const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon);
void loadComplete (void);
void inProgressChanged (bool inProgress);
void error (int errorCode, const QString& errorMsg);
void paramsChanged (QVariantList params);
void paramLabelsChanged (QStringList paramLabels);
void circleEnabledChanged (bool circleEnabled);
void circleRadiusFactChanged (Fact* circleRadiusFact);
void polygonSupportedChanged (bool polygonSupported);
void polygonEnabledChanged (bool polygonEnabled);
void breachReturnSupportedChanged (bool breachReturnSupported);
void removeAllComplete (bool error);
void sendComplete (bool error);
protected:
private slots:
void _sendComplete (bool error);
void _planManagerLoadComplete (bool removeAllRequested);
private:
void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
Vehicle* _vehicle;
QList<QGeoCoordinate> _polygon;
PlanManager _planManager;
QList<QGCFencePolygon> _polygons;
QList<QGCFenceCircle> _circles;
QGeoCoordinate _breachReturnPoint;
bool _firstParamLoadComplete;
QList<QGCFencePolygon> _sendPolygons;
QList<QGCFenceCircle> _sendCircles;
};
#endif
......@@ -110,6 +110,7 @@ public:
bool loadTextFile(QFile& file, QString& errorString);
// Overrides from PlanElementController
bool supported (void) const final { return true; };
void start (bool editMode) final;
void save (QJsonObject& json) final;
bool load (const QJsonObject& json, QString& errorString) final;
......
This diff is collapsed.
......@@ -11,22 +11,11 @@
#ifndef MissionManager_H
#define MissionManager_H
#include <QObject>
#include <QLoggingCategory>
#include <QThread>
#include <QMutex>
#include <QTimer>
#include "MissionItem.h"
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include "LinkInterface.h"
class Vehicle;
#include "PlanManager.h"
Q_DECLARE_LOGGING_CATEGORY(MissionManagerLog)
class MissionManager : public QObject
class MissionManager : public PlanManager
{
Q_OBJECT
......@@ -34,128 +23,14 @@ public:
MissionManager(Vehicle* vehicle);
~MissionManager();
bool inProgress(void);
const QList<MissionItem*>& missionItems(void) { return _missionItems; }
/// Current mission item as reported by MISSION_CURRENT
int currentIndex(void) const { return _currentMissionIndex; }
/// Last current mission item reported while in Mission flight mode
int lastCurrentIndex(void) const { return _lastCurrentIndex; }
/// Load the mission items from the vehicle
/// Signals newMissionItemsAvailable when done
void loadFromVehicle(void);
/// Writes the specified set of mission items to the vehicle
/// @param missionItems Items to send to vehicle
/// Signals sendComplete when done
void writeMissionItems(const QList<MissionItem*>& missionItems);
/// Writes the specified set mission items to the vehicle as an ArduPilot guided mode mission item.
/// @param gotoCoord Coordinate to move to
/// @param altChangeOnly true: only altitude change, false: lat/lon/alt change
void writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoCoord, bool altChangeOnly);
/// Removes all mission items from vehicle
/// Signals removeAllComplete when done
void removeAll(void);
/// Generates a new mission which starts from the specified index. It will include all the CMD_DO items
/// from mission start to resumeIndex in the generate mission.
void generateResumeMission(int resumeIndex);
/// Error codes returned in error signal
typedef enum {
InternalError,
AckTimeoutError, ///< Timed out waiting for response from vehicle
ProtocolOrderError, ///< Incorrect protocol sequence from vehicle
RequestRangeError, ///< Vehicle requested item out of range
ItemMismatchError, ///< Vehicle returned item with seq # different than requested
VehicleError, ///< Vehicle returned error
MissingRequestsError, ///< Vehicle did not request all items during write sequence
MaxRetryExceeded, ///< Retry failed
} ErrorCode_t;
// These values are public so the unit test can set appropriate signal wait times
static const int _ackTimeoutMilliseconds = 1000;
static const int _maxRetryCount = 5;
signals:
void newMissionItemsAvailable(bool removeAllRequested);
void inProgressChanged(bool inProgress);
void error(int errorCode, const QString& errorMsg);
void currentIndexChanged(int currentIndex);
void lastCurrentIndexChanged(int lastCurrentIndex);
void resumeMissionReady(void);
void resumeMissionUploadFail(void);
void progressPct(double progressPercentPct);
void removeAllComplete (bool error);
void sendComplete (bool error);
private slots:
void _mavlinkMessageReceived(const mavlink_message_t& message);
void _ackTimeout(void);
private:
typedef enum {
AckNone, ///< State machine is idle
AckMissionCount, ///< MISSION_COUNT message expected
AckMissionItem, ///< MISSION_ITEM expected
AckMissionRequest, ///< MISSION_REQUEST is expected, or MISSION_ACK to end sequence
AckMissionClearAll, ///< MISSION_CLEAR_ALL sent, MISSION_ACK is expected
AckGuidedItem, ///< MISSION_ACK expected in response to ArduPilot guided mode single item send
} AckType_t;
typedef enum {
TransactionNone,
TransactionRead,
TransactionWrite,
TransactionRemoveAll
} TransactionType_t;
void _startAckTimeout(AckType_t ack);
bool _checkForExpectedAck(AckType_t receivedAck);
void _readTransactionComplete(void);
void _handleMissionCount(const mavlink_message_t& message);
void _handleMissionItem(const mavlink_message_t& message, bool missionItemInt);
void _handleMissionRequest(const mavlink_message_t& message, bool missionItemInt);
void _handleMissionAck(const mavlink_message_t& message);
void _handleMissionCurrent(const mavlink_message_t& message);
void _requestNextMissionItem(void);
void _clearMissionItems(void);
void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
QString _ackTypeToString(AckType_t ackType);
QString _missionResultToString(MAV_MISSION_RESULT result);
void _finishTransaction(bool success);
void _requestList(void);
void _writeMissionCount(void);
void _writeMissionItemsWorker(void);
void _clearAndDeleteMissionItems(void);
void _clearAndDeleteWriteMissionItems(void);
QString _lastMissionReqestString(MAV_MISSION_RESULT result);
void _removeAllWorker(void);
private:
Vehicle* _vehicle;
LinkInterface* _dedicatedLink;
QTimer* _ackTimeoutTimer;
AckType_t _expectedAck;
int _retryCount;
TransactionType_t _transactionInProgress;
bool _resumeMission;
QList<int> _itemIndicesToWrite; ///< List of mission items which still need to be written to vehicle
QList<int> _itemIndicesToRead; ///< List of mission items which still need to be requested from vehicle
int _lastMissionRequest; ///< Index of item last requested by MISSION_REQUEST
QMutex _dataMutex;
QList<MissionItem*> _missionItems; ///< Set of mission items on vehicle
QList<MissionItem*> _writeMissionItems; ///< Set of mission items currently being written to vehicle
int _currentMissionIndex;
int _lastCurrentIndex;
};
#endif
......@@ -27,6 +27,7 @@ public:
PlanElementController(PlanMasterController* masterController, QObject* parent = NULL);
~PlanElementController();
Q_PROPERTY(bool supported READ supported NOTIFY supportedChanged) ///< true: Element is supported by Vehicle
Q_PROPERTY(bool containsItems READ containsItems NOTIFY containsItemsChanged) ///< true: Elemement is non-empty
Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) ///< true: information is currently being saved/sent, false: no active save/send in progress
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: unsaved/sent changes are present, false: no changes since last save/send
......@@ -41,10 +42,11 @@ public:
virtual void removeAll (void) = 0; ///< Removes all from controller only
virtual bool showPlanFromManagerVehicle (void) = 0; /// true: controller is waiting for the current load to complete
virtual bool containsItems (void) const = 0;
virtual bool syncInProgress (void) const = 0;
virtual bool dirty (void) const = 0;
virtual void setDirty (bool dirty) = 0;
virtual bool supported (void) const = 0;
virtual bool containsItems (void) const = 0;
virtual bool syncInProgress (void) const = 0;
virtual bool dirty (void) const = 0;
virtual void setDirty (bool dirty) = 0;
/// Sends the current plan element to the vehicle
/// Signals sendComplete when done
......@@ -58,6 +60,7 @@ public:
virtual void managerVehicleChanged(Vehicle* managerVehicle) = 0;
signals:
void supportedChanged (bool supported);
void containsItemsChanged (bool containsItems);
void syncInProgressChanged (bool syncInProgress);
void dirtyChanged (bool dirty);
......
This diff is collapsed.
/****************************************************************************
*
* (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 PlanManager_H
#define PlanManager_H
#include <QObject>
#include <QLoggingCategory>
#include <QTimer>
#include "MissionItem.h"
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include "LinkInterface.h"
class Vehicle;
Q_DECLARE_LOGGING_CATEGORY(PlanManagerLog)
/// The PlanManager class is the base class for the Mission, GeoFence and Rally Point managers. All of which use the
/// new mavlink v2 mission protocol.
class PlanManager : public QObject
{
Q_OBJECT
public:
PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType);
~PlanManager();
bool inProgress(void) const;
const QList<MissionItem*>& missionItems(void) { return _missionItems; }
/// Current mission item as reported by MISSION_CURRENT
int currentIndex(void) const { return _currentMissionIndex; }
/// Last current mission item reported while in Mission flight mode
int lastCurrentIndex(void) const { return _lastCurrentIndex; }
/// Load the mission items from the vehicle
/// Signals newMissionItemsAvailable when done
void loadFromVehicle(void);
/// Writes the specified set of mission items to the vehicle
/// @param missionItems Items to send to vehicle
/// Signals sendComplete when done
void writeMissionItems(const QList<MissionItem*>& missionItems);
/// Removes all mission items from vehicle
/// Signals removeAllComplete when done
void removeAll(void);
/// Error codes returned in error signal
typedef enum {
InternalError,
AckTimeoutError, ///< Timed out waiting for response from vehicle
ProtocolOrderError, ///< Incorrect protocol sequence from vehicle
RequestRangeError, ///< Vehicle requested item out of range
ItemMismatchError, ///< Vehicle returned item with seq # different than requested
VehicleError, ///< Vehicle returned error
MissingRequestsError, ///< Vehicle did not request all items during write sequence
MaxRetryExceeded, ///< Retry failed
MissionTypeMismatch, ///< MAV_MISSION_TYPE does not match _planType
} ErrorCode_t;
// These values are public so the unit test can set appropriate signal wait times
static const int _ackTimeoutMilliseconds = 1000;
static const int _maxRetryCount = 5;
signals:
void newMissionItemsAvailable (bool removeAllRequested);
void inProgressChanged (bool inProgress);
void error (int errorCode, const QString& errorMsg);
void currentIndexChanged (int currentIndex);
void lastCurrentIndexChanged (int lastCurrentIndex);
void progressPct (double progressPercentPct);
void removeAllComplete (bool error);
void sendComplete (bool error);
void resumeMissionReady (void);
void resumeMissionUploadFail (void);
private slots:
void _mavlinkMessageReceived(const mavlink_message_t& message);
void _ackTimeout(void);
protected:
typedef enum {
AckNone, ///< State machine is idle
AckMissionCount, ///< MISSION_COUNT message expected
AckMissionItem, ///< MISSION_ITEM expected
AckMissionRequest, ///< MISSION_REQUEST is expected, or MISSION_ACK to end sequence
AckMissionClearAll, ///< MISSION_CLEAR_ALL sent, MISSION_ACK is expected
AckGuidedItem, ///< MISSION_ACK expected in response to ArduPilot guided mode single item send
} AckType_t;
typedef enum {
TransactionNone,
TransactionRead,
TransactionWrite,
TransactionRemoveAll
} TransactionType_t;
void _startAckTimeout(AckType_t ack);
bool _checkForExpectedAck(AckType_t receivedAck);
void _readTransactionComplete(void);
void _handleMissionCount(const mavlink_message_t& message);
void _handleMissionItem(const mavlink_message_t& message, bool missionItemInt);
void _handleMissionRequest(const mavlink_message_t& message, bool missionItemInt);
void _handleMissionAck(const mavlink_message_t& message);
void _handleMissionCurrent(const mavlink_message_t& message);
void _requestNextMissionItem(void);
void _clearMissionItems(void);
void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
QString _ackTypeToString(AckType_t ackType);
QString _missionResultToString(MAV_MISSION_RESULT result);
void _finishTransaction(bool success);
void _requestList(void);
void _writeMissionCount(void);
void _writeMissionItemsWorker(void);
void _clearAndDeleteMissionItems(void);
void _clearAndDeleteWriteMissionItems(void);
QString _lastMissionReqestString(MAV_MISSION_RESULT result);
void _removeAllWorker(void);
void _connectToMavlink(void);
void _disconnectFromMavlink(void);
QString _planTypeString(void);
protected:
Vehicle* _vehicle;
MAV_MISSION_TYPE _planType;
LinkInterface* _dedicatedLink;
QTimer* _ackTimeoutTimer;
AckType_t _expectedAck;
int _retryCount;
TransactionType_t _transactionInProgress;
bool _resumeMission;
QList<int> _itemIndicesToWrite; ///< List of mission items which still need to be written to vehicle
QList<int> _itemIndicesToRead; ///< List of mission items which still need to be requested from vehicle
int _lastMissionRequest; ///< Index of item last requested by MISSION_REQUEST
QList<MissionItem*> _missionItems; ///< Set of mission items on vehicle
QList<MissionItem*> _writeMissionItems; ///< Set of mission items currently being written to vehicle
int _currentMissionIndex;
int _lastCurrentIndex;
};
#endif
......@@ -177,8 +177,14 @@ void PlanMasterController::_loadMissionComplete(void)
if (_editMode && _loadGeoFence) {
_loadGeoFence = false;
_loadRallyPoints = true;
qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete _geoFenceController.loadFromVehicle";
_geoFenceController.loadFromVehicle();
if (_geoFenceController.supported()) {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete _geoFenceController.loadFromVehicle";
_geoFenceController.loadFromVehicle();
} else {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete GeoFence not supported skipping";
_geoFenceController.removeAll();
_loadGeoFenceComplete();
}
setDirty(false);
}
}
......@@ -187,8 +193,14 @@ void PlanMasterController::_loadGeoFenceComplete(void)
{
if (_editMode && _loadRallyPoints) {
_loadRallyPoints = false;
qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadGeoFenceComplete _rallyPointController.loadFromVehicle";
_rallyPointController.loadFromVehicle();
if (_rallyPointController.supported()) {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadGeoFenceComplete _rallyPointController.loadFromVehicle";
_rallyPointController.loadFromVehicle();
} else {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete Rally Points not supported skipping";
_rallyPointController.removeAll();
_loadRallyPointsComplete();
}
setDirty(false);
}
}
......@@ -204,10 +216,15 @@ void PlanMasterController::_loadRallyPointsComplete(void)
void PlanMasterController::_sendMissionComplete(void)
{
if (_sendGeoFence) {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle start fence sendToVehicle";
_sendGeoFence = false;
_sendRallyPoints = true;
_geoFenceController.sendToVehicle();
if (_geoFenceController.supported()) {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle start GeoFence sendToVehicle";
_geoFenceController.sendToVehicle();
} else {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle GeoFence not supported skipping";
_sendGeoFenceComplete();
}
setDirty(false);
}
}
......@@ -215,16 +232,21 @@ void PlanMasterController::_sendMissionComplete(void)
void PlanMasterController::_sendGeoFenceComplete(void)
{
if (_sendRallyPoints) {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle start rally sendToVehicle";
_sendRallyPoints = false;
_rallyPointController.sendToVehicle();
if (_rallyPointController.supported()) {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle start rally sendToVehicle";
_rallyPointController.sendToVehicle();
} else {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle Rally Points not support skipping";
_sendRallyPointsComplete();
}
}
}
void PlanMasterController::_sendRallyPointsComplete(void)
{
if (_syncInProgress) {
qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle rally point send complete";
qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle Rally Point send complete";
_syncInProgress = false;
emit syncInProgressChanged(false);
}
......@@ -361,8 +383,12 @@ void PlanMasterController::removeAllFromVehicle(void)
{
if (!offline()) {
_missionController.removeAllFromVehicle();
_geoFenceController.removeAllFromVehicle();
_rallyPointController.removeAllFromVehicle();
if (_geoFenceController.supported()) {
_geoFenceController.removeAllFromVehicle();
}
if (_rallyPointController.supported()) {
_rallyPointController.removeAllFromVehicle();
}
setDirty(false);
} else {
qWarning() << "PlanMasterController::removeAllFromVehicle called while offline";
......
/****************************************************************************
*
* (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 "QGCFenceCircle.h"
#include "JsonHelper.h"
const char* QGCFenceCircle::_jsonInclusionKey = "inclusion";
QGCFenceCircle::QGCFenceCircle(QObject* parent)
: QGCMapCircle (parent)
, _inclusion (true)
{
_init();
}
QGCFenceCircle::QGCFenceCircle(const QGeoCoordinate& center, double radius, bool inclusion, QObject* parent)
: QGCMapCircle (center, radius, parent)
, _inclusion (inclusion)
{
_init();
}
QGCFenceCircle::QGCFenceCircle(const QGCFenceCircle& other, QObject* parent)
: QGCMapCircle (other, parent)
, _inclusion (other._inclusion)
{
_init();
}
void QGCFenceCircle::_init(void)
{
connect(this, &QGCFenceCircle::inclusionChanged, this, &QGCFenceCircle::_setDirty);
}
const QGCFenceCircle& QGCFenceCircle::operator=(const QGCFenceCircle& other)
{
QGCMapCircle::operator=(other);
setInclusion(other._inclusion);
return *this;
}
void QGCFenceCircle::_setDirty(void)
{
setDirty(true);
}
void QGCFenceCircle::saveToJson(QJsonObject& json)
{
QGCMapCircle::saveToJson(json);
json[_jsonInclusionKey] = _inclusion;
}
bool QGCFenceCircle::loadFromJson(const QJsonObject& json, QString& errorString)
{
if (!QGCMapCircle::loadFromJson(json, errorString)) {
return false;
}
errorString.clear();
QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ _jsonInclusionKey, QJsonValue::Bool, true },
};
if (!JsonHelper::validateKeys(json, keyInfoList, errorString)) {
return false;
}
setInclusion(json[_jsonInclusionKey].toBool());
return true;
}
void QGCFenceCircle::setInclusion(bool inclusion)
{
if (inclusion != _inclusion) {
_inclusion = inclusion;
emit inclusionChanged(inclusion);
}
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#pragma once
#include "QGCMapCircle.h"
/// The QGCFenceCircle class provides a cicle used by GeoFence support.
class QGCFenceCircle : public QGCMapCircle
{
Q_OBJECT
public:
QGCFenceCircle(QObject* parent = NULL);
QGCFenceCircle(const QGeoCoordinate& center, double radius, bool inclusion, QObject* parent = NULL);
QGCFenceCircle(const QGCFenceCircle& other, QObject* parent = NULL);
const QGCFenceCircle& operator=(const QGCFenceCircle& other);
Q_PROPERTY(bool inclusion READ inclusion WRITE setInclusion NOTIFY inclusionChanged)
/// Saves the QGCFenceCircle to the json object.
/// @param json Json object to save to
void saveToJson(QJsonObject& json);
/// Load a QGCFenceCircle from json
/// @param json Json object to load from
/// @param errorString Error string if return is false
/// @return true: success, false: failure (errorString set)
bool loadFromJson(const QJsonObject& json, QString& errorString);
// Property methods
bool inclusion (void) const { return _inclusion; }
void setInclusion (bool inclusion);
signals:
void inclusionChanged(bool inclusion);
private slots:
void _setDirty(void);
private:
void _init(void);
bool _inclusion;
static const char* _jsonInclusionKey;
};
/****************************************************************************
*
* (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 "QGCFencePolygon.h"
#include "JsonHelper.h"
const char* QGCFencePolygon::_jsonInclusionKey = "inclusion";
QGCFencePolygon::QGCFencePolygon(bool inclusion, QObject* parent)
: QGCMapPolygon (parent)
, _inclusion (inclusion)
{
_init();
}
QGCFencePolygon::QGCFencePolygon(const QGCFencePolygon& other, QObject* parent)
: QGCMapPolygon (other, parent)
, _inclusion (other._inclusion)
{
_init();
}
void QGCFencePolygon::_init(void)
{
connect(this, &QGCFencePolygon::inclusionChanged, this, &QGCFencePolygon::_setDirty);
}
const QGCFencePolygon& QGCFencePolygon::operator=(const QGCFencePolygon& other)
{
QGCMapPolygon::operator=(other);
setInclusion(other._inclusion);
return *this;
}
void QGCFencePolygon::_setDirty(void)
{
setDirty(true);
}
void QGCFencePolygon::saveToJson(QJsonObject& json)
{
QGCMapPolygon::saveToJson(json);
json[_jsonInclusionKey] = _inclusion;
}
bool QGCFencePolygon::loadFromJson(const QJsonObject& json, bool required, QString& errorString)
{
if (!QGCMapPolygon::loadFromJson(json, required, errorString)) {
return false;
}
errorString.clear();
QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ _jsonInclusionKey, QJsonValue::Bool, true },
};
if (!JsonHelper::validateKeys(json, keyInfoList, errorString)) {
return false;
}
setInclusion(json[_jsonInclusionKey].toBool());
return true;
}
void QGCFencePolygon::setInclusion(bool inclusion)
{
if (inclusion != _inclusion) {
_inclusion = inclusion;
emit inclusionChanged(inclusion);
}
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#pragma once
#include "QGCMapPolygon.h"
/// The QGCFencePolygon class provides a polygon used by GeoFence support.
class QGCFencePolygon : public QGCMapPolygon
{
Q_OBJECT
public:
QGCFencePolygon(bool inclusion, QObject* parent = NULL);
QGCFencePolygon(const QGCFencePolygon& other, QObject* parent = NULL);
const QGCFencePolygon& operator=(const QGCFencePolygon& other);
Q_PROPERTY(bool inclusion READ inclusion WRITE setInclusion NOTIFY inclusionChanged)
/// Saves the QGCFencePolygon to the json object.
/// @param json Json object to save to
void saveToJson(QJsonObject& json);
/// Load a QGCFencePolygon from json
/// @param json Json object to load from
/// @param required true: no polygon in object will generate error
/// @param errorString Error string if return is false
/// @return true: success, false: failure (errorString set)
bool loadFromJson(const QJsonObject& json, bool required, QString& errorString);
// Property methods
bool inclusion (void) const { return _inclusion; }
void setInclusion (bool inclusion);
signals:
void inclusionChanged (bool inclusion);
private slots:
void _setDirty(void);
private:
void _init(void);
bool _inclusion;
static const char* _jsonInclusionKey;
};
[
{
"name": "Radius",
"shortDescription": "Radius for geofence circle.",
"type": "double",
"decimalPlaces": 2,
"min": 0.1,
"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.
*
****************************************************************************/
#include "QGCMapCircle.h"
#include "QGCGeo.h"
#include "JsonHelper.h"
#include "QGCQGeoCoordinate.h"
#include <QGeoRectangle>
#include <QDebug>
#include <QJsonArray>
const char* QGCMapCircle::jsonCircleKey = "circle";
const char* QGCMapCircle::_jsonCenterKey = "center";
const char* QGCMapCircle::_jsonRadiusKey = "radius";
const char* QGCMapCircle::_radiusFactName = "Radius";
QGCMapCircle::QGCMapCircle(QObject* parent)
: QObject (parent)
, _dirty (false)
, _interactive (false)
{
_init();
}
QGCMapCircle::QGCMapCircle(const QGeoCoordinate& center, double radius, QObject* parent)
: QObject (parent)
, _dirty (false)
, _center (center)
, _radius (FactSystem::defaultComponentId, _radiusFactName, FactMetaData::valueTypeDouble)
, _interactive (false)
{
_radius.setRawValue(radius);
_init();
}
QGCMapCircle::QGCMapCircle(const QGCMapCircle& other, QObject* parent)
: QObject (parent)
, _dirty (false)
, _center (other._center)
, _radius (FactSystem::defaultComponentId, _radiusFactName, FactMetaData::valueTypeDouble)
, _interactive (false)
{
_radius.setRawValue(other._radius.rawValue());
_init();
}
const QGCMapCircle& QGCMapCircle::operator=(const QGCMapCircle& other)
{
setCenter(other._center);
_radius.setRawValue(other._radius.rawValue());
setDirty(true);
return *this;
}
void QGCMapCircle::_init(void)
{
_nameToMetaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/QGCMapCircle.Facts.json"), this);
_radius.setMetaData(_nameToMetaDataMap[_radiusFactName]);
connect(this, &QGCMapCircle::centerChanged, this, &QGCMapCircle::_setDirty);
connect(&_radius, &Fact::rawValueChanged, this, &QGCMapCircle::_setDirty);
}
void QGCMapCircle::setDirty(bool dirty)
{
if (_dirty != dirty) {
_dirty = dirty;
emit dirtyChanged(dirty);
}
}
void QGCMapCircle::saveToJson(QJsonObject& json)
{
QJsonValue jsonValue;
QJsonObject circleObject;
JsonHelper::saveGeoCoordinate(_center, false /* writeAltitude*/, jsonValue);
circleObject.insert(_jsonCenterKey, jsonValue);
circleObject.insert(_jsonRadiusKey, _radius.rawValue().toDouble());
json.insert(jsonCircleKey, circleObject);
}
bool QGCMapCircle::loadFromJson(const QJsonObject& json, QString& errorString)
{
errorString.clear();
QList<JsonHelper::KeyValidateInfo> circleKeyInfo = {
{ jsonCircleKey, QJsonValue::Object, true },
};
if (!JsonHelper::validateKeys(json, circleKeyInfo, errorString)) {
return false;
}
QJsonObject circleObject = json[jsonCircleKey].toObject();
QList<JsonHelper::KeyValidateInfo> circleObjectKeyInfo = {
{ _jsonCenterKey, QJsonValue::Array, true },
{ _jsonRadiusKey, QJsonValue::Double, true },
};
if (!JsonHelper::validateKeys(circleObject, circleObjectKeyInfo, errorString)) {
return false;
}
QGeoCoordinate center;
if (!JsonHelper::loadGeoCoordinate(json[_jsonCenterKey], false /* altitudeRequired */, center, errorString)) {
return false;
}
setCenter(center);
_radius.setRawValue(json[_jsonRadiusKey].toDouble());
return true;
}
void QGCMapCircle::setCenter(QGeoCoordinate newCenter)
{
if (newCenter != _center) {
_center = newCenter;
setDirty(true);
emit centerChanged(newCenter);
}
}
void QGCMapCircle::_setDirty(void)
{
setDirty(true);
}
void QGCMapCircle::setInteractive(bool interactive)
{
if (_interactive != interactive) {
_interactive = interactive;
emit interactiveChanged(interactive);
}
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <QGeoCoordinate>
#include <QVariantList>
#include <QPolygon>
#include "QmlObjectListModel.h"
#include "FactSystem.h"
/// The QGCMapCircle represents a circular area which can be displayed on a Map control.
class QGCMapCircle : public QObject
{
Q_OBJECT
public:
QGCMapCircle(QObject* parent = NULL);
QGCMapCircle(const QGeoCoordinate& center, double radius, QObject* parent = NULL);
QGCMapCircle(const QGCMapCircle& other, QObject* parent = NULL);
const QGCMapCircle& operator=(const QGCMapCircle& other);
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_PROPERTY(QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged)
Q_PROPERTY(Fact* radius READ radius CONSTANT)
Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged)
/// Saves the polygon to the json object.
/// @param json Json object to save to
void saveToJson(QJsonObject& json);
/// Load a circle from json
/// @param json Json object to load from
/// @param errorString Error string if return is false
/// @return true: success, false: failure (errorString set)
bool loadFromJson(const QJsonObject& json, QString& errorString);
// Property methods
bool dirty (void) const { return _dirty; }
QGeoCoordinate center (void) const { return _center; }
Fact* radius (void) { return &_radius; }
bool interactive (void) const { return _interactive; }
void setDirty (bool dirty);
void setCenter (QGeoCoordinate newCenter);
void setInteractive (bool interactive);
static const char* jsonCircleKey;
signals:
void dirtyChanged (bool dirty);
void centerChanged (QGeoCoordinate center);
void interactiveChanged (bool interactive);
private slots:
void _setDirty(void);
private:
void _init(void);
bool _dirty;
QGeoCoordinate _center;
Fact _radius;
bool _interactive;
QMap<QString, FactMetaData*> _nameToMetaDataMap;
static const char* _jsonCenterKey;
static const char* _jsonRadiusKey;
static const char* _radiusFactName;
};
/****************************************************************************
*
* (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.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtLocation 5.3
import QtPositioning 5.3
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
/// QGCMapCircle map visuals
Item {
id: _root
property var mapControl ///< Map control to place item in
property var mapCircle ///< QGCMapCircle object
property bool interactive: mapCircle.interactive /// true: user can manipulate polygon
property color interiorColor: "transparent"
property real interiorOpacity: 1
property int borderWidth: 0
property color borderColor: "black"
property var _circleComponent
property var _centerDragHandleComponent
function addVisuals() {
_circleComponent = circleComponent.createObject(mapControl)
mapControl.addMapItem(_circleComponent)
}
function removeVisuals() {
_circleComponent.destroy()
}
function addHandles() {
if (!_centerDragHandleComponent) {
_centerDragHandleComponent = centerDragHandleComponent.createObject(mapControl)
}
}
function removeHandles() {
if (_centerDragHandleComponent) {
_centerDragHandleComponent.destroy()
_centerDragHandleComponent = undefined
}
}
onInteractiveChanged: {
if (interactive) {
addHandles()
} else {
removeHandles()
}
}
Component.onCompleted: {
addVisuals()
if (interactive) {
addHandles()
}
}
Component.onDestruction: {
removeVisuals()
removeHandles()
}
Component {
id: circleComponent
MapCircle {
color: interiorColor
opacity: interiorOpacity
border.color: borderColor
border.width: borderWidth
center: mapCircle.center
radius: mapCircle.radius.rawValue
}
}
Component {
id: dragHandleComponent
MapQuickItem {
id: mapQuickItem
anchorPoint.x: dragHandle.width / 2
anchorPoint.y: dragHandle.height / 2
z: QGroundControl.zOrderMapItems + 2
sourceItem: Rectangle {
id: dragHandle
width: ScreenTools.defaultFontPixelHeight * 1.5
height: width
radius: width / 2
color: "white"
opacity: .90
}
}
}
Component {
id: centerDragAreaComponent
MissionItemIndicatorDrag {
onItemCoordinateChanged: mapCircle.center = itemCoordinate
}
}
Component {
id: centerDragHandleComponent
Item {
property var dragHandle
property var dragArea
Component.onCompleted: {
dragHandle = dragHandleComponent.createObject(mapControl)
dragHandle.coordinate = Qt.binding(function() { return mapCircle.center })
mapControl.addMapItem(dragHandle)
dragArea = centerDragAreaComponent.createObject(mapControl, { "itemIndicator": dragHandle, "itemCoordinate": mapCircle.center })
}
Component.onDestruction: {
dragHandle.destroy()
dragArea.destroy()
}
}
}
}
......@@ -18,18 +18,49 @@
const char* QGCMapPolygon::jsonPolygonKey = "polygon";
QGCMapPolygon::QGCMapPolygon(QObject* newCoordParent, QObject* parent)
: QObject(parent)
, _newCoordParent(newCoordParent)
, _dirty(false)
, _centerDrag(false)
, _ignoreCenterUpdates(false)
QGCMapPolygon::QGCMapPolygon(QObject* parent)
: QObject (parent)
, _dirty (false)
, _centerDrag (false)
, _ignoreCenterUpdates (false)
, _interactive (false)
{
_init();
}
QGCMapPolygon::QGCMapPolygon(const QGCMapPolygon& other, QObject* parent)
: QObject (parent)
, _dirty (false)
, _centerDrag (false)
, _ignoreCenterUpdates (false)
, _interactive (false)
{
*this = other;
_init();
}
void QGCMapPolygon::_init(void)
{
connect(&_polygonModel, &QmlObjectListModel::dirtyChanged, this, &QGCMapPolygon::_polygonModelDirtyChanged);
connect(&_polygonModel, &QmlObjectListModel::countChanged, this, &QGCMapPolygon::_polygonModelCountChanged);
connect(&_polygonModel, &QmlObjectListModel::countChanged, this, &QGCMapPolygon::_updateCenter);
}
const QGCMapPolygon& QGCMapPolygon::operator=(const QGCMapPolygon& other)
{
clear();
QVariantList vertices = other.path();
for (int i=0; i<vertices.count(); i++) {
appendVertex(vertices[i].value<QGeoCoordinate>());
}
setDirty(true);
return *this;
}
void QGCMapPolygon::clear(void)
{
// Bug workaround, see below
......@@ -132,7 +163,7 @@ void QGCMapPolygon::setPath(const QList<QGeoCoordinate>& path)
_polygonModel.clearAndDeleteContents();
foreach(const QGeoCoordinate& coord, path) {
_polygonPath.append(QVariant::fromValue(coord));
_polygonModel.append(new QGCQGeoCoordinate(coord, _newCoordParent));
_polygonModel.append(new QGCQGeoCoordinate(coord, this));
}
setDirty(true);
......@@ -145,7 +176,7 @@ void QGCMapPolygon::setPath(const QVariantList& path)
_polygonModel.clearAndDeleteContents();
for (int i=0; i<_polygonPath.count(); i++) {
_polygonModel.append(new QGCQGeoCoordinate(_polygonPath[i].value<QGeoCoordinate>(), _newCoordParent));
_polygonModel.append(new QGCQGeoCoordinate(_polygonPath[i].value<QGeoCoordinate>(), this));
}
setDirty(true);
......@@ -179,7 +210,7 @@ bool QGCMapPolygon::loadFromJson(const QJsonObject& json, bool required, QString
}
for (int i=0; i<_polygonPath.count(); i++) {
_polygonModel.append(new QGCQGeoCoordinate(_polygonPath[i].value<QGeoCoordinate>(), _newCoordParent));
_polygonModel.append(new QGCQGeoCoordinate(_polygonPath[i].value<QGeoCoordinate>(), this));
}
setDirty(false);
......@@ -225,7 +256,7 @@ void QGCMapPolygon::splitPolygonSegment(int vertexIndex)
void QGCMapPolygon::appendVertex(const QGeoCoordinate& coordinate)
{
_polygonPath.append(QVariant::fromValue(coordinate));
_polygonModel.append(new QGCQGeoCoordinate(coordinate, _newCoordParent));
_polygonModel.append(new QGCQGeoCoordinate(coordinate, this));
emit pathChanged();
}
......@@ -315,3 +346,11 @@ void QGCMapPolygon::setCenterDrag(bool centerDrag)
emit centerDragChanged(centerDrag);
}
}
void QGCMapPolygon::setInteractive(bool interactive)
{
if (_interactive != interactive) {
_interactive = interactive;
emit interactiveChanged(interactive);
}
}
......@@ -24,14 +24,18 @@ class QGCMapPolygon : public QObject
Q_OBJECT
public:
QGCMapPolygon(QObject* newCoordParent, QObject* parent = NULL);
QGCMapPolygon(QObject* parent = NULL);
QGCMapPolygon(const QGCMapPolygon& other, QObject* parent = NULL);
Q_PROPERTY(int count READ count NOTIFY countChanged)
Q_PROPERTY(QVariantList path READ path NOTIFY pathChanged)
Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_PROPERTY(QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged)
Q_PROPERTY(bool centerDrag READ centerDrag WRITE setCenterDrag NOTIFY centerDragChanged)
const QGCMapPolygon& operator=(const QGCMapPolygon& other);
Q_PROPERTY(int count READ count NOTIFY countChanged)
Q_PROPERTY(QVariantList path READ path NOTIFY pathChanged)
Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_PROPERTY(QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged)
Q_PROPERTY(bool centerDrag READ centerDrag WRITE setCenterDrag NOTIFY centerDragChanged)
Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged)
Q_INVOKABLE void clear(void);
Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate);
......@@ -69,6 +73,7 @@ public:
void setDirty (bool dirty);
QGeoCoordinate center (void) const { return _center; }
bool centerDrag (void) const { return _centerDrag; }
bool interactive (void) const { return _interactive; }
QVariantList path (void) const { return _polygonPath; }
QmlObjectListModel* qmlPathModel(void) { return &_polygonModel; }
......@@ -78,6 +83,7 @@ public:
void setPath (const QVariantList& path);
void setCenter (QGeoCoordinate newCenter);
void setCenterDrag (bool centerDrag);
void setInteractive (bool interactive);
static const char* jsonPolygonKey;
......@@ -88,6 +94,7 @@ signals:
void cleared (void);
void centerChanged (QGeoCoordinate center);
void centerDragChanged (bool centerDrag);
void interactiveChanged (bool interactive);
private slots:
void _polygonModelCountChanged(int count);
......@@ -95,17 +102,18 @@ private slots:
void _updateCenter(void);
private:
void _init(void);
QPolygonF _toPolygonF(void) const;
QGeoCoordinate _coordFromPointF(const QPointF& point) const;
QPointF _pointFFromCoord(const QGeoCoordinate& coordinate) const;
QObject* _newCoordParent;
QVariantList _polygonPath;
QmlObjectListModel _polygonModel;
bool _dirty;
QGeoCoordinate _center;
bool _centerDrag;
bool _ignoreCenterUpdates;
bool _interactive;
};
#endif
......@@ -32,7 +32,7 @@ void QGCMapPolygonTest::init(void)
_rgModelSignals[modelCountChangedIndex] = SIGNAL(countChanged(int));
_rgModelSignals[modelDirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_mapPolygon = new QGCMapPolygon(this, this);
_mapPolygon = new QGCMapPolygon(this);
_pathModel = _mapPolygon->qmlPathModel();
QVERIFY(_pathModel);
......
......@@ -24,16 +24,16 @@ Item {
property var mapControl ///< Map control to place item in
property var mapPolygon ///< QGCMapPolygon object
property bool interactive: true /// true: user can manipulate polygon
property bool interactive: mapPolygon.interactive
property color interiorColor: "transparent"
property real interiorOpacity: 1
property int borderWidth: 0
property color borderColor: "black"
property var _polygonComponent
property var _dragHandlesComponent
property var _splitHandlesComponent
property var _centerDragHandleComponent
property var _polygonComponent
property var _dragHandlesComponent
property var _splitHandlesComponent
property var _centerDragHandleComponent
property real _zorderDragHandle: QGroundControl.zOrderMapItems + 3 // Highest to prevent splitting when items overlap
property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2
......@@ -111,7 +111,7 @@ Item {
}
Component.onCompleted: {
mapPolygonVisuals.addVisuals()
addVisuals()
if (interactive) {
addHandles()
}
......
......@@ -58,6 +58,7 @@ void RallyPointController::managerVehicleChanged(Vehicle* managerVehicle)
{
if (_managerVehicle) {
_rallyPointManager->disconnect(this);
_managerVehicle->disconnect(this);
_managerVehicle = NULL;
_rallyPointManager = NULL;
}
......@@ -74,7 +75,9 @@ void RallyPointController::managerVehicleChanged(Vehicle* managerVehicle)
connect(_rallyPointManager, &RallyPointManager::removeAllComplete, this, &RallyPointController::_managerRemoveAllComplete);
connect(_rallyPointManager, &RallyPointManager::inProgressChanged, this, &RallyPointController::syncInProgressChanged);
emit rallyPointsSupportedChanged(rallyPointsSupported());
connect(_managerVehicle, &Vehicle::capabilityBitsChanged, this, &RallyPointController::supportedChanged);
emit supportedChanged(supported());
}
bool RallyPointController::load(const QJsonObject& json, QString& errorString)
......@@ -234,9 +237,9 @@ void RallyPointController::addPoint(QGeoCoordinate point)
setDirty(true);
}
bool RallyPointController::rallyPointsSupported(void) const
bool RallyPointController::supported(void) const
{
return _rallyPointManager->rallyPointsSupported();
return (_managerVehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY) && (_managerVehicle->maxProtoVersion() >= 200);
}
void RallyPointController::removePoint(QObject* rallyPoint)
......
......@@ -29,7 +29,6 @@ public:
RallyPointController(PlanMasterController* masterController, 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)
......@@ -37,6 +36,7 @@ public:
Q_INVOKABLE void addPoint(QGeoCoordinate point);
Q_INVOKABLE void removePoint(QObject* rallyPoint);
bool supported (void) const final;
void save (QJsonObject& json) final;
bool load (const QJsonObject& json, QString& errorString) final;
void loadFromVehicle (void) final;
......@@ -50,7 +50,6 @@ public:
void managerVehicleChanged (Vehicle* managerVehicle) final;
bool showPlanFromManagerVehicle (void) final;
bool rallyPointsSupported (void) const;
QmlObjectListModel* points (void) { return &_points; }
QString editorQml (void) const;
QObject* currentRallyPoint (void) const { return _currentRallyPoint; }
......@@ -58,7 +57,6 @@ public:
void setCurrentRallyPoint(QObject* rallyPoint);
signals:
void rallyPointsSupportedChanged(bool rallyPointsSupported);
void currentRallyPointChanged(QObject* rallyPoint);
void loadComplete(void);
......
......@@ -49,3 +49,8 @@ void RallyPointManager::removeAll(void)
// No support in generic vehicle
emit removeAllComplete(false /* error */);
}
bool RallyPointManager::supported(void) const
{
return (_vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY) && (_vehicle->maxProtoVersion() >= 200);
}
......@@ -29,6 +29,9 @@ public:
RallyPointManager(Vehicle* vehicle);
~RallyPointManager();
/// Returns true if GeoFence is supported by this vehicle
virtual bool supported(void) const;
/// Returns true if the manager is currently communicating with the vehicle
virtual bool inProgress(void) const { return false; }
......@@ -44,8 +47,6 @@ public:
/// Signals removeAllCompleted when done
virtual void removeAll(void);
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"); }
......
This diff is collapsed.
......@@ -30,34 +30,53 @@ Item {
property var _breachReturnPointComponent
property var _mouseAreaComponent
property var _circleComponent
property var _mapPolygon: myGeoFenceController.mapPolygon
property bool _interactive: interactive
property bool _circleSupported: myGeoFenceController.circleRadiusFact !== null
property bool _circleEnabled: myGeoFenceController.circleEnabled
property real _circleRadius: _circleSupported ? myGeoFenceController.circleRadiusFact.rawValue : 0
property bool _polygonSupported: myGeoFenceController.polygonSupported
property bool _polygonEnabled: myGeoFenceController.polygonEnabled
property var _polygons: myGeoFenceController.polygons
property var _circles: myGeoFenceController.circles
function addPolygon(inclusionPolygon) {
// Initial polygon is inset to take 2/3rds space
var rect = Qt.rect(map.centerViewport.x, map.centerViewport.y, map.centerViewport.width, map.centerViewport.height)
rect.x += (rect.width * 0.25) / 2
rect.y += (rect.height * 0.25) / 2
rect.width *= 0.75
rect.height *= 0.75
var centerCoord = map.toCoordinate(Qt.point(rect.x + (rect.width / 2), rect.y + (rect.height / 2)), false /* clipToViewPort */)
var topLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y), false /* clipToViewPort */)
var topRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y), false /* clipToViewPort */)
var bottomLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y + rect.height), false /* clipToViewPort */)
var bottomRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y + rect.height), false /* clipToViewPort */)
// Initial polygon has max width and height of 3000 meters
var halfWidthMeters = Math.min(topLeftCoord.distanceTo(topRightCoord), 3000) / 2
var halfHeightMeters = Math.min(topLeftCoord.distanceTo(bottomLeftCoord), 3000) / 2
topLeftCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 0)
topRightCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 0)
bottomLeftCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 180)
bottomRightCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 180)
console.log(map.center)
console.log(topLeftCoord)
console.log(bottomRightCoord)
if (inclusionPolygon) {
myGeoFenceController.addInclusion(topLeftCoord, bottomRightCoord)
} else {
myGeoFenceController.addExclusion(topLeftCoord, bottomRightCoord)
}
}
Component.onCompleted: {
_circleComponent = circleComponent.createObject(map)
map.addMapItem(_circleComponent)
_breachReturnPointComponent = breachReturnPointComponent.createObject(map)
map.addMapItem(_breachReturnPointComponent)
_mouseAreaComponent = mouseAreaComponent.createObject(map)
}
Component.onDestruction: {
_circleComponent.destroy()
_breachReturnPointComponent.destroy()
_mouseAreaComponent.destroy()
}
Connections {
target: myGeoFenceController
onAddInitialFencePolygon: mapPolygonVisuals.addInitialPolygon()
}
// Mouse area to capture breach return point coordinate
Component {
id: mouseAreaComponent
......@@ -69,28 +88,29 @@ Item {
}
}
QGCMapPolygonVisuals {
id: mapPolygonVisuals
mapControl: map
mapPolygon: _mapPolygon
interactive: _interactive
borderWidth: 2
borderColor: "orange"
visible: _polygonSupported && (planView || _polygonEnabled)
Instantiator {
model: _polygons
delegate : QGCMapPolygonVisuals {
mapControl: map
mapPolygon: object
borderWidth: object.inclusion ? 2 : 0
borderColor: "orange"
interiorColor: object.inclusion ? "transparent" : "orange"
interiorOpacity: object.inclusion ? 1: 0.2
}
}
// GeoFence circle
Component {
id: circleComponent
Instantiator {
model: _circles
MapCircle {
z: QGroundControl.zOrderMapItems
border.width: 2
border.color: "orange"
color: "transparent"
center: homePosition ? homePosition : QtPositioning.coordinate()
radius: _circleRadius
visible: _circleSupported && _circleRadius > 0 && (planView || _circleEnabled)
delegate : QGCMapCircleVisuals {
mapControl: map
mapCircle: object
borderWidth: object.inclusion ? 2 : 0
borderColor: "orange"
interiorColor: object.inclusion ? "transparent" : "orange"
interiorOpacity: object.inclusion ? 1: 0.2
}
}
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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