GeoFenceController.cc 13.8 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/


/// @file
///     @author Don Gagne <don@thegagnes.com>

#include "GeoFenceController.h"
#include "Vehicle.h"
#include "FirmwarePlugin.h"
#include "MAVLinkProtocol.h"
#include "QGCApplication.h"
19 20
#include "ParameterManager.h"
#include "JsonHelper.h"
21
#include "QGCQGeoCoordinate.h"
Don Gagne's avatar
Don Gagne committed
22 23

#ifndef __mobile__
24
#include "MainWindow.h"
25
#include "QGCFileDialog.h"
Don Gagne's avatar
Don Gagne committed
26
#endif
27 28

#include <QJsonDocument>
29
#include <QJsonArray>
30 31 32

QGC_LOGGING_CATEGORY(GeoFenceControllerLog, "GeoFenceControllerLog")

33 34
const char* GeoFenceController::_jsonFileTypeValue =    "GeoFence";
const char* GeoFenceController::_jsonBreachReturnKey =  "breachReturn";
35

36 37 38
GeoFenceController::GeoFenceController(QObject* parent)
    : PlanElementController(parent)
    , _dirty(false)
39
    , _mapPolygon(this)
40
{
41 42
    connect(_mapPolygon.qmlPathModel(), &QmlObjectListModel::countChanged, this, &GeoFenceController::_updateContainsItems);
    connect(_mapPolygon.qmlPathModel(), &QmlObjectListModel::dirtyChanged, this, &GeoFenceController::_polygonDirtyChanged);
43 44 45 46 47 48 49 50 51 52 53 54
}

GeoFenceController::~GeoFenceController()
{

}

void GeoFenceController::start(bool editMode)
{
    qCDebug(GeoFenceControllerLog) << "start editMode" << editMode;

    PlanElementController::start(editMode);
55 56 57 58 59 60
    _init();
}

void GeoFenceController::startStaticActiveVehicle(Vehicle* vehicle)
{
    qCDebug(GeoFenceControllerLog) << "startStaticActiveVehicle";
61

62 63 64 65 66 67
    PlanElementController::startStaticActiveVehicle(vehicle);
    _init();
}

void GeoFenceController::_init(void)
{
68

69 70 71 72
}

void GeoFenceController::setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint)
{
73 74 75
    if (_breachReturnPoint != breachReturnPoint) {
        _breachReturnPoint = breachReturnPoint;
        setDirty(true);
76 77 78 79
        emit breachReturnPointChanged(breachReturnPoint);
    }
}

80
void GeoFenceController::_signalAll(void)
81
{
82 83 84
    emit circleEnabledChanged(circleEnabled());
    emit polygonEnabledChanged(polygonEnabled());
    emit breachReturnEnabledChanged(breachReturnEnabled());
85
    emit breachReturnPointChanged(breachReturnPoint());
86 87 88
    emit circleRadiusChanged(circleRadius());
    emit paramsChanged(params());
    emit paramLabelsChanged(paramLabels());
89
    emit editorQmlChanged(editorQml());
90
    emit dirtyChanged(dirty());
91 92
}

93
void GeoFenceController::_activeVehicleBeingRemoved(void)
94
{
95
    _activeVehicle->geoFenceManager()->disconnect(this);
96 97 98 99
}

