mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: fixed corner case in MAVLink routing
when a GCS sends a command to a system ID that isn't our system ID, the GCS may use a non-advertised component ID such as MAV_COMP_ID_SYSTEM_CONTROL. Those packets should be fowarded to the target system even though the target system has not specifically advertised that target sysid/compid tuple.
This commit is contained in:
parent
5b765ef0d9
commit
339d49d34a
|
@ -132,7 +132,8 @@ bool MAVLink_routing::check_and_forward(mavlink_channel_t in_channel, const mavl
|
|||
for (uint8_t i=0; i<num_routes; i++) {
|
||||
if (broadcast_system || (target_system == routes[i].sysid &&
|
||||
(broadcast_component ||
|
||||
target_component == routes[i].compid))) {
|
||||
target_component == routes[i].compid ||
|
||||
!match_system))) {
|
||||
if (in_channel != routes[i].channel && !sent_to_chan[routes[i].channel]) {
|
||||
if (comm_get_txspace(routes[i].channel) >=
|
||||
((uint16_t)msg->len) + MAVLINK_NUM_NON_PAYLOAD_BYTES) {
|
||||
|
|
Loading…
Reference in New Issue