mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: treat RPM_TYPE 1 as type 2 on non-PX4
makes upgrades easier
This commit is contained in:
parent
925555c995
commit
9b3788c83c
|
@ -105,12 +105,17 @@ void AP_RPM::init(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
for (uint8_t i=0; i<RPM_MAX_INSTANCES; i++) {
|
for (uint8_t i=0; i<RPM_MAX_INSTANCES; i++) {
|
||||||
const uint8_t type = _type[i];
|
uint8_t type = _type[i];
|
||||||
|
|
||||||
#if (CONFIG_HAL_BOARD == HAL_BOARD_PX4) || ((CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN) && (!defined(CONFIG_ARCH_BOARD_VRBRAIN_V51) && !defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)))
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_PX4) || ((CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN) && (!defined(CONFIG_ARCH_BOARD_VRBRAIN_V51) && !defined(CONFIG_ARCH_BOARD_VRUBRAIN_V52)))
|
||||||
if (type == RPM_TYPE_PX4_PWM) {
|
if (type == RPM_TYPE_PX4_PWM) {
|
||||||
drivers[i] = new AP_RPM_PX4_PWM(*this, i, state[i]);
|
drivers[i] = new AP_RPM_PX4_PWM(*this, i, state[i]);
|
||||||
}
|
}
|
||||||
|
#else
|
||||||
|
if (type == RPM_TYPE_PX4_PWM) {
|
||||||
|
// on non-PX4 treat PX4-pin as AUXPIN option, for upgrade
|
||||||
|
type = RPM_TYPE_PIN;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
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]);
|
||||||
|
|
Loading…
Reference in New Issue