Copter: move rc input check to esc_calibration_startup_check
No functional change
This commit is contained in:
parent
fc675a1e4a
commit
032bfad79f
@ -19,6 +19,13 @@ enum ESCCalibrationModes {
|
||||
void Copter::esc_calibration_startup_check()
|
||||
{
|
||||
#if FRAME_CONFIG != HELI_FRAME
|
||||
// delay up to 2 second for first radio input
|
||||
uint8_t i = 0;
|
||||
while ((i++ < 100) && (last_radio_update_ms == 0)) {
|
||||
delay(20);
|
||||
read_radio();
|
||||
}
|
||||
|
||||
// exit immediately if pre-arm rc checks fail
|
||||
arming.pre_arm_rc_checks(true);
|
||||
if (!ap.pre_arm_rc_check) {
|
||||
|
@ -59,13 +59,6 @@ void Copter::init_rc_out()
|
||||
hal.rcout->set_esc_scaling(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
||||
#endif
|
||||
|
||||
// delay up to 2 second for first radio input
|
||||
uint8_t i = 0;
|
||||
while ((i++ < 100) && (last_radio_update_ms == 0)) {
|
||||
delay(20);
|
||||
read_radio();
|
||||
}
|
||||
|
||||
// check if we should enter esc calibration mode
|
||||
esc_calibration_startup_check();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user