AP_BLHeli: use is_dshot_protocol in place of >= AP_HAL::RCOutput::MODE_PWM_DSHOT150

This commit is contained in:
Iampete1 2021-09-22 23:56:37 +01:00 committed by Andrew Tridgell
parent 3b8b90d170
commit 2b402ed2d7
1 changed files with 1 additions and 1 deletions

View File

@ -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;
} }