Plane: Fixed divide by zero error when transitioning to guided

This commit is contained in:
mattbooker 2022-09-06 21:56:33 -04:00 committed by Andrew Tridgell
parent 14be09d72c
commit 821ef1d4d9

View File

@ -2501,7 +2501,11 @@ void QuadPlane::vtol_position_controller(void)
const float distance = diff_wp.length();
const Vector2f rel_groundspeed_vector = landing_closing_velocity();
const float rel_groundspeed_sq = rel_groundspeed_vector.length_squared();
const float closing_groundspeed = rel_groundspeed_vector * diff_wp.normalized();
float closing_groundspeed = 0;
if (distance > 0.1) {
closing_groundspeed = rel_groundspeed_vector * diff_wp.normalized();
}
// calculate speed we should be at to reach the position2
// target speed at the position2 distance threshold, assuming