PX4FirmwarePlugin.cc 18.5 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 36 37 38 39 40 41 42 43
const char* PX4FirmwarePlugin::_manualFlightMode =      "Manual";
const char* PX4FirmwarePlugin::_altCtlFlightMode =      "Altitude";
const char* PX4FirmwarePlugin::_posCtlFlightMode =      "Position";
const char* PX4FirmwarePlugin::_missionFlightMode =     "Mission";
const char* PX4FirmwarePlugin::_holdFlightMode =        "Hold";
const char* PX4FirmwarePlugin::_takeoffFlightMode =     "Takeoff";
const char* PX4FirmwarePlugin::_landingFlightMode =     "Land";
const char* PX4FirmwarePlugin::_rtlFlightMode =         "Return";
const char* PX4FirmwarePlugin::_acroFlightMode =        "Acro";
const char* PX4FirmwarePlugin::_offboardFlightMode =    "Offboard";
const char* PX4FirmwarePlugin::_stabilizedFlightMode =  "Stabilized";
const char* PX4FirmwarePlugin::_rattitudeFlightMode =   "Rattitude";
const char* PX4FirmwarePlugin::_followMeFlightMode =    "Follow Me";
const char* PX4FirmwarePlugin::_rtgsFlightMode =        "Return to Groundstation";
const char* PX4FirmwarePlugin::_readyFlightMode =       "Ready";
44
const char* PX4FirmwarePlugin::_simpleFlightMode =      "Simple";
Daniel Agar's avatar
Daniel Agar committed
45

46 47 48
PX4FirmwarePlugin::PX4FirmwarePlugin(void)
    : _versionNotified(false)
{
49 50 51 52 53 54
    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");
55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100

    struct Modes2Name {
        uint8_t     main_mode;
        uint8_t     sub_mode;
        const char* name;       ///< Name for flight 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[] = {
        //main_mode                         sub_mode                                name                                        canBeSet  FW      MC
        { PX4_CUSTOM_MAIN_MODE_MANUAL,      0,                                      PX4FirmwarePlugin::_manualFlightMode,       true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_STABILIZED,  0,                                      PX4FirmwarePlugin::_stabilizedFlightMode,   true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_ACRO,        0,                                      PX4FirmwarePlugin::_acroFlightMode,         true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_RATTITUDE,   0,                                      PX4FirmwarePlugin::_rattitudeFlightMode,    true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_ALTCTL,      0,                                      PX4FirmwarePlugin::_altCtlFlightMode,       true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_POSCTL,      0,                                      PX4FirmwarePlugin::_posCtlFlightMode,       true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_SIMPLE,      0,                                      PX4FirmwarePlugin::_simpleFlightMode,       true,   false,  true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_LOITER,        PX4FirmwarePlugin::_holdFlightMode,         true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_MISSION,       PX4FirmwarePlugin::_missionFlightMode,      true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_RTL,           PX4FirmwarePlugin::_rtlFlightMode,          true,   true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET, PX4FirmwarePlugin::_followMeFlightMode,     true,   false,  true },
        { PX4_CUSTOM_MAIN_MODE_OFFBOARD,    0,                                      PX4FirmwarePlugin::_offboardFlightMode,     true,   false,  true },
        // modes that can't be directly set by the user
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_LAND,          PX4FirmwarePlugin::_landingFlightMode,      false,  true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_READY,         PX4FirmwarePlugin::_readyFlightMode,        false,  true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_RTGS,          PX4FirmwarePlugin::_rtgsFlightMode,         false,  true,   true },
        { PX4_CUSTOM_MAIN_MODE_AUTO,        PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF,       PX4FirmwarePlugin::_takeoffFlightMode,      false,  true,   true },
    };

    // 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;
        info.name =         pModes2Name->name;
        info.canBeSet =     pModes2Name->canBeSet;
        info.fixedWing =    pModes2Name->fixedWing;
        info.multiRotor =   pModes2Name->multiRotor;

        _flightModeInfoList.append(info);
    }
101
}
102

103 104 105
AutoPilotPlugin* PX4FirmwarePlugin::autopilotPlugin(Vehicle* vehicle)
{
    return new PX4AutoPilotPlugin(vehicle, vehicle);
106 107
}

Don Gagne's avatar
Don Gagne committed
108 109 110
QList<VehicleComponent*> PX4FirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle)
{
    Q_UNUSED(vehicle);
dogmaphobic's avatar
dogmaphobic committed
111

Don Gagne's avatar
Don Gagne committed
112 113 114
    return QList<VehicleComponent*>();
}

Daniel Agar's avatar
Daniel Agar committed
115
QStringList PX4FirmwarePlugin::flightModes(Vehicle* vehicle)
Don Gagne's avatar
Don Gagne committed
116 117
{
    QStringList flightModes;
dogmaphobic's avatar
dogmaphobic committed
118

119 120 121 122
    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
123 124 125 126 127

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

            if (fw || mc || other) {
128
                flightModes += info.name;
Daniel Agar's avatar
Daniel Agar committed
129
            }
Don Gagne's avatar
Don Gagne committed
130 131
        }
    }
