mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_AttitudeControl: added set_limit_accel_xy() API
for preventing integrator buildup
This commit is contained in:
parent
ed2f26d7b8
commit
d03a232659
@ -195,6 +195,10 @@ public:
|
||||
void set_jerk_xy(float jerk_cmsss) { _jerk_cmsss = jerk_cmsss; }
|
||||
void set_jerk_xy_to_default() { _jerk_cmsss = POSCONTROL_JERK_LIMIT_CMSSS; }
|
||||
|
||||
/// set_limit_accel_xy - mark that accel has been limited
|
||||
/// this prevents integrator buildup
|
||||
void set_limit_accel_xy(void) { _limit.accel_xy = true; }
|
||||
|
||||
/// calc_leash_length - calculates the horizontal leash length given a maximum speed, acceleration
|
||||
/// should be called whenever the speed, acceleration or position kP is modified
|
||||
void calc_leash_length_xy();
|
||||
|
Loading…
Reference in New Issue
Block a user