RallyPointController.cc 9.91 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22
/****************************************************************************
 *
 *   (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 "RallyPointController.h"
#include "RallyPoint.h"
#include "Vehicle.h"
#include "FirmwarePlugin.h"
#include "MAVLinkProtocol.h"
#include "QGCApplication.h"
#include "ParameterManager.h"
#include "JsonHelper.h"
#include "SimpleMissionItem.h"
23
#include "QGroundControlQmlGlobal.h"
24
#include "SettingsManager.h"
25
#include "AppSettings.h"
DonLakeFlyer's avatar
DonLakeFlyer committed
26
#include "PlanMasterController.h"
27 28

#ifndef __mobile__
29
#include "QGCQFileDialog.h"
30 31 32 33 34 35 36 37 38 39
#endif

#include <QJsonDocument>
#include <QJsonArray>

QGC_LOGGING_CATEGORY(RallyPointControllerLog, "RallyPointControllerLog")

const char* RallyPointController::_jsonFileTypeValue =  "RallyPoints";
const char* RallyPointController::_jsonPointsKey =      "points";

40 41 42
RallyPointController::RallyPointController(PlanMasterController* masterController, QObject* parent)
    : PlanElementController(masterController, parent)
    , _rallyPointManager(_managerVehicle->rallyPointManager())
43 44
    , _dirty(false)
    , _currentRallyPoint(NULL)
DonLakeFlyer's avatar
DonLakeFlyer committed
45
    , _itemsRequested(false)
46
{
47
    connect(&_points, &QmlObjectListModel::countChanged, this, &RallyPointController::_updateContainsItems);
48 49

    managerVehicleChanged(_managerVehicle);
50 51 52 53 54 55 56
}

RallyPointController::~RallyPointController()
{

}

57
void RallyPointController::managerVehicleChanged(Vehicle* managerVehicle)
58
{
59 60 61 62 63
    if (_managerVehicle) {
        _rallyPointManager->disconnect(this);
        _managerVehicle = NULL;
        _rallyPointManager = NULL;
    }
64

65 66 67 68 69 70 71
    _managerVehicle = managerVehicle;
    if (!_managerVehicle) {
        qWarning() << "RallyPointController::managerVehicleChanged managerVehicle=NULL";
        return;
    }

    _rallyPointManager = _managerVehicle->rallyPointManager();
DonLakeFlyer's avatar
DonLakeFlyer committed
72 73 74
    connect(_rallyPointManager, &RallyPointManager::loadComplete,       this, &RallyPointController::_managerLoadComplete);
    connect(_rallyPointManager, &RallyPointManager::sendComplete,       this, &RallyPointController::_managerSendComplete);
    connect(_rallyPointManager, &RallyPointManager::removeAllComplete,  this, &RallyPointController::_managerRemoveAllComplete);
75
    connect(_rallyPointManager, &RallyPointManager::inProgressChanged,  this, &RallyPointController::syncInProgressChanged);
76 77 78 79

    emit rallyPointsSupportedChanged(rallyPointsSupported());
}

80
bool RallyPointController::load(const QJsonObject& json, QString& errorString)
81
{
82 83
    QString errorStr;
    QString errorMessage = tr("Rally: %1");
84 85 86

    // Check for required keys
    QStringList requiredKeys = { _jsonPointsKey };
87 88
    if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorStr)) {
        errorString = errorMessage.arg(errorStr);
89 90 91 92
        return false;
    }

    QList<QGeoCoordinate> rgPoints;
93 94
    if (!JsonHelper::loadGeoCoordinateArray(json[_jsonPointsKey], true /* altitudeRequired */, rgPoints, errorStr)) {
        errorString = errorMessage.arg(errorStr);
95
        return false;
96
    }
97 98 99 100 101 102 103
    _points.clearAndDeleteContents();
    QObjectList pointList;
    for (int i=0; i<rgPoints.count(); i++) {
        pointList.append(new RallyPoint(rgPoints[i], this));
    }
    _points.swapObjectList(pointList);

