mirror of https://github.com/ArduPilot/ardupilot
allow for lower serial baud rates
not many people will use less than 9600 baud, except for those wanting to test extreme range radios, which is what I'm trying to do :-)
This commit is contained in:
parent
ef9418c2de
commit
1a861b3de5
|
@ -627,6 +627,9 @@ check_startup_for_CLI()
|
|||
static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
|
||||
{
|
||||
switch (rate) {
|
||||
case 1: return 1200;
|
||||
case 2: return 2400;
|
||||
case 4: return 4800;
|
||||
case 9: return 9600;
|
||||
case 19: return 19200;
|
||||
case 38: return 38400;
|
||||
|
|
|
@ -544,6 +544,9 @@ static void resetPerfData(void) {
|
|||
static uint32_t map_baudrate(int8_t rate, uint32_t default_baud)
|
||||
{
|
||||
switch (rate) {
|
||||
case 1: return 1200;
|
||||
case 2: return 2400;
|
||||
case 4: return 4800;
|
||||
case 9: return 9600;
|
||||
case 19: return 19200;
|
||||
case 38: return 38400;
|
||||
|
|
Loading…
Reference in New Issue