AP_SerialManager: Added 256000 baud rate to display
This commit is contained in:
parent
43ed4175b1
commit
2e1e99eafc
@ -51,7 +51,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. 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.
|
// @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,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,256:256000,460:460800,500:500000,921:921600,1500:1500000
|
||||||
// @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),
|
||||||
|
|
||||||
@ -74,7 +74,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. 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.
|
// @Description: The baud rate used on the Telem1 port. 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,256:256000,500:500000,921:921600,1500:1500000
|
||||||
// @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),
|
||||||
|
|
||||||
@ -89,7 +89,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 2_BAUD
|
// @Param: 2_BAUD
|
||||||
// @DisplayName: Telemetry 2 Baud Rate
|
// @DisplayName: Telemetry 2 Baud Rate
|
||||||
// @Description: The baud rate of the Telem2 port. 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.
|
// @Description: The baud rate of the Telem2 port. 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,256:256000,500:500000,921:921600,1500:1500000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("2_BAUD", 4, AP_SerialManager, state[2].baud, AP_SERIALMANAGER_MAVLINK_BAUD/1000),
|
AP_GROUPINFO("2_BAUD", 4, AP_SerialManager, state[2].baud, AP_SERIALMANAGER_MAVLINK_BAUD/1000),
|
||||||
|
|
||||||
@ -104,7 +104,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 3_BAUD
|
// @Param: 3_BAUD
|
||||||
// @DisplayName: Serial 3 (GPS) Baud Rate
|
// @DisplayName: Serial 3 (GPS) Baud Rate
|
||||||
// @Description: The baud rate used for the Serial 3 (GPS). 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.
|
// @Description: The baud rate used for the Serial 3 (GPS). 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,256:256000,500:500000,921:921600,1500:1500000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("3_BAUD", 6, AP_SerialManager, state[3].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
|
AP_GROUPINFO("3_BAUD", 6, AP_SerialManager, state[3].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
|
||||||
|
|
||||||
@ -119,7 +119,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 4_BAUD
|
// @Param: 4_BAUD
|
||||||
// @DisplayName: Serial 4 Baud Rate
|
// @DisplayName: Serial 4 Baud Rate
|
||||||
// @Description: The baud rate used for Serial4. 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.
|
// @Description: The baud rate used for Serial4. 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,256:256000,500:500000,921:921600,1500:1500000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("4_BAUD", 8, AP_SerialManager, state[4].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
|
AP_GROUPINFO("4_BAUD", 8, AP_SerialManager, state[4].baud, AP_SERIALMANAGER_GPS_BAUD/1000),
|
||||||
|
|
||||||
@ -134,7 +134,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 5_BAUD
|
// @Param: 5_BAUD
|
||||||
// @DisplayName: Serial 5 Baud Rate
|
// @DisplayName: Serial 5 Baud Rate
|
||||||
// @Description: The baud rate used for Serial5. 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.
|
// @Description: The baud rate used for Serial5. 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,256:256000,500:500000,921:921600,1500:1500000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("5_BAUD", 10, AP_SerialManager, state[5].baud, SERIAL5_BAUD),
|
AP_GROUPINFO("5_BAUD", 10, AP_SerialManager, state[5].baud, SERIAL5_BAUD),
|
||||||
|
|
||||||
@ -151,7 +151,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 6_BAUD
|
// @Param: 6_BAUD
|
||||||
// @DisplayName: Serial 6 Baud Rate
|
// @DisplayName: Serial 6 Baud Rate
|
||||||
// @Description: The baud rate used for Serial6. 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.
|
// @Description: The baud rate used for Serial6. 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,256:256000,500:500000,921:921600,1500:1500000
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("6_BAUD", 13, AP_SerialManager, state[6].baud, SERIAL6_BAUD),
|
AP_GROUPINFO("6_BAUD", 13, AP_SerialManager, state[6].baud, SERIAL6_BAUD),
|
||||||
|
|
||||||
@ -479,6 +479,7 @@ uint32_t AP_SerialManager::map_baudrate(int32_t rate) const
|
|||||||
case 111: return 111100;
|
case 111: return 111100;
|
||||||
case 115: return 115200;
|
case 115: return 115200;
|
||||||
case 230: return 230400;
|
case 230: return 230400;
|
||||||
|
case 256: return 256000;
|
||||||
case 460: return 460800;
|
case 460: return 460800;
|
||||||
case 500: return 500000;
|
case 500: return 500000;
|
||||||
case 921: return 921600;
|
case 921: return 921600;
|
||||||
|
Loading…
Reference in New Issue
Block a user