GeoFenceController.cc 14 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"
Don Gagne's avatar
Don Gagne committed
21 22

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

#include <QJsonDocument>
27 28 29

QGC_LOGGING_CATEGORY(GeoFenceControllerLog, "GeoFenceControllerLog")

30 31
const char* GeoFenceController::_jsonFileTypeValue =    "GeoFence";
const char* GeoFenceController::_jsonBreachReturnKey =  "breachReturn";
32

33 34 35 36
GeoFenceController::GeoFenceController(QObject* parent)
    : PlanElementController(parent)
    , _dirty(false)
{
37

38 39 40 41 42 43 44 45 46 47 48 49 50
}

GeoFenceController::~GeoFenceController()
{

}

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

    PlanElementController::start(editMode);

51
    connect(&_polygon, &QGCMapPolygon::dirtyChanged, this, &GeoFenceController::_polygonDirtyChanged);
52 53 54 55
}

void GeoFenceController::setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint)
{
56 57 58
    if (_breachReturnPoint != breachReturnPoint) {
        _breachReturnPoint = breachReturnPoint;
        setDirty(true);
59 60 61 62
        emit breachReturnPointChanged(breachReturnPoint);
    }
}

63
void GeoFenceController::_signalAll(void)
64
{
65
    emit fenceSupportedChanged(fenceSupported());
66
    emit fenceEnabledChanged(fenceEnabled());
67 68 69
    emit circleSupportedChanged(circleSupported());
    emit polygonSupportedChanged(polygonSupported());
    emit breachReturnSupportedChanged(breachReturnSupported());
70
    emit breachReturnPointChanged(breachReturnPoint());
71 72 73
    emit circleRadiusChanged(circleRadius());
    emit paramsChanged(params());
    emit paramLabelsChanged(paramLabels());
74
    emit editorQmlChanged(editorQml());
75
    emit dirtyChanged(dirty());
76 77
}

78
void GeoFenceController::_activeVehicleBeingRemoved(void)
79
{
80
    _activeVehicle->geoFenceManager()->disconnect(this);
81 82 83 84
}

void GeoFenceController::_activeVehicleSet(void)
{
85
    GeoFenceManager* geoFenceManager = _activeVehicle->geoFenceManager();
86 87
    connect(geoFenceManager, &GeoFenceManager::fenceSupportedChanged,           this, &GeoFenceController::fenceSupportedChanged);
    connect(geoFenceManager, &GeoFenceManager::fenceEnabledChanged,             this, &GeoFenceController::fenceEnabledChanged);
88 89 90 91 92 93 94 95
    connect(geoFenceManager, &GeoFenceManager::circleSupportedChanged,          this, &GeoFenceController::_setDirty);
    connect(geoFenceManager, &GeoFenceManager::polygonSupportedChanged,         this, &GeoFenceController::_setDirty);
    connect(geoFenceManager, &GeoFenceManager::circleSupportedChanged,          this, &GeoFenceController::circleSupportedChanged);
    connect(geoFenceManager, &GeoFenceManager::polygonSupportedChanged,         this, &GeoFenceController::polygonSupportedChanged);
    connect(geoFenceManager, &GeoFenceManager::breachReturnSupportedChanged,    this, &GeoFenceController::breachReturnSupportedChanged);
    connect(geoFenceManager, &GeoFenceManager::circleRadiusChanged,             this, &GeoFenceController::circleRadiusChanged);
    connect(geoFenceManager, &GeoFenceManager::paramsChanged,                   this, &GeoFenceController::paramsChanged);
    connect(geoFenceManager, &GeoFenceManager::paramLabelsChanged,              this, &GeoFenceController::paramLabelsChanged);
96
    connect(geoFenceManager, &GeoFenceManager::loadComplete,                    this, &GeoFenceController::_loadComplete);
97
    connect(geoFenceManager, &GeoFenceManager::inProgressChanged,               this, &GeoFenceController::syncInProgressChanged);
98

99 100 101
    if (!geoFenceManager->inProgress()) {
        _loadComplete(geoFenceManager->breachReturnPoint(), geoFenceManager->polygon());
    }
102

Don Gagne's avatar
Don Gagne committed
103
    _signalAll();
104
}
Don Gagne's avatar
Don Gagne committed
105

106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133
bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorString)
{
    QJsonObject json = jsonDoc.object();

    // Check for required keys
    QStringList requiredKeys;
    requiredKeys << JsonHelper::jsonVersionKey << JsonHelper::jsonFileTypeKey;
    if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorString)) {
        return false;
    }

#if 0
    // Validate base key types
    QStringList             keyList;
    QList<QJsonValue::Type> typeList;
    keyList << jsonSimpleItemsKey << _jsonVersionKey << _jsonGroundStationKey << _jsonMavAutopilotKey << _jsonComplexItemsKey << _jsonPlannedHomePositionKey;
    typeList << QJsonValue::Array << QJsonValue::String << QJsonValue::String << QJsonValue::Double << QJsonValue::Array << QJsonValue::Object;
    if (!JsonHelper::validateKeyTypes(json, keyList, typeList, errorString)) {
        return false;
    }
#endif

    // Version check
    if (json[JsonHelper::jsonVersionKey].toString() != "1.0") {
        errorString = QStringLiteral("QGroundControl does not support this file version");
        return false;
    }

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

138 139
    if (breachReturnSupported()) {
        if (json.contains(_jsonBreachReturnKey)
140
                && !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) {
141 142 143 144 145 146 147 148 149 150 151 152
            return false;
        }
    } else {
        _breachReturnPoint = QGeoCoordinate();
    }

    if (polygonSupported()) {
        if (!_polygon.loadFromJson(json, false /* reauired */, errorString)) {
            return false;
        }
    } else {
        _polygon.clear();
153
    }
