From 7978872e327a002b5f7ad76a634bc92fd5a0c667 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 8 Jan 2016 16:12:03 -0800 Subject: [PATCH] AP_Plane: set path_propportion in TECS --- ArduPlane/altitude.cpp | 1 + ArduPlane/navigation.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp index 2b517def70..0294d8ee53 100644 --- a/ArduPlane/altitude.cpp +++ b/ArduPlane/altitude.cpp @@ -64,6 +64,7 @@ void Plane::setup_glide_slope(void) auto_state.wp_distance = get_distance(current_loc, next_WP_loc); auto_state.wp_proportion = location_path_proportion(current_loc, prev_WP_loc, next_WP_loc); + SpdHgt_Controller->set_path_proportion(auto_state.wp_proportion); /* work out if we will gradually change altitude, or try to get to diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 48b4262c5b..937a88a3fa 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -64,6 +64,7 @@ void Plane::navigate() auto_state.wp_distance = get_distance(current_loc, next_WP_loc); auto_state.wp_proportion = location_path_proportion(current_loc, prev_WP_loc, next_WP_loc); + SpdHgt_Controller->set_path_proportion(auto_state.wp_proportion); // update total loiter angle loiter_angle_update();