mirror of https://github.com/ArduPilot/ardupilot
AC_PosControl: Fix divide by zero check in limit_vector_length
This commit is contained in:
parent
706ff85be7
commit
b15b5516cb
|
@ -1197,7 +1197,7 @@ void AC_PosControl::check_for_ekf_z_reset()
|
|||
bool AC_PosControl::limit_vector_length(float& vector_x, float& vector_y, float max_length)
|
||||
{
|
||||
float vector_length = norm(vector_x, vector_y);
|
||||
if ((vector_length > max_length) && is_positive(max_length)) {
|
||||
if ((vector_length > max_length) && is_positive(vector_length)) {
|
||||
vector_x *= (max_length / vector_length);
|
||||
vector_y *= (max_length / vector_length);
|
||||
return true;
|
||||
|
|
Loading…
Reference in New Issue