mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_SerialManager: correct docs for SERIAL8
This commit is contained in:
parent
25aedc4ee7
commit
20a91dc1c8
@ -345,7 +345,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
|
|
||||||
// @Param: 8_BAUD
|
// @Param: 8_BAUD
|
||||||
// @DisplayName: Serial 8 Baud Rate
|
// @DisplayName: Serial 8 Baud Rate
|
||||||
// @Description: The baud rate used for Serial7. 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 for Serial8. 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
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("8_BAUD", 27, AP_SerialManager, state[8].baud, SERIAL8_BAUD),
|
AP_GROUPINFO("8_BAUD", 27, AP_SerialManager, state[8].baud, SERIAL8_BAUD),
|
||||||
|
Loading…
Reference in New Issue
Block a user