FirmwarePlugin.cc 34 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.
 *
 ****************************************************************************/
9

10
#include "FirmwarePlugin.h"
Don Gagne's avatar
Don Gagne committed
11
#include "QGCApplication.h"
12
#include "Generic/GenericAutoPilotPlugin.h"
13
#include "CameraMetaData.h"
14 15
#include "SettingsManager.h"
#include "AppSettings.h"
16
#include "QGCFileDownload.h"
17
#include "QGCCameraManager.h"
Don Gagne's avatar
Don Gagne committed
18

19
#include <QRegularExpression>
Don Gagne's avatar
Don Gagne committed
20 21
#include <QDebug>

22 23
QGC_LOGGING_CATEGORY(FirmwarePluginLog, "FirmwarePluginLog")

24
static FirmwarePluginFactoryRegister* _instance = nullptr;
25

26
const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle.");
27

28 29
QVariantList FirmwarePlugin::_cameraList;

30
const QString FirmwarePlugin::px4FollowMeFlightMode(QObject::tr("Follow Me"));
31 32 33 34 35 36

FirmwarePluginFactory::FirmwarePluginFactory(void)
{
    FirmwarePluginFactoryRegister::instance()->registerPluginFactory(this);
}

37 38 39 40 41 42 43
QList<MAV_TYPE> FirmwarePluginFactory::supportedVehicleTypes(void) const
{
    QList<MAV_TYPE> vehicleTypes;
    vehicleTypes << MAV_TYPE_FIXED_WING << MAV_TYPE_QUADROTOR << MAV_TYPE_VTOL_QUADROTOR << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE;
    return vehicleTypes;
}

44 45 46 47 48 49 50 51 52 53 54 55 56 57
FirmwarePluginFactoryRegister* FirmwarePluginFactoryRegister::instance(void)
{
    if (!_instance) {
        _instance = new FirmwarePluginFactoryRegister;
    }

    return _instance;
}

AutoPilotPlugin* FirmwarePlugin::autopilotPlugin(Vehicle* vehicle)
{
    return new GenericAutoPilotPlugin(vehicle, vehicle);
}

58
bool FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities)
Don Gagne's avatar
Don Gagne committed
59
{
60
    Q_UNUSED(vehicle);
Don Gagne's avatar
Don Gagne committed
61 62 63 64
    Q_UNUSED(capabilities);
    return false;
}

65
QList<VehicleComponent*> FirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle)
Don Gagne's avatar
Don Gagne committed
66 67
{
    Q_UNUSED(vehicle);
68

Don Gagne's avatar
Don Gagne committed
69 70 71
    return QList<VehicleComponent*>();
}

Don Gagne's avatar
Don Gagne committed
72
QString FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) const
Don Gagne's avatar
Don Gagne committed
73 74
{
    QString flightMode;
75

Don Gagne's avatar
Don Gagne committed
76 77 78 79 80
    struct Bit2Name {
        uint8_t     baseModeBit;
        const char* name;
    };
    static const struct Bit2Name rgBit2Name[] = {
81 82 83 84 85 86
    { MAV_MODE_FLAG_MANUAL_INPUT_ENABLED,   "Manual" },
    { MAV_MODE_FLAG_STABILIZE_ENABLED,      "Stabilize" },
    { MAV_MODE_FLAG_GUIDED_ENABLED,         "Guided" },
    { MAV_MODE_FLAG_AUTO_ENABLED,           "Auto" },
    { MAV_MODE_FLAG_TEST_ENABLED,           "Test" },
};
87

Don Gagne's avatar
Don Gagne committed
88
    Q_UNUSED(custom_mode);
89

Don Gagne's avatar
Don Gagne committed
90 91 92 93 94 95 96 97 98 99 100 101 102 103
    if (base_mode == 0) {
        flightMode = "PreFlight";
    } else if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
        flightMode = QString("Custom:0x%1").arg(custom_mode, 0, 16);
    } else {
        for (size_t i=0; i<sizeof(rgBit2Name)/sizeof(rgBit2Name[0]); i++) {
            if (base_mode & rgBit2Name[i].baseModeBit) {
                if (i != 0) {
                    flightMode += " ";
                }
                flightMode += rgBit2Name[i].name;
            }
        }
    }
104

Don Gagne's avatar
Don Gagne committed
105 106 107
    return flightMode;
}

108
bool FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode)
Don Gagne's avatar
Don Gagne committed
109 110 111 112
{
    Q_UNUSED(flightMode);
    Q_UNUSED(base_mode);
    Q_UNUSED(custom_mode);
113

114
    qWarning() << "FirmwarePlugin::setFlightMode called on base class, not supported";
115

Don Gagne's avatar
Don Gagne committed
116 117
    return false;
}
118

