mirror of https://github.com/ArduPilot/ardupilot
AP_Plane: set path_propportion in TECS
This commit is contained in:
parent
89ce0b062b
commit
7978872e32
|
@ -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
|
||||||
|
|
|
@ -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();
|
||||||
|
|
Loading…
Reference in New Issue