mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_SerialManager: add support for Sagetech protocol
This commit is contained in:
parent
bd445bafc4
commit
b74c22864d
@ -92,7 +92,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: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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV
|
// @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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:Sagetech
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink2),
|
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink2),
|
||||||
@ -109,7 +109,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: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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV
|
// @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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:Sagetech
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SERIAL2_PROTOCOL),
|
AP_GROUPINFO("2_PROTOCOL", 3, AP_SerialManager, state[2].protocol, SERIAL2_PROTOCOL),
|
||||||
@ -126,7 +126,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: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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV
|
// @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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:Sagetech
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SERIAL3_PROTOCOL),
|
AP_GROUPINFO("3_PROTOCOL", 5, AP_SerialManager, state[3].protocol, SERIAL3_PROTOCOL),
|
||||||
@ -143,7 +143,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: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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV
|
// @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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:Sagetech
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SERIAL4_PROTOCOL),
|
AP_GROUPINFO("4_PROTOCOL", 7, AP_SerialManager, state[4].protocol, SERIAL4_PROTOCOL),
|
||||||
@ -160,7 +160,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: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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV
|
// @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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:Sagetech
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL),
|
AP_GROUPINFO("5_PROTOCOL", 9, AP_SerialManager, state[5].protocol, SERIAL5_PROTOCOL),
|
||||||
@ -179,7 +179,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 6_PROTOCOL
|
// @Param: 6_PROTOCOL
|
||||||
// @DisplayName: Serial6 protocol selection
|
// @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.
|
// @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, 23:RCIN, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV
|
// @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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:Sagetech
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("6_PROTOCOL", 12, AP_SerialManager, state[6].protocol, SERIAL6_PROTOCOL),
|
AP_GROUPINFO("6_PROTOCOL", 12, AP_SerialManager, state[6].protocol, SERIAL6_PROTOCOL),
|
||||||
@ -278,7 +278,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|||||||
// @Param: 7_PROTOCOL
|
// @Param: 7_PROTOCOL
|
||||||
// @DisplayName: Serial7 protocol selection
|
// @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.
|
// @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, 23:RCIN, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV
|
// @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, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:Sagetech
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO("7_PROTOCOL", 23, AP_SerialManager, state[7].protocol, SERIAL7_PROTOCOL),
|
AP_GROUPINFO("7_PROTOCOL", 23, AP_SerialManager, state[7].protocol, SERIAL7_PROTOCOL),
|
||||||
@ -463,6 +463,12 @@ void AP_SerialManager::init()
|
|||||||
state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
state[i].uart->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case SerialProtocol_Sagetech:
|
||||||
|
state[i].uart->begin(state[i].baud,
|
||||||
|
AP_SERIALMANAGER_SAGETECH_BUFSIZE_RX,
|
||||||
|
AP_SERIALMANAGER_SAGETECH_BUFSIZE_TX);
|
||||||
|
break;
|
||||||
|
|
||||||
case SerialProtocol_SLCAN:
|
case SerialProtocol_SLCAN:
|
||||||
state[i].uart->begin(map_baudrate(state[i].baud),
|
state[i].uart->begin(map_baudrate(state[i].baud),
|
||||||
AP_SERIALMANAGER_SLCAN_BUFSIZE_RX,
|
AP_SERIALMANAGER_SLCAN_BUFSIZE_RX,
|
||||||
|
@ -84,6 +84,9 @@
|
|||||||
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX 128
|
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX 128
|
||||||
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX 128
|
#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX 128
|
||||||
|
|
||||||
|
#define AP_SERIALMANAGER_SAGETECH_BUFSIZE_RX 128
|
||||||
|
#define AP_SERIALMANAGER_SAGETECH_BUFSIZE_TX 128
|
||||||
|
|
||||||
// MegaSquirt EFI protocol
|
// MegaSquirt EFI protocol
|
||||||
#define AP_SERIALMANAGER_EFI_MS_BAUD 115
|
#define AP_SERIALMANAGER_EFI_MS_BAUD 115
|
||||||
#define AP_SERIALMANAGER_EFI_MS_BUFSIZE_RX 512
|
#define AP_SERIALMANAGER_EFI_MS_BUFSIZE_RX 512
|
||||||
@ -147,6 +150,7 @@ public:
|
|||||||
SerialProtocol_Winch = 31,
|
SerialProtocol_Winch = 31,
|
||||||
SerialProtocol_MSP = 32,
|
SerialProtocol_MSP = 32,
|
||||||
SerialProtocol_DJI_FPV = 33,
|
SerialProtocol_DJI_FPV = 33,
|
||||||
|
SerialProtocol_Sagetech = 34,
|
||||||
SerialProtocol_NumProtocols // must be the last value
|
SerialProtocol_NumProtocols // must be the last value
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user