mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: Fix to SITL RPM driver instance
This commit is contained in:
parent
7e35622015
commit
5f11afde6d
|
@ -111,7 +111,7 @@ void AP_RPM::init(void)
|
||||||
}
|
}
|
||||||
for (uint8_t i=0; i<RPM_MAX_INSTANCES; i++) {
|
for (uint8_t i=0; i<RPM_MAX_INSTANCES; i++) {
|
||||||
uint8_t type = _type[i];
|
uint8_t type = _type[i];
|
||||||
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||||
if (type == RPM_TYPE_PWM) {
|
if (type == RPM_TYPE_PWM) {
|
||||||
// PWM option same as PIN option, for upgrade
|
// PWM option same as PIN option, for upgrade
|
||||||
type = RPM_TYPE_PIN;
|
type = RPM_TYPE_PIN;
|
||||||
|
@ -119,6 +119,7 @@ void AP_RPM::init(void)
|
||||||
if (type == RPM_TYPE_PIN) {
|
if (type == RPM_TYPE_PIN) {
|
||||||
drivers[i] = new AP_RPM_Pin(*this, i, state[i]);
|
drivers[i] = new AP_RPM_Pin(*this, i, state[i]);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
#if EFI_ENABLED
|
#if EFI_ENABLED
|
||||||
if (type == RPM_TYPE_EFI) {
|
if (type == RPM_TYPE_EFI) {
|
||||||
drivers[i] = new AP_RPM_EFI(*this, i, state[i]);
|
drivers[i] = new AP_RPM_EFI(*this, i, state[i]);
|
||||||
|
|
Loading…
Reference in New Issue