Skip to content

Commit

Permalink
AC_WPNav: correct calculation of predict-accel when zeroing pilot des…
Browse files Browse the repository at this point in the history
…ired accel
  • Loading branch information
peterbarker committed Jul 4, 2024
1 parent 649f985 commit 646ea6c
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion libraries/AC_WPNav/AC_Loiter.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,9 @@ class AC_Loiter
Vector2f get_pilot_desired_acceleration() const { return Vector2f{_desired_accel.x, _desired_accel.y}; }

/// 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
void get_stopping_point_xy(Vector2f& stopping_point) const;
Expand Down

0 comments on commit 646ea6c

Please sign in to comment.