mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_SerialManager: uartA with 460800 baud for aerofc
This commit is contained in:
parent
b1a6b03cbf
commit
a682bb837a
@ -82,4 +82,7 @@
|
||||
|
||||
#define HAL_COMPASS_IST8310_I2C_ADDR 0x0E
|
||||
#define HAL_COMPASS_IST8310_I2C_BUS 1
|
||||
|
||||
#undef HAL_SERIAL0_BAUD_DEFAULT
|
||||
#define HAL_SERIAL0_BAUD_DEFAULT 460800
|
||||
#endif
|
||||
|
@ -38,7 +38,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Param: 0_BAUD
|
||||
// @DisplayName: Serial0 baud rate
|
||||
// @Description: The baud rate used on the USB console. The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
|
||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,500:500000,921:921600,1500:1500000
|
||||
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,460:460800,500:500000,921:921600,1500:1500000
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("0_BAUD", 0, AP_SerialManager, state[0].baud, AP_SERIALMANAGER_CONSOLE_BAUD/1000),
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user