Plane: If LAND_FLARE_SEC is 0 use LAND_FLARE_ALT for aim_height.

See discussion here:

https://github.com/diydrones/ardupilot/pull/2197
This commit is contained in:
Michael Day 2015-04-29 09:56:20 -06:00 committed by Andrew Tridgell
parent 05d065b471
commit 8a6fc0ad77
1 changed files with 7 additions and 5 deletions

View File

@ -51,10 +51,9 @@ static bool verify_land()
after landing if we've had positive baro drift)
*/
if (height <= g.land_flare_alt ||
(aparm.land_flare_sec != 0 &&
(height <= auto_state.land_sink_rate * aparm.land_flare_sec ||
(!rangefinder_state.in_range && location_passed_point(current_loc, prev_WP_loc, next_WP_loc)))) ||
(fabsf(auto_state.land_sink_rate) < 0.2f && !is_flying()) ) {
(aparm.land_flare_sec > 0 && height <= auto_state.land_sink_rate * aparm.land_flare_sec) ||
(!rangefinder_state.in_range && location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) ||
(fabsf(auto_state.land_sink_rate) < 0.2f && !is_flying())) {
if (!auto_state.land_complete) {
if (!is_flying() && (hal.scheduler->millis()-auto_state.last_flying_ms) > 3000) {
@ -159,6 +158,9 @@ static void setup_landing_glide_slope(void)
// the height we aim for is the one to give us the right flare point
float aim_height = aparm.land_flare_sec * sink_rate;
if (aim_height <= 0) {
aim_height = g.land_flare_alt;
}
// don't allow the aim height to be too far above LAND_FLARE_ALT
if (g.land_flare_alt > 0 && aim_height > g.land_flare_alt*2) {