AP_SerialManager: default wifi port to MAVLink at 921600 on Pixracer

This commit is contained in:
Andrew Tridgell 2016-04-13 21:24:42 +10:00
parent 8695668da3
commit 8b6322082e
1 changed files with 11 additions and 2 deletions

View File

@ -26,6 +26,15 @@
extern const AP_HAL::HAL& hal;
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V4
#define SERIAL4_PROTOCOL SerialProtocol_MAVLink
#define SERIAL4_BAUD 921600
#else
#define SERIAL4_PROTOCOL SerialProtocol_GPS
#define SERIAL4_BAUD AP_SERIALMANAGER_GPS_BAUD/1000
#endif
const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Param: 0_BAUD
// @DisplayName: Serial0 baud rate
@ -81,14 +90,14 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Description: Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
// @Values: 1:GCS Mavlink, 3:Frsky D-PORT, 4:Frsky S-PORT, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar
// @User: Standard
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SerialProtocol_GPS),
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SERIAL4_PROTOCOL),
// @Param: 4_BAUD
// @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.
// @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
// @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, SERIAL4_BAUD),
AP_GROUPEND
};