3#include <QtCore/QObject>
4#include <QtPositioning/QGeoCoordinate>
38 const QList<QGCFencePolygon>&
polygons(
void) {
return _polygons; }
39 const QList<QGCFenceCircle>&
circles(
void) {
return _circles; }
56 void error (
int errorCode,
const QString& errorMsg);
61 void _sendComplete (
bool error);
62 void _planManagerLoadComplete (
bool removeAllRequested);
65 void _sendError(
ErrorCode_t errorCode,
const QString& errorMsg);
67 QList<QGCFencePolygon> _polygons;
68 QList<QGCFenceCircle> _circles;
69 QGeoCoordinate _breachReturnPoint;
70 bool _firstParamLoadComplete =
false;
71 QList<QGCFencePolygon> _sendPolygons;
72 QList<QGCFenceCircle> _sendCircles;
This is the base class for firmware specific geofence managers.
void removeAll(void)
Signals removeAllComplete when done.
void sendToVehicle(const QGeoCoordinate &breachReturn, QmlObjectListModel &polygons, QmlObjectListModel &circles)
Signals sendComplete when done.
void error(int errorCode, const QString &errorMsg)
void inProgressChanged(bool inProgress)
const QGeoCoordinate & breachReturnPoint(void) const
const QList< QGCFencePolygon > & polygons(void)
ErrorCode_t
Error codes returned in error signal.
@ BadPolygonItemFormat
Error re-creating polygons from mission items.
@ UnsupportedCommand
Usupported command in mission type.
@ PolygonTooManyPoints
Too many points for valid fence polygon.
@ PolygonTooFewPoints
Too few points for valid fence polygon.
@ IncompletePolygonLoad
Incomplete polygon loaded.
bool supported(void) const
void removeAllComplete(bool error)
void sendComplete(bool error)
bool polygonEnabled(void) const
const QList< QGCFenceCircle > & circles(void)
The PlanManager class is the base class for the Mission, GeoFence and Rally Point managers....
bool inProgress(void) const