Copter: don't check PWM type directly use helpers

This commit is contained in:
Iampete1 2021-09-22 16:17:25 +01:00 committed by Andrew Tridgell
parent b472300191
commit 1f163453fc
2 changed files with 3 additions and 3 deletions

View File

@ -9,7 +9,7 @@
// check if we should enter esc calibration mode // check if we should enter esc calibration mode
void Copter::esc_calibration_startup_check() void Copter::esc_calibration_startup_check()
{ {
if (motors->get_pwm_type() == AP_Motors::PWM_TYPE_BRUSHED) { if (motors->is_brushed_pwm_type()) {
// ESC cal not valid for brushed motors // ESC cal not valid for brushed motors
return; return;
} }
@ -153,7 +153,7 @@ void Copter::esc_calibration_setup()
// clear esc flag for next time // clear esc flag for next time
g.esc_calibrate.set_and_save(ESCCAL_NONE); g.esc_calibrate.set_and_save(ESCCAL_NONE);
if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_ONESHOT) { if (motors->is_normal_pwm_type()) {
// run at full speed for oneshot ESCs (actually done on push) // run at full speed for oneshot ESCs (actually done on push)
motors->set_update_rate(g.rc_speed); motors->set_update_rate(g.rc_speed);
} else { } else {

View File

@ -574,7 +574,7 @@ case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX:
} }
// brushed 16kHz defaults to 16kHz pulses // brushed 16kHz defaults to 16kHz pulses
if (motors->get_pwm_type() == AP_Motors::PWM_TYPE_BRUSHED) { if (motors->is_brushed_pwm_type()) {
g.rc_speed.set_default(16000); g.rc_speed.set_default(16000);
} }