QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
GeoFenceController.cc
Go to the documentation of this file.
2#include "Vehicle.h"
3#include "ParameterManager.h"
4#include "GeoJsonHelper.h"
5#include "JsonParsing.h"
7#include "SettingsManager.h"
8#include "AppSettings.h"
9#include "GeoFenceManager.h"
10#include "QGCFenceCircle.h"
11#include "QGCFencePolygon.h"
12#include "QGCLoggingCategory.h"
13
14#include <QtCore/QJsonArray>
15#include <QtCore/QJsonDocument>
16
17QGC_LOGGING_CATEGORY(GeoFenceControllerLog, "PlanManager.GeoFenceController")
18
19QMap<QString, FactMetaData*> GeoFenceController::_metaDataMap;
20
22 : PlanElementController (masterController, parent)
23 , _managerVehicle (masterController->managerVehicle())
24 , _geoFenceManager (masterController->managerVehicle()->geoFenceManager())
25 , _breachReturnAltitudeFact (0, _breachReturnAltitudeFactName, FactMetaData::valueTypeDouble)
26 , _breachReturnDefaultAltitude (SettingsManager::instance()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble())
27{
28 if (_metaDataMap.isEmpty()) {
29 _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/BreachReturn.FactMetaData.json"), nullptr /* metaDataParent */);
30 }
31
32 _breachReturnAltitudeFact.setMetaData(_metaDataMap[_breachReturnAltitudeFactName]);
33 _breachReturnAltitudeFact.setRawValue(_breachReturnDefaultAltitude);
34
37
38 connect(this, &GeoFenceController::breachReturnPointChanged, this, &GeoFenceController::_setDirty);
39 connect(&_breachReturnAltitudeFact, &Fact::rawValueChanged, this, &GeoFenceController::_setDirty);
40 connect(&_polygons, &QmlObjectListModel::dirtyChanged, this, &GeoFenceController::_setDirty);
41 connect(&_circles, &QmlObjectListModel::dirtyChanged, this, &GeoFenceController::_setDirty);
42}
43
48
49void GeoFenceController::start(bool flyView)
50{
51 qCDebug(GeoFenceControllerLog) << "start flyView" << flyView;
52
53 _managerVehicleChanged(_masterController->managerVehicle());
54 connect(_masterController, &PlanMasterController::managerVehicleChanged, this, &GeoFenceController::_managerVehicleChanged);
55
57 _init();
58}
59
60void GeoFenceController::_init(void)
61{
62
63}
64
65void GeoFenceController::setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint)
66{
67 if (_breachReturnPoint != breachReturnPoint) {
68 _breachReturnPoint = breachReturnPoint;
69 setDirty(true);
71 }
72}
73
74void GeoFenceController::_managerVehicleChanged(Vehicle* managerVehicle)
75{
76 if (_managerVehicle) {
77 _geoFenceManager->disconnect(this);
78 _managerVehicle->disconnect(this);
79 _managerVehicle->parameterManager()->disconnect(this);
80 _managerVehicle = nullptr;
81 _geoFenceManager = nullptr;
82 }
83
84 _managerVehicle = managerVehicle;
85 if (!_managerVehicle) {
86 qWarning() << "GeoFenceController::managerVehicleChanged managerVehicle=nullptr";
87 return;
88 }
89
90 _geoFenceManager = _managerVehicle->geoFenceManager();
91 connect(_geoFenceManager, &GeoFenceManager::loadComplete, this, &GeoFenceController::_managerLoadComplete);
92 connect(_geoFenceManager, &GeoFenceManager::sendComplete, this, &GeoFenceController::_managerSendComplete);
93 connect(_geoFenceManager, &GeoFenceManager::removeAllComplete, this, &GeoFenceController::_managerRemoveAllComplete);
95
96 (void) connect(_managerVehicle, &Vehicle::capabilityBitsChanged, this, [this](uint64_t capabilityBits) {
97 Q_UNUSED(capabilityBits);
99 });
100
101 connect(_managerVehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &GeoFenceController::_parametersReady);
102 _parametersReady();
103
105}
106
107bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
108{
109 removeAll();
110
111 errorString.clear();
112
113 if (!json.contains(JsonParsing::jsonVersionKey) ||
114 (json.contains(JsonParsing::jsonVersionKey) && json[JsonParsing::jsonVersionKey].toInt() == 1)) {
115 // We just ignore old version 1 or prior data
116 return true;
117 }
118
119 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
120 { JsonParsing::jsonVersionKey, QJsonValue::Double, true },
121 { _jsonCirclesKey, QJsonValue::Array, true },
122 { _jsonPolygonsKey, QJsonValue::Array, true },
123 { _jsonBreachReturnKey, QJsonValue::Array, false },
124 };
125 if (!JsonParsing::validateKeys(json, keyInfoList, errorString)) {
126 return false;
127 }
128
129 if (json[JsonParsing::jsonVersionKey].toInt() != _jsonCurrentVersion) {
130 errorString = tr("GeoFence supports version %1").arg(_jsonCurrentVersion);
131 return false;
132 }
133
134 QJsonArray jsonPolygonArray = json[_jsonPolygonsKey].toArray();
135 for (const QJsonValue jsonPolygonValue: jsonPolygonArray) {
136 if (jsonPolygonValue.type() != QJsonValue::Object) {
137 errorString = tr("GeoFence polygon not stored as object");
138 return false;
139 }
140
141 QGCFencePolygon* fencePolygon = new QGCFencePolygon(false /* inclusion */, this /* parent */);
142 if (!fencePolygon->loadFromJson(jsonPolygonValue.toObject(), true /* required */, errorString)) {
143 return false;
144 }
145 _polygons.append(fencePolygon);
146 }
147
148 QJsonArray jsonCircleArray = json[_jsonCirclesKey].toArray();
149 for (const QJsonValue jsonCircleValue: jsonCircleArray) {
150 if (jsonCircleValue.type() != QJsonValue::Object) {
151 errorString = tr("GeoFence circle not stored as object");
152 return false;
153 }
154
155 QGCFenceCircle* fenceCircle = new QGCFenceCircle(this /* parent */);
156 if (!fenceCircle->loadFromJson(jsonCircleValue.toObject(), errorString)) {
157 return false;
158 }
159 _circles.append(fenceCircle);
160 }
161
162 if (json.contains(_jsonBreachReturnKey)) {
163 if (!GeoJsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], true /* altitudeRequred */, _breachReturnPoint, errorString)) {
164 return false;
165 }
166 _breachReturnAltitudeFact.setRawValue(_breachReturnPoint.altitude());
167 } else {
168 _breachReturnPoint = QGeoCoordinate();
169 _breachReturnAltitudeFact.setRawValue(_breachReturnDefaultAltitude);
170 }
171 emit breachReturnPointChanged(_breachReturnPoint);
172
173 setDirty(false);
174
175 return true;
176}
177
178void GeoFenceController::save(QJsonObject& json)
179{
180 json[JsonParsing::jsonVersionKey] = _jsonCurrentVersion;
181
182 QJsonArray jsonPolygonArray;
183 for (int i=0; i<_polygons.count(); i++) {
184 QJsonObject jsonPolygon;
185 QGCFencePolygon* fencePolygon = _polygons.value<QGCFencePolygon*>(i);
186 fencePolygon->saveToJson(jsonPolygon);
187 jsonPolygonArray.append(jsonPolygon);
188 }
189 json[_jsonPolygonsKey] = jsonPolygonArray;
190
191 QJsonArray jsonCircleArray;
192 for (int i=0; i<_circles.count(); i++) {
193 QJsonObject jsonCircle;
194 QGCFenceCircle* fenceCircle = _circles.value<QGCFenceCircle*>(i);
195 fenceCircle->saveToJson(jsonCircle);
196 jsonCircleArray.append(jsonCircle);
197 }
198 json[_jsonCirclesKey] = jsonCircleArray;
199
200 if (_breachReturnPoint.isValid()) {
201 QJsonValue jsonCoordinate;
202
203 _breachReturnPoint.setAltitude(_breachReturnAltitudeFact.rawValue().toDouble());
204 GeoJsonHelper::saveGeoCoordinate(_breachReturnPoint, true /* writeAltitude */, jsonCoordinate);
205 json[_jsonBreachReturnKey] = jsonCoordinate;
206 }
207}
208
210{
211 setBreachReturnPoint(QGeoCoordinate());
212 _polygons.clearAndDeleteContents();
213 _circles.clearAndDeleteContents();
214}
215
217{
218 if (_masterController->offline()) {
219 qCCritical(GeoFenceControllerLog) << "GeoFenceController::removeAllFromVehicle called while offline";
220 } else if (syncInProgress()) {
221 qCCritical(GeoFenceControllerLog) << "GeoFenceController::removeAllFromVehicle called while syncInProgress";
222 } else {
223 _geoFenceManager->removeAll();
224 }
225}
226
228{
229 if (_masterController->offline()) {
230 qCCritical(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle called while offline";
231 } else if (syncInProgress()) {
232 qCCritical(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle called while syncInProgress";
233 } else {
234 _itemsRequested = true;
235 _geoFenceManager->loadFromVehicle();
236 }
237}
238
240{
241 if (_masterController->offline()) {
242 qCCritical(GeoFenceControllerLog) << "GeoFenceController::sendToVehicle called while offline";
243 } else if (syncInProgress()) {
244 qCCritical(GeoFenceControllerLog) << "GeoFenceController::sendToVehicle called while syncInProgress";
245 } else {
246 qCDebug(GeoFenceControllerLog) << "GeoFenceController::sendToVehicle";
247 _geoFenceManager->sendToVehicle(_breachReturnPoint, _polygons, _circles);
248 setDirty(false);
249 }
250}
251
253{
254 return _geoFenceManager->inProgress();
255}
256
258{
259 return _dirty;
260}
261
262
264{
265 if (dirty != _dirty) {
266 _dirty = dirty;
267 if (!dirty) {
268 for (int i=0; i<_polygons.count(); i++) {
269 QGCFencePolygon* polygon = _polygons.value<QGCFencePolygon*>(i);
270 polygon->setDirty(false);
271 }
272 for (int i=0; i<_circles.count(); i++) {
273 QGCFenceCircle* circle = _circles.value<QGCFenceCircle*>(i);
274 circle->setDirty(false);
275 }
276 }
277 emit dirtyChanged(dirty);
278 }
279}
280
281void GeoFenceController::_polygonDirtyChanged(bool dirty)
282{
283 if (dirty) {
284 setDirty(true);
285 }
286}
287
288void GeoFenceController::_setDirty(void)
289{
290 setDirty(true);
291}
292
293void GeoFenceController::_setFenceFromManager(const QList<QGCFencePolygon>& polygons,
294 const QList<QGCFenceCircle>& circles)
295{
296 _polygons.clearAndDeleteContents();
297 _circles.clearAndDeleteContents();
298
299 for (int i=0; i<polygons.count(); i++) {
300 _polygons.append(new QGCFencePolygon(polygons[i], this));
301 }
302
303 for (int i=0; i<circles.count(); i++) {
304 _circles.append(new QGCFenceCircle(circles[i], this));
305 }
306
307 setDirty(false);
308}
309
310void GeoFenceController::_setReturnPointFromManager(QGeoCoordinate breachReturnPoint)
311{
312 _breachReturnPoint = breachReturnPoint;
313 emit breachReturnPointChanged(_breachReturnPoint);
314 if (_breachReturnPoint.isValid()) {
315 _breachReturnAltitudeFact.setRawValue(_breachReturnPoint.altitude());
316 } else {
317 _breachReturnAltitudeFact.setRawValue(_breachReturnDefaultAltitude);
318 }
319}
320
321void GeoFenceController::_managerLoadComplete(void)
322{
323 // Fly view always reloads on _loadComplete
324 // Plan view only reloads if:
325 // - Load was specifically requested
326 // - There is no current Plan
327 if (_flyView || _itemsRequested || isEmpty()) {
328 _setReturnPointFromManager(_geoFenceManager->breachReturnPoint());
329 _setFenceFromManager(_geoFenceManager->polygons(), _geoFenceManager->circles());
330 setDirty(false);
331 emit loadComplete();
332 }
333 _itemsRequested = false;
334}
335
336void GeoFenceController::_managerSendComplete(bool error)
337{
338 // Fly view always reloads on manager sendComplete
339 if (!error && _flyView) {
341 }
342}
343
344void GeoFenceController::_managerRemoveAllComplete(bool error)
345{
346 if (!error) {
347 // Remove all from vehicle so we always update
349 }
350}
351
353{
354 return _polygons.count() > 0 || _circles.count() > 0;
355}
356
358{
359 qCDebug(GeoFenceControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
360 if (_masterController->offline()) {
361 qCCritical(GeoFenceControllerLog) << "GeoFenceController::showPlanFromManagerVehicle called while offline";
362 return true; // stops further propagation of showPlanFromManagerVehicle due to error
363 } else {
364 _itemsRequested = true;
365 if (!_managerVehicle->initialPlanRequestComplete()) {
366 // The vehicle hasn't completed initial load, we can just wait for loadComplete to be signalled automatically
367 qCDebug(GeoFenceControllerLog) << "showPlanFromManagerVehicle: !initialPlanRequestComplete, wait for signal";
368 return true;
369 } else if (syncInProgress()) {
370 // If the sync is already in progress, _loadComplete will be called automatically when it is done. So no need to do anything.
371 qCDebug(GeoFenceControllerLog) << "showPlanFromManagerVehicle: syncInProgress wait for signal";
372 return true;
373 } else {
374 // Fake a _loadComplete with the current items
375 qCDebug(GeoFenceControllerLog) << "showPlanFromManagerVehicle: sync complete simulate signal";
376 _itemsRequested = true;
377 _managerLoadComplete();
378 return false;
379 }
380 }
381}
382
383void GeoFenceController::addInclusionPolygon(QGeoCoordinate topLeft, QGeoCoordinate bottomRight)
384{
385 QGeoCoordinate topRight(topLeft.latitude(), bottomRight.longitude());
386 QGeoCoordinate bottomLeft(bottomRight.latitude(), topLeft.longitude());
387
388 double halfWidthMeters = topLeft.distanceTo(topRight) / 2.0;
389 double halfHeightMeters = topLeft.distanceTo(bottomLeft) / 2.0;
390
391 QGeoCoordinate centerLeftEdge = topLeft.atDistanceAndAzimuth(halfHeightMeters, 180);
392 QGeoCoordinate centerTopEdge = topLeft.atDistanceAndAzimuth(halfWidthMeters, 90);
393 QGeoCoordinate center(centerLeftEdge.latitude(), centerTopEdge.longitude());
394
395 // Initial polygon is inset to take 3/4s of viewport with max width/height of 3000 meters
396 halfWidthMeters = qMin(halfWidthMeters * 0.75, 1500.0);
397 halfHeightMeters = qMin(halfHeightMeters * 0.75, 1500.0);
398
399 // Initial polygon has max width and height of 3000 meters
400 topLeft = center.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 0);
401 topRight = center.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 0);
402 bottomLeft = center.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 180);
403 bottomRight = center.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 180);
404
405 QGCFencePolygon* polygon = new QGCFencePolygon(true /* inclusion */, this);
406 polygon->appendVertex(topLeft);
407 polygon->appendVertex(topRight);
408 polygon->appendVertex(bottomRight);
409 polygon->appendVertex(bottomLeft);
410 _polygons.append(polygon);
411
413 polygon->setInteractive(true);
414}
415
416void GeoFenceController::addInclusionCircle(QGeoCoordinate topLeft, QGeoCoordinate bottomRight)
417{
418 QGeoCoordinate topRight(topLeft.latitude(), bottomRight.longitude());
419 QGeoCoordinate bottomLeft(bottomRight.latitude(), topLeft.longitude());
420
421 // Initial radius is inset to take 3/4s of viewport and max of 1500 meters
422 double halfWidthMeters = topLeft.distanceTo(topRight) / 2.0;
423 double halfHeightMeters = topLeft.distanceTo(bottomLeft) / 2.0;
424 double radius = qMin(qMin(halfWidthMeters, halfHeightMeters) * 0.75, 1500.0);
425
426 QGeoCoordinate centerLeftEdge = topLeft.atDistanceAndAzimuth(halfHeightMeters, 180);
427 QGeoCoordinate centerTopEdge = topLeft.atDistanceAndAzimuth(halfWidthMeters, 90);
428 QGeoCoordinate center(centerLeftEdge.latitude(), centerTopEdge.longitude());
429
430 QGCFenceCircle* circle = new QGCFenceCircle(center, radius, true /* inclusion */, this);
431 _circles.append(circle);
432
434 circle->setInteractive(true);
435}
436
438{
439 if (index < 0 || index > _polygons.count() - 1) {
440 return;
441 }
442
443 QGCFencePolygon* polygon = qobject_cast<QGCFencePolygon*>(_polygons.removeAt(index));
444 polygon->deleteLater();
445}
446
448{
449 if (index < 0 || index > _circles.count() - 1) {
450 return;
451 }
452
453 QGCFenceCircle* circle = qobject_cast<QGCFenceCircle*>(_circles.removeAt(index));
454 circle->deleteLater();
455}
456
458{
459 for (int i=0; i<_polygons.count(); i++) {
460 _polygons.value<QGCFencePolygon*>(i)->setInteractive(false);
461 }
462 for (int i=0; i<_circles.count(); i++) {
463 _circles.value<QGCFenceCircle*>(i)->setInteractive(false);
464 }
465}
466
468{
469 return _managerVehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE;
470}
471
472/* Returns the radius of the "paramCircularFence"
473 * which is called the "Geofence Failsafe" in PX4 and the "Circular Geofence" on Ardupilot
474 * this code should ideally live in the firmware plugin since it is specific to apm and px4 firmwares */
476{
477 if(_managerVehicle->isOfflineEditingVehicle()){
478 return 0;
479 }
480
481 if(_managerVehicle->px4Firmware()){
482 if(!_managerVehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, _px4ParamCircularFence)){
483 return 0;
484 }
485
486 return _managerVehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, _px4ParamCircularFence)->rawValue().toDouble();
487 }
488
489 if(_managerVehicle->apmFirmware())
490 {
491 if (!_managerVehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, _apmParamCircularFenceRadius) ||
492 !_managerVehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, _apmParamCircularFenceEnabled) ||
493 !_managerVehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, _apmParamCircularFenceType)){
494 return 0;
495 }
496
497 bool apm_fence_enabled = _managerVehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, _apmParamCircularFenceEnabled)->rawValue().toBool();
498 bool apm_fence_type_circle = (1 << 1) & _managerVehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, _apmParamCircularFenceType)->rawValue().toUInt();
499
500 if(!apm_fence_enabled || !apm_fence_type_circle)
501 return 0;
502
503 return _managerVehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, _apmParamCircularFenceRadius)->rawValue().toDouble();
504 }
505
506 return 0;
507}
508
509void GeoFenceController::_parametersReady(void)
510{
511 /* When parameters are ready we setup notifications of param changes
512 * so that if a param changes we can emit paramCircularFenceChanged
513 * and trigger an update to the UI */
514
515 // First disconnect from any existing facts
516 if (_px4ParamCircularFenceFact) {
517 _px4ParamCircularFenceFact->disconnect(this);
518 _px4ParamCircularFenceFact = nullptr;
519 }
520 if (_apmParamCircularFenceRadiusFact) {
521 _apmParamCircularFenceRadiusFact->disconnect(this);
522 _apmParamCircularFenceRadiusFact = nullptr;
523 }
524 if (_apmParamCircularFenceEnabledFact) {
525 _apmParamCircularFenceEnabledFact->disconnect(this);
526 _apmParamCircularFenceEnabledFact = nullptr;
527 }
528 if (_apmParamCircularFenceTypeFact) {
529 _apmParamCircularFenceTypeFact->disconnect(this);
530 _apmParamCircularFenceTypeFact = nullptr;
531 }
532
533 // then connect to needed paremters
534 // While checking they exist to avoid errors
535 ParameterManager* _paramManager = _managerVehicle->parameterManager();
536
537 if(_managerVehicle->isOfflineEditingVehicle()){
539 return;
540 }
541
542 if(_managerVehicle->px4Firmware()){
543 if(!_paramManager->parameterExists(ParameterManager::defaultComponentId, _px4ParamCircularFence)){
545 return;
546 }
547
548 _px4ParamCircularFenceFact = _paramManager->getParameter(ParameterManager::defaultComponentId, _px4ParamCircularFence);
549 connect(_px4ParamCircularFenceFact, &Fact::rawValueChanged, this, &GeoFenceController::paramCircularFenceChanged);
550 }
551 else if(_managerVehicle->apmFirmware())
552 {
553 if (!_paramManager->parameterExists(ParameterManager::defaultComponentId, _apmParamCircularFenceRadius) ||
554 !_paramManager->parameterExists(ParameterManager::defaultComponentId, _apmParamCircularFenceEnabled) ||
555 !_paramManager->parameterExists(ParameterManager::defaultComponentId, _apmParamCircularFenceType)){
557 return;
558 }
559
560 _apmParamCircularFenceRadiusFact = _paramManager->getParameter(ParameterManager::defaultComponentId, _apmParamCircularFenceRadius);
561 _apmParamCircularFenceEnabledFact = _paramManager->getParameter(ParameterManager::defaultComponentId, _apmParamCircularFenceEnabled);
562 _apmParamCircularFenceTypeFact = _paramManager->getParameter(ParameterManager::defaultComponentId, _apmParamCircularFenceType);
563 connect(_apmParamCircularFenceRadiusFact, &Fact::rawValueChanged, this, &GeoFenceController::paramCircularFenceChanged);
564 connect(_apmParamCircularFenceEnabledFact, &Fact::rawValueChanged, this, &GeoFenceController::paramCircularFenceChanged);
565 connect(_apmParamCircularFenceTypeFact, &Fact::rawValueChanged, this, &GeoFenceController::paramCircularFenceChanged);
566 }
567
569}
570
572{
573 return _polygons.count() == 0 && _circles.count() == 0 && !_breachReturnPoint.isValid();
574
575}
QString errorString
Error error
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Holds the meta data associated with a Fact.
static QMap< QString, FactMetaData * > createMapFromJsonFile(const QString &jsonFilename, QObject *metaDataParent)
void rawValueChanged(const QVariant &value)
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
bool showPlanFromManagerVehicle(void) final
Q_INVOKABLE void addInclusionPolygon(QGeoCoordinate topLeft, QGeoCoordinate bottomRight)
void removeAllFromVehicle(void) final
void breachReturnPointChanged(QGeoCoordinate breachReturnPoint)
void setDirty(bool dirty) final
bool containsItems(void) const final
double paramCircularFence(void)
QmlObjectListModel * polygons(void)
void sendToVehicle(void) final
Q_INVOKABLE void deletePolygon(int index)
QmlObjectListModel * circles(void)
bool syncInProgress(void) const final
void loadComplete(void)
void removeAll(void) final
Removes all from controller only.
void paramCircularFenceChanged(void)
Q_INVOKABLE void addInclusionCircle(QGeoCoordinate topLeft, QGeoCoordinate bottomRight)
void setBreachReturnPoint(const QGeoCoordinate &breachReturnPoint)
bool load(const QJsonObject &json, QString &errorString) final
bool supported(void) const final
true: controller is waiting for the current load to complete
void loadFromVehicle(void) final
bool isEmpty(void) const
bool dirty(void) const final
void start(bool flyView) final
Should be called immediately upon Component.onCompleted.
void save(QJsonObject &json) final
QGeoCoordinate breachReturnPoint(void) const
Q_INVOKABLE void clearAllInteractive(void)
Clears the interactive bit from all fence items.
Q_INVOKABLE void deleteCircle(int index)
void removeAll(void)
Signals removeAllComplete when done.
void sendToVehicle(const QGeoCoordinate &breachReturn, QmlObjectListModel &polygons, QmlObjectListModel &circles)
Signals sendComplete when done.
void inProgressChanged(bool inProgress)
const QGeoCoordinate & breachReturnPoint(void) const
const QList< QGCFencePolygon > & polygons(void)
void loadComplete(void)
void removeAllComplete(bool error)
void sendComplete(bool error)
const QList< QGCFenceCircle > & circles(void)
void dirtyChanged(bool dirty)
void countChanged(int count)
bool parameterExists(int componentId, const QString &paramName) const
Fact * getParameter(int componentId, const QString &paramName)
void parametersReadyChanged(bool parametersReady)
static constexpr int defaultComponentId
This is the abstract base clas for Plan Element controllers.
void supportedChanged(bool supported)
void syncInProgressChanged(bool syncInProgress)
PlanMasterController * _masterController
virtual void start(bool flyView)
Should be called immediately upon Component.onCompleted.
void dirtyChanged(bool dirty)
void loadFromVehicle(void)
bool inProgress(void) const
Master controller for mission, fence, rally.
void managerVehicleChanged(Vehicle *managerVehicle)
The QGCFenceCircle class provides a cicle used by GeoFence support.
bool loadFromJson(const QJsonObject &json, QString &errorString)
void saveToJson(QJsonObject &json)
The QGCFencePolygon class provides a polygon used by GeoFence support.
void saveToJson(QJsonObject &json)
bool loadFromJson(const QJsonObject &json, bool required, QString &errorString)
void setInteractive(bool interactive)
void setDirty(bool dirty)
void setDirty(bool dirty)
void setInteractive(bool interactive)
Q_INVOKABLE void appendVertex(const QGeoCoordinate &coordinate)
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
T value(int index) const
QObject * removeAt(int index)
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
Provides access to all app settings.
bool px4Firmware() const
Definition Vehicle.h:494
void capabilityBitsChanged(uint64_t capabilityBits)
uint64_t capabilityBits() const
Definition Vehicle.h:697
bool isOfflineEditingVehicle() const
Definition Vehicle.h:510
GeoFenceManager * geoFenceManager()
Definition Vehicle.h:571
bool apmFirmware() const
Definition Vehicle.h:495
ParameterManager * parameterManager()
Definition Vehicle.h:573
bool initialPlanRequestComplete() const
Definition Vehicle.h:703
bool loadGeoCoordinate(const QJsonValue &jsonValue, bool altitudeRequired, QGeoCoordinate &coordinate, QString &errorString)
void saveGeoCoordinate(const QGeoCoordinate &coordinate, bool writeAltitude, QJsonValue &jsonValue)
Saves a QGeoCoordinate as [lat, lon, alt] array (QGC plan format).
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
Validates that all required keys are present and that listed keys have the expected type.
constexpr const char * jsonVersionKey
Definition JsonParsing.h:12