|
|
|
@ -245,3 +245,43 @@ void AP_SerialManager::set_console_baud(enum SerialProtocol protocol) const
@@ -245,3 +245,43 @@ void AP_SerialManager::set_console_baud(enum SerialProtocol protocol) const
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
* map from a 16 bit EEPROM baud rate to a real baud rate |
|
|
|
|
* The practical rates for APM1/APM2 are up to 500kbaud, although |
|
|
|
|
* beyond 115200 isn't recommended. For PX4 we can do 1.5MBit, |
|
|
|
|
* although 921600 is more reliable |
|
|
|
|
*/ |
|
|
|
|
uint32_t AP_SerialManager::map_baudrate(int32_t rate) const |
|
|
|
|
{ |
|
|
|
|
if (rate <= 0) { |
|
|
|
|
rate = 57; |
|
|
|
|
} |
|
|
|
|
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; |
|
|
|
|
case 57: return 57600; |
|
|
|
|
case 100: return 100000; |
|
|
|
|
case 111: return 111100; |
|
|
|
|
case 115: return 115200; |
|
|
|
|
case 230: return 230400; |
|
|
|
|
case 460: return 460800; |
|
|
|
|
case 500: return 500000; |
|
|
|
|
case 921: return 921600; |
|
|
|
|
case 1500: return 1500000; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (rate > 2000) { |
|
|
|
|
// assume it is a direct baudrate. This allows for users to
|
|
|
|
|
// set an exact baudrate as long as it is over 2000 baud
|
|
|
|
|
return (uint32_t)rate; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// otherwise allow any other kbaud rate
|
|
|
|
|
return rate*1000; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|