119 120 121 122 123
int FirmwarePlugin::defaultJoystickTXMode(void)
{
    return 2;
}

124 125 126 127 128 129
bool FirmwarePlugin::supportsThrottleModeCenterZero(void)
{
    // By default, this is supported
    return true;
}

130
bool FirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/)
131 132 133 134 135
{
    // By default, this is not supported
    return false;
}

136 137 138 139 140
bool FirmwarePlugin::supportsRadio(void)
{
    return true;
}

141 142 143 144 145
bool FirmwarePlugin::supportsMotorInterference(void)
{
    return true;
}

146 147 148 149 150
bool FirmwarePlugin::supportsJSButton(void)
{
    return false;
}

151
bool FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
Don Gagne's avatar
Don Gagne committed
152 153
{
    Q_UNUSED(vehicle);
154
    Q_UNUSED(message);
Don Gagne's avatar
Don Gagne committed
155
    // Generic plugin does no message adjustment
156
    return true;
Don Gagne's avatar
Don Gagne committed
157 158
}

159
void FirmwarePlugin::adjustOutgoingMavlinkMessageThreadSafe(Vehicle* /*vehicle*/, LinkInterface* /*outgoingLink*/, mavlink_message_t* /*message*/)
Don Gagne's avatar
Don Gagne committed
160 161 162
{
    // Generic plugin does no message adjustment
}
163

164
void FirmwarePlugin::initializeVehicle(Vehicle* vehicle)
165 166
{
    Q_UNUSED(vehicle);
167

168 169
    // Generic Flight Stack is by definition "generic", so no extra work
}
170

171
bool FirmwarePlugin::sendHomePositionToVehicle(void)
172 173 174 175 176 177
{
    // Generic stack does not want home position sent in the first position.
    // Subsequent sequence numbers must be adjusted.
    // This is the mavlink spec default.
    return false;
}
178

179
QList<MAV_CMD> FirmwarePlugin::supportedMissionCommands(void)
Don Gagne's avatar
Don Gagne committed
180 181 182 183
{
    // Generic supports all commands
    return QList<MAV_CMD>();
}
184

185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203
QString FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
{
    switch (vehicleType) {
    case MAV_TYPE_GENERIC:
        return QStringLiteral(":/json/MavCmdInfoCommon.json");
    case MAV_TYPE_FIXED_WING:
        return QStringLiteral(":/json/MavCmdInfoFixedWing.json");
    case MAV_TYPE_QUADROTOR:
        return QStringLiteral(":/json/MavCmdInfoMultiRotor.json");
    case MAV_TYPE_VTOL_QUADROTOR:
        return QStringLiteral(":/json/MavCmdInfoVTOL.json");
    case MAV_TYPE_SUBMARINE:
        return QStringLiteral(":/json/MavCmdInfoSub.json");
    case MAV_TYPE_GROUND_ROVER:
        return QStringLiteral(":/json/MavCmdInfoRover.json");
    default:
        qWarning() << "FirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType;
        return QString();
    }
204
}
205

206
void FirmwarePlugin::_getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
207 208 209 210 211
{
    Q_UNUSED(metaDataFile);
    majorVersion = -1;
    minorVersion = -1;
}
Don Gagne's avatar
Don Gagne committed
212 213 214 215 216 217 218 219 220 221 222 223

bool FirmwarePlugin::isGuidedMode(const Vehicle* vehicle) const
{
    // Not supported by generic vehicle
    Q_UNUSED(vehicle);
    return false;
}

void FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode)
{
    Q_UNUSED(vehicle);
    Q_UNUSED(guidedMode);
224
    qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
225 226 227 228 229 230
}

void FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
{
    // Not supported by generic vehicle
    Q_UNUSED(vehicle);
231
    qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
232 233
}

DonLakeFlyer's avatar
DonLakeFlyer committed
234
void FirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL)
Don Gagne's avatar
Don Gagne committed
235 236 237
{
    // Not supported by generic vehicle
    Q_UNUSED(vehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
238
    Q_UNUSED(smartRTL);
239
    qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
240 241 242 243 244 245
}

void FirmwarePlugin::guidedModeLand(Vehicle* vehicle)
{
    // Not supported by generic vehicle
    Q_UNUSED(vehicle);
246
    qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
247 248
}

249
void FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel)
Don Gagne's avatar
Don Gagne committed
250 251 252
{
    // Not supported by generic vehicle
    Q_UNUSED(vehicle);
253
    Q_UNUSED(takeoffAltRel);
254
    qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
255 256 257 258 259 260 261
}

void FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
{
    // Not supported by generic vehicle
    Q_UNUSED(vehicle);
    Q_UNUSED(gotoCoord);
262
    qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
263 264
}

265
void FirmwarePlugin::guidedModeChangeAltitude(Vehicle*, double)
Don Gagne's avatar
Don Gagne committed
266 267
{
    // Not supported by generic vehicle
268
    qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
269
}
270

271
void FirmwarePlugin::startMission(Vehicle*)
272 273
{
    // Not supported by generic vehicle
274
    qgcApp()->showAppMessage(guided_mode_not_supported_by_vehicle);
275 276
}

277 278
const FirmwarePlugin::remapParamNameMajorVersionMap_t& FirmwarePlugin::paramNameRemapMajorVersionMap(void) const
{
Don Gagne's avatar
Don Gagne committed
279 280 281
    static const remapParamNameMajorVersionMap_t remap;

    return remap;
282 283
}

284
int FirmwarePlugin::remapParamNameHigestMinorVersionNumber(int) const
285 286 287
{
    return 0;
}
288

289
QString FirmwarePlugin::vehicleImageOpaque(const Vehicle*) const
290 291 292 293
{
    return QStringLiteral("/qmlimages/vehicleArrowOpaque.svg");
}

294
QString FirmwarePlugin::vehicleImageOutline(const Vehicle*) const
295 296 297 298
{
    return QStringLiteral("/qmlimages/vehicleArrowOutline.svg");
}

299
QString FirmwarePlugin::vehicleImageCompass(const Vehicle*) const
300 301 302
{
    return QStringLiteral("/qmlimages/compassInstrumentArrow.svg");
}
303

304
const QVariantList& FirmwarePlugin::toolIndicators(const Vehicle*)
305 306
{
    //-- Default list of indicators for all vehicles.
307 308
    if(_toolIndicatorList.size() == 0) {
        _toolIndicatorList = QVariantList({
309 310 311 312 313
            QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/MessageIndicator.qml")),
            QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSIndicator.qml")),
            QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/TelemetryRSSIIndicator.qml")),
            QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/RCRSSIIndicator.qml")),
            QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/BatteryIndicator.qml")),
314 315 316 317 318 319 320 321 322 323
        });
    }
    return _toolIndicatorList;
}

const QVariantList& FirmwarePlugin::modeIndicators(const Vehicle*)
{
    //-- Default list of indicators for all vehicles.
    if(_modeIndicatorList.size() == 0) {
        _modeIndicatorList = QVariantList({
324
            QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ROIIndicator.qml")),
DonLakeFlyer's avatar
DonLakeFlyer committed
325
            QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ArmedIndicator.qml")),
326 327
            QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ModeIndicator.qml")),
            QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/VTOLModeIndicator.qml")),
328
            QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/MultiVehicleSelector.qml")),
329 330
            QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/LinkIndicator.qml")),
        });
331
    }
332
    return _modeIndicatorList;
333
}
334