dogmaphobic's avatar
dogmaphobic committed
132

Don Gagne's avatar
Don Gagne committed
133 134 135
    return flightModes;
}

Don Gagne's avatar
Don Gagne committed
136
QString PX4FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) const
Don Gagne's avatar
Don Gagne committed
137 138
{
    QString flightMode = "Unknown";
dogmaphobic's avatar
dogmaphobic committed
139

Don Gagne's avatar
Don Gagne committed
140 141 142
    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
143

Don Gagne's avatar
Don Gagne committed
144
        bool found = false;
145 146 147
        foreach (const FlightModeInfo_t& info, _flightModeInfoList) {
            if (info.main_mode == px4_mode.main_mode && info.sub_mode == px4_mode.sub_mode) {
                flightMode = info.name;
Don Gagne's avatar
Don Gagne committed
148 149 150 151
                found = true;
                break;
            }
        }
dogmaphobic's avatar
dogmaphobic committed
152

Don Gagne's avatar
Don Gagne committed
153 154 155 156 157 158
        if (!found) {
            qWarning() << "Unknown flight mode" << custom_mode;
        }
    } else {
        qWarning() << "PX4 Flight Stack flight mode without custom mode enabled?";
    }
dogmaphobic's avatar
dogmaphobic committed
159

Don Gagne's avatar
Don Gagne committed
160 161 162 163 164 165 166
    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
167

Don Gagne's avatar
Don Gagne committed
168
    bool found = false;
169 170
    foreach (const FlightModeInfo_t& info, _flightModeInfoList) {
        if (flightMode.compare(info.name, Qt::CaseInsensitive) == 0) {
Don Gagne's avatar
Don Gagne committed
171 172 173
            union px4_custom_mode px4_mode;

            px4_mode.data = 0;
174 175
            px4_mode.main_mode = info.main_mode;
            px4_mode.sub_mode = info.sub_mode;
dogmaphobic's avatar
dogmaphobic committed
176

Don Gagne's avatar
Don Gagne committed
177 178
            *base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
            *custom_mode = px4_mode.data;
dogmaphobic's avatar
dogmaphobic committed
179

Don Gagne's avatar
Don Gagne committed
180 181 182 183
            found = true;
            break;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
184

Don Gagne's avatar
Don Gagne committed
185 186 187
    if (!found) {
        qWarning() << "Unknown flight Mode" << flightMode;
    }
dogmaphobic's avatar
dogmaphobic committed
188

Don Gagne's avatar
Don Gagne committed
189 190
    return found;
}
191 192 193

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

197 198 199 200 201
bool PX4FirmwarePlugin::supportsManualControl(void)
{
    return true;
}

202
bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities)
Don Gagne's avatar
Don Gagne committed
203
{
204
    if (vehicle->multiRotor()) {
205
        return (capabilities & (MavCmdPreflightStorageCapability | GuidedModeCapability | SetFlightModeCapability | PauseVehicleCapability | OrbitModeCapability)) == capabilities;
206 207
    } else {
        return (capabilities & (MavCmdPreflightStorageCapability | GuidedModeCapability | SetFlightModeCapability | PauseVehicleCapability)) == capabilities;
208
    }
Don Gagne's avatar
Don Gagne committed
209
}
210 211 212 213

void PX4FirmwarePlugin::initializeVehicle(Vehicle* vehicle)
{
    Q_UNUSED(vehicle);
dogmaphobic's avatar
dogmaphobic committed
214

215 216
    // PX4 Flight Stack doesn't need to do any extra work
}
217 218 219 220 221 222 223

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

225
void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType)
226
{
227 228 229 230 231 232 233
    PX4ParameterMetaData* px4MetaData = qobject_cast<PX4ParameterMetaData*>(parameterMetaData);

    if (px4MetaData) {
        px4MetaData->addMetaDataToFact(fact, vehicleType);
    } else {
        qWarning() << "Internal error: pointer passed to PX4FirmwarePlugin::addMetaDataToFact not PX4ParameterMetaData";
    }
234
}
Don Gagne's avatar
Don Gagne committed
235 236 237 238 239

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

240
    list << MAV_CMD_NAV_WAYPOINT
241
         << MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TIME << MAV_CMD_NAV_LOITER_TO_ALT
Don Gagne's avatar
Don Gagne committed
242
         << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF
243
         << MAV_CMD_DO_JUMP
Don Gagne's avatar
Don Gagne committed
244
         << MAV_CMD_DO_VTOL_TRANSITION << MAV_CMD_NAV_VTOL_TAKEOFF << MAV_CMD_NAV_VTOL_LAND
245
         << MAV_CMD_DO_DIGICAM_CONTROL
246
         << MAV_CMD_DO_SET_CAM_TRIGG_DIST
247
         << MAV_CMD_DO_SET_SERVO
Don Gagne's avatar
Don Gagne committed
248
         << MAV_CMD_DO_CHANGE_SPEED
