mirror of https://github.com/ArduPilot/ardupilot
AP_Landing: Change from division to multiplication
This commit is contained in:
parent
b80dca38ff
commit
42a2a51dc7
|
@ -300,8 +300,8 @@ void AP_Landing::type_slope_setup_landing_glide_slope(const Location &prev_WP_lo
|
||||||
float flare_distance = groundspeed * flare_time;
|
float flare_distance = groundspeed * flare_time;
|
||||||
|
|
||||||
// don't allow the flare before half way along the final leg
|
// don't allow the flare before half way along the final leg
|
||||||
if (flare_distance > total_distance/2) {
|
if (flare_distance > total_distance*0.5f) {
|
||||||
flare_distance = total_distance/2;
|
flare_distance = total_distance*0.5f;
|
||||||
}
|
}
|
||||||
|
|
||||||
// project a point 500 meters past the landing point, passing
|
// project a point 500 meters past the landing point, passing
|
||||||
|
|
Loading…
Reference in New Issue