Gus Grubba's avatar
Gus Grubba committed
335
const QVariantList& FirmwarePlugin::cameraList(const Vehicle*)
336 337 338 339
{
    if (_cameraList.size() == 0) {
        CameraMetaData* metaData;

Gus Grubba's avatar
Gus Grubba committed
340
        metaData = new CameraMetaData(
341 342
            //tr("Canon S100 @ 5.2mm f/2"),
            tr("Canon S100 PowerShot"),
Gus Grubba's avatar
Gus Grubba committed
343 344 345 346 347 348 349 350 351
            7.6,                 // sensorWidth
            5.7,                 // sensorHeight
            4000,                // imageWidth
            3000,                // imageHeight
            5.2,                 // focalLength
            true,                // true: landscape orientation
            false,               // true: camera is fixed orientation
            0,                   // minimum trigger interval
            this);               // parent
352 353
        _cameraList.append(QVariant::fromValue(metaData));

Gus Grubba's avatar
Gus Grubba committed
354
        metaData = new CameraMetaData(
355 356
            //tr("Canon EOS-M 22mm f/2"),
            tr("Canon EOS-M 22mm"),
Gus Grubba's avatar
Gus Grubba committed
357 358 359 360 361 362 363 364 365
            22.3,                // sensorWidth
            14.9,                // sensorHeight
            5184,                // imageWidth
            3456,                // imageHeight
            22,                  // focalLength
            true,                // true: landscape orientation
            false,               // true: camera is fixed orientation
            0,                   // minimum trigger interval
            this);               // parent
366 367
        _cameraList.append(QVariant::fromValue(metaData));

Gus Grubba's avatar
Gus Grubba committed
368
        metaData = new CameraMetaData(
369 370
            //tr("Canon G9X @ 10.2mm f/2"),
            tr("Canon G9 X PowerShot"),
Gus Grubba's avatar
Gus Grubba committed
371 372 373 374 375 376 377 378 379
            13.2,                // sensorWidth
            8.8,                 // sensorHeight
            5488,                // imageWidth
            3680,                // imageHeight
            10.2,                // focalLength
            true,                // true: landscape orientation
            false,               // true: camera is fixed orientation
            0,                   // minimum trigger interval
            this);               // parent
380 381
        _cameraList.append(QVariant::fromValue(metaData));

Gus Grubba's avatar
Gus Grubba committed
382
        metaData = new CameraMetaData(
383 384
            //tr("Canon SX260 HS @ 4.5mm f/3.5"),
            tr("Canon SX260 HS PowerShot"),
Gus Grubba's avatar
Gus Grubba committed
385 386 387 388 389 390 391 392 393
            6.17,                // sensorWidth
            4.55,                // sensorHeight
            4000,                // imageWidth
            3000,                // imageHeight
            4.5,                 // focalLength
            true,                // true: landscape orientation
            false,               // true: camera is fixed orientation
            0,                   // minimum trigger interval
            this);               // parent
394 395
        _cameraList.append(QVariant::fromValue(metaData));

Gus Grubba's avatar
Gus Grubba committed
396 397 398 399 400 401 402 403 404 405 406
        metaData = new CameraMetaData(
            tr("GoPro Hero 4"),
            6.17,               // sensorWidth
            4.55,               // sendsorHeight
            4000,               // imageWidth
            3000,               // imageHeight
            2.98,               // focalLength
            true,               // landscape
            false,              // fixedOrientation
            0,                  // minTriggerInterval
            this);
407
        _cameraList.append(QVariant::fromValue(metaData));
408

Gus Grubba's avatar
Gus Grubba committed
409
        metaData = new CameraMetaData(
410 411
            //tr("Parrot Sequoia RGB"),
            tr("Parrot Sequioa RGB"),
Gus Grubba's avatar
Gus Grubba committed
412 413 414 415 416 417 418 419 420
            6.17,               // sensorWidth
            4.63,               // sendsorHeight
            4608,               // imageWidth
            3456,               // imageHeight
            4.9,                // focalLength
            true,               // landscape
            false,              // fixedOrientation
            1,                  // minTriggerInterval
            this);
421 422
        _cameraList.append(QVariant::fromValue(metaData));

Gus Grubba's avatar
Gus Grubba committed
423
        metaData = new CameraMetaData(
424 425
            //tr("Parrot Sequoia Monochrome"),
            tr("Parrot Sequioa Monochrome"),
Gus Grubba's avatar
Gus Grubba committed
426 427 428 429 430 431 432 433 434
            4.8,                // sensorWidth
            3.6,                // sendsorHeight
            1280,               // imageWidth
            960,                // imageHeight
            4.0,                // focalLength
            true,               // landscape
            false,              // fixedOrientation
            0.8,                // minTriggerInterval
            this);
435
        _cameraList.append(QVariant::fromValue(metaData));
André's avatar
André committed
436

Gus Grubba's avatar
Gus Grubba committed
437 438 439 440 441 442 443 444 445 446 447
        metaData = new CameraMetaData(
            tr("RedEdge"),
            4.8,                // sensorWidth
            3.6,                // sendsorHeight
            1280,               // imageWidth
            960,                // imageHeight
            5.5,                // focalLength
            true,               // landscape
            false,              // fixedOrientation
            0,                  // minTriggerInterval
            this);
André's avatar
André committed
448
        _cameraList.append(QVariant::fromValue(metaData));
DonLakeFlyer's avatar
DonLakeFlyer committed
449

Gus Grubba's avatar
Gus Grubba committed
450
        metaData = new CameraMetaData(
451 452
            //tr("Ricoh GR II 18.3mm f/2.8"),
            tr("Ricoh GR II"),
Gus Grubba's avatar
Gus Grubba committed
453 454 455 456 457 458 459 460 461
            23.7,               // sensorWidth
            15.7,               // sendsorHeight
            4928,               // imageWidth
            3264,               // imageHeight
            18.3,               // focalLength
            true,               // landscape
            false,              // fixedOrientation
            0,                  // minTriggerInterval
            this);
DonLakeFlyer's avatar
DonLakeFlyer committed
462 463
        _cameraList.append(QVariant::fromValue(metaData));

Gus Grubba's avatar
Gus Grubba committed
464 465 466 467 468 469 470 471 472 473 474
        metaData = new CameraMetaData(
            tr("Sentera Double 4K Sensor"),
            6.2,                // sensorWidth
            4.65,               // sendsorHeight
            4000,               // imageWidth
            3000,               // imageHeight
            5.4,                // focalLength
            true,               // landscape
            false,              // fixedOrientation
            0,                  // minTriggerInterval
            this);
DonLakeFlyer's avatar
DonLakeFlyer committed
475
        _cameraList.append(QVariant::fromValue(metaData));
476

Gus Grubba's avatar
Gus Grubba committed
477 478 479 480 481 482 483 484 485 486 487
        metaData = new CameraMetaData(
            tr("Sentera NDVI Single Sensor"),
            4.68,               // sensorWidth
            3.56,               // sendsorHeight
            1248,               // imageWidth
            952,                // imageHeight
            4.14,               // focalLength
            true,               // landscape
            false,              // fixedOrientation
            0,                  // minTriggerInterval
            this);
488 489
        _cameraList.append(QVariant::fromValue(metaData));

Gus Grubba's avatar
Gus Grubba committed
490 491
        metaData = new CameraMetaData(
            //-- http://www.sony.co.uk/electronics/interchangeable-lens-cameras/ilce-6000-body-kit#product_details_default
492 493
            //tr("Sony a6000 Sony 16mm f/2.8"),
            tr("Sony a6000 16mm"),
Gus Grubba's avatar
Gus Grubba committed
494 495 496 497 498 499 500 501 502
            23.5,               // sensorWidth
            15.6,               // sensorHeight
            6000,               // imageWidth
            4000,               // imageHeight
            16,                 // focalLength
            true,               // true: landscape orientation
            false,              // true: camera is fixed orientation
            2.0,                // minimum trigger interval
            this);              // parent
503
        _cameraList.append(QVariant::fromValue(metaData));
Jared Szechy's avatar
Jared Szechy committed
504

Gus Grubba's avatar
Gus Grubba committed
505 506 507 508 509 510 511 512 513 514 515
        metaData = new CameraMetaData(
            tr("Sony a6300 Zeiss 21mm f/2.8"),
            23.5,               // sensorWidth
            15.6,               // sensorHeight
            6000,               // imageWidth
            4000,               // imageHeight
            21,                 // focalLength
            true,               // true: landscape orientation
            true,               // true: camera is fixed orientation
            2.0,                // minimum trigger interval
            this);              // parent
Jared Szechy's avatar
Jared Szechy committed
516
        _cameraList.append(QVariant::fromValue(metaData));
Don Gagne's avatar
Don Gagne committed
517

Gus Grubba's avatar
Gus Grubba committed
518 519 520 521 522 523 524 525 526 527 528
        metaData = new CameraMetaData(
            tr("Sony a6300 Sony 28mm f/2.0"),
            23.5,               // sensorWidth
            15.6,               // sensorHeight
            6000,               // imageWidth
            4000,               // imageHeight
            28,                 // focalLength
            true,               // true: landscape orientation
            true,               // true: camera is fixed orientation
            2.0,                // minimum trigger interval
            this);              // parent
Don Gagne's avatar
Don Gagne committed
529 530
        _cameraList.append(QVariant::fromValue(metaData));

Gus Grubba's avatar
Gus Grubba committed
531 532 533 534 535 536 537 538 539 540 541
        metaData = new CameraMetaData(
            tr("Sony a7R II Zeiss 21mm f/2.8"),
            35.814,             // sensorWidth
            23.876,             // sensorHeight
            7952,               // imageWidth
            5304,               // imageHeight
            21,                 // focalLength
            true,               // true: landscape orientation
            true,               // true: camera is fixed orientation
            2.0,                // minimum trigger interval
            this);              // parent
Don Gagne's avatar
Don Gagne committed
542
        _cameraList.append(QVariant::fromValue(metaData));
Gus Grubba's avatar
Gus Grubba committed
543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568

        metaData = new CameraMetaData(
            tr("Sony a7R II Sony 28mm f/2.0"),
            35.814,             // sensorWidth
            23.876,             // sensorHeight
            7952,               // imageWidth
            5304,               // imageHeight
            28,                 // focalLength
            true,               // true: landscape orientation
            true,               // true: camera is fixed orientation
            2.0,                // minimum trigger interval
            this);              // parent
        _cameraList.append(QVariant::fromValue(metaData));

        metaData = new CameraMetaData(
            tr("Sony DSC-QX30U @ 4.3mm f/3.5"),
            7.82,               // sensorWidth
            5.865,              // sensorHeight
            5184,               // imageWidth
            3888,               // imageHeight
            4.3,                // focalLength
            true,               // true: landscape orientation
            false,              // true: camera is fixed orientation
            2.0,                // minimum trigger interval
            this);              // parent
        _cameraList.append(QVariant::fromValue(metaData));
Paul Picazo's avatar
Paul Picazo committed
569 570 571 572 573 574 575 576 577 578 579 580 581
        
        metaData = new CameraMetaData(
            tr("Sony DSC-RX0"),
            13.2,               // sensorWidth
            8.8,                // sensorHeight
            4800,               // imageWidth
            3200,               // imageHeight
            7.7,                // focalLength
            true,               // true: landscape orientation
            false,              // true: camera is fixed orientation
            0,                  // minimum trigger interval
            this);              // parent
        _cameraList.append(QVariant::fromValue(metaData));
Gus Grubba's avatar
Gus Grubba committed
582 583 584 585

        metaData = new CameraMetaData(
            //-- http://www.sony.co.uk/electronics/interchangeable-lens-cameras/ilce-qx1-body-kit/specifications
            //-- http://www.sony.com/electronics/camera-lenses/sel16f28/specifications
586 587
            //tr("Sony ILCE-QX1 Sony 16mm f/2.8"),
            tr("Sony ILCE-QX1"),
Gus Grubba's avatar
Gus Grubba committed
588 589 590 591 592 593 594 595 596 597 598 599 600
            23.2,                // sensorWidth
            15.4,                // sensorHeight
            5456,                // imageWidth
            3632,                // imageHeight
            16,                  // focalLength
            true,                // true: landscape orientation
            false,               // true: camera is fixed orientation
            0,                   // minimum trigger interval
            this);               // parent
        _cameraList.append(QVariant::fromValue(metaData));

        metaData = new CameraMetaData(
            //-- http://www.sony.co.uk/electronics/interchangeable-lens-cameras/ilce-qx1-body-kit/specifications
601 602
            //tr("Sony NEX-5R Sony 20mm f/2.8"),
            tr("Sony NEX-5R 20mm"),
Gus Grubba's avatar
Gus Grubba committed
603 604 605 606 607 608 609 610 611 612 613 614
            23.2,                // sensorWidth
            15.4,                // sensorHeight
            4912,                // imageWidth
            3264,                // imageHeight
            20,                  // focalLength
            true,                // true: landscape orientation
            false,               // true: camera is fixed orientation
            1,                   // minimum trigger interval
            this);               // parent
        _cameraList.append(QVariant::fromValue(metaData));

        metaData = new CameraMetaData(
615 616
            //tr("Sony RX100 II @ 10.4mm f/1.8"),
            tr("Sony RX100 II 28mm"),
Gus Grubba's avatar
Gus Grubba committed
617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679
            13.2,                // sensorWidth
            8.8,                 // sensorHeight
            5472,                // imageWidth
            3648,                // imageHeight
            10.4,                // focalLength
            true,                // true: landscape orientation
            false,               // true: camera is fixed orientation
            0,                   // minimum trigger interval
            this);               // parent
        _cameraList.append(QVariant::fromValue(metaData));

        metaData = new CameraMetaData(
            tr("Yuneec CGOET"),
            5.6405,             // sensorWidth
            3.1813,             // sensorHeight
            1920,               // imageWidth
            1080,               // imageHeight
            3.5,                // focalLength
            true,               // true: landscape orientation
            true,               // true: camera is fixed orientation
            1.3,                // minimum trigger interval
            this);              // parent
        _cameraList.append(QVariant::fromValue(metaData));

        metaData = new CameraMetaData(
            tr("Yuneec E10T"),
            5.6405,             // sensorWidth
            3.1813,             // sensorHeight
            1920,               // imageWidth
            1080,               // imageHeight
            23,                 // focalLength
            true,               // true: landscape orientation
            true,               // true: camera is fixed orientation
            1.3,                // minimum trigger interval
            this);              // parent
        _cameraList.append(QVariant::fromValue(metaData));

        metaData = new CameraMetaData(
            tr("Yuneec E50"),
            6.2372,             // sensorWidth
            4.7058,             // sensorHeight
            4000,               // imageWidth
            3000,               // imageHeight
            7.2,                // focalLength
            true,               // true: landscape orientation
            true,               // true: camera is fixed orientation
            1.3,                // minimum trigger interval
            this);              // parent
        _cameraList.append(QVariant::fromValue(metaData));

        metaData = new CameraMetaData(
            tr("Yuneec E90"),
            13.3056,            // sensorWidth
            8.656,              // sensorHeight
            5472,               // imageWidth
            3648,               // imageHeight
            8.29,               // focalLength
            true,               // true: landscape orientation
            true,               // true: camera is fixed orientation
            1.3,                // minimum trigger interval
            this);              // parent
        _cameraList.append(QVariant::fromValue(metaData));

Yuya Yabe's avatar
Yuya Yabe committed
680 681 682 683 684 685 686 687 688 689 690 691 692
        metaData = new CameraMetaData(
            tr("Flir Duo R"),
            160,                // sensorWidth
            120,                // sensorHeight
            1920,               // imageWidth
            1080,               // imageHeight
            1.9,                // focalLength
            true,               // true: landscape orientation
            true,               // true: camera is fixed orientation
            0,                  // minimum trigger interval
            this);              // parent
        _cameraList.append(QVariant::fromValue(metaData));

693 694 695 696
    }

    return _cameraList;
}
697

