mavlink: filter command_acks by target

When we receive a command_long or command_int message to
answer, it arrives with a source sysid/compid, so this means we can send
the command_ack back on the appropriate MAVLink instances instead of all
of them.

This commit filters outgoing command_ack messages, so they are only sent
on the MAVLink instances where the sysid/compid has been seen in the
past.

This means that a command_ack is likely still sent on multiple links for
a setup with redundant links.

This should also prevent command_acks from being blasted on Iridium links
when it's not required.

Signed-off-by: Julian Oes <julian@oes.ch>
This commit is contained in:
Julian Oes 2023-01-06 15:44:05 +13:00 committed by Daniel Agar
parent 19cee04f3a
commit 243caac44a

View File

@ -2397,7 +2397,12 @@ Mavlink::task_main(int argc, char *argv[])
_vehicle_command_ack_sub.get_last_generation());
}
if (!command_ack.from_external && command_ack.command < vehicle_command_s::VEHICLE_CMD_PX4_INTERNAL_START) {
const bool is_target_known = _receiver.component_was_seen(command_ack.target_system, command_ack.target_component);
if (!command_ack.from_external
&& command_ack.command < vehicle_command_s::VEHICLE_CMD_PX4_INTERNAL_START
&& is_target_known) {
mavlink_command_ack_t msg{};
msg.result = command_ack.result;
msg.command = command_ack.command;
@ -2406,11 +2411,7 @@ Mavlink::task_main(int argc, char *argv[])
msg.target_system = command_ack.target_system;
msg.target_component = command_ack.target_component;
// TODO: always transmit the acknowledge once it is only sent over the instance the command is received
//bool _transmitting_enabled_temp = _transmitting_enabled;
//_transmitting_enabled = true;
mavlink_msg_command_ack_send_struct(get_channel(), &msg);
//_transmitting_enabled = _transmitting_enabled_temp;
if (command_ack.command == vehicle_command_s::VEHICLE_CMD_LOGGING_START) {
cmd_logging_start_acknowledgement = true;