PX4FirmwarePlugin.cc 20.7 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/
dogmaphobic's avatar
dogmaphobic committed
9

Don Gagne's avatar
Don Gagne committed
10 11 12 13 14

/// @file
///     @author Don Gagne <don@thegagnes.com>

#include "PX4FirmwarePlugin.h"
15
#include "PX4ParameterMetaData.h"
16
#include "QGCApplication.h"
17 18 19 20 21 22 23
#include "PX4AutoPilotPlugin.h"
#include "PX4AdvancedFlightModesController.h"
#include "PX4SimpleFlightModesController.h"
#include "AirframeComponentController.h"
#include "SensorsComponentController.h"
#include "PowerComponentController.h"
#include "RadioComponentController.h"
Don Gagne's avatar
Don Gagne committed
24 25 26

#include <QDebug>

Daniel Agar's avatar
Daniel Agar committed
27
#include "px4_custom_mode.h"
Don Gagne's avatar
Don Gagne committed
28

29 30 31 32 33 34 35
PX4FirmwarePluginInstanceData::PX4FirmwarePluginInstanceData(QObject* parent)
    : QObject(parent)
    , versionNotified(false)
{

}

36
PX4FirmwarePlugin::PX4FirmwarePlugin(void)
37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52
    : _manualFlightMode(tr("Manual"))
    , _acroFlightMode(tr("Acro"))
    , _stabilizedFlightMode(tr("Stabilized"))
    , _rattitudeFlightMode(tr("Rattitude"))
    , _altCtlFlightMode(tr("Altitude"))
    , _posCtlFlightMode(tr("Position"))
    , _offboardFlightMode(tr("Offboard"))
    , _readyFlightMode(tr("Ready"))
    , _takeoffFlightMode(tr("Takeoff"))
    , _holdFlightMode(tr("Hold"))
    , _missionFlightMode(tr("Mission"))
    , _rtlFlightMode(tr("Return"))
    , _landingFlightMode(tr("Land"))
    , _rtgsFlightMode(tr("Return to Groundstation"))
    , _followMeFlightMode(tr("Follow Me"))
    , _simpleFlightMode(tr("Simple"))
53
{
54 55 56 57 58 59
    qmlRegisterType<PX4AdvancedFlightModesController>   ("QGroundControl.Controllers", 1, 0, "PX4AdvancedFlightModesController");
    qmlRegisterType<PX4SimpleFlightModesController>     ("QGroundControl.Controllers", 1, 0, "PX4SimpleFlightModesController");
    qmlRegisterType<AirframeComponentController>        ("QGroundControl.Controllers", 1, 0, "AirframeComponentController");
    qmlRegisterType<SensorsComponentController>         ("QGroundControl.Controllers", 1, 0, "SensorsComponentController");
    qmlRegisterType<PowerComponentController>           ("QGroundControl.Controllers", 1, 0, "PowerComponentController");
    qmlRegisterType<RadioComponentController>           ("QGroundControl.Controllers", 1, 0, "RadioComponentController");
60 61 62 63 64 65 66 67 68 69

    struct Modes2Name {
        uint8_t     main_mode;
        uint8_t     sub_mode;
        bool        canBeSet;   ///< true: Vehicle can be set to this flight mode
        bool        fixedWing;  /// fixed wing compatible
        bool        multiRotor;  /// multi rotor compatible
    };

    static const struct Modes2Name rgModes2Name[] = {
70 71 72 73 74 75 76
        //main_mode                         sub_mode                                canBeSet  FW      MC
        { PX4_CUSTOM_MAIN_MODE_MANUAL,      0,                                      true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_STABILIZED,  0,                                      true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_ACRO,        0,                                      true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_RATTITUDE,   0,                                      true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_ALTCTL,      0,                                      true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_POSCTL,      0,                                      true,   true,   true },
77 78
        // simple can't be set by the user right now
        { PX4_CUSTOM_MAIN_MODE_SIMPLE,      0,                                      false,   false,  true },
79 80 81 82 83
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_LOITER,        true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_MISSION,       true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_RTL,           true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET, true,   false,  true },
        { PX4_CUSTOM_MAIN_MODE_OFFBOARD,    0,                                      true,   false,  true },
84
        // modes that can't be directly set by the user
85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_LAND,          false,  true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_READY,         false,  true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_RTGS,          false,  true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF,       false,  true,   true },
    };

    // Must be in same order as above structure
    const QString* rgModeNames[] = {
        &_manualFlightMode,
        &_stabilizedFlightMode,
        &_acroFlightMode,
        &_rattitudeFlightMode,
        &_altCtlFlightMode,
        &_posCtlFlightMode,
        &_simpleFlightMode,
        &_holdFlightMode,
        &_missionFlightMode,
        &_rtlFlightMode,
        &_followMeFlightMode,
        &_offboardFlightMode,
        &_landingFlightMode,
        &_readyFlightMode,
        &_rtgsFlightMode,
        &_takeoffFlightMode,
109 110 111 112 113 114 115 116 117 118
    };

    // Convert static information to dynamic list. This allows for plugin override class to manipulate list.
    for (size_t i=0; i<sizeof(rgModes2Name)/sizeof(rgModes2Name[0]); i++) {
        const struct Modes2Name* pModes2Name = &rgModes2Name[i];

        FlightModeInfo_t info;

        info.main_mode =    pModes2Name->main_mode;
        info.sub_mode =     pModes2Name->sub_mode;
119
        info.name =         rgModeNames[i];
120 121 122 123 124 125
        info.canBeSet =     pModes2Name->canBeSet;
        info.fixedWing =    pModes2Name->fixedWing;
        info.multiRotor =   pModes2Name->multiRotor;

        _flightModeInfoList.append(info);
    }
