From 46d910539c3a48bdc8c95195d10cfc2b3a1ccd03 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Apr 2017 14:51:10 +1000 Subject: [PATCH] Plane: fixed a warning --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 60ab61b2a5..0588295566 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -722,7 +722,7 @@ void QuadPlane::run_z_controller(void) if (now - last_pidz_active_ms > 2000) { // set alt target to current height on transition. This // starts the Z controller off with the right values - GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Reset alt target to %.1f", inertial_nav.get_altitude()); + GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Reset alt target to %.1f", (double)inertial_nav.get_altitude()); pos_control->set_alt_target(inertial_nav.get_altitude()); pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());