APMFirmwarePlugin.cc 35.6 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
Don Gagne's avatar
Don Gagne committed
9

Don Gagne's avatar
Don Gagne committed
10
#include "APMFirmwarePlugin.h"
11
#include "APMAutoPilotPlugin.h"
12
#include "QGCMAVLink.h"
13
#include "QGCApplication.h"
14 15 16
#include "APMFlightModesComponentController.h"
#include "APMAirframeComponentController.h"
#include "APMSensorsComponentController.h"
17
#include "APMFollowComponentController.h"
18
#include "APMSubMotorComponentController.h"
19
#include "MissionManager.h"
20
#include "ParameterManager.h"
21
#include "QGCFileDownload.h"
22 23
#include "SettingsManager.h"
#include "AppSettings.h"
24
#include "APMMavlinkStreamRateSettings.h"
25 26 27 28
#include "ArduPlaneFirmwarePlugin.h"
#include "ArduCopterFirmwarePlugin.h"
#include "ArduRoverFirmwarePlugin.h"
#include "ArduSubFirmwarePlugin.h"
Don Gagne's avatar
Don Gagne committed
29

Don Gagne's avatar
Don Gagne committed
30 31
#include <QTcpSocket>

Pritam Ghanghas's avatar
Pritam Ghanghas committed
32
QGC_LOGGING_CATEGORY(APMFirmwarePluginLog, "APMFirmwarePluginLog")
Don Gagne's avatar
Don Gagne committed
33

34
static const QRegExp APM_FRAME_REXP("^Frame: ");
35

Don Gagne's avatar
Don Gagne committed
36 37
const char* APMFirmwarePlugin::_artooIP =                   "10.1.1.1"; ///< IP address of ARTOO controller
const int   APMFirmwarePlugin::_artooVideoHandshakePort =   5502;       ///< Port for video handshake on ARTOO controller
38

39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61
/*
 * @brief APMCustomMode encapsulates the custom modes for APM
 */
APMCustomMode::APMCustomMode(uint32_t mode, bool settable) :
    _mode(mode),
    _settable(settable)
{
}

void APMCustomMode::setEnumToStringMapping(const QMap<uint32_t, QString>& enumToString)
{
    _enumToString = enumToString;
}

QString APMCustomMode::modeString() const
{
    QString mode = _enumToString.value(modeAsInt());
    if (mode.isEmpty()) {
        mode = "mode" + QString::number(modeAsInt());
    }
    return mode;
}

62
APMFirmwarePlugin::APMFirmwarePlugin(void)
Don Gagne's avatar
Don Gagne committed
63
    : _coaxialMotors(false)
Don Gagne's avatar
Don Gagne committed
64
{
65 66 67
    qmlRegisterType<APMFlightModesComponentController>  ("QGroundControl.Controllers", 1, 0, "APMFlightModesComponentController");
    qmlRegisterType<APMAirframeComponentController>     ("QGroundControl.Controllers", 1, 0, "APMAirframeComponentController");
    qmlRegisterType<APMSensorsComponentController>      ("QGroundControl.Controllers", 1, 0, "APMSensorsComponentController");
68
    qmlRegisterType<APMFollowComponentController>       ("QGroundControl.Controllers", 1, 0, "APMFollowComponentController");
69
    qmlRegisterType<APMSubMotorComponentController>     ("QGroundControl.Controllers", 1, 0, "APMSubMotorComponentController");
70
}
Don Gagne's avatar
Don Gagne committed
71

72 73 74
AutoPilotPlugin* APMFirmwarePlugin::autopilotPlugin(Vehicle* vehicle)
{
    return new APMAutoPilotPlugin(vehicle, vehicle);
Don Gagne's avatar
Don Gagne committed
75 76
}

77
bool APMFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabilities capabilities)
Don Gagne's avatar
Don Gagne committed
78
{
79 80 81
    uint32_t available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability;
    if (vehicle->multiRotor()) {
        available |= TakeoffVehicleCapability;
82
    } else if (vehicle->vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
83
        available |= TakeoffVehicleCapability;
84
    }
85

86
    return (capabilities & available) == capabilities;
Don Gagne's avatar
Don Gagne committed
87 88 89 90 91
}

QList<VehicleComponent*> APMFirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle)
{
    Q_UNUSED(vehicle);
92

Don Gagne's avatar
Don Gagne committed
93 94 95
    return QList<VehicleComponent*>();
}

Daniel Agar's avatar
Daniel Agar committed
96
QStringList APMFirmwarePlugin::flightModes(Vehicle* vehicle)
97
{
Daniel Agar's avatar
Daniel Agar committed
98
    Q_UNUSED(vehicle)
99 100 101 102 103 104 105
    QStringList flightModesList;
    foreach (const APMCustomMode& customMode, _supportedModes) {
        if (customMode.canBeSet()) {
            flightModesList << customMode.modeString();
        }
    }
    return flightModesList;
Don Gagne's avatar
Don Gagne committed
106 107
}

Don Gagne's avatar
Don Gagne committed
108
QString APMFirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) const
Don Gagne's avatar
Don Gagne committed
109
{
110 111 112 113 114 115 116 117 118 119
    QString flightMode = "Unknown";

    if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
        foreach (const APMCustomMode& customMode, _supportedModes) {
            if (customMode.modeAsInt() == custom_mode) {
                flightMode = customMode.modeString();
            }
        }
    }
    return flightMode;
Don Gagne's avatar
Don Gagne committed
120 121 122 123
}

