diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index c225c8f950..b36aadae37 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -272,12 +272,12 @@ void NOINLINE Sub::send_nav_controller_output(mavlink_channel_t chan) const Vector3f &targets = attitude_control.get_att_target_euler_cd(); mavlink_msg_nav_controller_output_send( chan, - targets.x / 1.0e2f, - targets.y / 1.0e2f, - targets.z / 1.0e2f, - wp_nav.get_wp_bearing_to_destination() / 1.0e2f, - wp_nav.get_wp_distance_to_destination() / 1.0e2f, - pos_control.get_alt_error() / 1.0e2f, + targets.x * 1.0e-2f, + targets.y * 1.0e-2f, + targets.z * 1.0e-2f, + wp_nav.get_wp_bearing_to_destination() * 1.0e-2f, + MIN(wp_nav.get_wp_distance_to_destination() * 1.0e-2f, UINT16_MAX), + pos_control.get_alt_error() * 1.0e-2f, 0, 0); }