Skip to content

Commit

Permalink
Firmware: Flight Mode Review Changes
Browse files Browse the repository at this point in the history
* Remove loose flight mode strings
* Force All Enums in switch cases
* Update function calls to parse flight mode list
  • Loading branch information
bytesByHarsh authored Dec 28, 2024
1 parent 79b1d7d commit 41e4226
Show file tree
Hide file tree
Showing 20 changed files with 394 additions and 183 deletions.
8 changes: 8 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -553,4 +553,12 @@ elseif(MACOS)
install(SCRIPT "${CMAKE_SOURCE_DIR}/cmake/CreateMacDMG.cmake")
endif()

## Enforce Handling of All Enum Cases

if(WIN32)
add_compile_options(/w44265 /we44265)
else()
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wswitch -Werror=switch")
endif()

include(printSummary)
77 changes: 60 additions & 17 deletions custom-example/src/FirmwarePlugin/CustomFirmwarePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -59,43 +59,86 @@ bool CustomFirmwarePlugin::hasGimbal(Vehicle* /*vehicle*/, bool& rollSupported,

void CustomFirmwarePlugin::updateAvailableFlightModes(FlightModeList modeList)
{
_availableFlightModeList.clear();
for(auto mode: modeList){

for(auto &mode: modeList){
PX4CustomMode::Mode cMode = static_cast<PX4CustomMode::Mode>(mode.custom_mode);
// Update Multi Rotor
switch (mode.custom_mode) {
case PX4CustomMode::POSCTL_ORBIT:
mode.multiRotor = false;
break;
default:
switch (cMode) {
case PX4CustomMode::MANUAL :
case PX4CustomMode::STABILIZED :
case PX4CustomMode::ACRO :
case PX4CustomMode::RATTITUDE :
case PX4CustomMode::ALTCTL :
case PX4CustomMode::OFFBOARD :
case PX4CustomMode::SIMPLE :
case PX4CustomMode::POSCTL_POSCTL :
case PX4CustomMode::AUTO_LOITER :
case PX4CustomMode::AUTO_MISSION :
case PX4CustomMode::AUTO_RTL :
case PX4CustomMode::AUTO_FOLLOW_TARGET:
case PX4CustomMode::AUTO_LAND :
case PX4CustomMode::AUTO_PRECLAND :
case PX4CustomMode::AUTO_READY :
case PX4CustomMode::AUTO_RTGS :
case PX4CustomMode::AUTO_TAKEOFF :
mode.multiRotor = true;
break;
case PX4CustomMode::POSCTL_ORBIT :
mode.multiRotor = false;
break;
}

// Update Fixed Wing
switch (mode.custom_mode){
case PX4CustomMode::OFFBOARD:
case PX4CustomMode::SIMPLE:
case PX4CustomMode::POSCTL_ORBIT:
switch (cMode){
case PX4CustomMode::OFFBOARD :
case PX4CustomMode::SIMPLE :
case PX4CustomMode::POSCTL_ORBIT :
case PX4CustomMode::AUTO_FOLLOW_TARGET:
case PX4CustomMode::AUTO_PRECLAND:
case PX4CustomMode::AUTO_PRECLAND :
mode.fixedWing = false;
break;
default:
case PX4CustomMode::MANUAL :
case PX4CustomMode::STABILIZED :
case PX4CustomMode::ACRO :
case PX4CustomMode::RATTITUDE :
case PX4CustomMode::ALTCTL :
case PX4CustomMode::POSCTL_POSCTL :
case PX4CustomMode::AUTO_LOITER :
case PX4CustomMode::AUTO_MISSION :
case PX4CustomMode::AUTO_RTL :
case PX4CustomMode::AUTO_LAND :
case PX4CustomMode::AUTO_READY :
case PX4CustomMode::AUTO_RTGS :
case PX4CustomMode::AUTO_TAKEOFF :
mode.fixedWing = true;
break;
}

// Update CanBeSet
switch (mode.custom_mode){
switch (cMode){
case PX4CustomMode::AUTO_LOITER:
case PX4CustomMode::AUTO_RTL:
case PX4CustomMode::AUTO_MISSION:
mode.canBeSet = true;
break;
default:
case PX4CustomMode::OFFBOARD :
case PX4CustomMode::SIMPLE :
case PX4CustomMode::POSCTL_ORBIT :
case PX4CustomMode::AUTO_FOLLOW_TARGET:
case PX4CustomMode::AUTO_PRECLAND :
case PX4CustomMode::MANUAL :
case PX4CustomMode::STABILIZED :
case PX4CustomMode::ACRO :
case PX4CustomMode::RATTITUDE :
case PX4CustomMode::ALTCTL :
case PX4CustomMode::POSCTL_POSCTL :
case PX4CustomMode::AUTO_LAND :
case PX4CustomMode::AUTO_READY :
case PX4CustomMode::AUTO_RTGS :
case PX4CustomMode::AUTO_TAKEOFF :
mode.canBeSet = false;
break;
}

_updateModeMappings(mode);
}
_updateModeMappings(modeList);
}
6 changes: 3 additions & 3 deletions src/AutoPilotPlugins/APM/APMSubMotorComponent.qml
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ SetupPage {

property int neutralValue: 50;
property int _lastIndex: 0;
property bool canRunManualTest: controller.vehicle.flightMode !== 'Motor Detection' && controller.vehicle.armed && motorPage.visible && setupView.visible
property bool canRunManualTest: controller.vehicle.flightMode !== controller.vehicle.motorDetectionFlightMode && controller.vehicle.armed && motorPage.visible && setupView.visible
property var shouldRunManualTest: false // Does the operator intend to run the motor test?

APMSubMotorComponentController {
Expand Down Expand Up @@ -237,10 +237,10 @@ SetupPage {
QGCButton {
id: startAutoDetection
text: "Auto-Detect Directions"
enabled: controller.vehicle.flightMode !== 'Motor Detection'
enabled: controller.vehicle.flightMode !== controller.vehicle.motorDetectionFlightMode

onClicked: function() {
controller.vehicle.flightMode = "Motor Detection"
controller.vehicle.flightMode = controller.vehicle.motorDetectionFlightMode
controller.vehicle.armed = true
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/AutoPilotPlugins/APM/APMSubMotorComponentController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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 (_vehicle->flightMode() == _vehicle->motorDetectionFlightMode()
&& (text.toLower().contains("thruster") || text.toLower().contains("motor"))) {
_motorDetectionMessages += text + QStringLiteral("\n");
emit motorDetectionMessagesChanged();
Expand Down
10 changes: 5 additions & 5 deletions src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -57,11 +57,11 @@ APMFirmwarePlugin::APMFirmwarePlugin(void)
});

updateAvailableFlightModes({
// Mode Name , SM, Custom Mode CanBeSet adv FW MR
{ _guidedFlightMode , 0, APMCustomMode::GUIDED, true , true , false , true },
{ _rtlFlightMode , 0, APMCustomMode::RTL, true , true , false , true },
{ _smartRtlFlightMode , 0, APMCustomMode::SMART_RTL, true , true , false , true },
{ _autoFlightMode , 0, APMCustomMode::AUTO, true , true , false , true },
// Mode Name , Custom Mode CanBeSet adv
{ _guidedFlightMode , APMCustomMode::GUIDED, true , true },
{ _rtlFlightMode , APMCustomMode::RTL, true , true },
{ _smartRtlFlightMode , APMCustomMode::SMART_RTL, true , true },
{ _autoFlightMode , APMCustomMode::AUTO, true , true },
});

qmlRegisterType<APMFlightModesComponentController> ("QGroundControl.Controllers", 1, 0, "APMFlightModesComponentController");
Expand Down
70 changes: 40 additions & 30 deletions src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -77,33 +77,33 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
});

updateAvailableFlightModes({
// Mode Name ,SM, Custom Mode CanBeSet adv FW MR
{ _stabilizeFlightMode , 0, APMCopterMode::STABILIZE, true , true , false , true },
{ _acroFlightMode , 0, APMCopterMode::ACRO, true , true , false , true },
{ _altHoldFlightMode , 0, APMCopterMode::ALT_HOLD, true , true , false , true },
{ _autoFlightMode , 0, APMCopterMode::AUTO, true , true , false , true },
{ _guidedFlightMode , 0, APMCopterMode::GUIDED, true , true , false , true },
{ _loiterFlightMode , 0, APMCopterMode::LOITER, true , true , false , true },
{ _rtlFlightMode , 0, APMCopterMode::RTL, true , true , false , true },
{ _circleFlightMode , 0, APMCopterMode::CIRCLE, true , true , false , true },
{ _landFlightMode , 0, APMCopterMode::LAND, true , true , false , true },
{ _driftFlightMode , 0, APMCopterMode::DRIFT, true , true , false , true },
{ _sportFlightMode , 0, APMCopterMode::SPORT, true , true , false , true },
{ _flipFlightMode , 0, APMCopterMode::FLIP, true , true , false , true },
{ _autotuneFlightMode , 0, APMCopterMode::AUTOTUNE, true , true , false , true },
{ _posHoldFlightMode , 0, APMCopterMode::POS_HOLD, true , true , false , true },
{ _brakeFlightMode , 0, APMCopterMode::BRAKE, true , true , false , true },
{ _throwFlightMode , 0, APMCopterMode::THROW, true , true , false , true },
{ _avoidADSBFlightMode , 0, APMCopterMode::AVOID_ADSB, true , true , false , true },
{ _guidedNoGPSFlightMode , 0, APMCopterMode::GUIDED_NOGPS, true , true , false , true },
{ _smartRtlFlightMode , 0, APMCopterMode::SMART_RTL, true , true , false , true },
{ _flowHoldFlightMode , 0, APMCopterMode::FLOWHOLD, true , true , false , true },
{ _followFlightMode , 0, APMCopterMode::FOLLOW, true , true , false , true },
{ _zigzagFlightMode , 0, APMCopterMode::ZIGZAG, true , true , false , true },
{ _systemIDFlightMode , 0, APMCopterMode::SYSTEMID, true , true , false , true },
{ _autoRotateFlightMode , 0, APMCopterMode::AUTOROTATE, true , true , false , true },
{ _autoRTLFlightMode , 0, APMCopterMode::AUTO_RTL, true , true , false , true },
{ _turtleFlightMode , 0, APMCopterMode::TURTLE, true , true , false , true },
// Mode Name , Custom Mode CanBeSet adv
{ _stabilizeFlightMode , APMCopterMode::STABILIZE, true , true },
{ _acroFlightMode , APMCopterMode::ACRO, true , true },
{ _altHoldFlightMode , APMCopterMode::ALT_HOLD, true , true },
{ _autoFlightMode , APMCopterMode::AUTO, true , true },
{ _guidedFlightMode , APMCopterMode::GUIDED, true , true },
{ _loiterFlightMode , APMCopterMode::LOITER, true , true },
{ _rtlFlightMode , APMCopterMode::RTL, true , true },
{ _circleFlightMode , APMCopterMode::CIRCLE, true , true },
{ _landFlightMode , APMCopterMode::LAND, true , true },
{ _driftFlightMode , APMCopterMode::DRIFT, true , true },
{ _sportFlightMode , APMCopterMode::SPORT, true , true },
{ _flipFlightMode , APMCopterMode::FLIP, true , true },
{ _autotuneFlightMode , APMCopterMode::AUTOTUNE, true , true },
{ _posHoldFlightMode , APMCopterMode::POS_HOLD, true , true },
{ _brakeFlightMode , APMCopterMode::BRAKE, true , true },
{ _throwFlightMode , APMCopterMode::THROW, true , true },
{ _avoidADSBFlightMode , APMCopterMode::AVOID_ADSB, true , true },
{ _guidedNoGPSFlightMode , APMCopterMode::GUIDED_NOGPS, true , true },
{ _smartRtlFlightMode , APMCopterMode::SMART_RTL, true , true },
{ _flowHoldFlightMode , APMCopterMode::FLOWHOLD, true , true },
{ _followFlightMode , APMCopterMode::FOLLOW, true , true },
{ _zigzagFlightMode , APMCopterMode::ZIGZAG, true , true },
{ _systemIDFlightMode , APMCopterMode::SYSTEMID, true , true },
{ _autoRotateFlightMode , APMCopterMode::AUTOROTATE, true , true },
{ _autoRTLFlightMode , APMCopterMode::AUTO_RTL, true , true },
{ _turtleFlightMode , APMCopterMode::TURTLE, true , true },
});

if (!_remapParamNameIntialized) {
Expand Down Expand Up @@ -184,15 +184,25 @@ QString ArduCopterFirmwarePlugin::gotoFlightMode() const
return guidedFlightMode();
}

QString ArduCopterFirmwarePlugin::takeOffFlightMode() const
{
return guidedFlightMode();
}

QString ArduCopterFirmwarePlugin::stabilizedFlightMode() const
{
return _modeEnumToString.value(APMCopterMode::STABILIZE, _stabilizeFlightMode);
}

void ArduCopterFirmwarePlugin::updateAvailableFlightModes(FlightModeList modeList)
{
_availableFlightModeList.clear();
for(auto mode: modeList){
for(auto &mode: modeList){
mode.fixedWing = false;
mode.multiRotor = true;
_updateModeMappings(mode);
}

_updateModeMappings(modeList);

}

uint32_t ArduCopterFirmwarePlugin::_convertToCustomFlightModeEnum(uint32_t val) const
Expand Down
2 changes: 2 additions & 0 deletions src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,8 @@ class ArduCopterFirmwarePlugin : public APMFirmwarePlugin
QString takeControlFlightMode (void) const override;
QString followFlightMode (void) const override;
QString gotoFlightMode (void) const override;
QString takeOffFlightMode (void) const override;
QString stabilizedFlightMode (void) const override;
QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); }
bool supportsSmartRTL (void) const override { return true; }

Expand Down
61 changes: 33 additions & 28 deletions src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -67,31 +67,31 @@ ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(void)
});

updateAvailableFlightModes({
// Mode Name , SM, Custom Mode CanBeSet adv FW MR
{ _manualFlightMode , 0 , APMPlaneMode::MANUAL , true , true , true , true},
{ _circleFlightMode , 0 , APMPlaneMode::CIRCLE , true , true , true , true},
{ _stabilizeFlightMode , 0 , APMPlaneMode::STABILIZE , true , true , true , true},
{ _trainingFlightMode , 0 , APMPlaneMode::TRAINING , true , true , true , true},
{ _acroFlightMode , 0 , APMPlaneMode::ACRO , true , true , true , true},
{ _flyByWireAFlightMode , 0 , APMPlaneMode::FLY_BY_WIRE_A , true , true , true , true},
{ _flyByWireBFlightMode , 0 , APMPlaneMode::FLY_BY_WIRE_B , true , true , true , true},
{ _cruiseFlightMode , 0 , APMPlaneMode::CRUISE , true , true , true , true},
{ _autoTuneFlightMode , 0 , APMPlaneMode::AUTOTUNE , true , true , true , true},
{ _autoFlightMode , 0 , APMPlaneMode::AUTO , true , true , true , true},
{ _rtlFlightMode , 0 , APMPlaneMode::RTL , true , true , true , true},
{ _loiterFlightMode , 0 , APMPlaneMode::LOITER , true , true , true , true},
{ _takeoffFlightMode , 0 , APMPlaneMode::TAKEOFF , true , true , true , true},
{ _avoidADSBFlightMode , 0 , APMPlaneMode::AVOID_ADSB , true , true , true , true},
{ _guidedFlightMode , 0 , APMPlaneMode::GUIDED , true , true , true , true},
{ _initializingFlightMode , 0 , APMPlaneMode::INITIALIZING , true , true , true , true},
{ _qStabilizeFlightMode , 0 , APMPlaneMode::QSTABILIZE , true , true , true , true},
{ _qHoverFlightMode , 0 , APMPlaneMode::QHOVER , true , true , true , true},
{ _qLoiterFlightMode , 0 , APMPlaneMode::QLOITER , true , true , true , true},
{ _qLandFlightMode , 0 , APMPlaneMode::QLAND , true , true , true , true},
{ _qRTLFlightMode , 0 , APMPlaneMode::QRTL , true , true , true , true},
{ _qAutotuneFlightMode , 0 , APMPlaneMode::QAUTOTUNE , true , true , true , true},
{ _qAcroFlightMode , 0 , APMPlaneMode::QACRO , true , true , true , true},
{ _thermalFlightMode , 0 , APMPlaneMode::THERMAL , true , true , true , true},
// Mode Name , Custom Mode CanBeSet adv
{ _manualFlightMode , APMPlaneMode::MANUAL , true , true },
{ _circleFlightMode , APMPlaneMode::CIRCLE , true , true },
{ _stabilizeFlightMode , APMPlaneMode::STABILIZE , true , true },
{ _trainingFlightMode , APMPlaneMode::TRAINING , true , true },
{ _acroFlightMode , APMPlaneMode::ACRO , true , true },
{ _flyByWireAFlightMode , APMPlaneMode::FLY_BY_WIRE_A , true , true },
{ _flyByWireBFlightMode , APMPlaneMode::FLY_BY_WIRE_B , true , true },
{ _cruiseFlightMode , APMPlaneMode::CRUISE , true , true },
{ _autoTuneFlightMode , APMPlaneMode::AUTOTUNE , true , true },
{ _autoFlightMode , APMPlaneMode::AUTO , true , true },
{ _rtlFlightMode , APMPlaneMode::RTL , true , true },
{ _loiterFlightMode , APMPlaneMode::LOITER , true , true },
{ _takeoffFlightMode , APMPlaneMode::TAKEOFF , true , true },
{ _avoidADSBFlightMode , APMPlaneMode::AVOID_ADSB , true , true },
{ _guidedFlightMode , APMPlaneMode::GUIDED , true , true },
{ _initializingFlightMode , APMPlaneMode::INITIALIZING , true , true },
{ _qStabilizeFlightMode , APMPlaneMode::QSTABILIZE , true , true },
{ _qHoverFlightMode , APMPlaneMode::QHOVER , true , true },
{ _qLoiterFlightMode , APMPlaneMode::QLOITER , true , true },
{ _qLandFlightMode , APMPlaneMode::QLAND , true , true },
{ _qRTLFlightMode , APMPlaneMode::QRTL , true , true },
{ _qAutotuneFlightMode , APMPlaneMode::QAUTOTUNE , true , true },
{ _qAcroFlightMode , APMPlaneMode::QACRO , true , true },
{ _thermalFlightMode , APMPlaneMode::THERMAL , true , true },
});

if (!_remapParamNameIntialized) {
Expand All @@ -110,14 +110,19 @@ int ArduPlaneFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVer
return majorVersionNumber == 3 ? 10 : Vehicle::versionNotSetValue;
}

QString ArduPlaneFirmwarePlugin::stabilizedFlightMode() const
{
return _modeEnumToString.value(APMPlaneMode::STABILIZE, _stabilizeFlightMode);
}

void ArduPlaneFirmwarePlugin::updateAvailableFlightModes(FlightModeList modeList)
{
_availableFlightModeList.clear();
for(auto mode: modeList){
for(auto &mode: modeList){
mode.fixedWing = true;
mode.multiRotor = true;
_updateModeMappings(mode);
}

_updateModeMappings(modeList);
}

uint32_t ArduPlaneFirmwarePlugin::_convertToCustomFlightModeEnum(uint32_t val) const
Expand Down
1 change: 1 addition & 0 deletions src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ class ArduPlaneFirmwarePlugin : public APMFirmwarePlugin
int remapParamNameHigestMinorVersionNumber (int majorVersionNumber) const final;
const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; }

QString stabilizedFlightMode (void) const override;
void updateAvailableFlightModes (FlightModeList modeList) final;

protected:
Expand Down
Loading

0 comments on commit 41e4226

Please sign in to comment.