GeoFenceController.cc 12.7 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";

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

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

GeoFenceController::~GeoFenceController()
{

}

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

    PlanElementController::start(editMode);

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

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

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

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

void GeoFenceController::_activeVehicleSet(void)
{
85 86 87 88 89 90 91 92 93 94 95 96 97
    GeoFenceManager* geoFenceManager = _activeVehicle->geoFenceManager();
    connect(geoFenceManager, &GeoFenceManager::circleSupportedChanged,          this, &GeoFenceController::_setDirty);
    connect(geoFenceManager, &GeoFenceManager::polygonSupportedChanged,         this, &GeoFenceController::_setDirty);
    connect(geoFenceManager, &GeoFenceManager::fenceSupportedChanged,           this, &GeoFenceController::fenceSupportedChanged);
    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::polygonChanged,                  this, &GeoFenceController::_setPolygon);
    connect(geoFenceManager, &GeoFenceManager::breachReturnPointChanged,        this, &GeoFenceController::setBreachReturnPoint);
    connect(geoFenceManager, &GeoFenceManager::paramsChanged,                   this, &GeoFenceController::paramsChanged);
    connect(geoFenceManager, &GeoFenceManager::paramLabelsChanged,              this, &GeoFenceController::paramLabelsChanged);

98 99 100
    _setPolygon(geoFenceManager->polygon());
    setBreachReturnPoint(geoFenceManager->breachReturnPoint());

Don Gagne's avatar
Don Gagne committed
101
    _signalAll();
102
}
Don Gagne's avatar
Don Gagne committed
103

104 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 134 135 136 137
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;
    }

    if (!_activeVehicle->getParameterManager()->loadFromJson(json, false /* required */, errorString)) {
        return false;
    }

    if (!_polygon.loadFromJson(json, false /* reauired */, errorString)) {
        return false;
138
    }
139 140

    return true;
141 142
}

143 144 145
#if 0
// NYI
bool GeoFenceController::_loadTextFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
146
{
147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178
    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;
    }
179

180 181 182 183 184 185 186 187 188 189 190 191 192
    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;
193
}
194
#endif
195 196 197

void GeoFenceController::loadFromFile(const QString& filename)
{
198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225
    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);
    }

    setDirty(false);
226 227
}

228
void GeoFenceController::loadFromFilePicker(void)
229
{
230 231
#ifndef __mobile__
    QString filename = QGCFileDialog::getOpenFileName(NULL, "Select GeoFence File to load", QString(), "Mission file (*.fence);;All Files (*.*)");
232

233 234 235 236 237
    if (filename.isEmpty()) {
        return;
    }
    loadFromFile(filename);
#endif
238 239 240 241
}

void GeoFenceController::saveToFile(const QString& filename)
{
242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294
    qDebug() << filename;

    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;
        ParameterManager*   paramMgr = _activeVehicle->getParameterManager();
        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);
        }

        _polygon.saveToJson(fenceFileObject);

        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
295 296 297 298 299 300 301 302 303
}

void GeoFenceController::removeAll(void)
{
    _clearGeoFence();
}

void GeoFenceController::loadFromVehicle(void)
{
304
    if (_activeVehicle->getParameterManager()->parametersAreReady() && !syncInProgress()) {
305
        _activeVehicle->geoFenceManager()->loadFromVehicle();
306
    } else {
307
        qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->getParameterManager()->parametersAreReady() << syncInProgress();
308 309 310 311 312
    }
}

void GeoFenceController::sendToVehicle(void)
{
313
    if (_activeVehicle->getParameterManager()->parametersAreReady() && !syncInProgress()) {
314 315
        _activeVehicle->geoFenceManager()->setPolygon(polygon());
        _activeVehicle->geoFenceManager()->setBreachReturnPoint(breachReturnPoint());
316
        setDirty(false);
317 318
        _polygon.setDirty(false);
        _activeVehicle->geoFenceManager()->sendToVehicle();
319
    } else {
320
        qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->getParameterManager()->parametersAreReady() << syncInProgress();
321 322 323 324 325 326
    }
}

void GeoFenceController::_clearGeoFence(void)
{
    setBreachReturnPoint(QGeoCoordinate());
327
    _polygon.clear();
328 329 330 331
}

bool GeoFenceController::syncInProgress(void) const
{
332
    return _activeVehicle->geoFenceManager()->inProgress();
333 334 335 336
}

bool GeoFenceController::dirty(void) const
{
337
    return _dirty | _polygon.dirty();
338 339 340 341 342 343 344 345
}


void GeoFenceController::setDirty(bool dirty)
{
    if (dirty != _dirty) {
        _dirty = dirty;
        if (!dirty) {
346
            _polygon.setDirty(dirty);
347 348 349 350 351 352 353 354 355 356 357
        }
        emit dirtyChanged(dirty);
    }
}

void GeoFenceController::_polygonDirtyChanged(bool dirty)
{
    if (dirty) {
        setDirty(true);
    }
}
358 359 360

bool GeoFenceController::fenceSupported(void) const
{
361
    return _activeVehicle->geoFenceManager()->fenceSupported();
362 363 364 365
}

bool GeoFenceController::circleSupported(void) const
{
366
    return _activeVehicle->geoFenceManager()->circleSupported();
367 368 369 370
}

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

bool GeoFenceController::breachReturnSupported(void) const
{
376
    return _activeVehicle->geoFenceManager()->breachReturnSupported();
377 378 379 380 381 382 383 384 385 386
}

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

void GeoFenceController::_setPolygon(const QList<QGeoCoordinate>& polygon)
{
    _polygon.setPath(polygon);
Don Gagne's avatar
Don Gagne committed
387 388
    // This is coming from a GeoFenceManager::loadFromVehicle call
    setDirty(false);
389 390 391 392
}

float GeoFenceController::circleRadius(void) const
{
393
    return _activeVehicle->geoFenceManager()->circleRadius();
394 395 396 397
}

QVariantList GeoFenceController::params(void) const
{
398
    return _activeVehicle->geoFenceManager()->params();
399 400 401 402
}

QStringList GeoFenceController::paramLabels(void) const
{
403
    return _activeVehicle->geoFenceManager()->paramLabels();
404
}
405 406 407

QString GeoFenceController::editorQml(void) const
{
408
    return _activeVehicle->geoFenceManager()->editorQml();
409
}