mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
GCS_MAVLink: routing: do not process our own packets locally
returning true from this method means we will process the packets locally. If that message changes the vehicle state that could be bad.
This commit is contained in:
parent
d05b598ce5
commit
67bb7417ec
@ -94,7 +94,7 @@ bool MAVLink_routing::check_and_forward(GCS_MAVLINK &in_link, const mavlink_mess
|
|||||||
// incorrect serial configuration.
|
// incorrect serial configuration.
|
||||||
if (msg.sysid == mavlink_system.sysid &&
|
if (msg.sysid == mavlink_system.sysid &&
|
||||||
msg.compid == mavlink_system.compid) {
|
msg.compid == mavlink_system.compid) {
|
||||||
return true;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// learn new routes including private channels
|
// learn new routes including private channels
|
||||||
|
Loading…
Reference in New Issue
Block a user