Newer
Older
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "Generic/GenericAutoPilotPlugin.h"
#include "SettingsManager.h"
#include "AppSettings.h"
Willian Galvani
committed
#include "QGCFileDownload.h"
Willian Galvani
committed
#include <QRegularExpression>
QGC_LOGGING_CATEGORY(FirmwarePluginLog, "FirmwarePluginLog")
static FirmwarePluginFactoryRegister* _instance = nullptr;
const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle.");
QVariantList FirmwarePlugin::_cameraList;
const QString FirmwarePlugin::px4FollowMeFlightMode(QObject::tr("Follow Me"));
FirmwarePluginFactory::FirmwarePluginFactory(void)
{
FirmwarePluginFactoryRegister::instance()->registerPluginFactory(this);
}
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;
}
FirmwarePluginFactoryRegister* FirmwarePluginFactoryRegister::instance(void)
{
if (!_instance) {
_instance = new FirmwarePluginFactoryRegister;
}
return _instance;
}
AutoPilotPlugin* FirmwarePlugin::autopilotPlugin(Vehicle* vehicle)
{
return new GenericAutoPilotPlugin(vehicle, vehicle);
}
bool FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities)
QList<VehicleComponent*> FirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle)
QString FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) const
struct Bit2Name {
uint8_t baseModeBit;
const char* name;
};
static const struct Bit2Name rgBit2Name[] = {
{ 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" },
};
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;
}
}
}
bool FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode)
{
Q_UNUSED(flightMode);
Q_UNUSED(base_mode);
Q_UNUSED(custom_mode);
qWarning() << "FirmwarePlugin::setFlightMode called on base class, not supported";
int FirmwarePlugin::defaultJoystickTXMode(void)
{
return 2;
}
bool FirmwarePlugin::supportsThrottleModeCenterZero(void)
{
// By default, this is supported
return true;
}
Gus Grubba
committed
bool FirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/)
{
// By default, this is not supported
return false;
}
bool FirmwarePlugin::supportsRadio(void)
{
return true;
}
bool FirmwarePlugin::supportsMotorInterference(void)
{
return true;
}
bool FirmwarePlugin::supportsJSButton(void)
{
return false;
}
bool FirmwarePlugin::supportsTerrainFrame(void) const
{
// Generic firmware supports this since we don't know
return true;
}
bool FirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
void FirmwarePlugin::adjustOutgoingMavlinkMessage(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message)
Q_UNUSED(outgoingLink);
Q_UNUSED(message);
// Generic plugin does no message adjustment
}
void FirmwarePlugin::initializeVehicle(Vehicle* vehicle)
// Generic Flight Stack is by definition "generic", so no extra work
}
bool FirmwarePlugin::sendHomePositionToVehicle(void)
{
// 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;
}
QList<MAV_CMD> FirmwarePlugin::supportedMissionCommands(void)
{
// Generic supports all commands
return QList<MAV_CMD>();
}
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();
}
void FirmwarePlugin::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion)
{
Q_UNUSED(metaDataFile);
majorVersion = -1;
minorVersion = -1;
}
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);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
}
void FirmwarePlugin::pauseVehicle(Vehicle* vehicle)
{
// Not supported by generic vehicle
Q_UNUSED(vehicle);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
{
// Not supported by generic vehicle
Q_UNUSED(vehicle);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
}
void FirmwarePlugin::guidedModeLand(Vehicle* vehicle)
{
// Not supported by generic vehicle
Q_UNUSED(vehicle);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
void FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel)
{
// Not supported by generic vehicle
Q_UNUSED(vehicle);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
}
void FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
{
// Not supported by generic vehicle
Q_UNUSED(vehicle);
Q_UNUSED(gotoCoord);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
}
void FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel)
{
// Not supported by generic vehicle
Q_UNUSED(vehicle);
Q_UNUSED(altitudeRel);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
void FirmwarePlugin::startMission(Vehicle* vehicle)
{
// Not supported by generic vehicle
Q_UNUSED(vehicle);
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
}
const FirmwarePlugin::remapParamNameMajorVersionMap_t& FirmwarePlugin::paramNameRemapMajorVersionMap(void) const
{
static const remapParamNameMajorVersionMap_t remap;
return remap;
}
int FirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const
{
Q_UNUSED(majorVersionNumber);
return 0;
}
QString FirmwarePlugin::vehicleImageOpaque(const Vehicle* vehicle) const
{
Q_UNUSED(vehicle);
return QStringLiteral("/qmlimages/vehicleArrowOpaque.svg");
}
QString FirmwarePlugin::vehicleImageOutline(const Vehicle* vehicle) const
{
Q_UNUSED(vehicle);
return QStringLiteral("/qmlimages/vehicleArrowOutline.svg");
}
QString FirmwarePlugin::vehicleImageCompass(const Vehicle* vehicle) const
{
Q_UNUSED(vehicle);
return QStringLiteral("/qmlimages/compassInstrumentArrow.svg");
}
const QVariantList &FirmwarePlugin::toolBarIndicators(const Vehicle* vehicle)
{
Q_UNUSED(vehicle);
//-- Default list of indicators for all vehicles.
if(_toolBarIndicatorList.size() == 0) {
_toolBarIndicatorList = QVariantList({
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/MultiVehicleSelector.qml")),
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")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ModeIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/VTOLModeIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/ArmedIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSRTKIndicator.qml")),
QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/LinkIndicator.qml")),
});
}
return _toolBarIndicatorList;
}
const QVariantList& FirmwarePlugin::cameraList(const Vehicle* vehicle)
{
Q_UNUSED(vehicle);
if (_cameraList.size() == 0) {
CameraMetaData* metaData;
Gus Grubba
committed
//tr("Canon S100 @ 5.2mm f/2"),
tr("Canon S100 PowerShot"),
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
_cameraList.append(QVariant::fromValue(metaData));
Gus Grubba
committed
//tr("Canon EOS-M 22mm f/2"),
tr("Canon EOS-M 22mm"),
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
_cameraList.append(QVariant::fromValue(metaData));
Gus Grubba
committed
//tr("Canon G9X @ 10.2mm f/2"),
tr("Canon G9 X PowerShot"),
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
_cameraList.append(QVariant::fromValue(metaData));
Gus Grubba
committed
//tr("Canon SX260 HS @ 4.5mm f/3.5"),
tr("Canon SX260 HS PowerShot"),
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
_cameraList.append(QVariant::fromValue(metaData));
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);
_cameraList.append(QVariant::fromValue(metaData));
Gus Grubba
committed
//tr("Parrot Sequoia RGB"),
tr("Parrot Sequioa RGB"),
6.17, // sensorWidth
4.63, // sendsorHeight
4608, // imageWidth
3456, // imageHeight
4.9, // focalLength
true, // landscape
false, // fixedOrientation
1, // minTriggerInterval
this);
_cameraList.append(QVariant::fromValue(metaData));
Gus Grubba
committed
//tr("Parrot Sequoia Monochrome"),
tr("Parrot Sequioa Monochrome"),
4.8, // sensorWidth
3.6, // sendsorHeight
1280, // imageWidth
960, // imageHeight
4.0, // focalLength
true, // landscape
false, // fixedOrientation
0.8, // minTriggerInterval
this);
_cameraList.append(QVariant::fromValue(metaData));
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);
Gus Grubba
committed
//tr("Ricoh GR II 18.3mm f/2.8"),
tr("Ricoh GR II"),
23.7, // sensorWidth
15.7, // sendsorHeight
4928, // imageWidth
3264, // imageHeight
18.3, // focalLength
true, // landscape
false, // fixedOrientation
0, // minTriggerInterval
this);
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);
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);
_cameraList.append(QVariant::fromValue(metaData));
metaData = new CameraMetaData(
//-- http://www.sony.co.uk/electronics/interchangeable-lens-cameras/ilce-6000-body-kit#product_details_default
Gus Grubba
committed
//tr("Sony a6000 Sony 16mm f/2.8"),
tr("Sony a6000 16mm"),
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
_cameraList.append(QVariant::fromValue(metaData));
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
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
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
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
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));
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
Gus Grubba
committed
//tr("Sony ILCE-QX1 Sony 16mm f/2.8"),
tr("Sony ILCE-QX1"),
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
Gus Grubba
committed
//tr("Sony NEX-5R Sony 20mm f/2.8"),
tr("Sony NEX-5R 20mm"),
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(
Gus Grubba
committed
//tr("Sony RX100 II @ 10.4mm f/1.8"),
tr("Sony RX100 II 28mm"),
613
614
615
616
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
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));
}
return _cameraList;
}
QMap<QString, FactGroup*>* FirmwarePlugin::factGroups(void) {
// Generic plugin has no FactGroups
bool FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const
{
return vehicle->multiRotor() ? false : true;
}
bool FirmwarePlugin::_armVehicleAndValidate(Vehicle* vehicle)
if (vehicle->armed()) {
return true;
}
bool armedChanged = false;
// We try arming 3 times
for (int retries=0; retries<3; retries++) {
// 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;
}
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
for (int i=0; i<13; i++) {
if (vehicle->flightMode() == flightMode) {
flightModeChanged = true;
break;
}
QGC::SLEEP::msleep(100);
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
}
if (flightModeChanged) {
return flightModeChanged;
void FirmwarePlugin::batteryConsumptionData(Vehicle* vehicle, int& mAhBattery, double& hoverAmps, double& cruiseAmps) const
mAhBattery = 0;
hoverAmps = 0;
cruiseAmps = 0;
QString FirmwarePlugin::autoDisarmParameter(Vehicle* vehicle)
{
Q_UNUSED(vehicle);
return QString();
}
bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitchSupported, bool& yawSupported)
{
Q_UNUSED(vehicle);
rollSupported = false;
pitchSupported = false;
yawSupported = false;
return false;
}
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;
}
}
QGCCameraManager* FirmwarePlugin::createCameraManager(Vehicle* vehicle)
return new QGCCameraManager(vehicle);
}
QGCCameraControl* FirmwarePlugin::createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject* parent)
{
return new QGCCameraControl(info, vehicle, compID, parent);
uint32_t FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode)
{
// Standard implementation assumes no special handling. Upper part of 32 bit value is not used.
return hlCustomMode;
}
Willian Galvani
committed
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
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();
});
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();
// Check if lower version than stable or same version but different type
if (currType == FIRMWARE_VERSION_TYPE_OFFICIAL && vehicle->versionCompare(version) < 0) {
Willian Galvani
committed
const static QString currentVersion = QString("%1.%2.%3").arg(vehicle->firmwareMajorVersion())
.arg(vehicle->firmwareMinorVersion())
.arg(vehicle->firmwarePatchVersion());
const static QString message = tr("Vehicle is not running latest stable firmware! Running %2-%1, latest stable is %3.");
qgcApp()->showMessage(message.arg(vehicle->firmwareVersionTypeString(), currentVersion, version));
}
}
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
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);
}