|
|
|
@ -68,6 +68,8 @@ struct Modes2Name {
@@ -68,6 +68,8 @@ struct Modes2Name {
|
|
|
|
|
uint8_t sub_mode; |
|
|
|
|
const char* name; ///< Name for flight mode
|
|
|
|
|
bool canBeSet; ///< true: Vehicle can be set to this flight mode
|
|
|
|
|
bool fixedWing; /// fixed wing compatible
|
|
|
|
|
bool multiRotor; /// multi rotor compatible
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
const char* PX4FirmwarePlugin::manualFlightMode = "Manual"; |
|
|
|
@ -89,21 +91,21 @@ const char* PX4FirmwarePlugin::followMeFlightMode = "Follow Me";
@@ -89,21 +91,21 @@ const char* PX4FirmwarePlugin::followMeFlightMode = "Follow Me";
|
|
|
|
|
/// Tranlates from PX4 custom modes to flight mode names
|
|
|
|
|
|
|
|
|
|
static const struct Modes2Name rgModes2Name[] = { |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_MANUAL, 0, PX4FirmwarePlugin::manualFlightMode, true }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_ACRO, 0, PX4FirmwarePlugin::acroFlightMode, true }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_STABILIZED, 0, PX4FirmwarePlugin::stabilizedFlightMode, true }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_RATTITUDE, 0, PX4FirmwarePlugin::rattitudeFlightMode, true }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_ALTCTL, 0, PX4FirmwarePlugin::altCtlFlightMode, true }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_POSCTL, 0, PX4FirmwarePlugin::posCtlFlightMode, true }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_OFFBOARD, 0, PX4FirmwarePlugin::offboardFlightMode, true }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_READY, PX4FirmwarePlugin::readyFlightMode, false }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF, PX4FirmwarePlugin::takeoffFlightMode, false }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LOITER, PX4FirmwarePlugin::pauseFlightMode, true }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_MISSION, PX4FirmwarePlugin::missionFlightMode, true }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTL, PX4FirmwarePlugin::rtlFlightMode, true }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LAND, PX4FirmwarePlugin::landingFlightMode, false }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTGS, PX4FirmwarePlugin::rtgsFlightMode, false }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_ME, PX4FirmwarePlugin::followMeFlightMode, true }, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_MANUAL, 0, PX4FirmwarePlugin::manualFlightMode, true, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_ACRO, 0, PX4FirmwarePlugin::acroFlightMode, true, false, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_STABILIZED, 0, PX4FirmwarePlugin::stabilizedFlightMode, true, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_RATTITUDE, 0, PX4FirmwarePlugin::rattitudeFlightMode, true, false, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_ALTCTL, 0, PX4FirmwarePlugin::altCtlFlightMode, true, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_POSCTL, 0, PX4FirmwarePlugin::posCtlFlightMode, true, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_OFFBOARD, 0, PX4FirmwarePlugin::offboardFlightMode, true, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_READY, PX4FirmwarePlugin::readyFlightMode, false, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF, PX4FirmwarePlugin::takeoffFlightMode, false, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LOITER, PX4FirmwarePlugin::pauseFlightMode, true, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_MISSION, PX4FirmwarePlugin::missionFlightMode, true, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTL, PX4FirmwarePlugin::rtlFlightMode, true, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_LAND, PX4FirmwarePlugin::landingFlightMode, false, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_RTGS, PX4FirmwarePlugin::rtgsFlightMode, false, true, true}, |
|
|
|
|
{ PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_ME, PX4FirmwarePlugin::followMeFlightMode, true, true, true}, |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
QList<VehicleComponent*> PX4FirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle) |
|
|
|
@ -113,7 +115,7 @@ QList<VehicleComponent*> PX4FirmwarePlugin::componentsForVehicle(AutoPilotPlugin
@@ -113,7 +115,7 @@ QList<VehicleComponent*> PX4FirmwarePlugin::componentsForVehicle(AutoPilotPlugin
|
|
|
|
|
return QList<VehicleComponent*>(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
QStringList PX4FirmwarePlugin::flightModes(void) |
|
|
|
|
QStringList PX4FirmwarePlugin::flightModes(Vehicle* vehicle) |
|
|
|
|
{ |
|
|
|
|
QStringList flightModes; |
|
|
|
|
|
|
|
|
@ -121,7 +123,15 @@ QStringList PX4FirmwarePlugin::flightModes(void)
@@ -121,7 +123,15 @@ QStringList PX4FirmwarePlugin::flightModes(void)
|
|
|
|
|
const struct Modes2Name* pModes2Name = &rgModes2Name[i]; |
|
|
|
|
|
|
|
|
|
if (pModes2Name->canBeSet) { |
|
|
|
|
flightModes += pModes2Name->name; |
|
|
|
|
bool fw = (vehicle->fixedWing() && pModes2Name->fixedWing); |
|
|
|
|
bool mc = (vehicle->multiRotor() && pModes2Name->multiRotor); |
|
|
|
|
|
|
|
|
|
// show all modes for generic, vtol, etc
|
|
|
|
|
bool other = !vehicle->fixedWing() && !vehicle->multiRotor(); |
|
|
|
|
|
|
|
|
|
if (fw || mc || other) { |
|
|
|
|
flightModes += pModes2Name->name; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|