@ -22,10 +22,29 @@
@@ -22,10 +22,29 @@
# include <AP_HAL/AP_HAL.h>
# include <AP_Math/AP_Math.h>
# include <AP_RCProtocol/AP_RCProtocol.h>
# include "AP_SerialManager.h"
extern const AP_HAL : : HAL & hal ;
# ifdef HAL_SERIAL2_PROTOCOL
# define SERIAL2_PROTOCOL HAL_SERIAL2_PROTOCOL
# else
# define SERIAL2_PROTOCOL SerialProtocol_MAVLink
# endif
# ifndef HAL_SERIAL3_PROTOCOL
# define SERIAL3_PROTOCOL SerialProtocol_GPS
# else
# define SERIAL3_PROTOCOL HAL_SERIAL3_PROTOCOL
# endif
# ifndef HAL_SERIAL4_PROTOCOL
# define SERIAL4_PROTOCOL SerialProtocol_GPS
# else
# define SERIAL4_PROTOCOL HAL_SERIAL4_PROTOCOL
# endif
# ifdef HAL_SERIAL5_PROTOCOL
# define SERIAL5_PROTOCOL HAL_SERIAL5_PROTOCOL
# define SERIAL5_BAUD HAL_SERIAL5_BAUD
@ -34,12 +53,6 @@ extern const AP_HAL::HAL& hal;
@@ -34,12 +53,6 @@ extern const AP_HAL::HAL& hal;
# define SERIAL5_BAUD AP_SERIALMANAGER_MAVLINK_BAUD / 1000
# endif
# ifdef HAL_SERIAL2_PROTOCOL
# define SERIAL2_PROTOCOL_DEFAULT HAL_SERIAL2_PROTOCOL
# else
# define SERIAL2_PROTOCOL_DEFAULT SerialProtocol_MAVLink
# endif
# ifndef HAL_SERIAL6_PROTOCOL
# define SERIAL6_PROTOCOL SerialProtocol_None
# define SERIAL6_BAUD AP_SERIALMANAGER_MAVLINK_BAUD / 1000
@ -56,7 +69,6 @@ extern const AP_HAL::HAL& hal;
@@ -56,7 +69,6 @@ extern const AP_HAL::HAL& hal;
# define SERIAL7_BAUD HAL_SERIAL7_BAUD
# endif
const AP_Param : : GroupInfo AP_SerialManager : : var_info [ ] = {
// @Param: 0_BAUD
// @DisplayName: Serial0 baud rate
@ -76,7 +88,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -76,7 +88,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, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN
// @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, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 1_PROTOCOL " , 1 , AP_SerialManager , state [ 1 ] . protocol , SerialProtocol_MAVLink ) ,
@ -91,10 +103,10 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -91,10 +103,10 @@ 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, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN
// @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, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 2_PROTOCOL " , 3 , AP_SerialManager , state [ 2 ] . protocol , SERIAL2_PROTOCOL_DEFAULT ) ,
AP_GROUPINFO ( " 2_PROTOCOL " , 3 , AP_SerialManager , state [ 2 ] . protocol , SERIAL2_PROTOCOL ) ,
// @Param: 2_BAUD
// @DisplayName: Telemetry 2 Baud Rate
@ -106,10 +118,10 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -106,10 +118,10 @@ 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, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN
// @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, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 3_PROTOCOL " , 5 , AP_SerialManager , state [ 3 ] . protocol , SerialProtocol_GPS ) ,
AP_GROUPINFO ( " 3_PROTOCOL " , 5 , AP_SerialManager , state [ 3 ] . protocol , SERIAL3_PROTOCOL ) ,
// @Param: 3_BAUD
// @DisplayName: Serial 3 (GPS) Baud Rate
@ -121,10 +133,10 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -121,10 +133,10 @@ 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, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN
// @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, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 4_PROTOCOL " , 7 , AP_SerialManager , state [ 4 ] . protocol , SerialProtocol_GPS ) ,
AP_GROUPINFO ( " 4_PROTOCOL " , 7 , AP_SerialManager , state [ 4 ] . protocol , SERIAL4_PROTOCOL ) ,
// @Param: 4_BAUD
// @DisplayName: Serial 4 Baud Rate
@ -136,7 +148,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -136,7 +148,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, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN
// @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, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 5_PROTOCOL " , 9 , AP_SerialManager , state [ 5 ] . protocol , SERIAL5_PROTOCOL ) ,
@ -153,7 +165,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -153,7 +165,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Param: 6_PROTOCOL
// @DisplayName: Serial6 protocol selection
// @Description: Control what protocol Serial6 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, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN
// @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, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 6_PROTOCOL " , 12 , AP_SerialManager , state [ 6 ] . protocol , SERIAL6_PROTOCOL ) ,
@ -238,7 +250,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -238,7 +250,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
// @Param: 7_PROTOCOL
// @DisplayName: Serial7 protocol selection
// @Description: Control what protocol Serial7 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, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN
// @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, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " 7_PROTOCOL " , 23 , AP_SerialManager , state [ 7 ] . protocol , SERIAL7_PROTOCOL ) ,
@ -398,6 +410,10 @@ void AP_SerialManager::init()
@@ -398,6 +410,10 @@ void AP_SerialManager::init()
AP_SERIALMANAGER_SLCAN_BUFSIZE_TX ) ;
break ;
case SerialProtocol_RCIN :
AP : : RC ( ) . add_uart ( state [ i ] . uart ) ;
break ;
default :
state [ i ] . uart - > begin ( map_baudrate ( state [ i ] . baud ) ) ;
}