void GeoFenceController::_activeVehicleSet(void)
{
100
    GeoFenceManager* geoFenceManager = _activeVehicle->geoFenceManager();
101 102 103 104 105 106 107 108 109
    connect(geoFenceManager, &GeoFenceManager::polygonEnabledChanged,       this, &GeoFenceController::_setDirty);
    connect(geoFenceManager, &GeoFenceManager::circleEnabledChanged,        this, &GeoFenceController::circleEnabledChanged);
    connect(geoFenceManager, &GeoFenceManager::polygonEnabledChanged,       this, &GeoFenceController::polygonEnabledChanged);
    connect(geoFenceManager, &GeoFenceManager::breachReturnEnabledChanged,  this, &GeoFenceController::breachReturnEnabledChanged);
    connect(geoFenceManager, &GeoFenceManager::circleRadiusChanged,         this, &GeoFenceController::circleRadiusChanged);
    connect(geoFenceManager, &GeoFenceManager::paramsChanged,               this, &GeoFenceController::paramsChanged);
    connect(geoFenceManager, &GeoFenceManager::paramLabelsChanged,          this, &GeoFenceController::paramLabelsChanged);
    connect(geoFenceManager, &GeoFenceManager::loadComplete,                this, &GeoFenceController::_loadComplete);
    connect(geoFenceManager, &GeoFenceManager::inProgressChanged,           this, &GeoFenceController::syncInProgressChanged);
110

111 112 113
    if (!geoFenceManager->inProgress()) {
        _loadComplete(geoFenceManager->breachReturnPoint(), geoFenceManager->polygon());
    }
114

Don Gagne's avatar
Don Gagne committed
115
    _signalAll();
116
}
Don Gagne's avatar
Don Gagne committed
117

118 119 120 121
bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorString)
{
    QJsonObject json = jsonDoc.object();

Don Gagne's avatar
Don Gagne committed
122 123 124 125 126 127 128
    int fileVersion;
    if (!JsonHelper::validateQGCJsonFile(json,
                                         _jsonFileTypeValue,    // expected file type
                                         1,                     // minimum supported version
                                         1,                     // maximum supported version
                                         fileVersion,
                                         errorString)) {
129 130 131
        return false;
    }

132
    if (!_activeVehicle->parameterManager()->loadFromJson(json, false /* required */, errorString)) {
133 134 135
        return false;
    }

136
    if (breachReturnEnabled()) {
137
        if (json.contains(_jsonBreachReturnKey)
138
                && !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) {
139 140 141 142 143 144
            return false;
        }
    } else {
        _breachReturnPoint = QGeoCoordinate();
    }

145
    if (polygonEnabled()) {
146
        if (!_mapPolygon.loadFromJson(json, true, errorString)) {
147 148
            return false;
        }
149
    }
150
    _mapPolygon.setDirty(false);
151 152

    return true;
153 154
}

155 156 157
#if 0
// NYI
bool GeoFenceController::_loadTextFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
158
{
159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190
    bool addPlannedHomePosition = false;

    QString firstLine = stream.readLine();
    const QStringList& version = firstLine.split(" ");

    bool versionOk = false;
    if (version.size() == 3 && version[0] == "QGC" && version[1] == "WPL") {
        if (version[2] == "110") {
            // ArduPilot file, planned home position is already in position 0
            versionOk = true;
        } else if (version[2] == "120") {
            // Old QGC file, no planned home position
            versionOk = true;
            addPlannedHomePosition = true;
        }
    }

    if (versionOk) {
        while (!stream.atEnd()) {
            SimpleMissionItem* item = new SimpleMissionItem(_activeVehicle, this);

            if (item->load(stream)) {
                visualItems->append(item);
            } else {
                errorString = QStringLiteral("The mission file is corrupted.");
                return false;
            }
        }
    } else {
        errorString = QStringLiteral("The mission file is not compatible with this version of QGroundControl.");
        return false;
    }
191

192 193 194 195 196 197 198 199 200 201 202 203 204
    if (addPlannedHomePosition || visualItems->count() == 0) {
        _addPlannedHomePosition(visualItems, true /* addToCenter */);

        // Update sequence numbers in DO_JUMP commands to take into account added home position in index 0
        for (int i=1; i<visualItems->count(); i++) {
            SimpleMissionItem* item = qobject_cast<SimpleMissionItem*>(visualItems->get(i));
            if (item && item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
                item->missionItem().setParam1((int)item->missionItem().param1() + 1);
            }
        }
    }

    return true;
205
}
206
#endif
207 208 209

