From 5c1d1a9d81b5364c1d8845ad55210c4c3bcc500e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Rub=C3=A9n=20P=C3=A9rez=20Alonso?= Date: Tue, 10 Dec 2024 16:42:52 +0100 Subject: [PATCH] Fix case-sensitive flight mode comparisons Fixed a bug where the "Start mission" action failed on ArduPilot, displaying an error popup with the message "Unable to start mission: Vehicle failed to change to Auto mode." The issue was caused by case-sensitive comparisons between flight mode strings from the vehicle and the reference strings. Moving away from using strings entirely should be considered. Replaced direct string comparisons with case-insensitive comparisons using QString::compare() with Qt::CaseInsensitive flag. This fix resolves the immediate issue and also corrects a few other incorrect mode comparisons unrelated to the "Start mission" problem. --- src/AutoPilotPlugins/APM/APMSubMotorComponentController.cc | 2 +- src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 2 +- src/FirmwarePlugin/FirmwarePlugin.cc | 4 ++-- src/Vehicle/StandardModes.cc | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/AutoPilotPlugins/APM/APMSubMotorComponentController.cc b/src/AutoPilotPlugins/APM/APMSubMotorComponentController.cc index 0df38a1706c..a76bc776246 100644 --- a/src/AutoPilotPlugins/APM/APMSubMotorComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSubMotorComponentController.cc @@ -22,7 +22,7 @@ void APMSubMotorComponentController::handleNewMessages(int uasid, int componenti Q_UNUSED(uasid); Q_UNUSED(componentid); Q_UNUSED(severity); - if (_vehicle->flightMode() == "Motor Detection" + if (QString::compare(_vehicle->flightMode(), "Motor Detection", Qt::CaseInsensitive) == 0 && (text.toLower().contains("thruster") || text.toLower().contains("motor"))) { _motorDetectionMessages += text + QStringLiteral("\n"); emit motorDetectionMessagesChanged(); diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index d7a3c404a99..681be13d796 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -670,7 +670,7 @@ const QVariantList& APMFirmwarePlugin::toolIndicators(const Vehicle* vehicle) bool APMFirmwarePlugin::isGuidedMode(const Vehicle* vehicle) const { - return vehicle->flightMode() == "Guided"; + return QString::compare(vehicle->flightMode(), "Guided", Qt::CaseInsensitive) == 0; } void APMFirmwarePlugin::_soloVideoHandshake(void) diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 976448877d0..eb041b65496 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -365,7 +365,7 @@ bool FirmwarePlugin::_armVehicleAndValidate(Vehicle* vehicle) bool FirmwarePlugin::_setFlightModeAndValidate(Vehicle* vehicle, const QString& flightMode) { - if (vehicle->flightMode() == flightMode) { + if (QString::compare(vehicle->flightMode(), flightMode, Qt::CaseInsensitive) == 0) { return true; } @@ -377,7 +377,7 @@ bool FirmwarePlugin::_setFlightModeAndValidate(Vehicle* vehicle, const QString& // Wait for vehicle to return flight mode for (int i=0; i<13; i++) { - if (vehicle->flightMode() == flightMode) { + if (QString::compare(vehicle->flightMode(), flightMode, Qt::CaseInsensitive) == 0) { flightModeChanged = true; break; } diff --git a/src/Vehicle/StandardModes.cc b/src/Vehicle/StandardModes.cc index 810def0dd48..3c09ea8a79c 100644 --- a/src/Vehicle/StandardModes.cc +++ b/src/Vehicle/StandardModes.cc @@ -175,7 +175,7 @@ QString StandardModes::flightMode(uint32_t custom_mode) const bool StandardModes::setFlightMode(const QString &flightMode, uint32_t *custom_mode) { for (auto iter = _modes.constBegin(); iter != _modes.constEnd(); ++iter) { - if (iter->name == flightMode) { + if (QString::compare(iter->name, flightMode, Qt::CaseInsensitive) == 0) { *custom_mode = iter.key(); return true; }