fix(mavlink): Remove deprecated MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES ... (#27251)

* fix(mavlink): Rem depr. MAV_CMD_REQUEST _AUTOPILOT_CAPABILITIES/T_PROTOCOL_VERSION

* docs(docs): Release note

* Update docs/en/releases/main.md

Co-authored-by: Julian Oes <julian@oes.ch>

---------

Co-authored-by: Julian Oes <julian@oes.ch>
This commit is contained in:
Hamish Willee
2026-05-11 10:38:35 +10:00
committed by GitHub
parent eef836966d
commit dbd38dc13f
2 changed files with 4 additions and 19 deletions
+2 -1
View File
@@ -102,7 +102,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### MAVLink
- TBD
- Removed support for deprecated request commands `MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES`, `MAV_CMD_REQUEST_PROTOCOL_VERSION`, `MAV_CMD_GET_HOME_POSITION`, `MAV_CMD_REQUEST_FLIGHT_INFORMATION`, `MAV_CMD_REQUEST_STORAGE_INFORMATION` (Replaced by `MAV_CMD_REQUEST_MESSAGE`).
([PX4-Autopilot#27251: fix(mavlink): Remove deprecated MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES](https://github.com/PX4/PX4-Autopilot/pull/27251), [PX4-Autopilot#27252: fix(mavlink): Remove legacy mavlink message requestors#27252](https://github.com/PX4/PX4-Autopilot/pull/27252))
### RC
+2 -18
View File
@@ -457,24 +457,8 @@ void MavlinkReceiver::handle_messages_in_gimbal_mode(mavlink_message_t &msg)
bool
MavlinkReceiver::evaluate_target_ok(int command, int target_system, int target_component)
{
/* evaluate if this system should accept this command */
bool target_ok = false;
switch (command) {
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
case MAV_CMD_REQUEST_PROTOCOL_VERSION:
/* broadcast and ignore component */
target_ok = (target_system == 0) || (target_system == mavlink_system.sysid);
break;
default:
target_ok = ((target_system == 0) || (target_system == mavlink_system.sysid))
&& ((target_component == mavlink_system.compid) || (target_component == MAV_COMP_ID_ALL));
break;
}
return target_ok;
return ((target_system == 0) || (target_system == mavlink_system.sysid))
&& ((target_component == mavlink_system.compid) || (target_component == MAV_COMP_ID_ALL));
}
void