@ -55,7 +55,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -55,7 +55,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:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 1_PROTOCOL " , 1 , AP_SerialManager , state [ 1 ] . protocol , SerialProtocol_MAVLink ) ,
@ -70,7 +70,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -70,7 +70,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:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 2_PROTOCOL " , 3 , AP_SerialManager , state [ 2 ] . protocol , SerialProtocol_MAVLink ) ,
@ -85,7 +85,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -85,7 +85,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:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 3_PROTOCOL " , 5 , AP_SerialManager , state [ 3 ] . protocol , SerialProtocol_GPS ) ,
@ -100,7 +100,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -100,7 +100,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:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 4_PROTOCOL " , 7 , AP_SerialManager , state [ 4 ] . protocol , SerialProtocol_GPS ) ,
@ -115,7 +115,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -115,7 +115,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:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out
// @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:SToRM32 Gimbal Serial, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 5_PROTOCOL " , 9 , AP_SerialManager , state [ 5 ] . protocol , SERIAL5_PROTOCOL ) ,
@ -243,6 +243,13 @@ void AP_SerialManager::init()
@@ -243,6 +243,13 @@ void AP_SerialManager::init()
state [ i ] . uart - > set_unbuffered_writes ( true ) ;
state [ i ] . uart - > set_flow_control ( AP_HAL : : UARTDriver : : FLOW_CONTROL_DISABLE ) ;
break ;
case SerialProtocol_ESCTelemetry :
// ESC telemetry protocol from BLHeli32 ESCs. Note that baudrate is hardcoded to 115200
state [ i ] . baud = 115200 ;
state [ i ] . uart - > begin ( map_baudrate ( state [ i ] . baud ) , 30 , 30 ) ;
state [ i ] . uart - > set_flow_control ( AP_HAL : : UARTDriver : : FLOW_CONTROL_DISABLE ) ;
break ;
}
}
}