Skip to content

Commit

Permalink
AP_Math: prevent FPE in SITL when limitting accel vectors
Browse files Browse the repository at this point in the history
the  cross-product code can produce something slightly negative.  Stop passing that into safe_sqrt; it isn't *that* safe on SITL!

Co-authored-by: Leonard Hall <leonardthall@gmail.com>
  • Loading branch information
peterbarker and lthall committed Jan 6, 2025
1 parent f523c88 commit 264e586
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion libraries/AP_Math/control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -387,7 +387,9 @@ bool limit_accel_xy(const Vector2f& vel, Vector2f& accel, float accel_max)
if (accel_cross.limit_length(accel_max)) {
accel_dir = 0.0;
} else {
float accel_max_dir = safe_sqrt(sq(accel_max) - accel_cross.length_squared());
// limit_length can't absolutely guarantee this
// subtraction won't be slightly negative, so MAX() is used:
float accel_max_dir = safe_sqrt(MAX(0, sq(accel_max) - accel_cross.length_squared()));
accel_dir = constrain_float(accel_dir, -accel_max_dir, accel_max_dir);
}
accel = accel_cross + vel_input_unit * accel_dir;
Expand Down

0 comments on commit 264e586

Please sign in to comment.