From d2e4b73edacbfc57c7cf905abaa9cdfa2bdac7dc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 21 Oct 2016 07:55:02 +1100 Subject: [PATCH] Revert "GCS_MAVLink: default to MAVLink2 enabled" Reverting change to MAVLink2 by default until SiK radio firmware issue with ECC is sorted out --- libraries/AP_SerialManager/AP_SerialManager.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 24bd3a4ab0..5eae8ea527 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -48,14 +48,14 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @Description: Control what protocol to use on the console. // @Values: 1:MAVlink1, 2:MAVLink2 // @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 // @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. // @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 - 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 // @DisplayName: Telem1 Baud Rate