bool APMFirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode)
{
124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142
    *base_mode = 0;
    *custom_mode = 0;

    bool found = false;

    foreach(const APMCustomMode& mode, _supportedModes) {
        if (flightMode.compare(mode.modeString(), Qt::CaseInsensitive) == 0) {
            *base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
            *custom_mode = mode.modeAsInt();
            found = true;
            break;
        }
    }

    if (!found) {
        qCWarning(APMFirmwarePluginLog) << "Unknown flight Mode" << flightMode;
    }

    return found;
Don Gagne's avatar
Don Gagne committed
143 144
}

145
void APMFirmwarePlugin::_handleIncomingParamValue(Vehicle* vehicle, mavlink_message_t* message)
Don Gagne's avatar
Don Gagne committed
146
{
Don Gagne's avatar
Don Gagne committed
147 148 149 150 151
    Q_UNUSED(vehicle);

    mavlink_param_value_t paramValue;
    mavlink_param_union_t paramUnion;

Don Gagne's avatar
Don Gagne committed
152 153
    memset(&paramValue, 0, sizeof(paramValue));

Don Gagne's avatar
Don Gagne committed
154 155 156 157 158 159 160
    // APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what
    // type they are. Fix that up to correct usage.

    mavlink_msg_param_value_decode(message, &paramValue);

    switch (paramValue.param_type) {
    case MAV_PARAM_TYPE_UINT8:
161
        paramUnion.param_uint8 = static_cast<uint8_t>(paramValue.param_value);
Don Gagne's avatar
Don Gagne committed
162 163
        break;
    case MAV_PARAM_TYPE_INT8:
164
        paramUnion.param_int8  = static_cast<int8_t>(paramValue.param_value);
Don Gagne's avatar
Don Gagne committed
165 166
        break;
    case MAV_PARAM_TYPE_UINT16:
167
        paramUnion.param_uint16 = static_cast<uint16_t>(paramValue.param_value);
Don Gagne's avatar
Don Gagne committed
168 169
        break;
    case MAV_PARAM_TYPE_INT16:
170
        paramUnion.param_int16 = static_cast<int16_t>(paramValue.param_value);
Don Gagne's avatar
Don Gagne committed
171 172
        break;
    case MAV_PARAM_TYPE_UINT32:
173
        paramUnion.param_uint32 = static_cast<uint32_t>(paramValue.param_value);
Don Gagne's avatar
Don Gagne committed
174 175
        break;
    case MAV_PARAM_TYPE_INT32:
176
        paramUnion.param_int32 = static_cast<int32_t>(paramValue.param_value);
Don Gagne's avatar
Don Gagne committed
177 178 179 180 181 182
        break;
    case MAV_PARAM_TYPE_REAL32:
        paramUnion.param_float = paramValue.param_value;
        break;
    default:
        qCCritical(APMFirmwarePluginLog) << "Invalid/Unsupported data type used in parameter:" << paramValue.param_type;
183 184
    }

Don Gagne's avatar
Don Gagne committed
185 186
    paramValue.param_value = paramUnion.param_float;

187 188 189
    // Re-Encoding is always done using mavlink 1.0
    mavlink_status_t* mavlinkStatusReEncode = mavlink_get_channel_status(0);
    mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
190 191
    mavlink_msg_param_value_encode_chan(message->sysid,
                                        message->compid,
192
                                        0,                  // Re-encoding uses reserved channel 0
193 194
                                        message,
                                        &paramValue);
Don Gagne's avatar
Don Gagne committed
195 196
}

197
void APMFirmwarePlugin::_handleOutgoingParamSetThreadSafe(Vehicle* /*vehicle*/, LinkInterface* outgoingLink, mavlink_message_t* message)
Don Gagne's avatar
Don Gagne committed
198 199 200 201
{
    mavlink_param_set_t     paramSet;
    mavlink_param_union_t   paramUnion;

Don Gagne's avatar
Don Gagne committed
202 203
    memset(&paramSet, 0, sizeof(paramSet));

Don Gagne's avatar
Don Gagne committed
204 205 206 207 208
    // APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what
    // type they are. Fix it back to the wrong way on the way out.

    mavlink_msg_param_set_decode(message, &paramSet);

209 210 211 212 213
    if (!_ardupilotComponentMap[paramSet.target_system][paramSet.target_component]) {
        // Message is targetted to non-ArduPilot firmware component, assume it uses current mavlink spec
        return;
    }

Don Gagne's avatar
Don Gagne committed
214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239
    paramUnion.param_float = paramSet.param_value;

    switch (paramSet.param_type) {
    case MAV_PARAM_TYPE_UINT8:
        paramSet.param_value = paramUnion.param_uint8;
        break;
    case MAV_PARAM_TYPE_INT8:
        paramSet.param_value = paramUnion.param_int8;
        break;
    case MAV_PARAM_TYPE_UINT16:
        paramSet.param_value = paramUnion.param_uint16;
        break;
    case MAV_PARAM_TYPE_INT16:
        paramSet.param_value = paramUnion.param_int16;
        break;
    case MAV_PARAM_TYPE_UINT32:
        paramSet.param_value = paramUnion.param_uint32;
        break;
    case MAV_PARAM_TYPE_INT32:
        paramSet.param_value = paramUnion.param_int32;
        break;
    case MAV_PARAM_TYPE_REAL32:
        // Already in param_float
        break;
    default:
        qCCritical(APMFirmwarePluginLog) << "Invalid/Unsupported data type used in parameter:" << paramSet.param_type;
Don Gagne's avatar
Don Gagne committed
240 241
    }

242
    _adjustOutgoingMavlinkMutex.lock();
243
    mavlink_msg_param_set_encode_chan(message->sysid, message->compid, outgoingLink->mavlinkChannel(), message, &paramSet);
244
    _adjustOutgoingMavlinkMutex.unlock();
Don Gagne's avatar
Don Gagne committed
245 246
}