void GeoFenceController::loadFromFile(const QString& filename)
{
210 211 212 213 214 215 216 217 218
    QString errorString;

    if (filename.isEmpty()) {
        return;
    }

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
Don Gagne's avatar
Don Gagne committed
219
        errorString = file.errorString() + QStringLiteral(" ") + filename;
220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236
    } else {
        QJsonDocument   jsonDoc;
        QByteArray      bytes = file.readAll();

        if (JsonHelper::isJsonFile(bytes, jsonDoc)) {
            _loadJsonFile(jsonDoc, errorString);
        } else {
            // FIXME: No MP file format support
            qgcApp()->showMessage("GeoFence file is in incorrect format.");
            return;
        }
    }

    if (!errorString.isEmpty()) {
        qgcApp()->showMessage(errorString);
    }

237 238
    _signalAll();
    setDirty(true);
239 240
}

241
void GeoFenceController::loadFromFilePicker(void)
242
{
243
#ifndef __mobile__
244
    QString filename = QGCFileDialog::getOpenFileName(MainWindow::instance(), "Select GeoFence File to load", QString(), "Fence file (*.fence);;All Files (*.*)");
245

246 247 248 249 250
    if (filename.isEmpty()) {
        return;
    }
    loadFromFile(filename);
#endif
251 252 253 254
}

void GeoFenceController::saveToFile(const QString& filename)
{
255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271
    if (filename.isEmpty()) {
        return;
    }

    QString fenceFilename = filename;
    if (!QFileInfo(filename).fileName().contains(".")) {
        fenceFilename += QString(".%1").arg(QGCApplication::fenceFileExtension);
    }

    QFile file(fenceFilename);

    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
        qgcApp()->showMessage(file.errorString());
    } else {
        QJsonObject fenceFileObject;    // top level json object

        fenceFileObject[JsonHelper::jsonFileTypeKey] =      _jsonFileTypeValue;
Don Gagne's avatar
Don Gagne committed
272
        fenceFileObject[JsonHelper::jsonVersionKey] =       1;
273 274 275
        fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue;

        QStringList         paramNames;
276
        ParameterManager*   paramMgr = _activeVehicle->parameterManager();
277 278 279 280 281 282 283
        GeoFenceManager*    fenceMgr = _activeVehicle->geoFenceManager();
        QVariantList        params = fenceMgr->params();

        for (int i=0; i< params.count(); i++) {
            paramNames.append(params[i].value<Fact*>()->name());
        }
        if (paramNames.count() > 0) {
284
            paramMgr->saveToJson(_activeVehicle->defaultComponentId(), paramNames, fenceFileObject);
285 286
        }

287
        if (breachReturnEnabled()) {
288
            QJsonValue jsonBreachReturn;
289
            JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn);
290 291 292
            fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn;
        }

293
        if (polygonEnabled()) {
294
            _mapPolygon.saveToJson(fenceFileObject);
295
        }
296 297 298 299 300 301 302 303 304 305 306

        QJsonDocument saveDoc(fenceFileObject);
        file.write(saveDoc.toJson());
    }

    setDirty(false);
}

void GeoFenceController::saveToFilePicker(void)
{
#ifndef __mobile__
307
    QString filename = QGCFileDialog::getSaveFileName(MainWindow::instance(), "Select file to save GeoFence to", QString(), "Fence file (*.fence);;All Files (*.*)");
308 309 310 311 312 313

    if (filename.isEmpty()) {
        return;
    }
    saveToFile(filename);
#endif
314 315 316 317
}

void GeoFenceController::removeAll(void)
{
318
    setBreachReturnPoint(QGeoCoordinate());
319
    _mapPolygon.clear();
320 321 322 323
}

void GeoFenceController::loadFromVehicle(void)
{
324
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
325
        _activeVehicle->geoFenceManager()->loadFromVehicle();
326
    } else {
327
        qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress();
328 329 330 331 332
    }
}

