RallyPointController.cc 7.04 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 39 40 41 42 43
#endif

#include <QJsonDocument>
#include <QJsonArray>

QGC_LOGGING_CATEGORY(RallyPointControllerLog, "RallyPointControllerLog")

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

RallyPointController::RallyPointController(QObject* parent)
    : PlanElementController(parent)
    , _dirty(false)
    , _currentRallyPoint(NULL)
{
44
    connect(&_points, &QmlObjectListModel::countChanged, this, &RallyPointController::_updateContainsItems);
45 46 47 48 49 50 51
}

RallyPointController::~RallyPointController()
{

}

52
void RallyPointController::activeVehicleBeingRemoved(void)
53 54 55
{
    _activeVehicle->rallyPointManager()->disconnect(this);
    _points.clearAndDeleteContents();
56
    _activeVehicle = NULL;
57 58
}

59
void RallyPointController::activeVehicleSet(Vehicle* activeVehicle)
60
{
61
    _activeVehicle = activeVehicle;
62 63 64 65 66 67 68 69 70 71
    RallyPointManager* rallyPointManager = _activeVehicle->rallyPointManager();
    connect(rallyPointManager, &RallyPointManager::loadComplete,        this, &RallyPointController::_loadComplete);
    connect(rallyPointManager, &RallyPointManager::inProgressChanged,   this, &RallyPointController::syncInProgressChanged);

    if (!rallyPointManager->inProgress()) {
        _loadComplete(rallyPointManager->points());
    }
    emit rallyPointsSupportedChanged(rallyPointsSupported());
}

72
bool RallyPointController::load(const QJsonObject& json, QString& errorString)
73
{
74 75
    QString errorStr;
    QString errorMessage = tr("Rally: %1");
76 77 78

    // Check for required keys
    QStringList requiredKeys = { _jsonPointsKey };
79 80
    if (!JsonHelper::validateRequiredKeys(json, requiredKeys, errorStr)) {
        errorString = errorMessage.arg(errorStr);
81 82 83 84
        return false;
    }

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

96
    setDirty(false);
97
    _setFirstPointCurrent();
98 99

    return true;
100 101
}

102
void RallyPointController::save(QJsonObject& json)
103
{
104
    json[JsonHelper::jsonVersionKey] = 1;
105

106 107 108 109 110
    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);
111
    }
112
    json[_jsonPointsKey] = QJsonValue(rgPoints);
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 138 139 140 141 142 143 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
}

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

void RallyPointController::loadFromVehicle(void)
{
    if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
        _activeVehicle->rallyPointManager()->loadFromVehicle();
    } else {
        qCWarning(RallyPointControllerLog) << "RallyPointController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress();
    }
}

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());
        }
        _activeVehicle->rallyPointManager()->sendToVehicle(rgPoints);
    } else {
        qCWarning(RallyPointControllerLog) << "RallyPointController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress();
    }
}

bool RallyPointController::syncInProgress(void) const
{
    return _activeVehicle->rallyPointManager()->inProgress();
}

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

QString RallyPointController::editorQml(void) const
{
    return _activeVehicle->rallyPointManager()->editorQml();
}

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
173
    emit loadComplete();
174 175 176 177 178 179 180 181
}

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

bool RallyPointController::rallyPointsSupported(void) const
{
    return _activeVehicle->rallyPointManager()->rallyPointsSupported();
}

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);
}
227 228 229 230 231 232 233 234 235 236 237 238 239 240 241

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

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

void RallyPointController::removeAllFromVehicle(void)
{
    _activeVehicle->rallyPointManager()->removeAll();
}