247
bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* /*vehicle*/, mavlink_message_t* message)
Don Gagne's avatar
Don Gagne committed
248
{
249 250
    // APM user facing calibration messages come through as high severity, we need to parse them out
    // and lower the severity on them so that they don't pop in the users face.
251

252 253 254 255
    QString messageText = _getMessageText(message);
    if (messageText.contains("Place vehicle") || messageText.contains("Calibration successful")) {
        _adjustCalibrationMessageSeverity(message);
        return true;
Don Gagne's avatar
Don Gagne committed
256
    }
257

258
    if (messageText.contains(APM_FRAME_REXP)) {
Don Gagne's avatar
Don Gagne committed
259 260 261 262 263 264 265 266
        // We need to parse the Frame: message in order to determine whether the motors are coaxial or not
        QRegExp frameTypeRegex("^Frame: (\\S*)");
        if (frameTypeRegex.indexIn(messageText) != -1) {
            QString frameType = frameTypeRegex.cap(1);
            if (!frameType.isEmpty() && (frameType == QStringLiteral("Y6") || frameType == QStringLiteral("OCTA_QUAD") || frameType == QStringLiteral("COAX"))) {
                _coaxialMotors = true;
            }
        }
Don Gagne's avatar
Don Gagne committed
267 268
    }

269
    return true;
Don Gagne's avatar
Don Gagne committed
270 271
}

272
void APMFirmwarePlugin::_handleIncomingHeartbeat(Vehicle* vehicle, mavlink_message_t* message)
Don Gagne's avatar
Don Gagne committed
273 274
{
    bool flying = false;
275

276 277
    mavlink_heartbeat_t heartbeat;
    mavlink_msg_heartbeat_decode(message, &heartbeat);
Don Gagne's avatar
Don Gagne committed
278

279 280 281
    if (message->compid == MAV_COMP_ID_AUTOPILOT1) {
        // We pull Vehicle::flying state from HEARTBEAT on ArduPilot. This is a firmware specific test.
        if (vehicle->armed()) {
Don Gagne's avatar
Don Gagne committed
282

283 284 285 286 287
            flying = heartbeat.system_status == MAV_STATE_ACTIVE;
            if (!flying && vehicle->flying()) {
                // If we were previously flying, and we go into critical or emergency assume we are still flying
                flying = heartbeat.system_status == MAV_STATE_CRITICAL || heartbeat.system_status == MAV_STATE_EMERGENCY;
            }
288
        }
289
        vehicle->_setFlying(flying);
290
    }
Don Gagne's avatar
Don Gagne committed
291

292 293 294 295 296 297
    // We need to know whether this component is part of the ArduPilot stack code or not so we can adjust mavlink quirks appropriately.
    // If the component sends a heartbeat we can know that. If it's doesn't there is pretty much no way to know.
    _ardupilotComponentMap[message->sysid][message->compid] = heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA;

    // Force the ESP8266 to be non-ArduPilot code (it doesn't send heartbeats)
    _ardupilotComponentMap[message->sysid][MAV_COMP_ID_UDP_BRIDGE] = false;
Don Gagne's avatar
Don Gagne committed
298 299
}

300
bool APMFirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
Don Gagne's avatar
Don Gagne committed
301
{
302 303 304
    if (message->msgid == MAVLINK_MSG_ID_HEARTBEAT) {
        // We need to look at all heartbeats that go by from any component
        _handleIncomingHeartbeat(vehicle, message);
305
        return true;
Don Gagne's avatar
Don Gagne committed
306 307
    }

308 309 310 311 312 313 314
    // Only translate messages which come from ArduPilot code. All other components are expected to follow current mavlink spec.
    if (_ardupilotComponentMap[vehicle->id()][message->compid]) {
        switch (message->msgid) {
        case MAVLINK_MSG_ID_PARAM_VALUE:
            _handleIncomingParamValue(vehicle, message);
            break;
        case MAVLINK_MSG_ID_STATUSTEXT:
315
            return _handleIncomingStatusText(vehicle, message);
316 317 318 319 320 321 322
        case MAVLINK_MSG_ID_RC_CHANNELS:
            _handleRCChannels(vehicle, message);
            break;
        case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
            _handleRCChannelsRaw(vehicle, message);
            break;
        }
Don Gagne's avatar
Don Gagne committed
323
    }
324 325

    return true;
Don Gagne's avatar
Don Gagne committed
326 327
}

328
void APMFirmwarePlugin::adjustOutgoingMavlinkMessageThreadSafe(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message)
Don Gagne's avatar
Don Gagne committed
329
{
330 331
    switch (message->msgid) {
    case MAVLINK_MSG_ID_PARAM_SET:
332
        _handleOutgoingParamSetThreadSafe(vehicle, outgoingLink, message);
333
        break;
Don Gagne's avatar
Don Gagne committed
334
    }
335 336
}

337
QString APMFirmwarePlugin::_getMessageText(mavlink_message_t* message) const
338 339 340
{
    QByteArray b;

341 342
    b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
    mavlink_msg_statustext_get_text(message, b.data());
343 344 345 346 347 348

    // Ensure NUL-termination
    b[b.length()-1] = '\0';
    return QString(b);
}

349
void APMFirmwarePlugin::_setInfoSeverity(mavlink_message_t* message) const
350
{
351 352 353
    // Re-Encoding is always done using mavlink 1.0
    mavlink_status_t* mavlinkStatusReEncode = mavlink_get_channel_status(0);
    mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
Don Gagne's avatar
Don Gagne committed
354

355 356 357 358 359 360 361 362 363
    mavlink_statustext_t statusText;
    mavlink_msg_statustext_decode(message, &statusText);

    statusText.severity = MAV_SEVERITY_INFO;
    mavlink_msg_statustext_encode_chan(message->sysid,
                                       message->compid,
                                       0,                  // Re-encoding uses reserved channel 0
                                       message,
                                       &statusText);
364 365
}

