Revert "GCS_MAVLink: default to MAVLink2 enabled"

Reverting change to MAVLink2 by default until SiK radio firmware issue
with ECC is sorted out
This commit is contained in:
Andrew Tridgell 2016-10-21 07:55:02 +11:00
parent 3d1db89655
commit d2e4b73eda
1 changed files with 2 additions and 2 deletions

View File

@ -48,14 +48,14 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Description: Control what protocol to use on the console. // @Description: Control what protocol to use on the console.
// @Values: 1:MAVlink1, 2:MAVLink2 // @Values: 1:MAVlink1, 2:MAVLink2
// @User: Standard // @User: Standard
AP_GROUPINFO("0_PROTOCOL", 11, AP_SerialManager, state[0].protocol, SerialProtocol_MAVLink2), AP_GROUPINFO("0_PROTOCOL", 11, AP_SerialManager, state[0].protocol, SerialProtocol_MAVLink),
// @Param: 1_PROTOCOL // @Param: 1_PROTOCOL
// @DisplayName: Telem1 protocol selection // @DisplayName: Telem1 protocol selection
// @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details. // @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360 // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360
// @User: Standard // @User: Standard
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink2), AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink),
// @Param: 1_BAUD // @Param: 1_BAUD
// @DisplayName: Telem1 Baud Rate // @DisplayName: Telem1 Baud Rate