APMGeoFenceManager.cc 14.3 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 18 19
const char* APMGeoFenceManager::_fenceTotalParam =  "FENCE_TOTAL";
const char* APMGeoFenceManager::_fenceActionParam = "FENCE_ACTION";
const char* APMGeoFenceManager::_fenceEnableParam = "FENCE_ENABLE";
20 21 22 23 24

APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle)
    : GeoFenceManager(vehicle)
    , _fenceSupported(false)
    , _breachReturnSupported(vehicle->fixedWing())
Don Gagne's avatar
Don Gagne committed
25 26
    , _circleSupported(false)
    , _polygonSupported(false)
27 28 29 30 31 32
    , _firstParamLoadComplete(false)
    , _circleRadiusFact(NULL)
    , _readTransactionInProgress(false)
    , _writeTransactionInProgress(false)
    , _fenceTypeFact(NULL)
{
33 34
    connect(_vehicle,                       &Vehicle::mavlinkMessageReceived,           this, &APMGeoFenceManager::_mavlinkMessageReceived);
    connect(_vehicle->parameterManager(),   &ParameterManager::parametersReadyChanged,  this, &APMGeoFenceManager::_parametersReady);
35

36
    if (_vehicle->parameterManager()->parametersReady()) {
37 38
        _parametersReady();
    }
39 40 41 42 43 44 45
}

APMGeoFenceManager::~APMGeoFenceManager()
{

}

46
void APMGeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon)
47
{
48 49 50 51
    if (_vehicle->isOfflineEditingVehicle()) {
        return;
    }

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

    if (!_geoFenceSupported()) {
        return;
    }

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

73 74 75
    _breachReturnPoint = breachReturn;
    _polygon = polygon;

76
    // Total point count, +1 polygon close in last index, +1 for breach in index 0
Don Gagne's avatar
Don Gagne committed
77
    _cWriteFencePoints = validatedPolygonCount ? validatedPolygonCount + 1 + 1 : 0;
78
    _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceTotalParam)->setRawValue(_cWriteFencePoints);
79 80 81 82 83 84

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

85
    emit loadComplete(_breachReturnPoint, _polygon);
86 87 88 89
}

void APMGeoFenceManager::loadFromVehicle(void)
{
90
    if (_vehicle->isOfflineEditingVehicle() || _readTransactionInProgress) {
91 92 93
        return;
    }

94
    _breachReturnPoint = QGeoCoordinate();
95 96 97 98 99 100
    _polygon.clear();

    if (!_geoFenceSupported()) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
101
    // Point 0: Breach return point (always sent, but supported by ArduPlane only)
102 103
    // Point [1,N]: Polygon points
    // Point N+1: Close polygon point (same as point 1)
104
    int cFencePoints = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceTotalParam)->rawValue().toInt();
Don Gagne's avatar
Don Gagne committed
105
    int minFencePoints = 5;
106 107
    qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::loadFromVehicle" << cFencePoints;
    if (cFencePoints == 0) {
108 109
        // No fence
        emit loadComplete(_breachReturnPoint, _polygon);
110 111 112 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
        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
139 140
            _readTransactionInProgress = false;
            emit inProgressChanged(inProgress());
141 142 143 144 145
            qCWarning(GeoFenceManagerLog) << "Indices out of sync" << fencePoint.idx << _currentFencePoint;
            return;
        }

        if (fencePoint.idx == 0) {
146
            _breachReturnPoint = QGeoCoordinate(fencePoint.lat, fencePoint.lng);
147 148 149 150 151 152 153 154 155 156 157
            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
158
                qCDebug(GeoFenceManagerLog) << "Fence point load complete";
159
                _readTransactionInProgress = false;
160
                emit loadComplete(_breachReturnPoint, _polygon);
161
                emit inProgressChanged(inProgress());
162 163 164 165 166 167 168 169 170 171 172
            }
        }
    }
}

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

    qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::_requestFencePoint" << pointIndex;
173 174 175 176 177 178 179 180
    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);
181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201
}

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;

202 203 204 205 206 207 208 209 210 211 212
    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);
213 214 215 216 217 218 219 220 221 222 223 224 225 226
}

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

