mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Plane: do landing flare if past landing point
this helps prevent us keeping the throttle on after we've landed if the baro has drifted enough that we think we are not yet at the flare altitude
This commit is contained in:
parent
b102c9d19c
commit
d0b6676547
@ -30,13 +30,16 @@ static bool verify_land()
|
||||
// low pass the sink rate to take some of the noise out
|
||||
auto_state.land_sink_rate = 0.8f * auto_state.land_sink_rate + 0.2f*sink_rate;
|
||||
|
||||
/* Set land_complete (which starts the flare) under 2 conditions:
|
||||
/* Set land_complete (which starts the flare) under 3 conditions:
|
||||
1) we are within LAND_FLARE_ALT meters of the landing altitude
|
||||
2) we are within LAND_FLARE_SEC of the landing point vertically
|
||||
by the calculated sink rate
|
||||
3) we have gone past the landing point (to prevent us keeping
|
||||
throttle on after landing if we've had positive baro drift)
|
||||
*/
|
||||
if (height <= g.land_flare_alt ||
|
||||
height <= -auto_state.land_sink_rate * g.land_flare_sec) {
|
||||
height <= -auto_state.land_sink_rate * g.land_flare_sec ||
|
||||
location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
|
||||
|
||||
if (!auto_state.land_complete) {
|
||||
gcs_send_text_fmt(PSTR("Flare %.1fm sink=%.2f speed=%.1f"),
|
||||
|
Loading…
Reference in New Issue
Block a user