10 changed files with 237 additions and 96 deletions
@ -0,0 +1,85 @@
@@ -0,0 +1,85 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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 "ParameterLoader.h" |
||||
|
||||
PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle) |
||||
: GeoFenceManager(vehicle) |
||||
, _firstParamLoadComplete(false) |
||||
, _circleRadiusFact(NULL) |
||||
{ |
||||
connect(_vehicle->getParameterLoader(), &ParameterLoader::parametersReady, this, &PX4GeoFenceManager::_parametersReady); |
||||
} |
||||
|
||||
PX4GeoFenceManager::~PX4GeoFenceManager() |
||||
{ |
||||
|
||||
} |
||||
|
||||
void PX4GeoFenceManager::_parametersReady(void) |
||||
{ |
||||
if (!_firstParamLoadComplete) { |
||||
_firstParamLoadComplete = true; |
||||
|
||||
_circleRadiusFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("GF_MAX_HOR_DIST")); |
||||
connect(_circleRadiusFact, &Fact::rawValueChanged, this, &PX4GeoFenceManager::_circleRadiusRawValueChanged); |
||||
emit circleRadiusChanged(circleRadius()); |
||||
|
||||
QStringList paramNames; |
||||
QStringList paramLabels; |
||||
|
||||
paramNames << QStringLiteral("GF_ACTION") << QStringLiteral("GF_MAX_HOR_DIST") << QStringLiteral("GF_MAX_VER_DIST"); |
||||
paramLabels << QStringLiteral("Action:") << QStringLiteral("Radius:") << QStringLiteral("Max Altitude:"); |
||||
|
||||
_params.clear(); |
||||
_paramLabels.clear(); |
||||
for (int i=0; i<paramNames.count(); i++) { |
||||
QString paramName = paramNames[i]; |
||||
if (_vehicle->parameterExists(FactSystem::defaultComponentId, paramName)) { |
||||
Fact* paramFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName); |
||||
_params << QVariant::fromValue(paramFact); |
||||
_paramLabels << paramLabels[i]; |
||||
} |
||||
} |
||||
emit paramsChanged(_params); |
||||
emit paramLabelsChanged(_paramLabels); |
||||
|
||||
emit circleSupportedChanged(circleSupported()); |
||||
|
||||
qCDebug(GeoFenceManagerLog) << "fenceSupported:circleSupported:polygonSupported:breachReturnSupported" << |
||||
fenceSupported() << circleSupported() << polygonSupported() << breachReturnSupported(); |
||||
} |
||||
} |
||||
|
||||
float PX4GeoFenceManager::circleRadius(void) const |
||||
{ |
||||
if (_circleRadiusFact) { |
||||
return _circleRadiusFact->rawValue().toFloat(); |
||||
} else { |
||||
return 0.0; |
||||
} |
||||
} |
||||
|
||||
void PX4GeoFenceManager::_circleRadiusRawValueChanged(QVariant value) |
||||
{ |
||||
emit circleRadiusChanged(value.toFloat()); |
||||
emit circleSupportedChanged(circleSupported()); |
||||
} |
||||
|
||||
bool PX4GeoFenceManager::circleSupported(void) const |
||||
{ |
||||
if (_circleRadiusFact) { |
||||
return _circleRadiusFact->rawValue().toFloat() >= 0.0; |
||||
} |
||||
|
||||
return false; |
||||
} |
@ -0,0 +1,45 @@
@@ -0,0 +1,45 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* (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 fenceSupported (void) const final { return true; } |
||||
bool circleSupported (void) const final; |
||||
float circleRadius (void) const final; |
||||
QVariantList params (void) const final { return _params; } |
||||
QStringList paramLabels (void) const final { return _paramLabels; } |
||||
|
||||
private slots: |
||||
void _circleRadiusRawValueChanged(QVariant value); |
||||
void _parametersReady(void); |
||||
|
||||
private: |
||||
bool _firstParamLoadComplete; |
||||
|
||||
QVariantList _params; |
||||
QStringList _paramLabels; |
||||
|
||||
Fact* _circleRadiusFact; |
||||
}; |
||||
|
||||
#endif |
Loading…
Reference in new issue