Browse Source

AP_SerialManager: added SPort passthrough protocol

master
floaledm 9 years ago committed by Andrew Tridgell
parent
commit
50eecf58a4
  1. 11
      libraries/AP_SerialManager/AP_SerialManager.cpp
  2. 1
      libraries/AP_SerialManager/AP_SerialManager.h

11
libraries/AP_SerialManager/AP_SerialManager.cpp

@ -53,7 +53,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @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 // @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 // @User: Standard
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink), 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 // @Param: 2_PROTOCOL
// @DisplayName: Telemetry 2 protocol selection // @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. // @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 // @User: Standard
AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SerialProtocol_MAVLink), 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 // @Param: 3_PROTOCOL
// @DisplayName: Serial 3 (GPS) protocol selection // @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. // @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 // @User: Standard
AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SerialProtocol_GPS), 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 // @Param: 4_PROTOCOL
// @DisplayName: Serial4 protocol selection // @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. // @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 // @User: Standard
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SerialProtocol_GPS), 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 // @Param: 5_PROTOCOL
// @DisplayName: Serial5 protocol selection // @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. // @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 // @User: Standard
AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL), 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 // begin is handled by AP_Frsky_telem library
break; break;
case SerialProtocol_FrSky_SPort: case SerialProtocol_FrSky_SPort:
case SerialProtocol_FrSky_SPort_Passthrough:
// Note baudrate is hardcoded to 57600 // Note baudrate is hardcoded to 57600
state[i].baud = AP_SERIALMANAGER_FRSKY_SPORT_BAUD/1000; // update baud param in case user looks at it 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 // begin is handled by AP_Frsky_telem library

1
libraries/AP_SerialManager/AP_SerialManager.h

@ -81,6 +81,7 @@ public:
SerialProtocol_AlexMos = 7, SerialProtocol_AlexMos = 7,
SerialProtocol_SToRM32 = 8, SerialProtocol_SToRM32 = 8,
SerialProtocol_Lidar = 9, SerialProtocol_Lidar = 9,
SerialProtocol_FrSky_SPort_Passthrough = 10, // FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
}; };
// Constructor // Constructor

Loading…
Cancel
Save