diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index bb73dad2f7..fa6910331b 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -184,7 +184,7 @@ void GCS_MAVLINK_Plane::send_nav_controller_output() const wp_nav_valid ? quadplane.wp_nav->get_wp_bearing_to_destination() : 0, wp_nav_valid ? MIN(quadplane.wp_nav->get_wp_distance_to_destination() * 0.01, UINT16_MAX) : 0, (plane.control_mode != &plane.mode_qstabilize) ? quadplane.pos_control->get_pos_error_z_cm() * 0.01 : 0, - plane.airspeed_error * 100, + plane.airspeed_error * 100, // incorrect units; see PR#7933 wp_nav_valid ? quadplane.wp_nav->crosstrack_error() : 0); return; } @@ -199,7 +199,7 @@ void GCS_MAVLINK_Plane::send_nav_controller_output() const nav_controller->target_bearing_cd() * 0.01, MIN(plane.auto_state.wp_distance, UINT16_MAX), plane.altitude_error_cm * 0.01, - plane.airspeed_error * 100, + plane.airspeed_error * 100, // incorrect units; see PR#7933 nav_controller->crosstrack_error()); } }