diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index a19d4122ae..94fe98314d 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -975,6 +975,10 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg) mavlink_manual_control_t packet; mavlink_msg_manual_control_decode(msg, &packet); + + if (packet.target != rover.g.sysid_this_mav) { + break; // only accept control aimed at us + } const int16_t roll = (packet.y == INT16_MAX) ? 0 : rover.channel_steer->get_radio_min() + (rover.channel_steer->get_radio_max() - rover.channel_steer->get_radio_min()) * (packet.y + 1000) / 2000.0f; const int16_t throttle = (packet.z == INT16_MAX) ? 0 : rover.channel_throttle->get_radio_min() + (rover.channel_throttle->get_radio_max() - rover.channel_throttle->get_radio_min()) * (packet.z + 1000) / 2000.0f;