mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Use MAVLink v1 only as opt-in (#25583)
* Remove support for MAVLink 1 * Add back support for MAVLink 1 but don't default to it * Update src/modules/mavlink/mavlink_params.c Co-authored-by: Hamish Willee <hamishwillee@gmail.com> --------- Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
This commit is contained in:
parent
33301764e4
commit
12035682d7
@ -26,7 +26,6 @@ param set-default TRIG_INTERFACE 3
|
||||
param set-default TRIG_MODE 4
|
||||
param set-default MNT_MODE_IN 4
|
||||
param set-default MNT_MODE_OUT 2
|
||||
param set-default MAV_PROTO_VER 2
|
||||
|
||||
param set-default CA_AIRFRAME 0
|
||||
param set-default CA_ROTOR_COUNT 6
|
||||
|
||||
@ -173,7 +173,6 @@ param set-default COM_RC_IN_MODE 1
|
||||
param set-default EKF2_REQ_GPS_H 0.5
|
||||
|
||||
param set-default IMU_GYRO_FFT_EN 1
|
||||
param set-default MAV_PROTO_VER 2 # Ensures QGC does not drop the first few packets after a SITL restart due to MAVLINK 1 packets
|
||||
|
||||
param set-default -s MC_AT_EN 1
|
||||
|
||||
|
||||
1
boards/ark/dist/init/rc.board_sensors
vendored
1
boards/ark/dist/init/rc.board_sensors
vendored
@ -11,7 +11,6 @@ param set-default SENS_AFBR_HYSTER 1
|
||||
|
||||
param set-default MAV_SYS_ID 158
|
||||
param set-default MAV_COMP_ID 158
|
||||
param set-default MAV_PROTO_VER 2
|
||||
|
||||
param set-default MAV_0_MODE 14
|
||||
param set-default MAV_0_FORWARD 0
|
||||
|
||||
@ -571,7 +571,6 @@
|
||||
1 1 MAV_FWDEXTSP 1 6
|
||||
1 1 MAV_HASH_CHK_EN 1 6
|
||||
1 1 MAV_HB_FORW_EN 1 6
|
||||
1 1 MAV_PROTO_VER 0 6
|
||||
1 1 MAV_RADIO_TOUT 5 6
|
||||
1 1 MAV_SIK_RADIO_ID 0 6
|
||||
1 1 MAV_SYS_ID 1 6
|
||||
|
||||
@ -161,7 +161,7 @@ There are different clients that support ulog streaming:
|
||||
|
||||
- If log streaming does not start, make sure the `logger` is running (see above), and inspect the console output while starting.
|
||||
- If it still does not work, make sure that MAVLink 2 is used.
|
||||
Enforce it by setting `MAV_PROTO_VER` to 2.
|
||||
`MAV_PROTO_VER` needs to be set to 2.
|
||||
- Log streaming uses a maximum of 70% of the configured MAVLink rate (`-r` parameter).
|
||||
If more is needed, messages are dropped.
|
||||
The currently used percentage can be inspected with `mavlink status` (1.8% is used in this example):
|
||||
|
||||
@ -203,7 +203,7 @@ This should be enabled by default on recent builds.
|
||||
To ensure MAVLink2 is used:
|
||||
|
||||
- Update the telemetry module firmware to the latest version (see [QGroundControl > Setup > Firmware](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/firmware.html)).
|
||||
- Set [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html))
|
||||
- Ensure [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) is set to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html))
|
||||
|
||||
#### Tuning
|
||||
|
||||
|
||||
@ -187,12 +187,7 @@ Mavlink::mavlink_update_parameters()
|
||||
{
|
||||
updateParams();
|
||||
|
||||
int32_t proto = _param_mav_proto_ver.get();
|
||||
|
||||
if (_protocol_version_switch != proto) {
|
||||
_protocol_version_switch = proto;
|
||||
set_proto_version(proto);
|
||||
}
|
||||
set_protocol_version(_param_mav_proto_ver.get());
|
||||
|
||||
if (_param_mav_type.get() < 0 || _param_mav_type.get() >= MAV_TYPE_ENUM_END) {
|
||||
_param_mav_type.set(0);
|
||||
@ -277,16 +272,13 @@ Mavlink::set_instance_id()
|
||||
return false;
|
||||
}
|
||||
|
||||
void
|
||||
Mavlink::set_proto_version(unsigned version)
|
||||
void Mavlink::set_protocol_version(unsigned version)
|
||||
{
|
||||
if ((version == 1 || version == 0) &&
|
||||
((_protocol_version_switch == 0) || (_protocol_version_switch == 1))) {
|
||||
if (version == 1) {
|
||||
get_status()->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
|
||||
_protocol_version = 1;
|
||||
|
||||
} else if (version == 2 &&
|
||||
((_protocol_version_switch == 0) || (_protocol_version_switch == 2))) {
|
||||
} else {
|
||||
get_status()->flags &= ~(MAVLINK_STATUS_FLAG_OUT_MAVLINK1);
|
||||
_protocol_version = 2;
|
||||
}
|
||||
@ -1156,13 +1148,7 @@ Mavlink::send_protocol_version()
|
||||
//memcpy(&msg.spec_version_hash, &mavlink_spec_git_version_binary, sizeof(msg.spec_version_hash));
|
||||
memcpy(&msg.library_version_hash, &mavlink_lib_git_version_binary, sizeof(msg.library_version_hash));
|
||||
|
||||
// Switch to MAVLink 2
|
||||
int curr_proto_ver = _protocol_version;
|
||||
set_proto_version(2);
|
||||
// Send response - if it passes through the link its fine to use MAVLink 2
|
||||
mavlink_msg_protocol_version_send_struct(get_channel(), &msg);
|
||||
// Reset to previous value
|
||||
set_proto_version(curr_proto_ver);
|
||||
}
|
||||
|
||||
int
|
||||
|
||||
@ -157,14 +157,7 @@ public:
|
||||
|
||||
mavlink_status_t *get_status() { return &_mavlink_status; }
|
||||
|
||||
/**
|
||||
* Set the MAVLink version
|
||||
*
|
||||
* Currently supporting v1 and v2
|
||||
*
|
||||
* @param version MAVLink version
|
||||
*/
|
||||
void set_proto_version(unsigned version);
|
||||
void set_protocol_version(unsigned version);
|
||||
|
||||
static int destroy_all_instances();
|
||||
|
||||
@ -620,8 +613,7 @@ private:
|
||||
uint64_t _last_write_success_time{0};
|
||||
uint64_t _last_write_try_time{0};
|
||||
uint64_t _mavlink_start_time{0};
|
||||
int32_t _protocol_version_switch{-1};
|
||||
int32_t _protocol_version{0};
|
||||
int32_t _protocol_version = 0; ///< after initialization the only values are 1 and 2
|
||||
|
||||
unsigned _bytes_tx{0};
|
||||
unsigned _bytes_txerr{0};
|
||||
|
||||
@ -52,11 +52,10 @@ PARAM_DEFINE_INT32(MAV_COMP_ID, 1);
|
||||
/**
|
||||
* MAVLink protocol version
|
||||
* @group MAVLink
|
||||
* @value 0 Default to 1, switch to 2 if GCS sends version 2
|
||||
* @value 1 Always use version 1
|
||||
* @value 2 Always use version 2
|
||||
* @value 1 Version 1 with auto-upgrade to v2 if detected
|
||||
* @value 2 Version 2
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MAV_PROTO_VER, 0);
|
||||
PARAM_DEFINE_INT32(MAV_PROTO_VER, 2);
|
||||
|
||||
/**
|
||||
* MAVLink SiK Radio ID
|
||||
|
||||
@ -3228,10 +3228,10 @@ MavlinkReceiver::run()
|
||||
for (ssize_t i = 0; i < nread; i++) {
|
||||
if (mavlink_parse_char(_mavlink.get_channel(), buf[i], &msg, &_status)) {
|
||||
|
||||
/* check if we received version 2 and request a switch. */
|
||||
// If we receive a complete MAVLink 2 packet, also switch the outgoing protocol version
|
||||
if (!(_mavlink.get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)) {
|
||||
/* this will only switch to proto version 2 if allowed in settings */
|
||||
_mavlink.set_proto_version(2);
|
||||
PX4_INFO("Upgrade to MAVLink v2 because of incoming packet");
|
||||
_mavlink.set_protocol_version(2);
|
||||
}
|
||||
|
||||
switch (_mavlink.get_mode()) {
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user