mirror of https://github.com/ArduPilot/ardupilot
AP_Bootloader: support changing baudrates on UARTs
This commit is contained in:
parent
e40457d98f
commit
0ebd05aa1a
|
@ -733,9 +733,14 @@ bootloader(unsigned timeout)
|
|||
// send the sync response for this command
|
||||
sync_response();
|
||||
|
||||
delay(5);
|
||||
|
||||
// set the baudrate
|
||||
port_setbaud(baud);
|
||||
|
||||
lock_bl_port();
|
||||
timeout = 0;
|
||||
|
||||
// this is different to what every other case in this
|
||||
// switch does! Most go through sync_response down the
|
||||
// bottom, but we need to undertake an action after
|
||||
|
|
|
@ -29,7 +29,7 @@ int16_t cin(unsigned timeout_ms)
|
|||
}
|
||||
}
|
||||
}
|
||||
chThdSleepMicroseconds(100);
|
||||
chThdSleepMicroseconds(500);
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
@ -43,7 +43,7 @@ int cin_word(uint32_t *wp, unsigned timeout_ms)
|
|||
}
|
||||
}
|
||||
}
|
||||
chThdSleepMicroseconds(100);
|
||||
chThdSleepMicroseconds(500);
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
@ -346,14 +346,14 @@ void init_uarts(void)
|
|||
*/
|
||||
void port_setbaud(uint32_t baudrate)
|
||||
{
|
||||
sercfg.speed = baudrate;
|
||||
#ifdef HAL_USE_SERIAL_USB
|
||||
if (uarts[last_uart] == (BaseChannel *)&SDU1) {
|
||||
// can't set baudrate on USB
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
sdStop((SerialDriver *)uarts[last_uart]);
|
||||
memset(&sercfg, 0, sizeof(sercfg));
|
||||
sercfg.speed = baudrate;
|
||||
sdStart((SerialDriver *)uarts[last_uart], &sercfg);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue