AP_Plane: set path_propportion in TECS

This commit is contained in:
Tom Pittenger 2016-01-08 16:12:03 -08:00 committed by Andrew Tridgell
parent 89ce0b062b
commit 7978872e32
2 changed files with 2 additions and 0 deletions

View File

@ -64,6 +64,7 @@ void Plane::setup_glide_slope(void)
auto_state.wp_distance = get_distance(current_loc, next_WP_loc); auto_state.wp_distance = get_distance(current_loc, next_WP_loc);
auto_state.wp_proportion = location_path_proportion(current_loc, auto_state.wp_proportion = location_path_proportion(current_loc,
prev_WP_loc, next_WP_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 work out if we will gradually change altitude, or try to get to

View File

@ -64,6 +64,7 @@ void Plane::navigate()
auto_state.wp_distance = get_distance(current_loc, next_WP_loc); auto_state.wp_distance = get_distance(current_loc, next_WP_loc);
auto_state.wp_proportion = location_path_proportion(current_loc, auto_state.wp_proportion = location_path_proportion(current_loc,
prev_WP_loc, next_WP_loc); prev_WP_loc, next_WP_loc);
SpdHgt_Controller->set_path_proportion(auto_state.wp_proportion);
// update total loiter angle // update total loiter angle
loiter_angle_update(); loiter_angle_update();