GCS_MAVLink: default to MAVLink2 enabled
this changes the default to enable MAVLink2 on USB and the primary telemetry port. Note that unless signing is enabled it won't send a MAVLink2 packet until the GCS sends a MAVLink2 packet
This commit is contained in:
parent
0445b51143
commit
c64a020384
@ -48,14 +48,14 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = {
|
||||
// @Description: Control what protocol to use on the console.
|
||||
// @Values: 1:MAVlink1, 2:MAVLink2
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("0_PROTOCOL", 11, AP_SerialManager, state[0].protocol, SerialProtocol_MAVLink),
|
||||
AP_GROUPINFO("0_PROTOCOL", 11, AP_SerialManager, state[0].protocol, SerialProtocol_MAVLink2),
|
||||
|
||||
// @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:Lidar, 10:FrSky SPort Passthrough (OpenTX)
|
||||
// @User: Standard
|
||||
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
|
||||
|
Loading…
Reference in New Issue
Block a user