diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 3e1670c637..7f58f75ddf 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -199,7 +199,7 @@ void Plane::send_nav_controller_output(mavlink_channel_t chan) nav_pitch_cd * 0.01f, nav_controller->nav_bearing_cd() * 0.01f, nav_controller->target_bearing_cd() * 0.01f, - auto_state.wp_distance, + MIN(auto_state.wp_distance, UINT16_MAX), altitude_error_cm * 0.01f, airspeed_error * 100, nav_controller->crosstrack_error());