Don Gagne's avatar
Don Gagne committed
366 367 368 369
void APMFirmwarePlugin::_adjustCalibrationMessageSeverity(mavlink_message_t* message) const
{
    mavlink_statustext_t statusText;
    mavlink_msg_statustext_decode(message, &statusText);
370 371 372
    // Re-Encoding is always done using mavlink 1.0
    mavlink_status_t* mavlinkStatusReEncode = mavlink_get_channel_status(0);
    mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
Don Gagne's avatar
Don Gagne committed
373
    statusText.severity = MAV_SEVERITY_INFO;
374
    mavlink_msg_statustext_encode_chan(message->sysid, message->compid, 0, message, &statusText);
Don Gagne's avatar
Don Gagne committed
375 376
}

377 378
void APMFirmwarePlugin::initializeStreamRates(Vehicle* vehicle)
{
379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402
    APMMavlinkStreamRateSettings* streamRates = qgcApp()->toolbox()->settingsManager()->apmMavlinkStreamRateSettings();

    struct StreamInfo_s {
        MAV_DATA_STREAM mavStream;
        int             streamRate;
    };

    StreamInfo_s rgStreamInfo[] = {
        { MAV_DATA_STREAM_RAW_SENSORS,      streamRates->streamRateRawSensors()->rawValue().toInt() },
        { MAV_DATA_STREAM_EXTENDED_STATUS,  streamRates->streamRateExtendedStatus()->rawValue().toInt() },
        { MAV_DATA_STREAM_RC_CHANNELS,      streamRates->streamRateRCChannels()->rawValue().toInt() },
        { MAV_DATA_STREAM_POSITION,         streamRates->streamRatePosition()->rawValue().toInt() },
        { MAV_DATA_STREAM_EXTRA1,           streamRates->streamRateExtra1()->rawValue().toInt() },
        { MAV_DATA_STREAM_EXTRA2,           streamRates->streamRateExtra2()->rawValue().toInt() },
        { MAV_DATA_STREAM_EXTRA3,           streamRates->streamRateExtra3()->rawValue().toInt() },
    };

    for (size_t i=0; i<sizeof(rgStreamInfo)/sizeof(rgStreamInfo[0]); i++) {
        const StreamInfo_s& streamInfo = rgStreamInfo[i];

        if (streamInfo.streamRate >= 0) {
            vehicle->requestDataStream(streamInfo.mavStream, static_cast<uint16_t>(streamInfo.streamRate));
        }
    }
403

404 405 406 407 408 409
    // ArduPilot only sends home position on first boot and then when it arms. It does not stream the position.
    // This means that depending on when QGC connects to the vehicle it may not have home position.
    // This can cause various features to not be available. So we request home position streaming ourselves.
    // The MAV_CMD_SET_MESSAGE_INTERVAL command is only supported on newer firmwares. So we set showError=false.
    // Which also means than on older firmwares you may be left with some missing features.
    vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_SET_MESSAGE_INTERVAL, false /* showError */, MAVLINK_MSG_ID_HOME_POSITION, 1000000 /* 1 second interval in usec */);
410 411 412
}


413 414
void APMFirmwarePlugin::initializeVehicle(Vehicle* vehicle)
{
415 416 417 418 419 420 421 422
    if (vehicle->isOfflineEditingVehicle()) {
        switch (vehicle->vehicleType()) {
        case MAV_TYPE_QUADROTOR:
        case MAV_TYPE_HEXAROTOR:
        case MAV_TYPE_OCTOROTOR:
        case MAV_TYPE_TRICOPTER:
        case MAV_TYPE_COAXIAL:
        case MAV_TYPE_HELICOPTER:
423
            vehicle->setFirmwareVersion(3, 6, 0);
424
            break;
DonLakeFlyer's avatar
DonLakeFlyer committed
425 426 427 428 429 430 431
        case MAV_TYPE_VTOL_DUOROTOR:
        case MAV_TYPE_VTOL_QUADROTOR:
        case MAV_TYPE_VTOL_TILTROTOR:
        case MAV_TYPE_VTOL_RESERVED2:
        case MAV_TYPE_VTOL_RESERVED3:
        case MAV_TYPE_VTOL_RESERVED4:
        case MAV_TYPE_VTOL_RESERVED5:
432
        case MAV_TYPE_FIXED_WING:
433
            vehicle->setFirmwareVersion(3, 9, 0);
434 435 436
            break;
        case MAV_TYPE_GROUND_ROVER:
        case MAV_TYPE_SURFACE_BOAT:
437
            vehicle->setFirmwareVersion(3, 5, 0);
438 439 440 441 442 443 444 445
            break;
        case MAV_TYPE_SUBMARINE:
            vehicle->setFirmwareVersion(3, 4, 0);
            break;
        default:
            // No version set
            break;
        }
446
    } else {
447 448 449 450
        if (qgcApp()->toolbox()->settingsManager()->appSettings()->apmStartMavlinkStreams()->rawValue().toBool()) {
            // Streams are not started automatically on APM stack (sort of)
            initializeStreamRates(vehicle);
        }
451
    }
452 453 454 455

    if (qgcApp()->toolbox()->settingsManager()->videoSettings()->videoSource()->rawValue() == VideoSettings::videoSource3DRSolo) {
        _soloVideoHandshake();
    }
456
}
457 458 459 460 461

void APMFirmwarePlugin::setSupportedModes(QList<APMCustomMode> supportedModes)
{
    _supportedModes = supportedModes;
}
462 463 464 465 466 467

