diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 63771441fb..1d27ec559a 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -257,7 +257,6 @@ void AP_SerialManager::set_blocking_writes_all(bool blocking) } // set_console_baud - sets the console's baud rate to the rate specified by the protocol -// used on APM2 to switch the console between the console baud rate (115200) and the SERIAL1 baud rate (user configurable) void AP_SerialManager::set_console_baud(enum SerialProtocol protocol, uint8_t instance) const { uint8_t found_instance = 0; @@ -276,10 +275,8 @@ void AP_SerialManager::set_console_baud(enum SerialProtocol protocol, uint8_t in } /* - * 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 + * map from a 16 bit EEPROM baud rate to a real baud rate. + * For PX4 we can do 1.5MBit, although 921600 is more reliable. */ uint32_t AP_SerialManager::map_baudrate(int32_t rate) const { diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index a6e112cf45..5524c5a0ce 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -112,7 +112,6 @@ public: void set_blocking_writes_all(bool blocking); // set_console_baud - sets the console's baud rate to the rate specified by the protocol - // used on APM2 to switch the console between the console baud rate (115200) and the SERIAL1 baud rate (user configurable) void set_console_baud(enum SerialProtocol protocol, uint8_t instance) const; // parameter var table