104
    setDirty(false);
105
    _setFirstPointCurrent();
106 107

    return true;
108 109
}

110
void RallyPointController::save(QJsonObject& json)
111
{
112
    json[JsonHelper::jsonVersionKey] = 1;
113

114 115 116 117 118
    QJsonArray rgPoints;
    QJsonValue jsonPoint;
    for (int i=0; i<_points.count(); i++) {
        JsonHelper::saveGeoCoordinate(qobject_cast<RallyPoint*>(_points[i])->coordinate(), true /* writeAltitude */, jsonPoint);
        rgPoints.append(jsonPoint);
119
    }
120
    json[_jsonPointsKey] = QJsonValue(rgPoints);
121 122 123 124 125 126 127 128 129
}

void RallyPointController::removeAll(void)
{
    _points.clearAndDeleteContents();
    setDirty(true);
    setCurrentRallyPoint(NULL);
}

DonLakeFlyer's avatar
DonLakeFlyer committed
130 131 132 133 134 135 136 137 138 139 140
void RallyPointController::removeAllFromVehicle(void)
{
    if (_masterController->offline()) {
        qCWarning(RallyPointControllerLog) << "RallyPointController::removeAllFromVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(RallyPointControllerLog) << "RallyPointController::removeAllFromVehicle called while syncInProgress";
    } else {
        _rallyPointManager->removeAll();
    }
}

141 142
void RallyPointController::loadFromVehicle(void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
143 144 145 146
    if (_masterController->offline()) {
        qCWarning(RallyPointControllerLog) << "RallyPointController::loadFromVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(RallyPointControllerLog) << "RallyPointController::loadFromVehicle called while syncInProgress";
147
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
148 149
        _itemsRequested = true;
        _rallyPointManager->loadFromVehicle();
150 151 152 153 154
    }
}

void RallyPointController::sendToVehicle(void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
155 156 157 158 159
    if (_masterController->offline()) {
        qCWarning(RallyPointControllerLog) << "RallyPointController::sendToVehicle called while offline";
    } else if (syncInProgress()) {
        qCWarning(RallyPointControllerLog) << "RallyPointController::sendToVehicle called while syncInProgress";
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
160
        qCDebug(RallyPointControllerLog) << "RallyPointController::sendToVehicle";
161 162 163 164 165
        setDirty(false);
        QList<QGeoCoordinate> rgPoints;
        for (int i=0; i<_points.count(); i++) {
            rgPoints.append(qobject_cast<RallyPoint*>(_points[i])->coordinate());
        }
166
        _rallyPointManager->sendToVehicle(rgPoints);
167 168 169 170 171
    }
}

bool RallyPointController::syncInProgress(void) const
{
172
    return _rallyPointManager->inProgress();
173 174 175 176 177 178 179 180 181 182 183 184
}

void RallyPointController::setDirty(bool dirty)
{
    if (dirty != _dirty) {
        _dirty = dirty;
        emit dirtyChanged(dirty);
    }
}

QString RallyPointController::editorQml(void) const
{
185
    return _rallyPointManager->editorQml();
186 187
}

DonLakeFlyer's avatar
DonLakeFlyer committed
188
void RallyPointController::_managerLoadComplete(const QList<QGeoCoordinate> rgPoints)
189
{
DonLakeFlyer's avatar
DonLakeFlyer committed
190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205
    // Fly view always reloads on _loadComplete
    // Plan view only reloads on _loadComplete if specifically requested
    if (!_editMode || _itemsRequested) {
        _points.clearAndDeleteContents();
        QObjectList pointList;
        for (int i=0; i<rgPoints.count(); i++) {
            pointList.append(new RallyPoint(rgPoints[i], this));
        }
        _points.swapObjectList(pointList);
        setDirty(false);
        _setFirstPointCurrent();
        emit loadComplete();
    }
    _itemsRequested = false;
}

