AC_WPNav: correct calculation of predict-accel when zeroing pilot desired accel

This commit is contained in:
Peter Barker 2024-07-04 17:37:24 +10:00 committed by Peter Barker
parent 11e49c5528
commit 99fb5a994e
1 changed files with 3 additions and 1 deletions

View File

@ -33,7 +33,9 @@ public:
Vector2f get_pilot_desired_acceleration() const { return Vector2f{_desired_accel.x, _desired_accel.y}; } Vector2f get_pilot_desired_acceleration() const { return Vector2f{_desired_accel.x, _desired_accel.y}; }
/// clear pilot desired acceleration /// clear pilot desired acceleration
void clear_pilot_desired_acceleration() { _desired_accel.zero(); } void clear_pilot_desired_acceleration() {
set_pilot_desired_acceleration(0, 0);
}
/// get vector to stopping point based on a horizontal position and velocity /// get vector to stopping point based on a horizontal position and velocity
void get_stopping_point_xy(Vector2f& stopping_point) const; void get_stopping_point_xy(Vector2f& stopping_point) const;