bool APMFirmwarePlugin::sendHomePositionToVehicle(void)
{
    // APM stack wants the home position sent in the first position
    return true;
}
468

469
FactMetaData* APMFirmwarePlugin::_getMetaDataForFact(QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType)
470
{
471
    APMParameterMetaData* apmMetaData = qobject_cast<APMParameterMetaData*>(parameterMetaData);
Don Gagne's avatar
Don Gagne committed
472

473
    if (apmMetaData) {
474
        return apmMetaData->getMetaDataForFact(name, vehicleType, type);
475 476 477
    } else {
        qWarning() << "Internal error: pointer passed to APMFirmwarePlugin::addMetaDataToFact not APMParameterMetaData";
    }
478 479

    return nullptr;
480
}
481

482
QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass)
Don Gagne's avatar
Don Gagne committed
483
{
Tomaz Canabrava's avatar
Tomaz Canabrava committed
484
    return {
485 486 487 488 489 490 491
#if 0
    // Waiting for module update
        MAV_CMD_DO_SET_REVERSE,
#endif
    };

    QList<MAV_CMD> supportedCommands = {
Tomaz Canabrava's avatar
Tomaz Canabrava committed
492 493
        MAV_CMD_NAV_WAYPOINT,
        MAV_CMD_NAV_LOITER_UNLIM, MAV_CMD_NAV_LOITER_TURNS, MAV_CMD_NAV_LOITER_TIME,
494
        MAV_CMD_NAV_RETURN_TO_LAUNCH,
Tomaz Canabrava's avatar
Tomaz Canabrava committed
495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517
        MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT,
        MAV_CMD_NAV_LOITER_TO_ALT,
        MAV_CMD_NAV_SPLINE_WAYPOINT,
        MAV_CMD_NAV_GUIDED_ENABLE,
        MAV_CMD_NAV_DELAY,
        MAV_CMD_CONDITION_DELAY, MAV_CMD_CONDITION_DISTANCE, MAV_CMD_CONDITION_YAW,
        MAV_CMD_DO_SET_MODE,
        MAV_CMD_DO_JUMP,
        MAV_CMD_DO_CHANGE_SPEED,
        MAV_CMD_DO_SET_HOME,
        MAV_CMD_DO_SET_RELAY, MAV_CMD_DO_REPEAT_RELAY,
        MAV_CMD_DO_SET_SERVO, MAV_CMD_DO_REPEAT_SERVO,
        MAV_CMD_DO_LAND_START,
        MAV_CMD_DO_SET_ROI,
        MAV_CMD_DO_DIGICAM_CONFIGURE, MAV_CMD_DO_DIGICAM_CONTROL,
        MAV_CMD_DO_MOUNT_CONTROL,
        MAV_CMD_DO_SET_CAM_TRIGG_DIST,
        MAV_CMD_DO_FENCE_ENABLE,
        MAV_CMD_DO_PARACHUTE,
        MAV_CMD_DO_INVERTED_FLIGHT,
        MAV_CMD_DO_GRIPPER,
        MAV_CMD_DO_GUIDED_LIMITS,
        MAV_CMD_DO_AUTOTUNE_ENABLE,
518 519 520
    };

    QList<MAV_CMD> vtolCommands = {
Tomaz Canabrava's avatar
Tomaz Canabrava committed
521 522
        MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND, MAV_CMD_DO_VTOL_TRANSITION,
    };
523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543

    QList<MAV_CMD> flightCommands = {
        MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
    };

    if (vehicleClass == QGCMAVLink::VehicleClassGeneric) {
        supportedCommands   += vtolCommands;
        supportedCommands   += flightCommands;
    }
    if (vehicleClass == QGCMAVLink::VehicleClassVTOL) {
        supportedCommands += vtolCommands;
        supportedCommands += flightCommands;
    } else if (vehicleClass == QGCMAVLink::VehicleClassFixedWing || vehicleClass == QGCMAVLink::VehicleClassMultiRotor) {
        supportedCommands += flightCommands;
    }

    if (qgcApp()->toolbox()->settingsManager()->planViewSettings()->useConditionGate()->rawValue().toBool()) {
        supportedCommands.append(MAV_CMD_CONDITION_GATE);
    }

    return supportedCommands;
Don Gagne's avatar
Don Gagne committed
544
}
545

546
QString APMFirmwarePlugin::missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const
547
{
548 549
    switch (vehicleClass) {
    case QGCMAVLink::VehicleClassGeneric:
550
        return QStringLiteral(":/json/APM-MavCmdInfoCommon.json");
551
    case QGCMAVLink::VehicleClassFixedWing:
552
        return QStringLiteral(":/json/APM-MavCmdInfoFixedWing.json");
553
    case QGCMAVLink::VehicleClassMultiRotor:
554
        return QStringLiteral(":/json/APM-MavCmdInfoMultiRotor.json");
555
    case QGCMAVLink::VehicleClassVTOL:
556
        return QStringLiteral(":/json/APM-MavCmdInfoVTOL.json");
557
    case QGCMAVLink::VehicleClassSub:
558
        return QStringLiteral(":/json/APM-MavCmdInfoSub.json");
559
    case QGCMAVLink::VehicleClassRoverBoat:
560
        return QStringLiteral(":/json/APM-MavCmdInfoRover.json");
561
    default:
562
        qWarning() << "APMFirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
563 564
        return QString();
    }
565
}
566

567
QObject* APMFirmwarePlugin::_loadParameterMetaData(const QString& metaDataFile)
568 569 570
{
    Q_UNUSED(metaDataFile);

Don Gagne's avatar
Don Gagne committed
571 572
    APMParameterMetaData* metaData = new APMParameterMetaData();
    metaData->loadParameterFactMetaDataFile(metaDataFile);
573 574
    return metaData;
}
Don Gagne's avatar
Don Gagne committed
575 576 577 578 579 580