126
}
127

128 129 130
AutoPilotPlugin* PX4FirmwarePlugin::autopilotPlugin(Vehicle* vehicle)
{
    return new PX4AutoPilotPlugin(vehicle, vehicle);
131 132
}

Don Gagne's avatar
Don Gagne committed
133 134 135
QList<VehicleComponent*> PX4FirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle)
{
    Q_UNUSED(vehicle);
dogmaphobic's avatar
dogmaphobic committed
136

Don Gagne's avatar
Don Gagne committed
137 138 139
    return QList<VehicleComponent*>();
}

Daniel Agar's avatar
Daniel Agar committed
140
QStringList PX4FirmwarePlugin::flightModes(Vehicle* vehicle)
Don Gagne's avatar
Don Gagne committed
141 142
{
    QStringList flightModes;
dogmaphobic's avatar
dogmaphobic committed
143

144 145 146 147
    foreach (const FlightModeInfo_t& info, _flightModeInfoList) {
        if (info.canBeSet) {
            bool fw = (vehicle->fixedWing() && info.fixedWing);
            bool mc = (vehicle->multiRotor() && info.multiRotor);
Daniel Agar's avatar
Daniel Agar committed
148 149 150 151 152

            // show all modes for generic, vtol, etc
            bool other = !vehicle->fixedWing() && !vehicle->multiRotor();

            if (fw || mc || other) {
153
                flightModes += *info.name;
Daniel Agar's avatar
Daniel Agar committed
154
            }
Don Gagne's avatar
Don Gagne committed
155 156
        }
    }
dogmaphobic's avatar
dogmaphobic committed
157

Don Gagne's avatar
Don Gagne committed
158 159 160
    return flightModes;
}

Don Gagne's avatar
Don Gagne committed
161
QString PX4FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) const
Don Gagne's avatar
Don Gagne committed
162 163
{
    QString flightMode = "Unknown";
dogmaphobic's avatar
dogmaphobic committed
164

Don Gagne's avatar
Don Gagne committed
165 166 167
    if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
        union px4_custom_mode px4_mode;
        px4_mode.data = custom_mode;
dogmaphobic's avatar
dogmaphobic committed
168

Don Gagne's avatar
Don Gagne committed
169
        bool found = false;
170 171
        foreach (const FlightModeInfo_t& info, _flightModeInfoList) {
            if (info.main_mode == px4_mode.main_mode && info.sub_mode == px4_mode.sub_mode) {
172
                flightMode = *info.name;
Don Gagne's avatar
Don Gagne committed
173 174 175 176
                found = true;
                break;
            }
        }
dogmaphobic's avatar
dogmaphobic committed
177

Don Gagne's avatar
Don Gagne committed
178 179
        if (!found) {
            qWarning() << "Unknown flight mode" << custom_mode;
180
            return tr("Unknown %1:%2").arg(base_mode).arg(custom_mode);
Don Gagne's avatar
Don Gagne committed
181 182 183 184
        }
    } else {
        qWarning() << "PX4 Flight Stack flight mode without custom mode enabled?";
    }
