mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
GCS_MAVLink: revert removal of private channel check when forwarding
This reverts 6dc77c97ce
The commit caused a regression on Solo as the gimbal is "nodding",
indicating traffic from the autopilot is getting through to the gimbal.
This commit is contained in:
parent
8e6cde25dc
commit
0c88af99da
@ -145,6 +145,13 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl
|
||||
memset(sent_to_chan, 0, sizeof(sent_to_chan));
|
||||
for (uint8_t i=0; i<num_routes; i++) {
|
||||
|
||||
// Skip if channel is private and the target system or component IDs do not match
|
||||
if ((GCS_MAVLINK::is_private(routes[i].channel)) &&
|
||||
(target_system != routes[i].sysid ||
|
||||
target_component != routes[i].compid)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (broadcast_system || (target_system == routes[i].sysid &&
|
||||
(broadcast_component ||
|
||||
target_component == routes[i].compid ||
|
||||
|
Loading…
Reference in New Issue
Block a user