void GeoFenceController::sendToVehicle(void)
{
333
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
334 335
        _activeVehicle->geoFenceManager()->sendToVehicle(_breachReturnPoint, _mapPolygon.pathModel());
        _mapPolygon.setDirty(false);
Don Gagne's avatar
Don Gagne committed
336
        setDirty(false);
337
    } else {
338
        qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress();
339 340 341 342 343
    }
}

bool GeoFenceController::syncInProgress(void) const
{
344
    return _activeVehicle->geoFenceManager()->inProgress();
345 346 347 348
}

bool GeoFenceController::dirty(void) const
{
349
    return _dirty;
350 351 352 353 354 355 356 357
}


void GeoFenceController::setDirty(bool dirty)
{
    if (dirty != _dirty) {
        _dirty = dirty;
        if (!dirty) {
358
            _mapPolygon.setDirty(dirty);
359 360 361 362 363 364 365 366 367 368 369
        }
        emit dirtyChanged(dirty);
    }
}

void GeoFenceController::_polygonDirtyChanged(bool dirty)
{
    if (dirty) {
        setDirty(true);
    }
}
370

371
bool GeoFenceController::circleEnabled(void) const
372
{
373
    return _activeVehicle->geoFenceManager()->circleEnabled();
374 375
}

376
bool GeoFenceController::polygonEnabled(void) const
377
{
378
    return _activeVehicle->geoFenceManager()->polygonEnabled();
379 380
}

381
bool GeoFenceController::breachReturnEnabled(void) const
382
{
383
    return _activeVehicle->geoFenceManager()->breachReturnEnabled();
384 385 386 387 388 389 390
}

void GeoFenceController::_setDirty(void)
{
    setDirty(true);
}

391
void GeoFenceController::_setPolygonFromManager(const QList<QGeoCoordinate>& polygon)
392
{
393 394 395 396 397
    _mapPolygon.clear();
    for (int i=0; i<polygon.count(); i++) {
        _mapPolygon.appendVertex(polygon[i]);
    }
    _mapPolygon.setDirty(false);
398 399 400 401 402 403
}

void GeoFenceController::_setReturnPointFromManager(QGeoCoordinate breachReturnPoint)
{
    _breachReturnPoint = breachReturnPoint;
    emit breachReturnPointChanged(_breachReturnPoint);
404 405 406 407
}

float GeoFenceController::circleRadius(void) const
{
408
    return _activeVehicle->geoFenceManager()->circleRadius();
409 410 411 412
}

QVariantList GeoFenceController::params(void) const
{
413
    return _activeVehicle->geoFenceManager()->params();
414 415 416 417
}

QStringList GeoFenceController::paramLabels(void) const
{
418
    return _activeVehicle->geoFenceManager()->paramLabels();
419
}
420 421 422

QString GeoFenceController::editorQml(void) const
{
423
    return _activeVehicle->geoFenceManager()->editorQml();
424
}
425 426 427 428 429 430

void GeoFenceController::_loadComplete(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon)
{
    _setReturnPointFromManager(breachReturn);
    _setPolygonFromManager(polygon);
    setDirty(false);
Don Gagne's avatar
Don Gagne committed
431
    emit loadComplete();
432
}
433 434 435 436 437

QString GeoFenceController::fileExtension(void) const
{
    return QGCApplication::fenceFileExtension;
}
438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464

bool GeoFenceController::containsItems(void) const
{
    return _mapPolygon.count() > 2;
}

void GeoFenceController::_updateContainsItems(void)
{
    emit containsItemsChanged(containsItems());
}

void GeoFenceController::removeAllFromVehicle(void)
{
    _activeVehicle->geoFenceManager()->removeAll();
}

void GeoFenceController::addFence(void)
{
    // GeoFenceMapVisuals control is resposible for this
    emit addFencePolygon();
}

void GeoFenceController::removeFence(void)
{
    _mapPolygon.clear();
}