diff --git a/ArduCopter/esc_calibration.cpp b/ArduCopter/esc_calibration.cpp index 152388d1ed..1457502252 100644 --- a/ArduCopter/esc_calibration.cpp +++ b/ArduCopter/esc_calibration.cpp @@ -9,7 +9,7 @@ // check if we should enter esc calibration mode 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 return; } @@ -153,7 +153,7 @@ void Copter::esc_calibration_setup() // clear esc flag for next time 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) motors->set_update_rate(g.rc_speed); } else { diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 681bf817a0..52d3a8185b 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -574,7 +574,7 @@ case AP_Motors::MOTOR_FRAME_DYNAMIC_SCRIPTING_MATRIX: } // 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); }