mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 00:33:56 -04:00
AC_PosControl: Fix divide by zero check in limit_vector_length
This commit is contained in:
parent
aa0d8cb386
commit
4afb6a5d2c
@ -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)
|
bool AC_PosControl::limit_vector_length(float& vector_x, float& vector_y, float max_length)
|
||||||
{
|
{
|
||||||
float vector_length = norm(vector_x, vector_y);
|
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_x *= (max_length / vector_length);
|
||||||
vector_y *= (max_length / vector_length);
|
vector_y *= (max_length / vector_length);
|
||||||
return true;
|
return true;
|
||||||
|
Loading…
Reference in New Issue
Block a user