698 699
QMap<QString, FactGroup*>* FirmwarePlugin::factGroups(void) {
    // Generic plugin has no FactGroups
Gus Grubba's avatar
Gus Grubba committed
700
    return nullptr;
701 702
}

703 704 705 706
bool FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const
{
    return vehicle->multiRotor() ? false : true;
}
707

708
bool FirmwarePlugin::_armVehicleAndValidate(Vehicle* vehicle)
709
{
710 711 712 713 714 715 716 717
    if (vehicle->armed()) {
        return true;
    }

    bool armedChanged = false;

    // We try arming 3 times
    for (int retries=0; retries<3; retries++) {
718
        vehicle->setArmed(true);
719 720 721 722 723 724 725 726 727 728 729 730 731

        // Wait for vehicle to return armed state for 3 seconds
        for (int i=0; i<30; i++) {
            if (vehicle->armed()) {
                armedChanged = true;
                break;
            }
            QGC::SLEEP::msleep(100);
            qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
        }
        if (armedChanged) {
            break;
        }
732 733
    }

734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749
    return armedChanged;
}

bool FirmwarePlugin::_setFlightModeAndValidate(Vehicle* vehicle, const QString& flightMode)
{
    if (vehicle->flightMode() == flightMode) {
        return true;
    }

    bool flightModeChanged = false;

    // We try 3 times
    for (int retries=0; retries<3; retries++) {
        vehicle->setFlightMode(flightMode);

        // Wait for vehicle to return flight mode
750
        for (int i=0; i<13; i++) {
751 752 753 754 755 756 757 758
            if (vehicle->flightMode() == flightMode) {
                flightModeChanged = true;
                break;
            }
            QGC::SLEEP::msleep(100);
            qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
        }
        if (flightModeChanged) {
759 760 761
            break;
        }
    }
762 763

    return flightModeChanged;
764
}
765

