mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: Remove redundant check for private channels
We can't learn the route for sending to a private channel, so we shouldn't need to actually check it when iterating the routes.
This commit is contained in:
parent
99ad126986
commit
6dc77c97ce
|
@ -144,13 +144,6 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl
|
|||
bool sent_to_chan[MAVLINK_COMM_NUM_BUFFERS];
|
||||
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 ||
|
||||
|
|
Loading…
Reference in New Issue