mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
Plane: Fixed divide by zero error when transitioning to guided
This commit is contained in:
parent
6e009a82ed
commit
e4b4d00645
@ -2501,7 +2501,11 @@ void QuadPlane::vtol_position_controller(void)
|
|||||||
const float distance = diff_wp.length();
|
const float distance = diff_wp.length();
|
||||||
const Vector2f rel_groundspeed_vector = landing_closing_velocity();
|
const Vector2f rel_groundspeed_vector = landing_closing_velocity();
|
||||||
const float rel_groundspeed_sq = rel_groundspeed_vector.length_squared();
|
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
|
// calculate speed we should be at to reach the position2
|
||||||
// target speed at the position2 distance threshold, assuming
|
// target speed at the position2 distance threshold, assuming
|
||||||
|
Loading…
Reference in New Issue
Block a user