mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: add clear_pilot_desired_acceleration
This allows quickly clearing out the pilot desired acceleration for loiter contoller.
This commit is contained in:
parent
40650aeb68
commit
db51d37071
|
@ -69,6 +69,9 @@ public:
|
|||
/// set_pilot_desired_acceleration - sets pilot desired acceleration from roll and pitch stick input
|
||||
void set_pilot_desired_acceleration(float control_roll, float control_pitch);
|
||||
|
||||
/// clear_pilot_desired_acceleration - clear pilot desired acceleration
|
||||
void clear_pilot_desired_acceleration() { _pilot_accel_fwd_cms = 0.0f; _pilot_accel_rgt_cms = 0.0f; }
|
||||
|
||||
/// get_stopping_point - returns vector to stopping point based on a horizontal position and velocity
|
||||
void get_loiter_stopping_point_xy(Vector3f& stopping_point) const;
|
||||
|
||||
|
|
Loading…
Reference in New Issue