mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: Make target altitude track current altitude when gliding.
This commit is contained in:
parent
2260fda4ec
commit
ed7e359f4d
@ -40,6 +40,10 @@ void Plane::adjust_altitude_target()
|
||||
landing.adjust_landing_slope_for_rangefinder_bump(rangefinder_state, prev_WP_loc, next_WP_loc, current_loc, auto_state.wp_distance, target_altitude.offset_cm);
|
||||
} else if (landing.get_target_altitude_location(target_location)) {
|
||||
set_target_altitude_location(target_location);
|
||||
} else if (g2.soaring_controller.is_active() && g2.soaring_controller.get_throttle_suppressed()) {
|
||||
// Reset target alt to current alt, to prevent large altitude errors when gliding.
|
||||
set_target_altitude_location(current_loc);
|
||||
reset_offset_altitude();
|
||||
} else if (reached_loiter_target()) {
|
||||
// once we reach a loiter target then lock to the final
|
||||
// altitude target
|
||||
|
Loading…
Reference in New Issue
Block a user