bool APMFirmwarePlugin::isGuidedMode(const Vehicle* vehicle) const
{
    return vehicle->flightMode() == "Guided";
}

581
void APMFirmwarePlugin::_soloVideoHandshake(void)
Don Gagne's avatar
Don Gagne committed
582
{
583
    QTcpSocket* socket = new QTcpSocket(this);
Don Gagne's avatar
Don Gagne committed
584

585
#if QT_VERSION < QT_VERSION_CHECK(5, 15, 0)
586
    QObject::connect(socket, static_cast<void (QTcpSocket::*)(QAbstractSocket::SocketError)>(&QTcpSocket::error), this, &APMFirmwarePlugin::_artooSocketError);
587
#else
588
    QObject::connect(socket, &QAbstractSocket::errorOccurred, this, &APMFirmwarePlugin::_artooSocketError);
589
#endif
590
    socket->connectToHost(_artooIP, _artooVideoHandshakePort);
Don Gagne's avatar
Don Gagne committed
591 592 593 594
}

void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketError)
{
595
    qgcApp()->showAppMessage(tr("Error during Solo video link setup: %1").arg(socketError));
Don Gagne's avatar
Don Gagne committed
596
}
Don Gagne's avatar
Don Gagne committed
597

598
QString APMFirmwarePlugin::_internalParameterMetaDataFile(Vehicle* vehicle)
Don Gagne's avatar
Don Gagne committed
599 600 601 602 603 604 605 606
{
    switch (vehicle->vehicleType()) {
    case MAV_TYPE_QUADROTOR:
    case MAV_TYPE_HEXAROTOR:
    case MAV_TYPE_OCTOROTOR:
    case MAV_TYPE_TRICOPTER:
    case MAV_TYPE_COAXIAL:
    case MAV_TYPE_HELICOPTER:
DonLakeFlyer's avatar
DonLakeFlyer committed
607 608 609 610
        if (vehicle->versionCompare(4, 0, 0) >= 0) {
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.4.0.xml");
        }
        if (vehicle->versionCompare(3, 7, 0) >= 0) {
611
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml");
612
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
613
        if (vehicle->versionCompare(3, 6, 0) >= 0) {
614
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml");
Don Gagne's avatar
Don Gagne committed
615
        }
616
        return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml");
617

DonLakeFlyer's avatar
DonLakeFlyer committed
618 619 620 621 622 623 624
    case MAV_TYPE_VTOL_DUOROTOR:
    case MAV_TYPE_VTOL_QUADROTOR:
    case MAV_TYPE_VTOL_TILTROTOR:
    case MAV_TYPE_VTOL_RESERVED2:
    case MAV_TYPE_VTOL_RESERVED3:
    case MAV_TYPE_VTOL_RESERVED4:
    case MAV_TYPE_VTOL_RESERVED5:
Don Gagne's avatar
Don Gagne committed
625
    case MAV_TYPE_FIXED_WING:
DonLakeFlyer's avatar
DonLakeFlyer committed
626 627 628
        if (vehicle->versionCompare(4, 0, 0) >= 0) {
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.4.0.xml");
        }
629 630
        if (vehicle->versionCompare(3, 10, 0) >= 0) {
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.10.xml");
631
        }
632 633
        if (vehicle->versionCompare(3, 9, 0) >= 0) {
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.9.xml");
Don Gagne's avatar
Don Gagne committed
634
        }
635
        return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml");
636

Don Gagne's avatar
Don Gagne committed
637 638
    case MAV_TYPE_GROUND_ROVER:
    case MAV_TYPE_SURFACE_BOAT:
DonLakeFlyer's avatar
DonLakeFlyer committed
639 640 641
        if (vehicle->versionCompare(4, 0, 0) >= 0) {
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.4.0.xml");
        }
642 643
        if (vehicle->versionCompare(3, 6, 0) >= 0) {
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.6.xml");
644
        }
645 646
        if (vehicle->versionCompare(3, 5, 0) >= 0) {
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.5.xml");
647
        }
648
        return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.xml");
649

650
    case MAV_TYPE_SUBMARINE:
651 652 653
        if (vehicle->versionCompare(4, 0, 0) >= 0) { // 4.0.x
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.4.0.xml");
        }
654 655
        if (vehicle->versionCompare(3, 6, 0) >= 0) { // 3.6.x
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.6.xml");
656
        }
657 658 659 660 661 662
        if (vehicle->versionCompare(3, 5, 0) >= 0) { // 3.5.x
            return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.5.xml");
        }
        // up to 3.4.x
        return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml");

Don Gagne's avatar
Don Gagne committed
663 664 665 666
    default:
        return QString();
    }
}
667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684

void APMFirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode)
{
    if (guidedMode) {
        _setFlightModeAndValidate(vehicle, "Guided");
    } else {
        pauseVehicle(vehicle);
    }
}

void APMFirmwarePlugin::pauseVehicle(Vehicle* vehicle)
{
    _setFlightModeAndValidate(vehicle, pauseFlightMode());
}

void APMFirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
{
    if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) {
685
        qgcApp()->showAppMessage(QStringLiteral("Unable to go to location, vehicle position not known."));
686 687 688 689 690 691 692 693 694 695 696
        return;
    }


    setGuidedMode(vehicle, true);

    QGeoCoordinate coordWithAltitude = gotoCoord;
    coordWithAltitude.setAltitude(vehicle->altitudeRelative()->rawValue().toDouble());
    vehicle->missionManager()->writeArduPilotGuidedMissionItem(coordWithAltitude, false /* altChangeOnly */);
}

