GeoFenceController.cc 10 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"
22
#include "AppSettings.h"
Don Gagne's avatar
Don Gagne committed
23 24

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

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

QGC_LOGGING_CATEGORY(GeoFenceControllerLog, "GeoFenceControllerLog")

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

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

GeoFenceController::~GeoFenceController()
{

}

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

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

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

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

void GeoFenceController::_init(void)
{
69

70 71 72 73
}

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

81
void GeoFenceController::_signalAll(void)
82
{
83 84
    emit breachReturnSupportedChanged(breachReturnSupported());
    emit breachReturnPointChanged(breachReturnPoint());
85
    emit circleEnabledChanged(circleEnabled());
86
    emit circleRadiusFactChanged(circleRadiusFact());
87
    emit polygonEnabledChanged(polygonEnabled());
88
    emit polygonSupportedChanged(polygonSupported());
89
    emit dirtyChanged(dirty());
90 91
}

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

void GeoFenceController::_activeVehicleSet(void)
{
99
    GeoFenceManager* geoFenceManager = _activeVehicle->geoFenceManager();
100 101 102 103 104 105 106
    connect(geoFenceManager, &GeoFenceManager::breachReturnSupportedChanged,    this, &GeoFenceController::breachReturnSupportedChanged);
    connect(geoFenceManager, &GeoFenceManager::circleEnabledChanged,            this, &GeoFenceController::circleEnabledChanged);
    connect(geoFenceManager, &GeoFenceManager::circleRadiusFactChanged,         this, &GeoFenceController::circleRadiusFactChanged);
    connect(geoFenceManager, &GeoFenceManager::polygonEnabledChanged,           this, &GeoFenceController::polygonEnabledChanged);
    connect(geoFenceManager, &GeoFenceManager::polygonSupportedChanged,         this, &GeoFenceController::polygonSupportedChanged);
    connect(geoFenceManager, &GeoFenceManager::loadComplete,                    this, &GeoFenceController::_loadComplete);
    connect(geoFenceManager, &GeoFenceManager::inProgressChanged,               this, &GeoFenceController::syncInProgressChanged);
107

108 109 110
    if (!geoFenceManager->inProgress()) {
        _loadComplete(geoFenceManager->breachReturnPoint(), geoFenceManager->polygon());
    }
111

Don Gagne's avatar
Don Gagne committed
112
    _signalAll();
113
}
Don Gagne's avatar
Don Gagne committed
114

115 116 117 118
bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorString)
{
    QJsonObject json = jsonDoc.object();

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

129
    if (!_activeVehicle->parameterManager()->loadFromJson(json, false /* required */, errorString)) {
130 131 132
        return false;
    }

133 134
    if (json.contains(_jsonBreachReturnKey)
            && !JsonHelper::loadGeoCoordinate(json[_jsonBreachReturnKey], false /* altitudeRequired */, _breachReturnPoint, errorString)) {
135 136
        return false;
    }
137

138 139
    if (!_mapPolygon.loadFromJson(json, true, errorString)) {
        return false;
140
    }
141
    _mapPolygon.setDirty(false);
142 143

    return true;
144 145 146 147
}

void GeoFenceController::loadFromFile(const QString& filename)
{
148 149 150 151 152 153 154 155 156
    QString errorString;

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

    QFile file(filename);

    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
Don Gagne's avatar
Don Gagne committed
157
        errorString = file.errorString() + QStringLiteral(" ") + filename;
158 159 160 161
    } else {
        QJsonDocument   jsonDoc;
        QByteArray      bytes = file.readAll();

162
        _loadJsonFile(jsonDoc, errorString);
163 164 165 166 167 168
    }

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

169 170
    _signalAll();
    setDirty(true);
171 172 173 174
}