154
    _polygon.setDirty(false);
155 156

    return true;
157 158
}

159 160 161
#if 0
// NYI
bool GeoFenceController::_loadTextFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
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 191 192 193 194
    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;
    }
195

196 197 198 199 200 201 202 203 204 205 206 207 208
    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;
209
}
210
#endif
211 212 213

void GeoFenceController::loadFromFile(const QString& filename)
{
214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240
    QString errorString;

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

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
        errorString = file.errorString();
    } 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);
    }

241 242
    _signalAll();
    setDirty(true);
243 244
}

245
void GeoFenceController::loadFromFilePicker(void)
246
{
247
#ifndef __mobile__
248
    QString filename = QGCFileDialog::getOpenFileName(NULL, "Select GeoFence File to load", QString(), "Fence file (*.fence);;All Files (*.*)");
249

250 251 252 253 254
    if (filename.isEmpty()) {
        return;
    }
    loadFromFile(filename);
#endif
255 256 257 258
}

void GeoFenceController::saveToFile(const QString& filename)
{
259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279
    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;
        fenceFileObject[JsonHelper::jsonVersionKey] =       QStringLiteral("1.0");
        fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue;

        QStringList         paramNames;
280
        ParameterManager*   paramMgr = _activeVehicle->parameterManager();
281 282 283 284 285 286 287 288 289 290
        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) {
            paramMgr->saveToJson(paramMgr->defaultComponentId(), paramNames, fenceFileObject);
        }

291 292
        if (breachReturnSupported()) {
            QJsonValue jsonBreachReturn;
293
            JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn);
294 295 296 297 298 299
            fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn;
        }

        if (polygonSupported()) {
            _polygon.saveToJson(fenceFileObject);
        }
300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317

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

    setDirty(false);
}

void GeoFenceController::saveToFilePicker(void)
{
#ifndef __mobile__
    QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save GeoFence to", QString(), "Fence file (*.fence);;All Files (*.*)");

    if (filename.isEmpty()) {
        return;
    }
    saveToFile(filename);
#endif
318 319 320 321
}

void GeoFenceController::removeAll(void)
{
322 323
    setBreachReturnPoint(QGeoCoordinate());
    _polygon.clear();
324 325 326 327
}

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

void GeoFenceController::sendToVehicle(void)
{
337
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
338
        _activeVehicle->geoFenceManager()->sendToVehicle(_breachReturnPoint, _polygon.coordinateList());
Don Gagne's avatar
Don Gagne committed
339 340
        _polygon.setDirty(false);
        setDirty(false);
341
    } else {
342
        qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress();
343 344 345 346 347
    }
}

bool GeoFenceController::syncInProgress(void) const
{
348
    return _activeVehicle->geoFenceManager()->inProgress();
349 350 351 352
}

bool GeoFenceController::dirty(void) const
{
353
    return _dirty | _polygon.dirty();
354 355 356 357 358 359 360 361
}


void GeoFenceController::setDirty(bool dirty)
{
    if (dirty != _dirty) {
        _dirty = dirty;
        if (!dirty) {
362
            _polygon.setDirty(dirty);
363 364 365 366 367 368 369 370 371 372 373
        }
        emit dirtyChanged(dirty);
    }
}

void GeoFenceController::_polygonDirtyChanged(bool dirty)
{
    if (dirty) {
        setDirty(true);
    }
}
374 375 376

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

380 381 382 383 384
bool GeoFenceController::fenceEnabled(void) const
{
    return _activeVehicle->geoFenceManager()->fenceEnabled();
}

385 386
bool GeoFenceController::circleSupported(void) const
{
387
    return _activeVehicle->geoFenceManager()->circleSupported();
388 389 390 391
}

bool GeoFenceController::polygonSupported(void) const
{
392
    return _activeVehicle->geoFenceManager()->polygonSupported();
393 394 395 396
}

bool GeoFenceController::breachReturnSupported(void) const
{
397
    return _activeVehicle->geoFenceManager()->breachReturnSupported();
398 399 400 401 402 403 404
}

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

405
void GeoFenceController::_setPolygonFromManager(const QList<QGeoCoordinate>& polygon)
406 407
{
    _polygon.setPath(polygon);
408 409 410 411 412 413 414 415
    _polygon.setDirty(false);
    emit polygonPathChanged(_polygon.path());
}

void GeoFenceController::_setReturnPointFromManager(QGeoCoordinate breachReturnPoint)
{
    _breachReturnPoint = breachReturnPoint;
    emit breachReturnPointChanged(_breachReturnPoint);
416 417 418 419
}

float GeoFenceController::circleRadius(void) const
{
420
    return _activeVehicle->geoFenceManager()->circleRadius();
421 422 423 424
}

QVariantList GeoFenceController::params(void) const
{
425
    return _activeVehicle->geoFenceManager()->params();
426 427 428 429
}

QStringList GeoFenceController::paramLabels(void) const
{
430
    return _activeVehicle->geoFenceManager()->paramLabels();
431
}
432 433 434

QString GeoFenceController::editorQml(void) const
{
435
    return _activeVehicle->geoFenceManager()->editorQml();
436
}
437 438 439 440 441 442

void GeoFenceController::_loadComplete(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon)
{
    _setReturnPointFromManager(breachReturn);
    _setPolygonFromManager(polygon);
    setDirty(false);
Don Gagne's avatar
Don Gagne committed
443
    emit loadComplete();
444
}
445 446 447 448 449

QString GeoFenceController::fileExtension(void) const
{
    return QGCApplication::fenceFileExtension;
}