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

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

#include <QJsonDocument>
28 29 30

QGC_LOGGING_CATEGORY(GeoFenceControllerLog, "GeoFenceControllerLog")

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

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

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

GeoFenceController::~GeoFenceController()
{

}

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

    PlanElementController::start(editMode);

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

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

64
void GeoFenceController::_signalAll(void)
65
{
66 67 68
    emit circleEnabledChanged(circleEnabled());
    emit polygonEnabledChanged(polygonEnabled());
    emit breachReturnEnabledChanged(breachReturnEnabled());
69
    emit breachReturnPointChanged(breachReturnPoint());
70 71 72
    emit circleRadiusChanged(circleRadius());
    emit paramsChanged(params());
    emit paramLabelsChanged(paramLabels());
73
    emit editorQmlChanged(editorQml());
74
    emit dirtyChanged(dirty());
75 76
}

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

void GeoFenceController::_activeVehicleSet(void)
{
84
    GeoFenceManager* geoFenceManager = _activeVehicle->geoFenceManager();
85 86 87 88 89 90 91 92 93
    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);
94

95 96 97
    if (!geoFenceManager->inProgress()) {
        _loadComplete(geoFenceManager->breachReturnPoint(), geoFenceManager->polygon());
    }
98

Don Gagne's avatar
Don Gagne committed
99
    _signalAll();
100
}
Don Gagne's avatar
Don Gagne committed
101

102 103 104 105
bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorString)
{
    QJsonObject json = jsonDoc.object();

Don Gagne's avatar
Don Gagne committed
106 107 108 109 110 111 112
    int fileVersion;
    if (!JsonHelper::validateQGCJsonFile(json,
                                         _jsonFileTypeValue,    // expected file type
                                         1,                     // minimum supported version
                                         1,                     // maximum supported version
                                         fileVersion,
                                         errorString)) {
113 114 115
        return false;
    }

116
    if (!_activeVehicle->parameterManager()->loadFromJson(json, false /* required */, errorString)) {
117 118 119
        return false;
    }

120
    if (breachReturnEnabled()) {
121
        if (json.contains(_jsonBreachReturnKey)
122
                && !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) {
123 124 125 126 127 128
            return false;
        }
    } else {
        _breachReturnPoint = QGeoCoordinate();
    }

129
    if (polygonEnabled()) {
130 131 132 133 134
        if (!_polygon.loadFromJson(json, false /* reauired */, errorString)) {
            return false;
        }
    } else {
        _polygon.clear();
135
    }
136
    _polygon.setDirty(false);
137 138

    return true;
139 140
}

141 142 143
#if 0
// NYI
bool GeoFenceController::_loadTextFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
144
{
145 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
    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;
    }
177

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

void GeoFenceController::loadFromFile(const QString& filename)
{
196 197 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
    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);
    }

223 224
    _signalAll();
    setDirty(true);
225 226
}

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

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

void GeoFenceController::saveToFile(const QString& filename)
{
241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257
    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
258
        fenceFileObject[JsonHelper::jsonVersionKey] =       1;
259 260 261
        fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue;

        QStringList         paramNames;
262
        ParameterManager*   paramMgr = _activeVehicle->parameterManager();
263 264 265 266 267 268 269 270 271 272
        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);
        }

273
        if (breachReturnEnabled()) {
274
            QJsonValue jsonBreachReturn;
275
            JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn);
276 277 278
            fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn;
        }

279
        if (polygonEnabled()) {
280 281
            _polygon.saveToJson(fenceFileObject);
        }
282 283 284 285 286 287 288 289 290 291 292

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

    setDirty(false);
}

void GeoFenceController::saveToFilePicker(void)
{
#ifndef __mobile__
293
    QString filename = QGCFileDialog::getSaveFileName(MainWindow::instance(), "Select file to save GeoFence to", QString(), "Fence file (*.fence);;All Files (*.*)");
294 295 296 297 298 299

    if (filename.isEmpty()) {
        return;
    }
    saveToFile(filename);
#endif
300 301 302 303
}

void GeoFenceController::removeAll(void)
{
304 305
    setBreachReturnPoint(QGeoCoordinate());
    _polygon.clear();
306 307 308 309
}

void GeoFenceController::loadFromVehicle(void)
{
310
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
311
        _activeVehicle->geoFenceManager()->loadFromVehicle();
312
    } else {
313
        qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress();
314 315 316 317 318
    }
}

void GeoFenceController::sendToVehicle(void)
{
319
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
320
        _activeVehicle->geoFenceManager()->sendToVehicle(_breachReturnPoint, _polygon.coordinateList());
Don Gagne's avatar
Don Gagne committed
321 322
        _polygon.setDirty(false);
        setDirty(false);
323
    } else {
324
        qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress();
325 326 327 328 329
    }
}

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

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


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

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

357
bool GeoFenceController::circleEnabled(void) const
358
{
359
    return _activeVehicle->geoFenceManager()->circleEnabled();
360 361
}

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

367
bool GeoFenceController::breachReturnEnabled(void) const
368
{
369
    return _activeVehicle->geoFenceManager()->breachReturnEnabled();
370 371 372 373 374 375 376
}

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

377
void GeoFenceController::_setPolygonFromManager(const QList<QGeoCoordinate>& polygon)
378 379
{
    _polygon.setPath(polygon);
380 381 382 383 384 385 386 387
    _polygon.setDirty(false);
    emit polygonPathChanged(_polygon.path());
}

void GeoFenceController::_setReturnPointFromManager(QGeoCoordinate breachReturnPoint)
{
    _breachReturnPoint = breachReturnPoint;
    emit breachReturnPointChanged(_breachReturnPoint);
388 389 390 391
}

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

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

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

QString GeoFenceController::editorQml(void) const
{
407
    return _activeVehicle->geoFenceManager()->editorQml();
408
}
409 410 411 412 413 414

void GeoFenceController::_loadComplete(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon)
{
    _setReturnPointFromManager(breachReturn);
    _setPolygonFromManager(polygon);
    setDirty(false);
Don Gagne's avatar
Don Gagne committed
415
    emit loadComplete();
416
}
417 418 419 420 421

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