Skip to content

Commit

Permalink
Merge pull request mavlink#4009 from DonLakeFlyer/PX4FencePlugin
Browse files Browse the repository at this point in the history
PX4 fence plugin
  • Loading branch information
DonLakeFlyer authored Sep 2, 2016
2 parents 625cb13 + c9dab61 commit 9624d5c
Show file tree
Hide file tree
Showing 10 changed files with 237 additions and 96 deletions.
2 changes: 2 additions & 0 deletions qgroundcontrol.pro
Original file line number Diff line number Diff line change
Expand Up @@ -700,6 +700,7 @@ HEADERS+= \
src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h \
src/FirmwarePlugin/PX4/px4_custom_mode.h \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \
src/FirmwarePlugin/PX4/PX4GeoFenceManager.h \
src/FirmwarePlugin/PX4/PX4ParameterMetaData.h \
src/Vehicle/MultiVehicleManager.h \
src/Vehicle/Vehicle.h \
Expand Down Expand Up @@ -761,6 +762,7 @@ SOURCES += \
src/FirmwarePlugin/FirmwarePlugin.cc \
src/FirmwarePlugin/FirmwarePluginManager.cc \
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \
src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc \
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc \
src/Vehicle/MultiVehicleManager.cc \
src/Vehicle/Vehicle.cc \
Expand Down
8 changes: 4 additions & 4 deletions src/AutoPilotPlugins/PX4/SafetyComponent.qml
Original file line number Diff line number Diff line change
Expand Up @@ -313,8 +313,8 @@ SetupPage {
id: fenceRadiusCheckBox
anchors.baseline: fenceRadiusField.baseline
text: qsTr("Max radius:")
checked: _fenceRadius.value >= 0
onClicked: _fenceRadius.value = checked ? 100 : -1
checked: _fenceRadius.value > 0
onClicked: _fenceRadius.value = checked ? 100 : 0
width: _middleRowWidth
}
FactTextField {
Expand All @@ -330,8 +330,8 @@ SetupPage {
id: fenceAltMaxCheckBox
anchors.baseline: fenceAltMaxField.baseline
text: qsTr("Max altitude:")
checked: _fenceAlt.value >= 0
onClicked: _fenceAlt.value = checked ? 100 : -1
checked: _fenceAlt.value > 0
onClicked: _fenceAlt.value = checked ? 100 : 0
width: _middleRowWidth
}
FactTextField {
Expand Down
52 changes: 27 additions & 25 deletions src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
#include "FirmwarePlugin.h"
#include "ParameterLoader.h"
#include "PX4ParameterMetaData.h"
#include "PX4GeoFenceManager.h"

class PX4FirmwarePlugin : public FirmwarePlugin
{
Expand All @@ -30,31 +31,32 @@ class PX4FirmwarePlugin : public FirmwarePlugin
QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle) final;
QList<MAV_CMD> supportedMissionCommands(void) final;

bool isCapable (const Vehicle *vehicle, FirmwareCapabilities capabilities) final;
QStringList flightModes (Vehicle* vehicle) final;
QString flightMode (uint8_t base_mode, uint32_t custom_mode) const final;
bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
void setGuidedMode (Vehicle* vehicle, bool guidedMode) final;
void pauseVehicle (Vehicle* vehicle) final;
void guidedModeRTL (Vehicle* vehicle) final;
void guidedModeLand (Vehicle* vehicle) final;
void guidedModeTakeoff (Vehicle* vehicle, double altitudeRel) final;
void guidedModeOrbit (Vehicle* vehicle, const QGeoCoordinate& centerCoord = QGeoCoordinate(), double radius = NAN, double velocity = NAN, double altitude = NAN) final;
void guidedModeGotoLocation (Vehicle* vehicle, const QGeoCoordinate& gotoCoord) final;
void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeRel) final;
bool isGuidedMode (const Vehicle* vehicle) const;
int manualControlReservedButtonCount(void) final;
bool supportsManualControl (void) final;
void initializeVehicle (Vehicle* vehicle) final;
bool sendHomePositionToVehicle (void) final;
void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam (void) const final { return QString("SYS_AUTOSTART"); }
QString missionCommandOverrides (MAV_TYPE vehicleType) const final;
QString getVersionParam (void) final { return QString("SYS_PARAM_VER"); }
QString internalParameterMetaDataFile (void) final { return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); }
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
QObject* loadParameterMetaData (const QString& metaDataFile);
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message);
bool isCapable (const Vehicle *vehicle, FirmwareCapabilities capabilities) final;
QStringList flightModes (Vehicle* vehicle) final;
QString flightMode (uint8_t base_mode, uint32_t custom_mode) const final;
bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
void setGuidedMode (Vehicle* vehicle, bool guidedMode) final;
void pauseVehicle (Vehicle* vehicle) final;
void guidedModeRTL (Vehicle* vehicle) final;
void guidedModeLand (Vehicle* vehicle) final;
void guidedModeTakeoff (Vehicle* vehicle, double altitudeRel) final;
void guidedModeOrbit (Vehicle* vehicle, const QGeoCoordinate& centerCoord = QGeoCoordinate(), double radius = NAN, double velocity = NAN, double altitude = NAN) final;
void guidedModeGotoLocation (Vehicle* vehicle, const QGeoCoordinate& gotoCoord) final;
void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeRel) final;
bool isGuidedMode (const Vehicle* vehicle) const;
int manualControlReservedButtonCount(void) final;
bool supportsManualControl (void) final;
void initializeVehicle (Vehicle* vehicle) final;
bool sendHomePositionToVehicle (void) final;
void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) final;
QString getDefaultComponentIdParam (void) const final { return QString("SYS_AUTOSTART"); }
QString missionCommandOverrides (MAV_TYPE vehicleType) const final;
QString getVersionParam (void) final { return QString("SYS_PARAM_VER"); }
QString internalParameterMetaDataFile (void) final { return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); }
void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) final { PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); }
QObject* loadParameterMetaData (const QString& metaDataFile);
bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message);
GeoFenceManager* newGeoFenceManager (Vehicle* vehicle) { return new PX4GeoFenceManager(vehicle); }

// Use these constants to set flight modes using setFlightMode method. Don't use hardcoded string names since the
// names may change.
Expand Down
85 changes: 85 additions & 0 deletions src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc
Original file line number Diff line number Diff line change
@@ -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;
}
45 changes: 45 additions & 0 deletions src/FirmwarePlugin/PX4/PX4GeoFenceManager.h
Original file line number Diff line number Diff line change
@@ -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
2 changes: 1 addition & 1 deletion src/MissionEditor/GeoFenceEditor.qml
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ QGCFlickable {
anchors.margins: _margin
anchors.left: parent.left
anchors.top: parent.top
text: qsTr("Geo-Fence (WIP careful!)")
text: qsTr("GeoFence (WIP careful!)")
color: "black"
}

Expand Down
Loading

0 comments on commit 9624d5c

Please sign in to comment.