void GeoFenceController::saveToFile(const QString& filename)
{
175 176 177 178 179 180
    if (filename.isEmpty()) {
        return;
    }

    QString fenceFilename = filename;
    if (!QFileInfo(filename).fileName().contains(".")) {
181
        fenceFilename += QString(".%1").arg(AppSettings::fenceFileExtension);
182 183 184 185 186 187 188 189 190 191
    }

    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
192
        fenceFileObject[JsonHelper::jsonVersionKey] =       1;
193 194
        fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue;

195 196 197
        QJsonValue jsonBreachReturn;
        JsonHelper::saveGeoCoordinate(_breachReturnPoint, false /* writeAltitude */, jsonBreachReturn);
        fenceFileObject[_jsonBreachReturnKey] = jsonBreachReturn;
198

199
        _mapPolygon.saveToJson(fenceFileObject);
200 201 202 203 204 205 206 207

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

    setDirty(false);
}

208 209
void GeoFenceController::removeAll(void)
{
210
    setBreachReturnPoint(QGeoCoordinate());
211
    _mapPolygon.clear();
212 213 214 215
}

void GeoFenceController::loadFromVehicle(void)
{
216
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
217
        _activeVehicle->geoFenceManager()->loadFromVehicle();
218
    } else {
219
        qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress();
220 221 222 223 224
    }
}

void GeoFenceController::sendToVehicle(void)
{
225
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
226 227
        _activeVehicle->geoFenceManager()->sendToVehicle(_breachReturnPoint, _mapPolygon.pathModel());
        _mapPolygon.setDirty(false);
Don Gagne's avatar
Don Gagne committed
228
        setDirty(false);
229
    } else {
230
        qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress();
231 232 233 234 235
    }
}

bool GeoFenceController::syncInProgress(void) const
{
236
    return _activeVehicle->geoFenceManager()->inProgress();
237 238 239 240
}

bool GeoFenceController::dirty(void) const
{
241
    return _dirty;
242 243 244 245 246 247 248 249
}


void GeoFenceController::setDirty(bool dirty)
{
    if (dirty != _dirty) {
        _dirty = dirty;
        if (!dirty) {
250
            _mapPolygon.setDirty(dirty);
251 252 253 254 255 256 257 258 259 260 261
        }
        emit dirtyChanged(dirty);
    }
}

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

263 264 265 266 267
bool GeoFenceController::breachReturnSupported(void) const
{
    return _activeVehicle->geoFenceManager()->breachReturnSupported();
}

268
bool GeoFenceController::circleEnabled(void) const
269
{
270
    return _activeVehicle->geoFenceManager()->circleEnabled();
271 272
}

273 274 275 276 277 278 279 280 281 282
Fact* GeoFenceController::circleRadiusFact(void) const
{
    return _activeVehicle->geoFenceManager()->circleRadiusFact();
}

bool GeoFenceController::polygonSupported(void) const
{
    return _activeVehicle->geoFenceManager()->polygonSupported();
}

283
bool GeoFenceController::polygonEnabled(void) const
284
{
285
    return _activeVehicle->geoFenceManager()->polygonEnabled();
286 287
}

288
QVariantList GeoFenceController::params(void) const
289
{
290 291 292 293 294 295
    return _activeVehicle->geoFenceManager()->params();
}

QStringList GeoFenceController::paramLabels(void) const
{
    return _activeVehicle->geoFenceManager()->paramLabels();
296 297 298 299 300 301 302
}

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

303
void GeoFenceController::_setPolygonFromManager(const QList<QGeoCoordinate>& polygon)
304
{
305 306 307 308 309
    _mapPolygon.clear();
    for (int i=0; i<polygon.count(); i++) {
        _mapPolygon.appendVertex(polygon[i]);
    }
    _mapPolygon.setDirty(false);
310 311 312 313 314 315
}

void GeoFenceController::_setReturnPointFromManager(QGeoCoordinate breachReturnPoint)
{
    _breachReturnPoint = breachReturnPoint;
    emit breachReturnPointChanged(_breachReturnPoint);
316 317
}

318 319 320 321 322
void GeoFenceController::_loadComplete(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon)
{
    _setReturnPointFromManager(breachReturn);
    _setPolygonFromManager(polygon);
    setDirty(false);
Don Gagne's avatar
Don Gagne committed
323
    emit loadComplete();
324
}
325 326 327

QString GeoFenceController::fileExtension(void) const
{
328
    return AppSettings::fenceFileExtension;
329
}
330 331 332 333 334 335 336 337 338 339 340 341 342 343 344

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

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

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