dogmaphobic's avatar
dogmaphobic committed
185

Don Gagne's avatar
Don Gagne committed
186 187 188 189 190 191 192
    return flightMode;
}

bool PX4FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode)
{
    *base_mode = 0;
    *custom_mode = 0;
dogmaphobic's avatar
dogmaphobic committed
193

Don Gagne's avatar
Don Gagne committed
194
    bool found = false;
195 196
    foreach (const FlightModeInfo_t& info, _flightModeInfoList) {
        if (flightMode.compare(info.name, Qt::CaseInsensitive) == 0) {
Don Gagne's avatar
Don Gagne committed
197 198 199
            union px4_custom_mode px4_mode;

            px4_mode.data = 0;
200 201
            px4_mode.main_mode = info.main_mode;
            px4_mode.sub_mode = info.sub_mode;
dogmaphobic's avatar
dogmaphobic committed
202

Don Gagne's avatar
Don Gagne committed
203 204
            *base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
            *custom_mode = px4_mode.data;
dogmaphobic's avatar
dogmaphobic committed
205

Don Gagne's avatar
Don Gagne committed
206 207 208 209
            found = true;
            break;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
210

Don Gagne's avatar
Don Gagne committed
211 212 213
    if (!found) {
        qWarning() << "Unknown flight Mode" << flightMode;
    }
dogmaphobic's avatar
dogmaphobic committed
214

Don Gagne's avatar
Don Gagne committed
215 216
    return found;
}
217 218 219

int PX4FirmwarePlugin::manualControlReservedButtonCount(void)
{
220
    return 0;   // 0 buttons reserved for rc switch simulation
221
}
Don Gagne's avatar
Don Gagne committed
222

223 224 225 226 227
bool PX4FirmwarePlugin::supportsManualControl(void)
{
    return true;
}

228
bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities)
Don Gagne's avatar
Don Gagne committed
229
{
230
    if (vehicle->multiRotor()) {
231
        return (capabilities & (MavCmdPreflightStorageCapability | GuidedModeCapability | SetFlightModeCapability | PauseVehicleCapability /*| OrbitModeCapability still NYI*/)) == capabilities;
232 233
    } else {
        return (capabilities & (MavCmdPreflightStorageCapability | GuidedModeCapability | SetFlightModeCapability | PauseVehicleCapability)) == capabilities;
234
    }
Don Gagne's avatar
Don Gagne committed
235
}
236 237 238

void PX4FirmwarePlugin::initializeVehicle(Vehicle* vehicle)
{
239
    vehicle->setFirmwarePluginInstanceData(new PX4FirmwarePluginInstanceData);
240
}
241 242 243 244 245 246 247

bool PX4FirmwarePlugin::sendHomePositionToVehicle(void)
{
    // PX4 stack does not want home position sent in the first position.
    // Subsequent sequence numbers must be adjusted.
    return false;
}
248

249
void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType)
250
{
251 252 253 254 255 256 257
    PX4ParameterMetaData* px4MetaData = qobject_cast<PX4ParameterMetaData*>(parameterMetaData);

    if (px4MetaData) {
        px4MetaData->addMetaDataToFact(fact, vehicleType);
    } else {
        qWarning() << "Internal error: pointer passed to PX4FirmwarePlugin::addMetaDataToFact not PX4ParameterMetaData";
    }
258
}
Don Gagne's avatar
Don Gagne committed
259 260 261 262 263

QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
{
    QList<MAV_CMD> list;

264
    list << MAV_CMD_NAV_WAYPOINT
265
         << MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TIME << MAV_CMD_NAV_LOITER_TO_ALT
Don Gagne's avatar
Don Gagne committed
266
         << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF
267
         << MAV_CMD_DO_JUMP
Don Gagne's avatar
Don Gagne committed
268
         << MAV_CMD_DO_VTOL_TRANSITION << MAV_CMD_NAV_VTOL_TAKEOFF << MAV_CMD_NAV_VTOL_LAND
269
         << MAV_CMD_DO_DIGICAM_CONTROL
270
         << MAV_CMD_DO_SET_CAM_TRIGG_DIST
271
         << MAV_CMD_DO_SET_SERVO
Don Gagne's avatar
Don Gagne committed
272
         << MAV_CMD_DO_CHANGE_SPEED
273
         << MAV_CMD_DO_LAND_START
274
         << MAV_CMD_DO_MOUNT_CONFIGURE
275
         << MAV_CMD_DO_MOUNT_CONTROL
276
         << MAV_CMD_SET_CAMERA_MODE
DonLakeFlyer's avatar
DonLakeFlyer committed
277 278
         << MAV_CMD_IMAGE_START_CAPTURE << MAV_CMD_IMAGE_STOP_CAPTURE << MAV_CMD_VIDEO_START_CAPTURE << MAV_CMD_VIDEO_STOP_CAPTURE
         << MAV_CMD_NAV_DELAY;
Jimmy Johnson's avatar
Jimmy Johnson committed
279

Don Gagne's avatar
Don Gagne committed
280 281
    return list;
}
282

283
QString PX4FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
284
{
285 286 287 288 289 290 291 292 293 294 295
    switch (vehicleType) {
    case MAV_TYPE_GENERIC:
        return QStringLiteral(":/json/PX4/MavCmdInfoCommon.json");
        break;
    case MAV_TYPE_FIXED_WING:
        return QStringLiteral(":/json/PX4/MavCmdInfoFixedWing.json");
        break;
    case MAV_TYPE_QUADROTOR:
        return QStringLiteral(":/json/PX4/MavCmdInfoMultiRotor.json");
        break;
    case MAV_TYPE_VTOL_QUADROTOR:
Don Gagne's avatar
Don Gagne committed
296
        return QStringLiteral(":/json/PX4/MavCmdInfoVTOL.json");
297 298 299 300 301 302 303 304 305 306 307
        break;
    case MAV_TYPE_SUBMARINE:
        return QStringLiteral(":/json/PX4/MavCmdInfoSub.json");
        break;
    case MAV_TYPE_GROUND_ROVER:
        return QStringLiteral(":/json/PX4/MavCmdInfoRover.json");
        break;
    default:
        qWarning() << "PX4FirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType;
        return QString();
    }
308
}
309 310 311 312

QObject* PX4FirmwarePlugin::loadParameterMetaData(const QString& metaDataFile)
{
    PX4ParameterMetaData* metaData = new PX4ParameterMetaData;
313 314 315
    if (!metaDataFile.isEmpty()) {
        metaData->loadParameterFactMetaDataFile(metaDataFile);
    }
316 317
    return metaData;
}
Don Gagne's avatar
Don Gagne committed
318 319 320

void PX4FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
{
321 322 323 324 325 326 327 328 329 330
    vehicle->sendMavCommand(vehicle->defaultComponentId(),
                            MAV_CMD_DO_REPOSITION,
                            true,   // show error if failed
                            -1.0f,
                            MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
                            0.0f,
                            NAN,
                            NAN,
                            NAN,
                            NAN);
Don Gagne's avatar
Don Gagne committed
331
}
332 333 334

void PX4FirmwarePlugin::guidedModeRTL(Vehicle* vehicle)
{
335
    _setFlightModeAndValidate(vehicle, _rtlFlightMode);
336 337 338 339
}

void PX4FirmwarePlugin::guidedModeLand(Vehicle* vehicle)
{
340
    _setFlightModeAndValidate(vehicle, _landingFlightMode);
341 342
}

