Commit 6043cf95 authored by Daniel Agar's avatar Daniel Agar

PX4 only show FW/MC modes

parent 71b9b3d7
...@@ -167,8 +167,9 @@ QList<VehicleComponent*> APMFirmwarePlugin::componentsForVehicle(AutoPilotPlugin ...@@ -167,8 +167,9 @@ QList<VehicleComponent*> APMFirmwarePlugin::componentsForVehicle(AutoPilotPlugin
return QList<VehicleComponent*>(); return QList<VehicleComponent*>();
} }
QStringList APMFirmwarePlugin::flightModes(void) QStringList APMFirmwarePlugin::flightModes(Vehicle* vehicle)
{ {
Q_UNUSED(vehicle)
QStringList flightModesList; QStringList flightModesList;
foreach (const APMCustomMode& customMode, _supportedModes) { foreach (const APMCustomMode& customMode, _supportedModes) {
if (customMode.canBeSet()) { if (customMode.canBeSet()) {
......
...@@ -87,7 +87,7 @@ public: ...@@ -87,7 +87,7 @@ public:
QList<MAV_CMD> supportedMissionCommands(void) final; QList<MAV_CMD> supportedMissionCommands(void) final;
bool isCapable(FirmwareCapabilities capabilities); bool isCapable(FirmwareCapabilities capabilities);
QStringList flightModes(void) final; QStringList flightModes(Vehicle* vehicle) final;
QString flightMode(uint8_t base_mode, uint32_t custom_mode) const final; QString flightMode(uint8_t base_mode, uint32_t custom_mode) const final;
bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final; bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
bool isGuidedMode(const Vehicle* vehicle) const final; bool isGuidedMode(const Vehicle* vehicle) const final;
......
...@@ -84,7 +84,10 @@ public: ...@@ -84,7 +84,10 @@ public:
virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle); virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle);
/// Returns the list of available flight modes /// Returns the list of available flight modes
virtual QStringList flightModes(void) { return QStringList(); } virtual QStringList flightModes(Vehicle* vehicle) {
Q_UNUSED(vehicle);
return QStringList();
}
/// Returns the name for this flight mode. Flight mode names must be human readable as well as audio speakable. /// Returns the name for this flight mode. Flight mode names must be human readable as well as audio speakable.
/// @param base_mode Base mode from mavlink HEARTBEAT message /// @param base_mode Base mode from mavlink HEARTBEAT message
......
...@@ -68,6 +68,8 @@ struct Modes2Name { ...@@ -68,6 +68,8 @@ struct Modes2Name {
uint8_t sub_mode; uint8_t sub_mode;
const char* name; ///< Name for flight mode const char* name; ///< Name for flight mode
bool canBeSet; ///< true: Vehicle can be set to this 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"; 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 /// Tranlates from PX4 custom modes to flight mode names
static const struct Modes2Name rgModes2Name[] = { static const struct Modes2Name rgModes2Name[] = {
{ PX4_CUSTOM_MAIN_MODE_MANUAL, 0, PX4FirmwarePlugin::manualFlightMode, true }, { PX4_CUSTOM_MAIN_MODE_MANUAL, 0, PX4FirmwarePlugin::manualFlightMode, true, true, true},
{ PX4_CUSTOM_MAIN_MODE_ACRO, 0, PX4FirmwarePlugin::acroFlightMode, true }, { PX4_CUSTOM_MAIN_MODE_ACRO, 0, PX4FirmwarePlugin::acroFlightMode, true, false, true},
{ PX4_CUSTOM_MAIN_MODE_STABILIZED, 0, PX4FirmwarePlugin::stabilizedFlightMode, true }, { PX4_CUSTOM_MAIN_MODE_STABILIZED, 0, PX4FirmwarePlugin::stabilizedFlightMode, true, true, true},
{ PX4_CUSTOM_MAIN_MODE_RATTITUDE, 0, PX4FirmwarePlugin::rattitudeFlightMode, true }, { PX4_CUSTOM_MAIN_MODE_RATTITUDE, 0, PX4FirmwarePlugin::rattitudeFlightMode, true, false, true},
{ PX4_CUSTOM_MAIN_MODE_ALTCTL, 0, PX4FirmwarePlugin::altCtlFlightMode, true }, { PX4_CUSTOM_MAIN_MODE_ALTCTL, 0, PX4FirmwarePlugin::altCtlFlightMode, true, true, true},
{ PX4_CUSTOM_MAIN_MODE_POSCTL, 0, PX4FirmwarePlugin::posCtlFlightMode, true }, { PX4_CUSTOM_MAIN_MODE_POSCTL, 0, PX4FirmwarePlugin::posCtlFlightMode, true, true, true},
{ PX4_CUSTOM_MAIN_MODE_OFFBOARD, 0, PX4FirmwarePlugin::offboardFlightMode, 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 }, { 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 }, { 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 }, { 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 }, { 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 }, { 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 }, { 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 }, { 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 }, { PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_ME, PX4FirmwarePlugin::followMeFlightMode, true, true, true},
}; };
QList<VehicleComponent*> PX4FirmwarePlugin::componentsForVehicle(AutoPilotPlugin* vehicle) 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*>(); return QList<VehicleComponent*>();
} }
QStringList PX4FirmwarePlugin::flightModes(void) QStringList PX4FirmwarePlugin::flightModes(Vehicle* vehicle)
{ {
QStringList flightModes; QStringList flightModes;
...@@ -121,9 +123,17 @@ QStringList PX4FirmwarePlugin::flightModes(void) ...@@ -121,9 +123,17 @@ QStringList PX4FirmwarePlugin::flightModes(void)
const struct Modes2Name* pModes2Name = &rgModes2Name[i]; const struct Modes2Name* pModes2Name = &rgModes2Name[i];
if (pModes2Name->canBeSet) { if (pModes2Name->canBeSet) {
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; flightModes += pModes2Name->name;
} }
} }
}
return flightModes; return flightModes;
} }
......
...@@ -42,7 +42,7 @@ public: ...@@ -42,7 +42,7 @@ public:
QList<MAV_CMD> supportedMissionCommands(void) final; QList<MAV_CMD> supportedMissionCommands(void) final;
bool isCapable (FirmwareCapabilities capabilities) final; bool isCapable (FirmwareCapabilities capabilities) final;
QStringList flightModes (void) final; QStringList flightModes (Vehicle* vehicle) final;
QString flightMode (uint8_t base_mode, uint32_t custom_mode) const final; QString flightMode (uint8_t base_mode, uint32_t custom_mode) const final;
bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final; bool setFlightMode (const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) final;
void setGuidedMode(Vehicle* vehicle, bool guidedMode) final; void setGuidedMode(Vehicle* vehicle, bool guidedMode) final;
......
...@@ -1193,7 +1193,7 @@ bool Vehicle::flightModeSetAvailable(void) ...@@ -1193,7 +1193,7 @@ bool Vehicle::flightModeSetAvailable(void)
QStringList Vehicle::flightModes(void) QStringList Vehicle::flightModes(void)
{ {
return _firmwarePlugin->flightModes(); return _firmwarePlugin->flightModes(this);
} }
QString Vehicle::flightMode(void) const QString Vehicle::flightMode(void) const
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment