mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AC_AttControl: add reset_rate_controller_I_terms()
This commit is contained in:
parent
0582cd254e
commit
011bc0a350
@ -126,6 +126,13 @@ void AC_AttitudeControl::relax_attitude_controllers()
|
||||
get_rate_yaw_pid().reset_I();
|
||||
}
|
||||
|
||||
void AC_AttitudeControl::reset_rate_controller_I_terms()
|
||||
{
|
||||
get_rate_roll_pid().reset_I();
|
||||
get_rate_pitch_pid().reset_I();
|
||||
get_rate_yaw_pid().reset_I();
|
||||
}
|
||||
|
||||
// The attitude controller works around the concept of the desired attitude, target attitude
|
||||
// and measured attitude. The desired attitude is the attitude input into the attitude controller
|
||||
// that expresses where the higher level code would like the aircraft to move to. The target attitude is moved
|
||||
|
@ -104,6 +104,9 @@ public:
|
||||
// Ensure attitude controller have zero errors to relax rate controller output
|
||||
void relax_attitude_controllers();
|
||||
|
||||
// reset rate controller I terms
|
||||
void reset_rate_controller_I_terms();
|
||||
|
||||
// Sets yaw target to vehicle heading
|
||||
void set_yaw_target_to_current_heading() { _attitude_target_euler_angle.z = _ahrs.yaw; }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user