AP_SerialManager: Add support for High Latency MAVLink protocol

This commit is contained in:
Stephen Dade 2022-01-26 13:50:59 +11:00 committed by Peter Barker
parent cb6f9ea6a1
commit da4602b5d2
2 changed files with 7 additions and 4 deletions

View File

@ -136,7 +136,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, 23:RCIN, 24:MegaSquirt EFI, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort
// @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 VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort, 43:MAVLink High Latency
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink2),
@ -461,6 +461,7 @@ void AP_SerialManager::init()
case SerialProtocol_Console:
case SerialProtocol_MAVLink:
case SerialProtocol_MAVLink2:
case SerialProtocol_MAVLinkHL:
uart->begin(map_baudrate(state[i].baud),
AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX,
AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX);
@ -676,7 +677,8 @@ AP_SerialManager::SerialProtocol AP_SerialManager::get_mavlink_protocol(mavlink_
uint8_t chan_idx = (uint8_t)(mav_chan - MAVLINK_COMM_0);
for (uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
if (state[i].protocol == SerialProtocol_MAVLink ||
state[i].protocol == SerialProtocol_MAVLink2) {
state[i].protocol == SerialProtocol_MAVLink2 ||
state[i].protocol == SerialProtocol_MAVLinkHL) {
if (instance == chan_idx) {
return (SerialProtocol)state[i].protocol.get();
}
@ -755,8 +757,8 @@ bool AP_SerialManager::protocol_match(enum SerialProtocol protocol1, enum Serial
}
// mavlink match
if (((protocol1 == SerialProtocol_MAVLink) || (protocol1 == SerialProtocol_MAVLink2)) &&
((protocol2 == SerialProtocol_MAVLink) || (protocol2 == SerialProtocol_MAVLink2))) {
if (((protocol1 == SerialProtocol_MAVLink) || (protocol1 == SerialProtocol_MAVLink2) || (protocol1 == SerialProtocol_MAVLinkHL)) &&
((protocol2 == SerialProtocol_MAVLink) || (protocol2 == SerialProtocol_MAVLink2) || (protocol2 == SerialProtocol_MAVLinkHL))) {
return true;
}

View File

@ -169,6 +169,7 @@ public:
SerialProtocol_AIS = 40,
SerialProtocol_CoDevESC = 41,
SerialProtocol_MSP_DisplayPort = 42,
SerialProtocol_MAVLinkHL = 43,
SerialProtocol_NumProtocols // must be the last value
};