343 344
void PX4FirmwarePlugin::guidedModeOrbit(Vehicle* vehicle, const QGeoCoordinate& centerCoord, double radius, double velocity, double altitude)
{
345
    if (!isGuidedMode(vehicle)) {
346
        setGuidedMode(vehicle, true);
347 348 349 350 351 352 353 354 355 356 357 358
    }

    vehicle->sendMavCommand(vehicle->defaultComponentId(),
                            MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE,
                            true,   // show error if fails
                            radius,
                            velocity,
                            altitude,
                            NAN,
                            centerCoord.isValid() ? centerCoord.latitude()  : NAN,
                            centerCoord.isValid() ? centerCoord.longitude() : NAN,
                            centerCoord.isValid() ? centerCoord.altitude()  : NAN);
359 360
}

361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383
void PX4FirmwarePlugin::_mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle)
{
    Q_UNUSED(vehicleId);
    Q_UNUSED(component);
    Q_UNUSED(noReponseFromVehicle);

    Vehicle* vehicle = dynamic_cast<Vehicle*>(sender());
    if (!vehicle) {
        qWarning() << "Dynamic cast failed!";
        return;
    }

    if (command == MAV_CMD_NAV_TAKEOFF && result == MAV_RESULT_ACCEPTED) {
        // Now that we are in takeoff mode we can arm the vehicle which will cause it to takeoff.
        // We specifically don't retry arming if it fails. This way we don't fight with the user if
        // They are trying to disarm.
        disconnect(vehicle, &Vehicle::mavCommandResult, this, &PX4FirmwarePlugin::_mavCommandResult);
        if (!vehicle->armed()) {
            vehicle->setArmed(true);
        }
    }
}

384
void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle)
385
{
386 387
    QString takeoffAltParam("MIS_TAKEOFF_ALT");

388
    if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) {
389
        qgcApp()->showMessage(tr("Unable to takeoff, vehicle position not known."));
390 391 392
        return;
    }

393 394 395 396 397 398
    if (!vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, takeoffAltParam)) {
        qgcApp()->showMessage(tr("Unable to takeoff, MIS_TAKEOFF_ALT parameter missing."));
        return;
    }
    Fact* takeoffAlt = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, takeoffAltParam);

399
    connect(vehicle, &Vehicle::mavCommandResult, this, &PX4FirmwarePlugin::_mavCommandResult);
400 401
    vehicle->sendMavCommand(vehicle->defaultComponentId(),
                            MAV_CMD_NAV_TAKEOFF,
402 403 404 405 406
                            true,                           // show error is fails
                            -1,                             // No pitch requested
                            0, 0,                           // param 2-4 unused
                            NAN, NAN, NAN,                  // No yaw, lat, lon
                            vehicle->altitudeAMSL()->rawValue().toDouble() + takeoffAlt->rawValue().toDouble());
407 408 409 410
}

void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
{
411
    if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) {
412
        qgcApp()->showMessage(tr("Unable to go to location, vehicle position not known."));
413 414 415
        return;
    }

416 417 418 419 420 421 422 423 424 425
    vehicle->sendMavCommand(vehicle->defaultComponentId(),
                            MAV_CMD_DO_REPOSITION,
                            true,   // show error is fails
                            -1.0f,
                            MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
                            0.0f,
                            NAN,
                            gotoCoord.latitude(),
                            gotoCoord.longitude(),
                            vehicle->altitudeAMSL()->rawValue().toFloat());
426 427
}

428
void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange)
429
{
430
    if (!vehicle->homePosition().isValid()) {
431
        qgcApp()->showMessage(tr("Unable to change altitude, home position unknown."));
432 433 434
        return;
    }
    if (qIsNaN(vehicle->homePosition().altitude())) {
435
        qgcApp()->showMessage(tr("Unable to change altitude, home position altitude unknown."));
436 437 438
        return;
    }

439
    double currentAltRel = vehicle->altitudeRelative()->rawValue().toDouble();
Don Gagne's avatar
Don Gagne committed
440
    double newAltRel = currentAltRel + altitudeChange;
441

442 443 444 445 446 447 448 449 450
    vehicle->sendMavCommand(vehicle->defaultComponentId(),
                            MAV_CMD_DO_REPOSITION,
                            true,   // show error is fails
                            -1.0f,
                            MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
                            0.0f,
                            NAN,
                            NAN,
                            NAN,
451
                            vehicle->homePosition().altitude() + newAltRel);
452 453
}

