RallyPointController.cc 6.9 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"
26 27

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

#include <QJsonDocument>
#include <QJsonArray>

QGC_LOGGING_CATEGORY(RallyPointControllerLog, "RallyPointControllerLog")

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

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

    managerVehicleChanged(_managerVehicle);
48 49 50 51 52 53 54
}

RallyPointController::~RallyPointController()
{

}

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

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

    _rallyPointManager = _managerVehicle->rallyPointManager();
    connect(_rallyPointManager, &RallyPointManager::loadComplete,       this, &RallyPointController::_loadComplete);
    connect(_rallyPointManager, &RallyPointManager::inProgressChanged,  this, &RallyPointController::syncInProgressChanged);
72 73 74 75

    emit rallyPointsSupportedChanged(rallyPointsSupported());
}

76
bool RallyPointController::load(const QJsonObject& json, QString& errorString)
77
{
78 79
    QString errorStr;
    QString errorMessage = tr("Rally: %1");
80 81 82

    // Check for required keys
    QStringList requiredKeys = { _jsonPointsKey };
83 84
    if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorStr)) {
        errorString = errorMessage.arg(errorStr);
85 86 87 88
        return false;
    }

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

100
    setDirty(false);
101
    _setFirstPointCurrent();
102 103

    return true;
104 105
}

106
void RallyPointController::save(QJsonObject& json)
107
{
108
    json[JsonHelper::jsonVersionKey] = 1;
109

110 111 112 113 114
    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);
115
    }
116
    json[_jsonPointsKey] = QJsonValue(rgPoints);
117 118 119 120 121 122 123 124 125 126 127
}

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

void RallyPointController::loadFromVehicle(void)
{
128 129
    if (!syncInProgress()) {
        _rallyPointManager->loadFromVehicle();
130
    } else {
131
        qCWarning(RallyPointControllerLog) << "RallyPointController::loadFromVehicle call while syncInProgress";
132 133 134 135 136 137 138 139 140 141 142
    }
}

void RallyPointController::sendToVehicle(void)
{
    if (!syncInProgress()) {
        setDirty(false);
        QList<QGeoCoordinate> rgPoints;
        for (int i=0; i<_points.count(); i++) {
            rgPoints.append(qobject_cast<RallyPoint*>(_points[i])->coordinate());
        }
143
        _rallyPointManager->sendToVehicle(rgPoints);
144
    } else {
145
        qCWarning(RallyPointControllerLog) << "RallyPointController::loadFromVehicle while syncInProgress";
146 147 148 149 150
    }
}

bool RallyPointController::syncInProgress(void) const
{
151
    return _rallyPointManager->inProgress();
152 153 154 155 156 157 158 159 160 161 162 163
}

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

QString RallyPointController::editorQml(void) const
{
164
    return _rallyPointManager->editorQml();
165 166 167 168 169 170 171 172 173 174 175 176
}

void RallyPointController::_loadComplete(const QList<QGeoCoordinate> rgPoints)
{
    _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();
Don Gagne's avatar
Don Gagne committed
177
    emit loadComplete();
178 179 180 181 182 183 184 185
}

void RallyPointController::addPoint(QGeoCoordinate point)
{
    double defaultAlt;
    if (_points.count()) {
        defaultAlt = qobject_cast<RallyPoint*>(_points[_points.count() - 1])->coordinate().altitude();
    } else {
186
        defaultAlt = qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble();
187 188 189 190 191 192 193 194 195 196
    }
    point.setAltitude(defaultAlt);
    RallyPoint* newPoint = new RallyPoint(point, this);
    _points.append(newPoint);
    setCurrentRallyPoint(newPoint);
    setDirty(true);
}

bool RallyPointController::rallyPointsSupported(void) const
{
197
    return _rallyPointManager->rallyPointsSupported();
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 226 227 228 229 230
}

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);
}
231 232 233 234 235 236 237 238 239 240 241 242 243

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

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

void RallyPointController::removeAllFromVehicle(void)
{
244
    _rallyPointManager->removeAll();
245
}