22#include <QtCore/QFile>
23#include <QtCore/QRegularExpression>
24#include <QtCore/QStandardPaths>
25#include <QtCore/QThread>
34 qCDebug(FirmwarePluginLog) <<
this;
39 qCDebug(FirmwarePluginLog) <<
this;
49 Q_UNUSED(custom_mode);
52 const uint8_t baseModeBit;
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" },
67 }
else if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
70 for (
size_t i = 0; i < std::size(rgBit2Name); i++) {
71 if (base_mode & rgBit2Name[i].baseModeBit) {
87 Q_UNUSED(custom_mode);
89 qCWarning(FirmwarePluginLog) <<
"FirmwarePlugin::setFlightMode called on base class, not supported";
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");
110 qCWarning(FirmwarePluginLog) <<
"FirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
118 Q_UNUSED(guidedMode);
144 Q_UNUSED(takeoffAltRel);
152 Q_UNUSED(forwardFlightLoiterRadius);
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")),
214 QVariant::fromValue(QUrl::fromUserInput(
"qrc:/qml/QGroundControl/Toolbar/GCSControlIndicator.qml")),
224 if (vehicle->
armed()) {
228 bool vehicleArmed =
false;
234 for (
int i = 0; i < 15; i++) {
235 if (vehicle->
armed()) {
239 QThread::msleep(100);
240 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
252 bool flightModeChanged =
false;
255 for (
int retries = 0; retries < 3; retries++) {
259 for (
int i = 0; i < 13; i++) {
261 flightModeChanged =
true;
264 QThread::msleep(100);
265 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
268 if (flightModeChanged) {
273 return flightModeChanged;
288 rollSupported =
false;
289 pitchSupported =
false;
290 yawSupported =
false;
308 qCDebug(FirmwarePluginLog) <<
"Skipping version check";
313 qCDebug(FirmwarePluginLog) <<
"Downloading" << versionFile;
315 (void) connect(downloader, &
QGCFileDownload::finished,
this, [vehicle,
this, versionFile](
bool success,
const QString &localFile,
const QString &errorMsg) {
318 }
else if (!errorMsg.isEmpty()) {
319 qCDebug(FirmwarePluginLog) <<
"Failed to download the latest fw version file. Error:" << errorMsg;
321 sender()->deleteLater();
324 if (!downloader->
start(versionFile)) {
325 downloader->deleteLater();
331 qCDebug(FirmwarePluginLog) <<
"Download complete" << remoteFile << localFile;
333 QFile versionFile(localFile);
334 if (!versionFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
335 qCWarning(FirmwarePluginLog) <<
"Error opening downloaded version file.";
339 QTextStream stream(&versionFile);
340 const QString versionFileContents = stream.readAll();
342 const QRegularExpressionMatch match = QRegularExpression(
_versionRegex()).match(versionFileContents);
344 qCDebug(FirmwarePluginLog) <<
"Looking for version number...";
346 if (match.hasMatch()) {
347 version = match.captured(1);
349 qCWarning(FirmwarePluginLog) <<
"Unable to parse version info from file" << remoteFile;
353 qCDebug(FirmwarePluginLog) <<
"Latest stable version = " << version;
358 if ((currType == FIRMWARE_VERSION_TYPE_OFFICIAL) && (vehicle->
versionCompare(version) < 0)) {
359 const QString currentVersionNumber = QStringLiteral(
"%1.%2.%3").arg(vehicle->
firmwareMajorVersion())
362 QGC::showAppMessage(tr(
"Vehicle is not running latest stable firmware! Running %1, latest stable is %2.").arg(currentVersionNumber, version));
372 if ((currMajor == major) && (currMinor == minor) && (currPatch == patch)) {
376 if ((currMajor > major)
377 || ((currMajor == major) && (currMinor > minor))
378 || ((currMajor == major) && (currMinor == minor) && (currPatch > patch)))
388 const QStringList versionNumbers = compare.split(
".");
389 if (versionNumbers.size() != 3) {
390 qCWarning(FirmwarePluginLog) <<
"Error parsing version number: wrong format";
394 const int major = versionNumbers[0].toInt();
395 const int minor = versionNumbers[1].toInt();
396 const int patch = versionNumbers[2].toInt();
408 mavlink_follow_target_t follow_target{};
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);
421 mavlink_msg_follow_target_encode_chan(
424 sharedLink->mavlinkChannel(),
448 qCDebug(FirmwarePluginLog) <<
"Flight Mode:" <<
flightMode.mode_name <<
" Custom Mode:" <<
flightMode.custom_mode;
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.";
470 const QString path = QStandardPaths::writableLocation(QStandardPaths::CacheLocation)
471 + QStringLiteral(
"/ParameterMetaData");
482 qCWarning(FirmwarePluginLog) <<
"No parameter metadata parser for firmware plugin" <<
this;
487 if (!metaDataFile.isEmpty()) {
496 if (autopilot == MAV_AUTOPILOT_GENERIC) {
502 if (internalVersion.isNull()) {
509 qCDebug(FirmwarePluginLog) <<
"Using internal parameter metadata:" << internalFile;
513 const int wantedMajorVersion = internalVersion.majorVersion();
517 const QStringList entries = cacheDir.entryList(QStringList(wildcard), QDir::Files);
520 QVersionNumber bestVersion;
521 for (
const QString &entry : entries) {
523 if (ver.isNull() || ver.majorVersion() != wantedMajorVersion) {
526 if (bestVersion.isNull() || ver > bestVersion) {
528 bestFile = cacheDir.filePath(entry);
532 if (bestFile.isEmpty()) {
533 qCDebug(FirmwarePluginLog) <<
"No cached parameter metadata found, using internal:" << internalFile;
537 if (internalVersion.majorVersion() == wantedMajorVersion && bestVersion <= internalVersion) {
538 qCDebug(FirmwarePluginLog) <<
"Internal metadata" << internalVersion.toString() <<
">= cache" << bestVersion.toString()
539 <<
"— using internal:" << internalFile;
542 qCDebug(FirmwarePluginLog) <<
"Using cached parameter metadata" << bestVersion.toString() <<
":" << bestFile;
549 if (autopilot == MAV_AUTOPILOT_GENERIC) {
555 if (data.isEmpty()) {
556 qCWarning(FirmwarePluginLog) <<
"Cannot cache parameter metadata: failed to read" << metaDataFile << readError;
562 bool validJson =
false;
565 qCDebug(FirmwarePluginLog) <<
"Skipping cache of non-JSON parameter metadata:" << metaDataFile;
568 if (newVersion.isNull()) {
572 newVersion = QVersionNumber(1, 0);
575 const int majorVersion = newVersion.majorVersion();
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);
581 for (
const QString &file : existing) {
586 if (!existingVersion.isNull() && newVersion < existingVersion) {
591 const QString cachePath = cacheDir.filePath(
592 QStringLiteral(
"%1_%2.%3.%4.json").arg(
kCachedMetaDataFilePrefix).arg(autopilot).arg(majorVersion).arg(newVersion.minorVersion()));
594 qCWarning(FirmwarePluginLog) <<
"Failed to cache parameter metadata to" << cachePath;
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;
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
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.
File download with progress, decompression, and hash verification.
void finished(bool success, const QString &localPath, const QString &errorMessage)
bool start(const QString &remoteUrl)
static constexpr const VehicleClass_t VehicleClassSub
static constexpr const VehicleClass_t VehicleClassFixedWing
static constexpr const VehicleClass_t VehicleClassMultiRotor
static constexpr const VehicleClass_t VehicleClassRoverBoat
static constexpr const VehicleClass_t VehicleClassVTOL
MAVLink Camera API controller - connected to a real mavlink v2 camera.
WeakLinkInterfacePtr primaryLink() const
QString flightMode() const
VehicleLinkManager * vehicleLinkManager()
int firmwareMinorVersion() const
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
void setFlightMode(const QString &flightMode)
int firmwareVersionType() const
int firmwarePatchVersion() const
Q_INVOKABLE int versionCompare(const QString &compare) const
Used to check if running current version is equal or higher than the one being compared.
int firmwareMajorVersion() const
void setArmed(bool armed, bool showError)
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)
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
static constexpr VehicleClass_t VehicleClassGeneric