454 455 456
void PX4FirmwarePlugin::startMission(Vehicle* vehicle)
{

457 458 459 460 461 462 463 464
    if (_setFlightModeAndValidate(vehicle, missionFlightMode())) {
        if (!_armVehicleAndValidate(vehicle)) {
            qgcApp()->showMessage(tr("Unable to start mission: Vehicle rejected arming."));
            return;
        }
    } else {
        qgcApp()->showMessage(tr("Unable to start mission: Vehicle not ready."));
    }
465 466
}

467 468 469
void PX4FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode)
{
    if (guidedMode) {
470
        _setFlightModeAndValidate(vehicle, _holdFlightMode);
471 472 473 474
    } else {
        pauseVehicle(vehicle);
    }
}
475 476 477 478

bool PX4FirmwarePlugin::isGuidedMode(const Vehicle* vehicle) const
{
    // Not supported by generic vehicle
479 480
    return (vehicle->flightMode() == _holdFlightMode || vehicle->flightMode() == _takeoffFlightMode
            || vehicle->flightMode() == _landingFlightMode);
481
}
482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502

bool PX4FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
{
    //-- Don't process messages to/from UDP Bridge. It doesn't suffer from these issues
    if (message->compid == MAV_COMP_ID_UDP_BRIDGE) {
        return true;
    }

    switch (message->msgid) {
    case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
        _handleAutopilotVersion(vehicle, message);
        break;
    }

    return true;
}

void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_message_t* message)
{
    Q_UNUSED(vehicle);

503 504
    PX4FirmwarePluginInstanceData* instanceData = qobject_cast<PX4FirmwarePluginInstanceData*>(vehicle->firmwarePluginInstanceData());
    if (!instanceData->versionNotified) {
505 506 507 508 509 510 511 512 513 514 515 516 517 518 519
        bool notifyUser = false;
        int supportedMajorVersion = 1;
        int supportedMinorVersion = 4;
        int supportedPatchVersion = 1;

        mavlink_autopilot_version_t version;
        mavlink_msg_autopilot_version_decode(message, &version);

        if (version.flight_sw_version != 0) {
            int majorVersion, minorVersion, patchVersion;

            majorVersion = (version.flight_sw_version >> (8*3)) & 0xFF;
            minorVersion = (version.flight_sw_version >> (8*2)) & 0xFF;
            patchVersion = (version.flight_sw_version >> (8*1)) & 0xFF;

520 521 522 523 524 525 526 527 528
            if (majorVersion < supportedMajorVersion) {
                notifyUser = true;
            } else if (majorVersion == supportedMajorVersion) {
                if (minorVersion < supportedMinorVersion) {
                    notifyUser = true;
                } else if (minorVersion == supportedMinorVersion) {
                    notifyUser = patchVersion < supportedPatchVersion;
                }
            }
529 530 531 532 533
        } else {
            notifyUser = true;
        }

        if (notifyUser) {
534
            instanceData->versionNotified = true;
535 536 537 538
            qgcApp()->showMessage(QString("QGroundControl supports PX4 Pro firmware Version %1.%2.%3 and above. You are using a version prior to that which will lead to unpredictable results. Please upgrade your firmware.").arg(supportedMajorVersion).arg(supportedMinorVersion).arg(supportedPatchVersion));
        }
    }
}
539

540 541
bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const
{
542 543 544 545 546 547 548
    if (vehicle->isOfflineEditingVehicle()) {
        return FirmwarePlugin::vehicleYawsToNextWaypointInMission(vehicle);
    } else {
        if (vehicle->multiRotor() && vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("MIS_YAWMODE"))) {
            Fact* yawMode = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("MIS_YAWMODE"));
            return yawMode && yawMode->rawValue().toInt() == 1;
        }
549
    }
550
    return true;
551
}