QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
FirmwarePlugin.cc
Go to the documentation of this file.
1#include "FirmwarePlugin.h"
2#include "AutoPilotPlugin.h"
3#include "Autotune.h"
5#include "MAVLinkLib.h"
6#include "MAVLinkProtocol.h"
7#include "ParameterMetaData.h"
8#include "AppMessages.h"
9#include "QGCApplication.h"
10#include "QGCCameraManager.h"
11#include "QGCFileDownload.h"
12#include "QGCLoggingCategory.h"
13#include "Vehicle.h"
14#include "VehicleLinkManager.h"
16#include "VehicleComponent.h"
17
18#include "QGCCompression.h"
19#include "QGCFileHelper.h"
20
21#include <QtCore/QDir>
22#include <QtCore/QFile>
23#include <QtCore/QRegularExpression>
24#include <QtCore/QStandardPaths>
25#include <QtCore/QThread>
26
27QGC_LOGGING_CATEGORY(FirmwarePluginLog, "FirmwarePlugin.FirmwarePlugin")
28
29static const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle.");
30
32 : QObject(parent)
33{
34 qCDebug(FirmwarePluginLog) << this;
35}
36
38{
39 qCDebug(FirmwarePluginLog) << this;
40}
41
43{
44 return new GenericAutoPilotPlugin(vehicle, vehicle);
45}
46
47QString FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) const
48{
49 Q_UNUSED(custom_mode);
50
51 struct Bit2Name {
52 const uint8_t baseModeBit;
53 const char *name;
54 };
55
56 static constexpr Bit2Name rgBit2Name[] = {
57 { MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, "Manual" },
58 { MAV_MODE_FLAG_STABILIZE_ENABLED, "Stabilize" },
59 { MAV_MODE_FLAG_GUIDED_ENABLED, "Guided" },
60 { MAV_MODE_FLAG_AUTO_ENABLED, "Auto" },
61 { MAV_MODE_FLAG_TEST_ENABLED, "Test" },
62 };
63
64 QString flightMode;
65 if (base_mode == 0) {
66 flightMode = "PreFlight";
67 } else if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
68 flightMode = _modeEnumToString.value(custom_mode, QStringLiteral("Custom:0x%1").arg(custom_mode, 0, 16));
69 } else {
70 for (size_t i = 0; i < std::size(rgBit2Name); i++) {
71 if (base_mode & rgBit2Name[i].baseModeBit) {
72 if (i != 0) {
73 flightMode += " ";
74 }
75 flightMode += rgBit2Name[i].name;
76 }
77 }
78 }
79
80 return flightMode;
81}
82
83bool FirmwarePlugin::setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const
84{
85 Q_UNUSED(flightMode);
86 Q_UNUSED(base_mode);
87 Q_UNUSED(custom_mode);
88
89 qCWarning(FirmwarePluginLog) << "FirmwarePlugin::setFlightMode called on base class, not supported";
90
91 return false;
92}
93
95{
96 switch (vehicleClass) {
98 return QStringLiteral(":/json/MavCmdInfoCommon.json");
100 return QStringLiteral(":/json/MavCmdInfoFixedWing.json");
102 return QStringLiteral(":/json/MavCmdInfoMultiRotor.json");
104 return QStringLiteral(":/json/MavCmdInfoVTOL.json");
106 return QStringLiteral(":/json/MavCmdInfoSub.json");
108 return QStringLiteral(":/json/MavCmdInfoRover.json");
109 default:
110 qCWarning(FirmwarePluginLog) << "FirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
111 return QString();
112 }
113}
114
115void FirmwarePlugin::setGuidedMode(Vehicle *vehicle, bool guidedMode) const
116{
117 Q_UNUSED(vehicle);
118 Q_UNUSED(guidedMode);
120}
121
123{
124 Q_UNUSED(vehicle);
126}
127
128void FirmwarePlugin::guidedModeRTL(Vehicle *vehicle, bool smartRTL) const
129{
130 Q_UNUSED(vehicle);
131 Q_UNUSED(smartRTL);
133}
134
136{
137 Q_UNUSED(vehicle);
139}
140
141void FirmwarePlugin::guidedModeTakeoff(Vehicle *vehicle, double takeoffAltRel) const
142{
143 Q_UNUSED(vehicle);
144 Q_UNUSED(takeoffAltRel);
146}
147
148bool FirmwarePlugin::guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius) const
149{
150 Q_UNUSED(vehicle);
151 Q_UNUSED(gotoCoord);
152 Q_UNUSED(forwardFlightLoiterRadius);
154 return false;
155}
156
162
167
172
173void FirmwarePlugin::guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &/*headingCoord*/) const
174{
175 Q_UNUSED(vehicle);
177}
178
180{
181 // Not supported by generic vehicle
183}
184
189
196
197const QVariantList &FirmwarePlugin::toolIndicators(const Vehicle*)
198{
199 //-- Default list of indicators for all vehicles.
200 if (_toolIndicatorList.isEmpty()) {
201 _toolIndicatorList = QVariantList({
202 QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/VehicleGPSIndicator.qml")),
203 QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/GPSResilienceIndicator.qml")),
204 QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/TelemetryRSSIIndicator.qml")),
205 QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/RCRSSIIndicator.qml")),
206 QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/BatteryIndicator.qml")),
207 QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/RemoteIDIndicator.qml")),
208 QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/GimbalIndicator.qml")),
209 QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/EscIndicator.qml")),
210 QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/JoystickIndicator.qml")),
211 QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/MultiVehicleSelector.qml")),
212#ifdef QT_DEBUG
213 // ControlIndicator is only available in debug builds for the moment
214 QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/GCSControlIndicator.qml")),
215#endif
216 });
217 }
218
219 return _toolIndicatorList;
220}
221
223{
224 if (vehicle->armed()) {
225 return true;
226 }
227
228 bool vehicleArmed = false;
229
230 // Only try arming the vehicle a single time. Doing retries on arming with a delay can lead to safety issues.
231 vehicle->setArmed(true, false /* showError */);
232
233 // Wait 1500 msecs for vehicle to arm (waiting for the next heartbeat)
234 for (int i = 0; i < 15; i++) {
235 if (vehicle->armed()) {
236 vehicleArmed = true;
237 break;
238 }
239 QThread::msleep(100);
240 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
241 }
242
243 return vehicleArmed;
244}
245
246bool FirmwarePlugin::_setFlightModeAndValidate(Vehicle *vehicle, const QString &flightMode) const
247{
248 if (vehicle->flightMode() == flightMode) {
249 return true;
250 }
251
252 bool flightModeChanged = false;
253
254 // We try 3 times
255 for (int retries = 0; retries < 3; retries++) {
256 vehicle->setFlightMode(flightMode);
257
258 // Wait for vehicle to return flight mode
259 for (int i = 0; i < 13; i++) {
260 if (vehicle->flightMode() == flightMode) {
261 flightModeChanged = true;
262 break;
263 }
264 QThread::msleep(100);
265 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
266 }
267
268 if (flightModeChanged) {
269 break;
270 }
271 }
272
273 return flightModeChanged;
274}
275
276
277void FirmwarePlugin::batteryConsumptionData(Vehicle *vehicle, int &mAhBattery, double &hoverAmps, double &cruiseAmps) const
278{
279 Q_UNUSED(vehicle);
280 mAhBattery = 0;
281 hoverAmps = 0;
282 cruiseAmps = 0;
283}
284
285bool FirmwarePlugin::hasGimbal(Vehicle *vehicle, bool &rollSupported, bool &pitchSupported, bool &yawSupported) const
286{
287 Q_UNUSED(vehicle);
288 rollSupported = false;
289 pitchSupported = false;
290 yawSupported = false;
291 return false;
292}
293
295{
296 return new QGCCameraManager(vehicle);
297}
298
300{
301 return new VehicleCameraControl(info, vehicle, compID, parent);
302}
303
305{
306 // This is required as mocklink uses a hardcoded firmware version
307 if (QGC::runningUnitTests()) {
308 qCDebug(FirmwarePluginLog) << "Skipping version check";
309 return;
310 }
311
312 const QString versionFile = _getLatestVersionFileUrl(vehicle);
313 qCDebug(FirmwarePluginLog) << "Downloading" << versionFile;
314 QGCFileDownload *const downloader = new QGCFileDownload(vehicle);
315 (void) connect(downloader, &QGCFileDownload::finished, this, [vehicle, this, versionFile](bool success, const QString &localFile, const QString &errorMsg) {
316 if (success) {
317 _versionFileDownloadFinished(versionFile, localFile, vehicle);
318 } else if (!errorMsg.isEmpty()) {
319 qCDebug(FirmwarePluginLog) << "Failed to download the latest fw version file. Error:" << errorMsg;
320 }
321 sender()->deleteLater();
322 });
323
324 if (!downloader->start(versionFile)) {
325 downloader->deleteLater();
326 }
327}
328
329void FirmwarePlugin::_versionFileDownloadFinished(const QString &remoteFile, const QString &localFile, const Vehicle *vehicle) const
330{
331 qCDebug(FirmwarePluginLog) << "Download complete" << remoteFile << localFile;
332 // Now read the version file and pull out the version string
333 QFile versionFile(localFile);
334 if (!versionFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
335 qCWarning(FirmwarePluginLog) << "Error opening downloaded version file.";
336 return;
337 }
338
339 QTextStream stream(&versionFile);
340 const QString versionFileContents = stream.readAll();
341 QString version;
342 const QRegularExpressionMatch match = QRegularExpression(_versionRegex()).match(versionFileContents);
343
344 qCDebug(FirmwarePluginLog) << "Looking for version number...";
345
346 if (match.hasMatch()) {
347 version = match.captured(1);
348 } else {
349 qCWarning(FirmwarePluginLog) << "Unable to parse version info from file" << remoteFile;
350 return;
351 }
352
353 qCDebug(FirmwarePluginLog) << "Latest stable version = " << version;
354
355 const int currType = vehicle->firmwareVersionType();
356
357 // Check if lower version than stable or same version but different type
358 if ((currType == FIRMWARE_VERSION_TYPE_OFFICIAL) && (vehicle->versionCompare(version) < 0)) {
359 const QString currentVersionNumber = QStringLiteral("%1.%2.%3").arg(vehicle->firmwareMajorVersion())
360 .arg(vehicle->firmwareMinorVersion())
361 .arg(vehicle->firmwarePatchVersion());
362 QGC::showAppMessage(tr("Vehicle is not running latest stable firmware! Running %1, latest stable is %2.").arg(currentVersionNumber, version));
363 }
364}
365
366int FirmwarePlugin::versionCompare(const Vehicle *vehicle, int major, int minor, int patch) const
367{
368 const int currMajor = vehicle->firmwareMajorVersion();
369 const int currMinor = vehicle->firmwareMinorVersion();
370 const int currPatch = vehicle->firmwarePatchVersion();
371
372 if ((currMajor == major) && (currMinor == minor) && (currPatch == patch)) {
373 return 0;
374 }
375
376 if ((currMajor > major)
377 || ((currMajor == major) && (currMinor > minor))
378 || ((currMajor == major) && (currMinor == minor) && (currPatch > patch)))
379 {
380 return 1;
381 }
382
383 return -1;
384}
385
386int FirmwarePlugin::versionCompare(const Vehicle *vehicle, const QString &compare) const
387{
388 const QStringList versionNumbers = compare.split(".");
389 if (versionNumbers.size() != 3) {
390 qCWarning(FirmwarePluginLog) << "Error parsing version number: wrong format";
391 return -1;
392 }
393
394 const int major = versionNumbers[0].toInt();
395 const int minor = versionNumbers[1].toInt();
396 const int patch = versionNumbers[2].toInt();
397
398 return versionCompare(vehicle, major, minor, patch);
399}
400
401void FirmwarePlugin::sendGCSMotionReport(Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimationCapabilities) const
402{
403 SharedLinkInterfacePtr sharedLink = vehicle->vehicleLinkManager()->primaryLink().lock();
404 if (!sharedLink) {
405 return;
406 }
407
408 mavlink_follow_target_t follow_target{};
409
410 follow_target.timestamp = qgcApp()->msecsSinceBoot();
411 follow_target.est_capabilities = estimationCapabilities;
412 follow_target.position_cov[0] = static_cast<float>(motionReport.pos_std_dev[0]);
413 follow_target.position_cov[2] = static_cast<float>(motionReport.pos_std_dev[2]);
414 follow_target.alt = static_cast<float>(motionReport.altMetersAMSL);
415 follow_target.lat = motionReport.lat_int;
416 follow_target.lon = motionReport.lon_int;
417 follow_target.vel[0] = static_cast<float>(motionReport.vxMetersPerSec);
418 follow_target.vel[1] = static_cast<float>(motionReport.vyMetersPerSec);
419
420 mavlink_message_t message{};
421 mavlink_msg_follow_target_encode_chan(
422 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
423 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
424 sharedLink->mavlinkChannel(),
425 &message,
426 &follow_target
427 );
428
429 (void) vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
430}
431
433{
434 return new Autotune(vehicle);
435}
436
438{
439 _flightModeList.clear();
440 _modeEnumToString.clear();
441
442 for (FirmwareFlightMode &flightMode : flightModeList) {
443 _modeEnumToString[flightMode.custom_mode] = flightMode.mode_name;
445 }
446
448 qCDebug(FirmwarePluginLog) << "Flight Mode:" << flightMode.mode_name << " Custom Mode:" << flightMode.custom_mode;
449 }
450}
451
453{
454 for (const FirmwareFlightMode &existingFlightMode : _flightModeList) {
455 if (existingFlightMode.custom_mode == newFlightMode.custom_mode) {
456 qCDebug(FirmwarePluginLog) << "Flight Mode:" << newFlightMode.mode_name << " Custom Mode:" << newFlightMode.custom_mode
457 << " already exists, not adding again.";
458 return;
459 }
460 }
461 _flightModeList += newFlightMode;
462}
463
464/*===========================================================================*/
465
466static constexpr const char *kCachedMetaDataFilePrefix = "ParameterFactMetaData";
467
468static QDir _parameterMetaDataCacheDir(bool ensureExists = false)
469{
470 const QString path = QStandardPaths::writableLocation(QStandardPaths::CacheLocation)
471 + QStringLiteral("/ParameterMetaData");
472 if (ensureExists) {
474 }
475 return QDir(path);
476}
477
479{
481 if (!metaData) {
482 qCWarning(FirmwarePluginLog) << "No parameter metadata parser for firmware plugin" << this;
483 return nullptr;
484 }
485
486 const QString metaDataFile = _cachedParameterMetaDataFile(vehicle);
487 if (!metaDataFile.isEmpty()) {
488 metaData->loadParameterFactMetaDataFile(metaDataFile);
489 }
490 return metaData;
491}
492
494{
495 const MAV_AUTOPILOT autopilot = _autopilotType();
496 if (autopilot == MAV_AUTOPILOT_GENERIC) {
497 return _internalParameterMetaDataFile(vehicle);
498 }
499
500 const QString internalFile = _internalParameterMetaDataFile(vehicle);
501 QVersionNumber internalVersion = ParameterMetaData::versionFromFileName(internalFile);
502 if (internalVersion.isNull()) {
503 internalVersion = ParameterMetaData::versionFromMetaDataFile(internalFile);
504 }
505
506 // Without a known internal version we can't safely compare against
507 // cache — use the bundled file to avoid stale overrides.
508 if (internalVersion.isNull() || QGC::runningUnitTests()) {
509 qCDebug(FirmwarePluginLog) << "Using internal parameter metadata:" << internalFile;
510 return internalFile;
511 }
512
513 const int wantedMajorVersion = internalVersion.majorVersion();
514
515 const QDir cacheDir = _parameterMetaDataCacheDir();
516 const QString wildcard = QStringLiteral("%1_%2.*.json").arg(kCachedMetaDataFilePrefix).arg(autopilot);
517 const QStringList entries = cacheDir.entryList(QStringList(wildcard), QDir::Files);
518
519 QString bestFile;
520 QVersionNumber bestVersion;
521 for (const QString &entry : entries) {
522 const QVersionNumber ver = ParameterMetaData::versionFromFileName(entry);
523 if (ver.isNull() || ver.majorVersion() != wantedMajorVersion) {
524 continue;
525 }
526 if (bestVersion.isNull() || ver > bestVersion) {
527 bestVersion = ver;
528 bestFile = cacheDir.filePath(entry);
529 }
530 }
531
532 if (bestFile.isEmpty()) {
533 qCDebug(FirmwarePluginLog) << "No cached parameter metadata found, using internal:" << internalFile;
534 return internalFile;
535 }
536
537 if (internalVersion.majorVersion() == wantedMajorVersion && bestVersion <= internalVersion) {
538 qCDebug(FirmwarePluginLog) << "Internal metadata" << internalVersion.toString() << ">= cache" << bestVersion.toString()
539 << "— using internal:" << internalFile;
540 return internalFile;
541 }
542 qCDebug(FirmwarePluginLog) << "Using cached parameter metadata" << bestVersion.toString() << ":" << bestFile;
543 return bestFile;
544}
545
546void FirmwarePlugin::cacheParameterMetaDataFile(const QString &metaDataFile)
547{
548 const MAV_AUTOPILOT autopilot = _autopilotType();
549 if (autopilot == MAV_AUTOPILOT_GENERIC) {
550 return;
551 }
552
553 QString readError;
554 const QByteArray data = QGCCompression::readFile(metaDataFile, &readError);
555 if (data.isEmpty()) {
556 qCWarning(FirmwarePluginLog) << "Cannot cache parameter metadata: failed to read" << metaDataFile << readError;
557 return;
558 }
559
560 // Reject non-JSON content (e.g. XML from older PX4 firmware images)
561 // and extract the catalog version in a single parse pass.
562 bool validJson = false;
563 QVersionNumber newVersion = ParameterMetaData::versionFromJsonData(data, &validJson);
564 if (!validJson) {
565 qCDebug(FirmwarePluginLog) << "Skipping cache of non-JSON parameter metadata:" << metaDataFile;
566 return;
567 }
568 if (newVersion.isNull()) {
569 // Valid JSON but no version stamps — use fallback so unversioned
570 // files still get cached with a major version that matches the
571 // default wantedMajorVersion in _cachedParameterMetaDataFile.
572 newVersion = QVersionNumber(1, 0);
573 }
574
575 const int majorVersion = newVersion.majorVersion();
576 const QDir cacheDir = _parameterMetaDataCacheDir(true);
577
578 const QString wildcard = QStringLiteral("%1_%2.%3.*.json").arg(kCachedMetaDataFilePrefix).arg(autopilot).arg(majorVersion);
579 const QStringList existing = cacheDir.entryList(QStringList(wildcard), QDir::Files);
580
581 for (const QString &file : existing) {
582 const QVersionNumber existingVersion = ParameterMetaData::versionFromFileName(file);
583 // Strict less-than: equal versions are replaced so that
584 // re-flashing with corrected metadata (same version stamp)
585 // updates the cache.
586 if (!existingVersion.isNull() && newVersion < existingVersion) {
587 return;
588 }
589 }
590
591 const QString cachePath = cacheDir.filePath(
592 QStringLiteral("%1_%2.%3.%4.json").arg(kCachedMetaDataFilePrefix).arg(autopilot).arg(majorVersion).arg(newVersion.minorVersion()));
593 if (!QGCFileHelper::atomicWrite(cachePath, data)) {
594 qCWarning(FirmwarePluginLog) << "Failed to cache parameter metadata to" << cachePath;
595 return;
596 }
597
598 for (const QString &file : existing) {
599 const QString fullPath = cacheDir.filePath(file);
600 if (fullPath != cachePath && !QFile::remove(fullPath)) {
601 qCWarning(FirmwarePluginLog) << "Failed to remove old cache file:" << file;
602 }
603 }
604}
605
606/*===========================================================================*/
607
static constexpr const char * kCachedMetaDataFilePrefix
static const QString guided_mode_not_supported_by_vehicle
static QDir _parameterMetaDataCacheDir(bool ensureExists=false)
QList< FirmwareFlightMode > FlightModeList
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
#define qgcApp()
struct __mavlink_message mavlink_message_t
Unified file download utility with decompression, verification, and QML support.
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_camera_information_t mavlink_camera_information_t
The AutoPilotPlugin class is an abstract base class which represents the methods and objects which ar...
virtual CommandSupportedResult anyVersionSupportsCommand(MAV_CMD) const
CommandSupportedResult getCommandSupported(MAV_CMD cmd) const
The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware ...
virtual void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle *vehicle, double airspeed_equiv) const
virtual void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle)
virtual void startMission(Vehicle *vehicle) const
Command the vehicle to start the mission.
virtual void checkIfIsLatestStable(Vehicle *vehicle) const
Used to check if running firmware is latest stable version.
FlightModeList _flightModeList
virtual const QVariantList & toolIndicators(const Vehicle *vehicle)
virtual void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double groundspeed) const
virtual bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const
virtual ~FirmwarePlugin()
virtual void guidedModeTakeoff(Vehicle *vehicle, double takeoffAltRel) const
Command vehicle to takeoff from current location to the specified height.
void cacheParameterMetaDataFile(const QString &metaDataFile)
virtual QString missionCommandOverrides(QGCMAVLinkTypes::VehicleClass_t vehicleClass) const
bool _setFlightModeAndValidate(Vehicle *vehicle, const QString &flightMode) const
virtual QString _internalParameterMetaDataFile(const Vehicle *) const
virtual QString _getLatestVersionFileUrl(Vehicle *) const
returns url with latest firmware release information.
void _updateFlightModeList(FlightModeList &flightModeList)
virtual void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const
Command vehicle to rotate towards specified location.
virtual bool guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius=0.0) const
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode) const
virtual void startTakeoff(Vehicle *vehicle) const
Command the vehicle to start a takeoff.
void _addNewFlightMode(FirmwareFlightMode &flightMode)
virtual void pauseVehicle(Vehicle *vehicle) const
virtual MAV_AUTOPILOT _autopilotType() const
int versionCompare(const Vehicle *vehicle, const QString &compare) const
virtual Autotune * createAutotune(Vehicle *vehicle) const
Creates Autotune object.
ParameterMetaData * loadParameterMetaData(const Vehicle *vehicle)
virtual AutoPilotPlugin * autopilotPlugin(Vehicle *vehicle) const
virtual void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const
Command vehicle to return to launch.
virtual ParameterMetaData * _createParameterMetaData()
virtual QString _versionRegex() const
Returns regex QString to extract version information from text.
bool _armVehicleAndValidate(Vehicle *vehicle) const
QVariantList _toolIndicatorList
QString _cachedParameterMetaDataFile(const Vehicle *vehicle) const
virtual void setGuidedMode(Vehicle *vehicle, bool guidedMode) const
Set guided flight mode.
FlightModeCustomModeMap _modeEnumToString
virtual void batteryConsumptionData(Vehicle *vehicle, int &mAhBattery, double &hoverAmps, double &cruiseAmps) const
virtual QGCCameraManager * createCameraManager(Vehicle *vehicle) const
Creates vehicle camera manager.
virtual void sendGCSMotionReport(Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimationCapabilities) const
Sends the appropriate mavlink message for follow me support.
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t
virtual const remapParamNameMajorVersionMap_t & paramNameRemapMajorVersionMap() const
virtual void guidedModeLand(Vehicle *vehicle) const
Command vehicle to land at current location.
virtual MavlinkCameraControlInterface * createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject *parent=nullptr) const
Camera control.
virtual bool hasGimbal(Vehicle *vehicle, bool &rollSupported, bool &pitchSupported, bool &yawSupported) const
virtual void _versionFileDownloadFinished(const QString &remoteFile, const QString &localFile, const Vehicle *vehicle) const
Callback to process file with latest release information.
This is the generic implementation of the AutoPilotPlugin class for mavs we do not have a specific Au...
static int getComponentId()
static MAVLinkProtocol * instance()
Abstract base class for all camera controls: real and simulated.
static QVersionNumber versionFromMetaDataFile(const QString &metaDataFile)
static QVersionNumber versionFromJsonData(const QByteArray &jsonData)
void loadParameterFactMetaDataFile(const QString &metaDataFile)
static QVersionNumber versionFromFileName(const QString &fileName)
Camera Manager.
File download with progress, decompression, and hash verification.
void finished(bool success, const QString &localPath, const QString &errorMessage)
bool start(const QString &remoteUrl)
MAVLink Camera API controller - connected to a real mavlink v2 camera.
WeakLinkInterfacePtr primaryLink() const
QString flightMode() const
Definition Vehicle.cc:1468
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
int firmwareMinorVersion() const
Definition Vehicle.h:650
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1389
void setFlightMode(const QString &flightMode)
Definition Vehicle.cc:1478
int firmwareVersionType() const
Definition Vehicle.h:652
int firmwarePatchVersion() const
Definition Vehicle.h:651
bool armed() const
Definition Vehicle.h:449
Q_INVOKABLE int versionCompare(const QString &compare) const
Used to check if running current version is equal or higher than the one being compared.
Definition Vehicle.cc:2743
int firmwareMajorVersion() const
Definition Vehicle.h:649
void setArmed(bool armed, bool showError)
Definition Vehicle.cc:1439
QByteArray readFile(const QString &filePath, QString *errorString, qint64 maxBytes)
Read file contents, transparently decompressing .gz/.xz/.zst/.bz2/.lz4 files.
bool atomicWrite(const QString &filePath, const QByteArray &data)
bool ensureDirectoryExists(const QString &path)
bool runningUnitTests()
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Definition AppMessages.cc:9
static constexpr VehicleClass_t VehicleClassGeneric