@ -121,7 +121,7 @@ void AP_RPM::init(void)
drivers[i] = new AP_RPM_Pin(*this, i, state[i]);
}
#endif
#if EFI_ENABLED
#if HAL_EFI_ENABLED
if (type == RPM_TYPE_EFI) {
drivers[i] = new AP_RPM_EFI(*this, i, state[i]);
@ -17,7 +17,7 @@
#include "RPM_EFI.h"
extern const AP_HAL::HAL& hal;
/*
@ -41,4 +41,4 @@ void AP_RPM_EFI::update(void)
state.last_reading_ms = AP_HAL::millis();
#endif // EFI_ENABLED
#endif // HAL_EFI_ENABLED