|
|
|
@ -30,7 +30,7 @@ extern const AP_HAL::HAL& hal;
@@ -30,7 +30,7 @@ extern const AP_HAL::HAL& hal;
|
|
|
|
|
#ifdef HAL_SERIAL2_PROTOCOL |
|
|
|
|
#define SERIAL2_PROTOCOL HAL_SERIAL2_PROTOCOL |
|
|
|
|
#else |
|
|
|
|
#define SERIAL2_PROTOCOL SerialProtocol_MAVLink |
|
|
|
|
#define SERIAL2_PROTOCOL SerialProtocol_MAVLink2 |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#ifndef HAL_SERIAL3_PROTOCOL |
|
|
|
@ -94,7 +94,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
@@ -94,7 +94,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
|
|
|
|
// @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
|
|
|
|
|
// @User: Standard
|
|
|
|
|
// @RebootRequired: True
|
|
|
|
|
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink), |
|
|
|
|
AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, SerialProtocol_MAVLink2), |
|
|
|
|
|
|
|
|
|
// @Param: 1_BAUD
|
|
|
|
|
// @DisplayName: Telem1 Baud Rate
|
|
|
|
|