206
void RallyPointController::_managerSendComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
207 208
{
    // Fly view always reloads after send
209
    if (!error && _editMode) {
DonLakeFlyer's avatar
DonLakeFlyer committed
210
        showPlanFromManagerVehicle();
211
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
212 213
}

214
void RallyPointController::_managerRemoveAllComplete(bool error)
DonLakeFlyer's avatar
DonLakeFlyer committed
215
{
216 217 218 219
    if (!error) {
        // Remove all from vehicle so we always update
        showPlanFromManagerVehicle();
    }
220 221 222 223 224 225 226 227
}

void RallyPointController::addPoint(QGeoCoordinate point)
{
    double defaultAlt;
    if (_points.count()) {
        defaultAlt = qobject_cast<RallyPoint*>(_points[_points.count() - 1])->coordinate().altitude();
    } else {
228
        defaultAlt = qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble();
229 230 231 232 233 234 235 236 237 238
    }
    point.setAltitude(defaultAlt);
    RallyPoint* newPoint = new RallyPoint(point, this);
    _points.append(newPoint);
    setCurrentRallyPoint(newPoint);
    setDirty(true);
}

bool RallyPointController::rallyPointsSupported(void) const
{
239
    return _rallyPointManager->rallyPointsSupported();
240 241 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
}

void RallyPointController::removePoint(QObject* rallyPoint)
{
    int foundIndex = 0;
    for (foundIndex=0; foundIndex<_points.count(); foundIndex++) {
        if (_points[foundIndex] == rallyPoint) {
            _points.removeOne(rallyPoint);
            rallyPoint->deleteLater();
        }
    }

    if (_points.count()) {
        int newIndex = qMin(foundIndex, _points.count() - 1);
        newIndex = qMax(newIndex, 0);
        setCurrentRallyPoint(_points[newIndex]);
    } else {
        setCurrentRallyPoint(NULL);
    }
}

void RallyPointController::setCurrentRallyPoint(QObject* rallyPoint)
{
    if (_currentRallyPoint != rallyPoint) {
        _currentRallyPoint = rallyPoint;
        emit currentRallyPointChanged(rallyPoint);
    }
}

void RallyPointController::_setFirstPointCurrent(void)
{
    setCurrentRallyPoint(_points.count() ? _points[0] : NULL);
}
273 274 275 276 277 278 279 280 281 282 283

bool RallyPointController::containsItems(void) const
{
    return _points.count() > 0;
}

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

DonLakeFlyer's avatar
DonLakeFlyer committed
284
bool RallyPointController::showPlanFromManagerVehicle (void)
285
{
DonLakeFlyer's avatar
DonLakeFlyer committed
286
    qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle _editMode" << _editMode;
DonLakeFlyer's avatar
DonLakeFlyer committed
287 288
    if (_masterController->offline()) {
        qCWarning(RallyPointControllerLog) << "RallyPointController::showPlanFromManagerVehicle called while offline";
Patrick José Pereira's avatar
Patrick José Pereira committed
289
        return true;    // stops further propagation of showPlanFromManagerVehicle due to error
DonLakeFlyer's avatar
DonLakeFlyer committed
290 291
    } else {
        if (!_managerVehicle->initialPlanRequestComplete()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
292
            // The vehicle hasn't completed initial load, we can just wait for loadComplete to be signalled automatically
DonLakeFlyer's avatar
DonLakeFlyer committed
293 294 295 296 297 298 299 300 301 302 303 304 305 306
            qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle: !initialPlanRequestComplete, wait for signal";
            return true;
        } else if (syncInProgress()) {
            // If the sync is already in progress, _loadComplete will be called automatically when it is done. So no need to do anything.
            qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle: syncInProgress wait for signal";
            return true;
        } else {
            // Fake a _loadComplete with the current items
            qCDebug(RallyPointControllerLog) << "showPlanFromManagerVehicle: sync complete simulate signal";
            _itemsRequested = true;
            _managerLoadComplete(_rallyPointManager->points());
            return false;
        }
    }
307
}