mirror of https://github.com/ArduPilot/ardupilot
AP_BLHeli: use is_dshot_protocol in place of >= AP_HAL::RCOutput::MODE_PWM_DSHOT150
This commit is contained in:
parent
3b8b90d170
commit
2b402ed2d7
|
@ -1339,7 +1339,7 @@ void AP_BLHeli::init(void)
|
||||||
// setting the digital mask changes the min/max PWM values
|
// setting the digital mask changes the min/max PWM values
|
||||||
// it's important that this is NOT done for non-digital channels as otherwise
|
// it's important that this is NOT done for non-digital channels as otherwise
|
||||||
// PWM min can result in motors turning. set for individual overrides first
|
// PWM min can result in motors turning. set for individual overrides first
|
||||||
if (mask && otype >= AP_HAL::RCOutput::MODE_PWM_DSHOT150) {
|
if (mask && hal.rcout->is_dshot_protocol(otype)) {
|
||||||
digital_mask = mask;
|
digital_mask = mask;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue