APMGeoFenceManager.cc 13.6 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/

#include "APMGeoFenceManager.h"
#include "Vehicle.h"
#include "FirmwarePlugin.h"
#include "MAVLinkProtocol.h"
#include "QGCApplication.h"
15
#include "ParameterManager.h"
16 17
#include "QmlObjectListModel.h"
#include "QGCQGeoCoordinate.h"
18

19 20 21
const char* APMGeoFenceManager::_fenceTotalParam =  "FENCE_TOTAL";
const char* APMGeoFenceManager::_fenceActionParam = "FENCE_ACTION";
const char* APMGeoFenceManager::_fenceEnableParam = "FENCE_ENABLE";
22 23 24 25

APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle)
    : GeoFenceManager(vehicle)
    , _fenceSupported(false)
26 27 28
    , _breachReturnEnabled(vehicle->fixedWing())
    , _circleEnabled(false)
    , _polygonEnabled(false)
29 30 31 32
    , _firstParamLoadComplete(false)
    , _readTransactionInProgress(false)
    , _writeTransactionInProgress(false)
    , _fenceTypeFact(NULL)
33 34
    , _fenceEnableFact(NULL)
    , _circleRadiusFact(NULL)
35
{
36 37
    connect(_vehicle,                       &Vehicle::mavlinkMessageReceived,           this, &APMGeoFenceManager::_mavlinkMessageReceived);
    connect(_vehicle->parameterManager(),   &ParameterManager::parametersReadyChanged,  this, &APMGeoFenceManager::_parametersReady);
38

39
    if (_vehicle->parameterManager()->parametersReady()) {
40 41
        _parametersReady();
    }
42 43 44 45 46 47 48
}

APMGeoFenceManager::~APMGeoFenceManager()
{

}

49
void APMGeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon)
50
{
51 52 53 54
    if (_vehicle->isOfflineEditingVehicle()) {
        return;
    }

55 56 57 58 59
    if (_readTransactionInProgress) {
        _sendError(InternalError, QStringLiteral("Geo-Fence write attempted while read in progress."));
        return;
    }

60
    if (!_fenceSupported) {
61 62 63 64
        return;
    }

    // Validate
65
    int validatedPolygonCount = 0;
66 67 68 69 70 71
    if (polygon.count() >= 3) {
        validatedPolygonCount = polygon.count();
    }
    if (polygon.count() > std::numeric_limits<uint8_t>::max()) {
        _sendError(TooManyPoints, QStringLiteral("Geo-Fence polygon has too many points: %1.").arg(_polygon.count()));
        validatedPolygonCount = 0;
72 73
    }

74
    _breachReturnPoint = breachReturn;
75
    _polygon.clear();
76
    if (validatedPolygonCount) {
77 78 79
        for (int i=0; i<polygon.count(); i++) {
            _polygon.append(polygon.value<QGCQGeoCoordinate*>(i)->coordinate());
        }
80
    }
81

82
    // Total point count, +1 polygon close in last index, +1 for breach in index 0
Don Gagne's avatar
Don Gagne committed
83
    _cWriteFencePoints = validatedPolygonCount ? validatedPolygonCount + 1 + 1 : 0;
84
    _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceTotalParam)->setRawValue(_cWriteFencePoints);
85 86 87 88 89 90

    // FIXME: No validation of correct fence received
    for (uint8_t index=0; index<_cWriteFencePoints; index++) {
        _sendFencePoint(index);
    }

91
    emit loadComplete(_breachReturnPoint, _polygon);
92 93 94 95
}

void APMGeoFenceManager::loadFromVehicle(void)
{
96
    if (_vehicle->isOfflineEditingVehicle() || _readTransactionInProgress) {
97 98 99
        return;
    }

100
    _breachReturnPoint = QGeoCoordinate();
101 102
    _polygon.clear();

103
    if (!_fenceSupported) {
104 105 106
        return;
    }

Don Gagne's avatar
Don Gagne committed
107
    // Point 0: Breach return point (always sent, but supported by ArduPlane only)
108 109
    // Point [1,N]: Polygon points
    // Point N+1: Close polygon point (same as point 1)
110
    int cFencePoints = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceTotalParam)->rawValue().toInt();
Don Gagne's avatar
Don Gagne committed
111
    int minFencePoints = 5;
112 113
    qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::loadFromVehicle" << cFencePoints;
    if (cFencePoints == 0) {
114 115
        // No fence
        emit loadComplete(_breachReturnPoint, _polygon);
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
        return;
    }
    if (cFencePoints < 0 || (cFencePoints > 0 && cFencePoints < minFencePoints)) {
        _sendError(TooFewPoints, QStringLiteral("Geo-Fence information from Vehicle has too few points: %1").arg(cFencePoints));
        return;
    }
    if (cFencePoints > std::numeric_limits<uint8_t>::max()) {
        _sendError(TooManyPoints, QStringLiteral("Geo-Fence information from Vehicle has too many points: %1").arg(cFencePoints));
        return;
    }

    _readTransactionInProgress = true;
    _cReadFencePoints = cFencePoints;
    _currentFencePoint = 0;

    _requestFencePoint(_currentFencePoint);
}