766

Don Gagne's avatar
Don Gagne committed
767
void FirmwarePlugin::batteryConsumptionData(Vehicle* vehicle, int& mAhBattery, double& hoverAmps, double& cruiseAmps) const
768 769
{
    Q_UNUSED(vehicle);
770 771 772
    mAhBattery  = 0;
    hoverAmps   = 0;
    cruiseAmps  = 0;
773
}
774 775 776 777 778 779

QString FirmwarePlugin::autoDisarmParameter(Vehicle* vehicle)
{
    Q_UNUSED(vehicle);
    return QString();
}
780

781 782 783 784 785 786 787 788
bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitchSupported, bool& yawSupported)
{
    Q_UNUSED(vehicle);
    rollSupported = false;
    pitchSupported = false;
    yawSupported = false;
    return false;
}
789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804

bool FirmwarePlugin::isVtol(const Vehicle* vehicle) const
{
    switch (vehicle->vehicleType()) {
    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:
        return true;
    default:
        return false;
    }
}
805

806
QGCCameraManager* FirmwarePlugin::createCameraManager(Vehicle* vehicle)
807
{
808
    return new QGCCameraManager(vehicle);
809 810 811 812
}

QGCCameraControl* FirmwarePlugin::createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject* parent)
{
813
    return new QGCCameraControl(info, vehicle, compID, parent);
814 815
}

