Plane: change format of reset alt target message

This commit is contained in:
mirkix 2017-09-18 20:21:01 +02:00 committed by Andrew Tridgell
parent 667cdcdfcf
commit 7c6be7c421
1 changed files with 1 additions and 1 deletions

View File

@ -747,7 +747,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().send_text(MAV_SEVERITY_INFO, "Reset alt target to %.1f", (double)inertial_nav.get_altitude());
gcs().send_text(MAV_SEVERITY_INFO, "Reset alt target to %.1f", (double)inertial_nav.get_altitude() / 100);
set_alt_target_current();
pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());