/// Called when a new mavlink message for out vehicle is received
void APMGeoFenceManager::_mavlinkMessageReceived(const mavlink_message_t& message)
{
    if (message.msgid == MAVLINK_MSG_ID_FENCE_POINT) {
        mavlink_fence_point_t fencePoint;

        mavlink_msg_fence_point_decode(&message, &fencePoint);
        qCDebug(GeoFenceManagerLog) << "From vehicle fence_point: idx:lat:lng" << fencePoint.idx << fencePoint.lat << fencePoint.lng;

        if (fencePoint.idx != _currentFencePoint) {
            // FIXME: Protocol out of whack
145 146
            _readTransactionInProgress = false;
            emit inProgressChanged(inProgress());
147 148 149 150 151
            qCWarning(GeoFenceManagerLog) << "Indices out of sync" << fencePoint.idx << _currentFencePoint;
            return;
        }

        if (fencePoint.idx == 0) {
152
            _breachReturnPoint = QGeoCoordinate(fencePoint.lat, fencePoint.lng);
153 154 155 156 157 158 159 160 161 162 163
            qCDebug(GeoFenceManagerLog) << "From vehicle: breach return point" << _breachReturnPoint;
            _requestFencePoint(++_currentFencePoint);
        } else if (fencePoint.idx < _cReadFencePoints - 1) {
            QGeoCoordinate polyCoord(fencePoint.lat, fencePoint.lng);
            _polygon.append(polyCoord);
            qCDebug(GeoFenceManagerLog) << "From vehicle: polygon point" << fencePoint.idx << polyCoord;
            if (fencePoint.idx < _cReadFencePoints - 2) {
                // Still more points to request
                _requestFencePoint(++_currentFencePoint);
            } else {
                // We've finished collecting fence points
164
                qCDebug(GeoFenceManagerLog) << "Fence point load complete";
165
                _readTransactionInProgress = false;
166
                emit loadComplete(_breachReturnPoint, _polygon);
167
                emit inProgressChanged(inProgress());
168 169 170 171 172 173 174 175 176 177 178
            }
        }
    }
}

void APMGeoFenceManager::_requestFencePoint(uint8_t pointIndex)
{
    mavlink_message_t   msg;
    MAVLinkProtocol*    mavlink = qgcApp()->toolbox()->mavlinkProtocol();

    qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::_requestFencePoint" << pointIndex;
179 180 181 182 183 184 185 186
    mavlink_msg_fence_fetch_point_pack_chan(mavlink->getSystemId(),
                                            mavlink->getComponentId(),
                                            _vehicle->priorityLink()->mavlinkChannel(),
                                            &msg,
                                            _vehicle->id(),
                                            _vehicle->defaultComponentId(),
                                            pointIndex);
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207
}

void APMGeoFenceManager::_sendFencePoint(uint8_t pointIndex)
{
    mavlink_message_t   msg;
    MAVLinkProtocol*    mavlink = qgcApp()->toolbox()->mavlinkProtocol();

    QGeoCoordinate fenceCoord;
    if (pointIndex == 0) {
        fenceCoord = breachReturnPoint();
    } else if (pointIndex == _cWriteFencePoints - 1) {
        // Polygon close point
        fenceCoord = _polygon[0];
    } else {
        // Polygon point
        fenceCoord = _polygon[pointIndex - 1];
    }

    // Total point count, +1 polygon close in last index, +1 for breach in index 0
    uint8_t totalPointCount = _polygon.count() + 1 + 1;

208 209 210 211 212 213 214 215 216 217 218
    mavlink_msg_fence_point_pack_chan(mavlink->getSystemId(),
                                      mavlink->getComponentId(),
                                      _vehicle->priorityLink()->mavlinkChannel(),
                                      &msg,
                                      _vehicle->id(),
                                      _vehicle->defaultComponentId(),
                                      pointIndex,                        // Index of point to set
                                      totalPointCount,
                                      fenceCoord.latitude(),
                                      fenceCoord.longitude());
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
219 220 221 222 223 224 225
}

bool APMGeoFenceManager::inProgress(void) const
{
    return _readTransactionInProgress || _writeTransactionInProgress;
}

226
void APMGeoFenceManager::_updateEnabledFlags(void)
227
{
228 229 230
    bool fenceEnabled;
    if (_fenceEnableFact) {
        fenceEnabled = _fenceEnableFact->rawValue().toBool();
231
    } else {
232
        fenceEnabled = true;
233 234
    }

235 236 237 238
    bool newCircleEnabled = _fenceSupported && fenceEnabled && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 2);
    if (newCircleEnabled != _circleEnabled) {
        _circleEnabled = newCircleEnabled;
        emit circleEnabledChanged(newCircleEnabled);
Don Gagne's avatar
Don Gagne committed
239 240
    }