bool APMGeoFenceManager::_geoFenceSupported(void)
{
    // FIXME: MockLink doesn't support geo fence yet
    if (qgcApp()->runningUnitTests()) {
        return false;
    }

227 228
    if (!_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceTotalParam) ||
            !_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceActionParam)) {
229 230 231 232 233 234
        return false;
    } else {
        return true;
    }
}

235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256
bool APMGeoFenceManager::fenceEnabled(void) const
{
    if (qgcApp()->runningUnitTests()) {
        return false;
    }

    if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceEnableParam)) {
        bool fenceEnabled = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceEnableParam)->rawValue().toBool();
        qCDebug(GeoFenceManagerLog) << "FENCE_ENABLE available" << fenceEnabled;
        return fenceEnabled;
    }

    qCDebug(GeoFenceManagerLog) << "FENCE_ENABLE not available";
    return true;
}

void APMGeoFenceManager::_fenceEnabledRawValueChanged(QVariant value)
{
    qCDebug(GeoFenceManagerLog) << "FENCE_ENABLE changed" << value.toBool();
    emit fenceEnabledChanged(!qgcApp()->runningUnitTests() && value.toBool());
}

257 258
void APMGeoFenceManager::_updateSupportedFlags(void)
{
Don Gagne's avatar
Don Gagne committed
259 260 261 262 263 264 265 266 267 268 269 270 271
    bool newCircleSupported = _fenceSupported && _vehicle->multiRotor() && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 2);
    if (newCircleSupported != _circleSupported) {
        _circleSupported = newCircleSupported;
        emit circleSupportedChanged(newCircleSupported);
    }

    bool newPolygonSupported = _fenceSupported &&
            ((_vehicle->multiRotor() && _fenceTypeFact && (_fenceTypeFact->rawValue().toInt() & 4)) ||
             _vehicle->fixedWing());
    if (newPolygonSupported != _polygonSupported) {
        _polygonSupported = newPolygonSupported;
        emit polygonSupportedChanged(newPolygonSupported);
    }
272 273 274 275 276 277 278
}

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

279
        _fenceSupported = _vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("FENCE_ACTION"));
280 281 282 283 284

        if (_fenceSupported) {
            QStringList paramNames;
            QStringList paramLabels;

285 286 287 288
            if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceEnableParam)) {
                connect(_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceEnableParam), &Fact::rawValueChanged, this, &APMGeoFenceManager::_fenceEnabledRawValueChanged);
            }

289
            if (_vehicle->multiRotor()) {
290
                _fenceTypeFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_TYPE"));
291

Don Gagne's avatar
Don Gagne committed
292
                connect(_fenceTypeFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateSupportedFlags);
293

294
                _circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_RADIUS"));
295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312
                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];
313 314
                if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, paramName)) {
                    Fact* paramFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName);
315 316 317 318 319 320 321 322
                    _params << QVariant::fromValue(paramFact);
                    _paramLabels << paramLabels[i];
                }
            }
            emit paramsChanged(_params);
            emit paramLabelsChanged(_paramLabels);

            emit fenceSupportedChanged(_fenceSupported);
Don Gagne's avatar
Don Gagne committed
323
            _updateSupportedFlags();
324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346
        }

        qCDebug(GeoFenceManagerLog) << "fenceSupported:circleSupported:polygonSupported:breachReturnSupported" <<
                                       _fenceSupported << circleSupported() << polygonSupported() << _breachReturnSupported;
    }
}

float APMGeoFenceManager::circleRadius(void) const
{
    if (_circleRadiusFact) {
        return _circleRadiusFact->rawValue().toFloat();
    } else {
        return 0.0;
    }
}

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

bool APMGeoFenceManager::circleSupported(void) const
{
Don Gagne's avatar
Don Gagne committed
347
    return _circleSupported;
348 349 350 351
}

bool APMGeoFenceManager::polygonSupported(void) const
{
Don Gagne's avatar
Don Gagne committed
352
    return _polygonSupported;
353
}
354 355 356 357 358 359 360

QString APMGeoFenceManager::editorQml(void) const
{
    return _vehicle->multiRotor() ?
                QStringLiteral("qrc:/FirmwarePlugin/APM/CopterGeoFenceEditor.qml") :
                QStringLiteral("qrc:/FirmwarePlugin/APM/PlaneGeoFenceEditor.qml");
}