mirror of https://github.com/ArduPilot/ardupilot
AP_SerialManager: Add 2Mbps for simulator
This commit is contained in:
parent
d0b7e5fe82
commit
0fedd83208
|
@ -119,7 +119,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @Param: 0_BAUD
|
// @Param: 0_BAUD
|
||||||
// @DisplayName: Serial0 baud rate
|
// @DisplayName: Serial0 baud rate
|
||||||
// @Description: The baud rate used on the USB console. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support 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.
|
// @Description: The baud rate used on the USB console. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support 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,230:230400,256:256000,460:460800,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,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000,2000:2000000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("0_BAUD", 0, AP_SerialManager, state[0].baud, AP_SERIALMANAGER_CONSOLE_BAUD/1000),
|
AP_GROUPINFO("0_BAUD", 0, AP_SerialManager, state[0].baud, AP_SERIALMANAGER_CONSOLE_BAUD/1000),
|
||||||
|
|
||||||
|
@ -144,7 +144,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||||
// @Param: 1_BAUD
|
// @Param: 1_BAUD
|
||||||
// @DisplayName: Telem1 Baud Rate
|
// @DisplayName: Telem1 Baud Rate
|
||||||
// @Description: The baud rate used on the Telem1 port. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support 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.
|
// @Description: The baud rate used on the Telem1 port. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support 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,230:230400,256:256000,460:460800,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,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000,2000:2000000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("1_BAUD", 2, AP_SerialManager, state[1].baud, AP_SERIALMANAGER_MAVLINK_BAUD/1000),
|
AP_GROUPINFO("1_BAUD", 2, AP_SerialManager, state[1].baud, AP_SERIALMANAGER_MAVLINK_BAUD/1000),
|
||||||
#endif
|
#endif
|
||||||
|
@ -646,6 +646,7 @@ uint32_t AP_SerialManager::map_baudrate(int32_t rate)
|
||||||
case 500: return 500000;
|
case 500: return 500000;
|
||||||
case 921: return 921600;
|
case 921: return 921600;
|
||||||
case 1500: return 1500000;
|
case 1500: return 1500000;
|
||||||
|
case 2000: return 2000000;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rate > 2000) {
|
if (rate > 2000) {
|
||||||
|
|
Loading…
Reference in New Issue