From 50eecf58a4d1be16bdffdf02f5df247de5dc7cb0 Mon Sep 17 00:00:00 2001 From: floaledm Date: Tue, 3 May 2016 16:29:30 -0500 Subject: [PATCH] AP_SerialManager: added SPort passthrough protocol --- libraries/AP_SerialManager/AP_SerialManager.cpp | 11 ++++++----- libraries/AP_SerialManager/AP_SerialManager.h | 1 + 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 6f04d17cdc..e63125e880 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -53,7 +53,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @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 + // @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) // @User: Standard AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink), @@ -67,7 +67,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @Param: 2_PROTOCOL // @DisplayName: Telemetry 2 protocol selection // @Description: Control what protocol to use on the Telem2 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 + // @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) // @User: Standard AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SerialProtocol_MAVLink), @@ -81,7 +81,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @Param: 3_PROTOCOL // @DisplayName: Serial 3 (GPS) protocol selection // @Description: Control what protocol Serial 3 (GPS) should be used for. 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 + // @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) // @User: Standard AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SerialProtocol_GPS), @@ -95,7 +95,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @Param: 4_PROTOCOL // @DisplayName: Serial4 protocol selection // @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:None, 1:Mavlink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Lidar + // @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) // @User: Standard AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SerialProtocol_GPS), @@ -109,7 +109,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @Param: 5_PROTOCOL // @DisplayName: Serial5 protocol selection // @Description: Control what protocol Serial5 port should be used for. 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 + // @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) // @User: Standard AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL), @@ -175,6 +175,7 @@ void AP_SerialManager::init() // begin is handled by AP_Frsky_telem library break; case SerialProtocol_FrSky_SPort: + case SerialProtocol_FrSky_SPort_Passthrough: // Note baudrate is hardcoded to 57600 state[i].baud = AP_SERIALMANAGER_FRSKY_SPORT_BAUD/1000; // update baud param in case user looks at it // begin is handled by AP_Frsky_telem library diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index dbc0ee819a..3b653e40f4 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -81,6 +81,7 @@ public: SerialProtocol_AlexMos = 7, SerialProtocol_SToRM32 = 8, SerialProtocol_Lidar = 9, + SerialProtocol_FrSky_SPort_Passthrough = 10, // FrSky SPort Passthrough (OpenTX) protocol (X-receivers) }; // Constructor