816 817 818 819 820
uint32_t FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode)
{
    // Standard implementation assumes no special handling. Upper part of 32 bit value is not used.
    return hlCustomMode;
}
821

822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839
void FirmwarePlugin::checkIfIsLatestStable(Vehicle* vehicle)
{
    // This is required as mocklink uses a hardcoded firmware version
    if (qgcApp()->runningUnitTests()) {
        qCDebug(FirmwarePluginLog) << "Skipping version check";
        return;
    }
    QString versionFile = _getLatestVersionFileUrl(vehicle);
    qCDebug(FirmwarePluginLog) << "Downloading" << versionFile;
    QGCFileDownload* downloader = new QGCFileDownload(this);
    connect(
        downloader,
        &QGCFileDownload::downloadFinished,
        this,
        [vehicle, this](QString remoteFile, QString localFile) {
            _versionFileDownloadFinished(remoteFile, localFile, vehicle);
            sender()->deleteLater();
        });
840 841 842 843 844 845 846 847
    connect(
          downloader,
          &QGCFileDownload::error,
          this,
          [=](QString errorMsg) {
              qCDebug(FirmwarePluginLog) << "Failed to download the latest fw version file. Error: " << errorMsg;
              downloader->deleteLater();
          });
848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878
    downloader->download(versionFile);
}

