As a workaround, I have added code on my MCU to explicitly ask ArduPilot not to send me those streams as follows and that has silenced them.
// Prep source and dest MAVLink addressing info, to be used in below actions.
uint8_t _system_id = FMX_SYS_ID; // MAVLink System ID of this device.
uint8_t _component_id = FMX_COMP_ID; // MAVLink Component ID of this device.
uint8_t _target_system = AP_SYS_ID; // MAVLink System ID of the autopilot.
uint8_t _target_component = AP_COMP_ID; // MAVLink Component ID of the autopilot.
// Build 1st COMMAND_LONG / MAV_CMD_SET_MESSAGE_INTERVAL message.
// components of the MAVLink COMMAND_LONG message - https://mavlink.io/en/messages/common.html#COMMAND_LONG
uint16_t _cl_command = MAV_CMD_SET_MESSAGE_INTERVAL; // https://mavlink.io/en/messages/common.html#MAV_CMD_SET_MESSAGE_INTERVAL
uint8_t _cl_confirmation = 0; // always 0 for first transmission, then incremented. https://mavlink.io/en/services/command.html#COMMAND_LONG
float _cl_param1 = MAVLINK_MSG_ID_POWER_STATUS; // MAVLink Message ID
float _cl_param2 = -1; // Interval (uS) between messages e.g. 1sec interval = 1000000uS or -1 to disable
float _cl_param3 = 0; // Not used, so set to zero.
float _cl_param4 = 0; // Not used, so set to zero.
float _cl_param5 = 0; // Not used, so set to zero.
float _cl_param6 = 0; // Not used, so set to zero.
float _cl_param7 = 0; // Not used, so set to zero.
// Initialize the required buffers
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
// UnRequest MAVLINK_MSG_ID_RC_CHANNELS_RAW (#35) - https://mavlink.io/en/messages/common.html#RC_CHANNELS_RAW
_cl_param1 = MAVLINK_MSG_ID_RC_CHANNELS_RAW; // MAVLink Message ID
mavlink_msg_command_long_pack(_system_id, _component_id, &msg, _target_system, _target_component, _cl_command, _cl_confirmation, _cl_param1, _cl_param2, _cl_param3, _cl_param4, _cl_param5, _cl_param6, _cl_param7);
len = mavlink_msg_to_send_buffer(buf, &msg); // put message into our send buffer and also get it's size in bytes.
Serial1.write(buf, len); //Write data to serial port byte by byte.
delay(500);
// UnRequest MAVLINK_MSG_ID_SERVO_OUTPUT_RAW (#36) - https://mavlink.io/en/messages/common.html#SERVO_OUTPUT_RAW
_cl_param1 = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; // MAVLink Message ID
mavlink_msg_command_long_pack(_system_id, _component_id, &msg, _target_system, _target_component, _cl_command, _cl_confirmation, _cl_param1, _cl_param2, _cl_param3, _cl_param4, _cl_param5, _cl_param6, _cl_param7);
len = mavlink_msg_to_send_buffer(buf, &msg); // put message into our send buffer and also get it's size in bytes.
Serial1.write(buf, len); //Write data to serial port byte by byte.
delay(500);
// UnRequest MAVLINK_MSG_ID_RC_CHANNELS (#65) - https://mavlink.io/en/messages/common.html#RC_CHANNELS
_cl_param1 = MAVLINK_MSG_ID_RC_CHANNELS; // MAVLink Message ID
mavlink_msg_command_long_pack(_system_id, _component_id, &msg, _target_system, _target_component, _cl_command, _cl_confirmation, _cl_param1, _cl_param2, _cl_param3, _cl_param4, _cl_param5, _cl_param6, _cl_param7);
len = mavlink_msg_to_send_buffer(buf, &msg); // put message into our send buffer and also get it's size in bytes.
Serial1.write(buf, len); //Write data to serial port byte by byte.
delay(500);
Now only HEARTBEATS are appearing and that’s ok, I can deal with them.
16:17:03.495 > case_rx_from_autopilot() - ATTEMPTING RX - starting at Millis:439390
16:17:03.496 > mavlink_receive() - MSG RCVD - magic:254 seq:238 src sysid:1 src compid:0 msgid#:0=HEARTBEAT Type:27 Autopilot:8 BaseMode:4 CustomMode/Flightmode:0 SystemStatus:4 MavlinkVersion:3
16:17:03.496 > mavlink_receive() - MSG RCVD - magic:254 seq:11 src sysid:255 src compid:190 msgid#:0=HEARTBEAT Type:6 Autopilot:8 BaseMode:0 CustomMode/Flightmode:0 SystemStatus:0 MavlinkVersion:3
16:17:03.496 > mavlink_receive() - MSG RCVD - magic:254 seq:42 src sysid:1 src compid:1 msgid#:0=HEARTBEAT Type:11 Autopilot:3 BaseMode:1 CustomMode/Flightmode:4 SystemStatus:5 MavlinkVersion:3
16:17:03.496 > mavlink_receive() - MSG RCVD - magic:254 seq:43 src sysid:1 src compid:1 msgid#:22=PARAM_VALUE param_id:STAT_RUNTIME param_value:6786463.00 param_type:6 param_count893 param_index65535
16:17:03.497 > mavlink_receive() - MSG RCVD - magic:254 seq:240 src sysid:1 src compid:0 msgid#:0=HEARTBEAT Type:27 Autopilot:8 BaseMode:4 CustomMode/Flightmode:0 SystemStatus:4 MavlinkVersion:3
16:17:03.497 > mavlink_receive() - MSG RCVD - magic:254 seq:13 src sysid:255 src compid:190 msgid#:0=HEARTBEAT Type:6 Autopilot:8 BaseMode:0 CustomMode/Flightmode:0 SystemStatus:0 MavlinkVersion:3
16:17:03.498 > mavlink_receive() - MSG RCVD - magic:254 seq:44 src sysid:1 src compid:1 msgid#:0=HEARTBEAT Type:11 Autopilot:3 BaseMode:1 CustomMode/Flightmode:4 SystemStatus:5 MavlinkVersion:3
16:17:03.498 > mavlink_receive() - MSG RCVD - magic:254 seq:242 src sysid:1 src compid:0 msgid#:0=HEARTBEAT Type:27 Autopilot:8 BaseMode:4 CustomMode/Flightmode:0 SystemStatus:4 MavlinkVersion:3
16:17:03.499 > mavlink_receive() - MSG RCVD - magic:254 seq:15 src sysid:255 src compid:190 msgid#:0=HEARTBEAT Type:6 Autopilot:8 BaseMode:0 CustomMode/Flightmode:0 SystemStatus:0 MavlinkVersion:3
16:17:03.499 > mavlink_receive() - MSG RCVD - magic:254 seq:45 src sysid:1 src compid:1 msgid#:0=HEARTBEAT Type:11 Autopilot:3 BaseMode:1 CustomMode/Flightmode:4 SystemStatus:5 MavlinkVersion:3
16:17:03.501 > mavlink_receive() - MSG RCVD - magic:254 seq:244 src sysid:1 src compid:0 msgid#:0=HEARTBEAT Type:27 Autopilot:8 BaseMode:4 CustomMode/Flightmode:0 SystemStatus:4 MavlinkVersion:3
16:17:03.501 > mavlink_receive() - MSG RCVD - magic:254 seq:17 src sysid:255 src compid:190 msgid#:0=HEARTBEAT Type:6 Autopilot:8 BaseMode:0 CustomMode/Flightmode:0 SystemStatus:0 MavlinkVersion:3
16:17:03.501 > mavlink_receive() - MSG RCVD - magic:254 seq:46 src sysid:1 src compid:1 msgid#:0=HEARTBEAT Type:11 Autopilot:3 BaseMode:1 CustomMode/Flightmode:4 SystemStatus:5 MavlinkVersion:3
16:17:03.502 > mavlink_receive() - MSG RCVD - magic:254 seq:246 src sysid:1 src compid:0 msgid#:0=HEARTBEAT Type:27 Autopilot:8 BaseMode:4 CustomMode/Flightmode:0 SystemStatus:4 MavlinkVersion:3
16:17:03.561 > mavlink_receive() - MSG RCVD - magic:254 seq:98 src sysid:1 src compid:0 msgid#:0=HEARTBEAT Type:27 Autopilot:8 BaseMode:4 CustomMode/Flightmode:0 SystemStatus:4 MavlinkVersion:3
16:17:04.024 > mavlink_receive() - MSG RCVD - magic:254 seq:164 src sysid:255 src compid:190 msgid#:0=HEARTBEAT Type:6 Autopilot:8 BaseMode:0 CustomMode/Flightmode:0 SystemStatus:0 MavlinkVersion:3
16:17:04.321 > mavlink_receive() - MSG RCVD - magic:254 seq:120 src sysid:1 src compid:1 msgid#:0=HEARTBEAT Type:11 Autopilot:3 BaseMode:1 CustomMode/Flightmode:4 SystemStatus:5 MavlinkVersion:3
16:17:04.561 > mavlink_receive() - MSG RCVD - magic:254 seq:100 src sysid:1 src compid:0 msgid#:0=HEARTBEAT Type:27 Autopilot:8 BaseMode:4 CustomMode/Flightmode:0 SystemStatus:4 MavlinkVersion:3
16:17:04.825 > mavlink_receive() - MSG RCVD - magic:254 seq:166 src sysid:255 src compid:190 msgid#:0=HEARTBEAT Type:6 Autopilot:8 BaseMode:0 CustomMode/Flightmode:0 SystemStatus:0 MavlinkVersion:3
16:17:05.322 > mavlink_receive() - MSG RCVD - magic:254 seq:121 src sysid:1 src compid:1 msgid#:0=HEARTBEAT Type:11 Autopilot:3 BaseMode:1 CustomMode/Flightmode:4 SystemStatus:5 MavlinkVersion:3
16:17:05.561 > mavlink_receive() - MSG RCVD - magic:254 seq:102 src sysid:1 src compid:0 msgid#:0=HEARTBEAT Type:27 Autopilot:8 BaseMode:4 CustomMode/Flightmode:0 SystemStatus:4 MavlinkVersion:3
16:17:05.866 > mavlink_receive() - MSG RCVD - magic:254 seq:168 src sysid:255 src compid:190 msgid#:0=HEARTBEAT Type:6 Autopilot:8 BaseMode:0 CustomMode/Flightmode:0 SystemStatus:0 MavlinkVersion:3
16:17:06.341 > mavlink_receive() - MSG RCVD - magic:254 seq:122 src sysid:1 src compid:1 msgid#:0=HEARTBEAT Type:11 Autopilot:3 BaseMode:1 CustomMode/Flightmode:4 SystemStatus:5 MavlinkVersion:3
16:17:06.490 > case_rx_from_autopilot() - Done RX - ending at Millis:442390
Cheers.