mirror of https://github.com/ArduPilot/ardupilot
AP_EFI: use enum class for protocol
This commit is contained in:
parent
5edfed0083
commit
7ea5bc7e3e
|
@ -72,18 +72,20 @@ void AP_EFI::init(void)
|
|||
// Init called twice, perhaps
|
||||
return;
|
||||
}
|
||||
// Check for MegaSquirt Serial EFI
|
||||
switch (type) {
|
||||
case EFI_COMMUNICATION_TYPE_NONE:
|
||||
break;
|
||||
case EFI_COMMUNICATION_TYPE_SERIAL_MS:
|
||||
backend = new AP_EFI_Serial_MS(*this);
|
||||
break;
|
||||
case EFI_COMMUNICATION_TYPE_NWPMU:
|
||||
switch ((Type)type.get()) {
|
||||
case Type::NONE:
|
||||
break;
|
||||
case Type::MegaSquirt:
|
||||
backend = new AP_EFI_Serial_MS(*this);
|
||||
break;
|
||||
case Type::NWPMU:
|
||||
#if HAL_EFI_NWPWU_ENABLED
|
||||
backend = new AP_EFI_NWPMU(*this);
|
||||
backend = new AP_EFI_NWPMU(*this);
|
||||
#endif
|
||||
break;
|
||||
break;
|
||||
default:
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Unknown EFI type");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -60,7 +60,7 @@ public:
|
|||
uint32_t get_rpm() const { return state.engine_speed_rpm; }
|
||||
|
||||
// returns enabled state of EFI
|
||||
bool enabled() const { return type != EFI_COMMUNICATION_TYPE_NONE; }
|
||||
bool enabled() const { return type != Type::NONE; }
|
||||
|
||||
bool is_healthy() const;
|
||||
|
||||
|
@ -68,10 +68,10 @@ public:
|
|||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
// Backend driver types
|
||||
enum EFI_Communication_Type {
|
||||
EFI_COMMUNICATION_TYPE_NONE = 0,
|
||||
EFI_COMMUNICATION_TYPE_SERIAL_MS = 1,
|
||||
EFI_COMMUNICATION_TYPE_NWPMU = 2,
|
||||
enum class Type : uint8_t {
|
||||
NONE = 0,
|
||||
MegaSquirt = 1,
|
||||
NWPMU = 2,
|
||||
};
|
||||
|
||||
static AP_EFI *get_singleton(void) {
|
||||
|
@ -91,7 +91,7 @@ protected:
|
|||
|
||||
private:
|
||||
// Front End Parameters
|
||||
AP_Int8 type;
|
||||
AP_Enum<Type> type;
|
||||
|
||||
// Tracking backends
|
||||
AP_EFI_Backend *backend;
|
||||
|
|
Loading…
Reference in New Issue