DonLakeFlyer's avatar
DonLakeFlyer committed
697
void APMFirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL)
698
{
DonLakeFlyer's avatar
DonLakeFlyer committed
699
    _setFlightModeAndValidate(vehicle, smartRTL ? smartRTLFlightMode() : rtlFlightMode());
700 701 702 703 704
}

void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange)
{
    if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) {
705
        qgcApp()->showAppMessage(tr("Unable to change altitude, vehicle altitude not known."));
706 707 708
        return;
    }

709 710 711 712 713
    if (abs(altitudeChange) < 0.01) {
        // This prevents unecessary changes to Guided mode when the users selects pause and doesn't really touch the altitude slider
        return;
    }

714 715 716 717 718 719 720
    setGuidedMode(vehicle, true);

    mavlink_message_t msg;
    mavlink_set_position_target_local_ned_t cmd;

    memset(&cmd, 0, sizeof(cmd));

721 722
    cmd.target_system    = static_cast<uint8_t>(vehicle->id());
    cmd.target_component = static_cast<uint8_t>(vehicle->defaultComponentId());
723 724 725 726
    cmd.coordinate_frame = MAV_FRAME_LOCAL_OFFSET_NED;
    cmd.type_mask = 0xFFF8; // Only x/y/z valid
    cmd.x = 0.0f;
    cmd.y = 0.0f;
727
    cmd.z = static_cast<float>(-(altitudeChange));
728 729

    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
730
    mavlink_msg_set_position_target_local_ned_encode_chan(
731 732
                static_cast<uint8_t>(mavlink->getSystemId()),
                static_cast<uint8_t>(mavlink->getComponentId()),
733
                vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
734 735
                &msg,
                &cmd);
736

737
    vehicle->sendMessageOnLinkThreadSafe(vehicle->vehicleLinkManager()->primaryLink(), msg);
738
}
739

740
void APMFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double altitudeRel)
741
{
742
    _guidedModeTakeoff(vehicle, altitudeRel);
743 744
}

745 746
double APMFirmwarePlugin::minimumTakeoffAltitude(Vehicle* vehicle)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
747
    double minTakeoffAlt = 0;
748 749 750 751
    QString takeoffAltParam(vehicle->vtol() ? QStringLiteral("Q_RTL_ALT") : QStringLiteral("PILOT_TKOFF_ALT"));
    float paramDivisor = vehicle->vtol() ? 1.0 : 100.0; // PILOT_TAKEOFF_ALT is in centimeters

    if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, takeoffAltParam)) {
752
        minTakeoffAlt = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, takeoffAltParam)->rawValue().toDouble() / static_cast<double>(paramDivisor);
DonLakeFlyer's avatar
DonLakeFlyer committed
753 754 755 756
    }

    if (minTakeoffAlt == 0) {
        minTakeoffAlt = FirmwarePlugin::minimumTakeoffAltitude(vehicle);
757
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
758 759

    return minTakeoffAlt;
760 761
}

762
bool APMFirmwarePlugin::_guidedModeTakeoff(Vehicle* vehicle, double altitudeRel)
763
{
DonLakeFlyer's avatar
DonLakeFlyer committed
764
    if (!vehicle->multiRotor() && !vehicle->vtol()) {
765
        qgcApp()->showAppMessage(tr("Vehicle does not support guided takeoff"));
DonLakeFlyer's avatar
DonLakeFlyer committed
766 767 768
        return false;
    }

769 770
    double vehicleAltitudeAMSL = vehicle->altitudeAMSL()->rawValue().toDouble();
    if (qIsNaN(vehicleAltitudeAMSL)) {
771
        qgcApp()->showAppMessage(tr("Unable to takeoff, vehicle position not known."));
772 773 774
        return false;
    }

775
    double takeoffAltRel = minimumTakeoffAltitude(vehicle);
776 777
    if (!qIsNaN(altitudeRel) && altitudeRel > takeoffAltRel) {
        takeoffAltRel = altitudeRel;
778 779 780
    }

    if (!_setFlightModeAndValidate(vehicle, "Guided")) {
781
        qgcApp()->showAppMessage(tr("Unable to takeoff: Vehicle failed to change to Guided mode."));
782 783 784 785
        return false;
    }

    if (!_armVehicleAndValidate(vehicle)) {
786
        qgcApp()->showAppMessage(tr("Unable to takeoff: Vehicle failed to arm."));
787 788 789 790 791 792 793
        return false;
    }

    vehicle->sendMavCommand(vehicle->defaultComponentId(),
                            MAV_CMD_NAV_TAKEOFF,
                            true, // show error
                            0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f,
794
                            static_cast<float>(takeoffAltRel));                     // Relative altitude
795 796 797 798 799 800

    return true;
}

void APMFirmwarePlugin::startMission(Vehicle* vehicle)
{
801 802 803
    if (vehicle->flying()) {
        // Vehicle already in the air, we just need to switch to auto
        if (!_setFlightModeAndValidate(vehicle, "Auto")) {
804
            qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle failed to change to Auto mode."));
805 806 807 808
        }
        return;
    }

809 810 811
    if (!vehicle->armed()) {
        // First switch to flight mode we can arm from
        if (!_setFlightModeAndValidate(vehicle, "Guided")) {
812
            qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle failed to change to Guided mode."));
813
            return;
814
        }
815

816
        if (!_armVehicleAndValidate(vehicle)) {
817
            qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle failed to arm."));
818 819
            return;
        }
820 821
    }

822 823
    if (vehicle->fixedWing()) {
        if (!_setFlightModeAndValidate(vehicle, "Auto")) {
824
            qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle failed to change to Auto mode."));
825 826 827 828
            return;
        }
    } else {
        vehicle->sendMavCommand(vehicle->defaultComponentId(), MAV_CMD_MISSION_START, true /*show error */);
829 830
    }
}
831 832 833

QString APMFirmwarePlugin::_getLatestVersionFileUrl(Vehicle* vehicle)
{
834
    const static QString baseUrl("http://firmware.ardupilot.org/%1/stable/Pixhawk1/git-version.txt");
835 836

    if (qobject_cast<ArduPlaneFirmwarePlugin*>(vehicle->firmwarePlugin())) {
837
        return baseUrl.arg("Plane");
838
    } else if (qobject_cast<ArduRoverFirmwarePlugin*>(vehicle->firmwarePlugin())) {
839
        return baseUrl.arg("Rover");
840
    } else if (qobject_cast<ArduSubFirmwarePlugin*>(vehicle->firmwarePlugin())) {
841
        return baseUrl.arg("Sub");
842 843 844 845 846
    } else if (qobject_cast<ArduCopterFirmwarePlugin*>(vehicle->firmwarePlugin())) {
        return baseUrl.arg("Copter");
    } else {
        qWarning() << "APMFirmwarePlugin::_getLatestVersionFileUrl Unknown vehicle firmware type" << vehicle->vehicleType();
        return QString();
847 848 849 850 851 852
    }
}

QString APMFirmwarePlugin::_versionRegex() {
    return QStringLiteral(" V([0-9,\\.]*)$");
}
853 854 855 856 857 858 859 860 861 862 863

void APMFirmwarePlugin::_handleRCChannels(Vehicle* vehicle, mavlink_message_t* message)
{
    mavlink_rc_channels_t channels;
    mavlink_msg_rc_channels_decode(message, &channels);
    //-- Ardupilot uses 0-255 to indicate 0-100% where QGC expects 0-100
    if(channels.rssi) {
        channels.rssi = static_cast<uint8_t>(static_cast<double>(channels.rssi) / 255.0 * 100.0);
    }
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
    mavlink_msg_rc_channels_encode_chan(
864 865
                static_cast<uint8_t>(mavlink->getSystemId()),
                static_cast<uint8_t>(mavlink->getComponentId()),
866
                vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
867 868
                message,
                &channels);
869 870 871 872 873 874 875 876 877 878 879 880
}

void APMFirmwarePlugin::_handleRCChannelsRaw(Vehicle* vehicle, mavlink_message_t *message)
{
    mavlink_rc_channels_raw_t channels;
    mavlink_msg_rc_channels_raw_decode(message, &channels);
    //-- Ardupilot uses 0-255 to indicate 0-100% where QGC expects 0-100
    if(channels.rssi) {
        channels.rssi = static_cast<uint8_t>(static_cast<double>(channels.rssi) / 255.0 * 100.0);
    }
    MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
    mavlink_msg_rc_channels_raw_encode_chan(
881 882
                static_cast<uint8_t>(mavlink->getSystemId()),
                static_cast<uint8_t>(mavlink->getComponentId()),
883
                vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
884 885
                message,
                &channels);
886 887
}

888 889
void APMFirmwarePlugin::_sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimationCapabilities)
{
890
    if (!vehicle->homePosition().isValid()) {
891 892 893
        static bool sentOnce = false;
        if (!sentOnce) {
            sentOnce = true;
894
            qgcApp()->showAppMessage(tr("Follow failed: Home position not set."));
895 896 897 898
        }
        return;
    }

899
    if (!(estimationCapabilities & (FollowMe::POS | FollowMe::VEL | FollowMe::HEADING))) {
900 901 902 903
        static bool sentOnce = false;
        if (!sentOnce) {
            sentOnce = true;
            qWarning() << "APMFirmwarePlugin::_sendGCSMotionReport estimateCapabilities" << estimationCapabilities;
904
            qgcApp()->showAppMessage(tr("Follow failed: Ground station cannot provide required position information."));
905 906 907 908 909 910 911 912 913
        }
        return;
    }

    MAVLinkProtocol* mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol();

    mavlink_global_position_int_t globalPositionInt;
    memset(&globalPositionInt, 0, sizeof(globalPositionInt));

914
    // Important note: QGC only supports sending the constant GCS home position altitude for follow me.
915 916 917
    globalPositionInt.time_boot_ms =    static_cast<uint32_t>(qgcApp()->msecsSinceBoot());
    globalPositionInt.lat =             motionReport.lat_int;
    globalPositionInt.lon =             motionReport.lon_int;
918 919 920 921 922 923
    globalPositionInt.alt =             static_cast<int32_t>(vehicle->homePosition().altitude() * 1000);    // mm
    globalPositionInt.relative_alt =    static_cast<int32_t>(0);                                            // mm
    globalPositionInt.vx =              static_cast<int16_t>(motionReport.vxMetersPerSec * 100);            // cm/sec
    globalPositionInt.vy =              static_cast<int16_t>(motionReport.vyMetersPerSec * 100);            // cm/sec
    globalPositionInt.vy =              static_cast<int16_t>(motionReport.vzMetersPerSec * 100);            // cm/sec
    globalPositionInt.hdg =             static_cast<uint16_t>(motionReport.headingDegrees * 100.0);         // centi-degrees
924 925 926 927

    mavlink_message_t message;
    mavlink_msg_global_position_int_encode_chan(static_cast<uint8_t>(mavlinkProtocol->getSystemId()),
                                          static_cast<uint8_t>(mavlinkProtocol->getComponentId()),
928
                                          vehicle->vehicleLinkManager()->primaryLink()->mavlinkChannel(),
929 930
                                          &message,
                                          &globalPositionInt);
931
    vehicle->sendMessageOnLinkThreadSafe(vehicle->vehicleLinkManager()->primaryLink(), message);
932
}