Copter: disable ESC calibration for brushed motors

This commit is contained in:
Andrew Tridgell 2017-06-04 18:02:30 +10:00 committed by Randy Mackay
parent 33feeb1c11
commit 650a0e06bd
1 changed files with 5 additions and 0 deletions

View File

@ -18,6 +18,11 @@ enum ESCCalibrationModes {
// check if we should enter esc calibration mode
void Copter::esc_calibration_startup_check()
{
if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_BRUSHED16kHz) {
// ESC cal not valid for brushed motors
return;
}
#if FRAME_CONFIG != HELI_FRAME
// delay up to 2 second for first radio input
uint8_t i = 0;