void FirmwarePlugin::_versionFileDownloadFinished(QString& remoteFile, QString& localFile, Vehicle* vehicle)
{
    qCDebug(FirmwarePluginLog) << "Download complete" << remoteFile << localFile;
    // Now read the version file and pull out the version string
    QFile versionFile(localFile);
    if (!versionFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
        qCWarning(FirmwarePluginLog) << "Error opening downloaded version file.";
        return;
    }

    QTextStream stream(&versionFile);
    QString versionFileContents = stream.readAll();
    QString version;
    QRegularExpressionMatch match = QRegularExpression(_versionRegex()).match(versionFileContents);

    qCDebug(FirmwarePluginLog) << "Looking for version number...";

    if (match.hasMatch()) {
        version = match.captured(1);
    } else {
        qCWarning(FirmwarePluginLog) << "Unable to parse version info from file" << remoteFile;
        return;
    }

    qCDebug(FirmwarePluginLog) << "Latest stable version = "  << version;

    int currType = vehicle->firmwareVersionType();

879
    // Check if lower version than stable or same version but different type
880
    if (currType == FIRMWARE_VERSION_TYPE_OFFICIAL && vehicle->versionCompare(version) < 0) {
881 882 883
        QString currentVersionNumber = QString("%1.%2.%3").arg(vehicle->firmwareMajorVersion())
                .arg(vehicle->firmwareMinorVersion())
                .arg(vehicle->firmwarePatchVersion());
884
        qgcApp()->showAppMessage(tr("Vehicle is not running latest stable firmware! Running %1, latest stable is %2.").arg(currentVersionNumber, version));
885 886
    }
}
887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918

int FirmwarePlugin::versionCompare(Vehicle* vehicle, int major, int minor, int patch)
{
    int currMajor = vehicle->firmwareMajorVersion();
    int currMinor = vehicle->firmwareMinorVersion();
    int currPatch = vehicle->firmwarePatchVersion();

    if (currMajor == major && currMinor == minor && currPatch == patch) {
        return 0;
    }

    if (currMajor > major
       || (currMajor == major && currMinor > minor)
       || (currMajor == major && currMinor == minor && currPatch > patch))
    {
        return 1;
    }
    return -1;
}

int FirmwarePlugin::versionCompare(Vehicle* vehicle, QString& compare)
{
    QStringList versionNumbers = compare.split(".");
    if(versionNumbers.size() != 3) {
        qCWarning(FirmwarePluginLog) << "Error parsing version number: wrong format";
        return -1;
    }
    int major = versionNumbers[0].toInt();
    int minor = versionNumbers[1].toInt();
    int patch = versionNumbers[2].toInt();
    return versionCompare(vehicle, major, minor, patch);
}
Don Gagne's avatar
Don Gagne committed
919 920 921 922 923

QString FirmwarePlugin::gotoFlightMode(void) const
{
    return QString();
}
924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946

void FirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimationCapabilities)
{
    MAVLinkProtocol* mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol();

    mavlink_follow_target_t follow_target = {};

    follow_target.timestamp =           qgcApp()->msecsSinceBoot();
    follow_target.est_capabilities =    estimationCapabilities;
    follow_target.position_cov[0] =     static_cast<float>(motionReport.pos_std_dev[0]);
    follow_target.position_cov[2] =     static_cast<float>(motionReport.pos_std_dev[2]);
    follow_target.alt =                 static_cast<float>(motionReport.altMetersAMSL);
    follow_target.lat =                 motionReport.lat_int;
    follow_target.lon =                 motionReport.lon_int;
    follow_target.vel[0] =              static_cast<float>(motionReport.vxMetersPerSec);
    follow_target.vel[1] =              static_cast<float>(motionReport.vyMetersPerSec);

    mavlink_message_t message;
    mavlink_msg_follow_target_encode_chan(static_cast<uint8_t>(mavlinkProtocol->getSystemId()),
                                          static_cast<uint8_t>(mavlinkProtocol->getComponentId()),
                                          vehicle->priorityLink()->mavlinkChannel(),
                                          &message,
                                          &follow_target);
947
    vehicle->sendMessageOnLinkThreadSafe(vehicle->priorityLink(), message);
948
}