249
         << MAV_CMD_DO_LAND_START
250
         << MAV_CMD_DO_MOUNT_CONFIGURE
251
         << MAV_CMD_DO_MOUNT_CONTROL;
Jimmy Johnson's avatar
Jimmy Johnson committed
252

Don Gagne's avatar
Don Gagne committed
253 254
    return list;
}
255

256
QString PX4FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
257
{
258 259 260 261 262 263 264 265 266 267 268
    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
269
        return QStringLiteral(":/json/PX4/MavCmdInfoVTOL.json");
270 271 272 273 274 275 276 277 278 279 280
        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();
    }
281
}
282 283 284 285

QObject* PX4FirmwarePlugin::loadParameterMetaData(const QString& metaDataFile)
{
    PX4ParameterMetaData* metaData = new PX4ParameterMetaData;
286 287 288
    if (!metaDataFile.isEmpty()) {
        metaData->loadParameterFactMetaDataFile(metaDataFile);
    }
289 290
    return metaData;
}
Don Gagne's avatar
Don Gagne committed
291 292 293

void PX4FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
{
294 295 296 297 298 299 300 301 302 303
    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
304
}
305 306 307

void PX4FirmwarePlugin::guidedModeRTL(Vehicle* vehicle)
{
308
    vehicle->setFlightMode(_rtlFlightMode);
309 310 311 312
}

void PX4FirmwarePlugin::guidedModeLand(Vehicle* vehicle)
{
313
    vehicle->setFlightMode(_landingFlightMode);
314 315
}

316 317
void PX4FirmwarePlugin::guidedModeOrbit(Vehicle* vehicle, const QGeoCoordinate& centerCoord, double radius, double velocity, double altitude)
{
318
    if (!isGuidedMode(vehicle)) {
319
        setGuidedMode(vehicle, true);
320 321 322 323 324 325 326 327 328 329 330 331
    }

    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);
332 333
}

334 335 336 337
void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double altitudeRel)
{
    Q_UNUSED(altitudeRel);
    if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) {
338
        qgcApp()->showMessage(tr("Unable to takeoff, vehicle position not known."));
339 340 341
        return;
    }

342 343 344 345 346 347 348 349 350 351
    vehicle->sendMavCommand(vehicle->defaultComponentId(),
                            MAV_CMD_NAV_TAKEOFF,
                            true,   // show error is fails
                            -1.0f,
                            0.0f,
                            0.0f,
                            NAN,
                            NAN,
                            NAN,
                            vehicle->altitudeAMSL()->rawValue().toDouble() + altitudeRel);
352 353 354 355
}

void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
{
356
    if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) {
357
        qgcApp()->showMessage(tr("Unable to go to location, vehicle position not known."));
358 359 360
        return;
    }

361 362 363 364 365 366 367 368 369 370
    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());
371 372 373 374
}

void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel)
{
375
    if (!vehicle->homePositionAvailable()) {
376
        qgcApp()->showMessage(tr("Unable to change altitude, home position unknown."));
377 378 379
        return;
    }
    if (qIsNaN(vehicle->homePosition().altitude())) {
380
        qgcApp()->showMessage(tr("Unable to change altitude, home position altitude unknown."));
381 382 383
        return;
    }

384 385 386 387 388 389 390 391 392 393
    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,
                            vehicle->homePosition().altitude() + altitudeRel);
394 395 396 397 398
}

void PX4FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode)
{
    if (guidedMode) {
399
        vehicle->setFlightMode(_holdFlightMode);
400 401 402 403
    } else {
        pauseVehicle(vehicle);
    }
}
404 405 406 407

bool PX4FirmwarePlugin::isGuidedMode(const Vehicle* vehicle) const
{
    // Not supported by generic vehicle
408 409
    return (vehicle->flightMode() == _holdFlightMode || vehicle->flightMode() == _takeoffFlightMode
            || vehicle->flightMode() == _landingFlightMode);
410
}
411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447

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);

    if (!_versionNotified) {
        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;

448 449 450 451 452 453 454 455 456
            if (majorVersion < supportedMajorVersion) {
                notifyUser = true;
            } else if (majorVersion == supportedMajorVersion) {
                if (minorVersion < supportedMinorVersion) {
                    notifyUser = true;
                } else if (minorVersion == supportedMinorVersion) {
                    notifyUser = patchVersion < supportedPatchVersion;
                }
            }
457 458 459 460 461 462 463 464 465 466
        } else {
            notifyUser = true;
        }

        if (notifyUser) {
            _versionNotified = true;
            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));
        }
    }
}
467 468 469 470 471 472 473 474 475 476 477 478 479 480 481

QString PX4FirmwarePlugin::missionFlightMode(void)
{
    return QString(_missionFlightMode);
}

QString PX4FirmwarePlugin::rtlFlightMode(void)
{
    return QString(_rtlFlightMode);
}

QString PX4FirmwarePlugin::takeControlFlightMode(void)
{
    return QString(_manualFlightMode);
}