Copter: delay up to 2sec for first radio pulse

Pixracer boards can take 1 second (or possibly longer) to start reading RC input.  This ensure we see the user's high throttle to indicate the user wants to perform the ESC calibration
This commit is contained in:
Randy Mackay 2017-01-26 12:01:18 +09:00
parent 855125381d
commit a25f51c893
1 changed files with 3 additions and 1 deletions

View File

@ -55,7 +55,9 @@ void Copter::init_rc_out()
motors->set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
#endif
for(uint8_t i = 0; i < 5; i++) {
// 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();
}