241
    bool newPolygonEnabled = _fenceSupported && fenceEnabled &&
Don Gagne's avatar
Don Gagne committed
242 243
            ((_vehicle->multiRotor() && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 4)) ||
             _vehicle->fixedWing());
244 245 246
    if (newPolygonEnabled != _polygonEnabled) {
        _polygonEnabled = newPolygonEnabled;
        emit polygonEnabledChanged(newPolygonEnabled);
Don Gagne's avatar
Don Gagne committed
247
    }
248 249 250 251 252 253 254
}

void APMGeoFenceManager::_parametersReady(void)
{
    if (!_firstParamLoadComplete) {
        _firstParamLoadComplete = true;

255 256 257
        _fenceSupported = _vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceTotalParam) &&
                _vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceActionParam) &&
                !qgcApp()->runningUnitTests();
258 259 260 261 262

        if (_fenceSupported) {
            QStringList paramNames;
            QStringList paramLabels;

263
            if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceEnableParam)) {
264 265
                _fenceEnableFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceEnableParam);
                connect(_fenceEnableFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateEnabledFlags);
266 267
            }

268
            if (_vehicle->multiRotor()) {
269
                _fenceTypeFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_TYPE"));
270
                connect(_fenceTypeFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateEnabledFlags);
271

272
                _circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_RADIUS"));
273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290
                connect(_circleRadiusFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_circleRadiusRawValueChanged);
                emit circleRadiusChanged(circleRadius());

                paramNames << QStringLiteral("FENCE_ENABLE") << QStringLiteral("FENCE_TYPE") << QStringLiteral("FENCE_ACTION") << QStringLiteral("FENCE_ALT_MAX")
                           << QStringLiteral("FENCE_RADIUS") << QStringLiteral("FENCE_MARGIN");
                paramLabels << QStringLiteral("Enabled:") << QStringLiteral("Type:") << QStringLiteral("Breach Action:") << QStringLiteral("Max Altitude:")
                            << QStringLiteral("Radius:") << QStringLiteral("Margin:");
            } if (_vehicle->fixedWing()) {
                paramNames << QStringLiteral("FENCE_ACTION") << QStringLiteral("FENCE_MINALT") << QStringLiteral("FENCE_MAXALT") << QStringLiteral("FENCE_RETALT")
                           << QStringLiteral("FENCE_AUTOENABLE") << QStringLiteral("FENCE_RET_RALLY");
                paramLabels << QStringLiteral("Breach Action:") << QStringLiteral("Min Altitude:") << QStringLiteral("Max Altitude:") << QStringLiteral("Return Altitude:")
                            << QStringLiteral("Auto-Enable:") << QStringLiteral("Return to Rally:");
            }

            _params.clear();
            _paramLabels.clear();
            for (int i=0; i<paramNames.count(); i++) {
                QString paramName = paramNames[i];
291 292
                if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, paramName)) {
                    Fact* paramFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName);
293 294 295 296 297 298 299
                    _params << QVariant::fromValue(paramFact);
                    _paramLabels << paramLabels[i];
                }
            }
            emit paramsChanged(_params);
            emit paramLabelsChanged(_paramLabels);

300
            _updateEnabledFlags();
301 302
        }

303 304
        qCDebug(GeoFenceManagerLog) << "fenceSupported:circleEnabled:polygonEnabled:breachReturnEnabled" <<
                                       _fenceSupported << _circleEnabled << _polygonEnabled << _breachReturnEnabled;
305 306 307 308 309
    }
}

float APMGeoFenceManager::circleRadius(void) const
{
310
    if (_circleRadiusFact) {
311 312 313 314 315 316 317 318 319 320 321
        return _circleRadiusFact->rawValue().toFloat();
    } else {
        return 0.0;
    }
}

void APMGeoFenceManager::_circleRadiusRawValueChanged(QVariant value)
{
    emit circleRadiusChanged(value.toFloat());
}

322 323
QString APMGeoFenceManager::editorQml(void) const
{
324 325 326 327 328 329 330
    if (_fenceSupported) {
        return _vehicle->multiRotor() ?
                    QStringLiteral("qrc:/FirmwarePlugin/APM/CopterGeoFenceEditor.qml") :
                    QStringLiteral("qrc:/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml");
    } else {
        return QStringLiteral("qrc:/FirmwarePlugin/NoGeoFenceEditor.qml");
    }
331
}
332 333 334 335 336 337 338

void APMGeoFenceManager::removeAll(void)
{
    QmlObjectListModel emptyPolygon;

    sendToVehicle(_breachReturnPoint, emptyPolygon);
}