AC_AttitudeControl: Improved Comments

This commit is contained in:
lthall
2026-02-04 23:01:21 +11:00
committed by Peter Barker
parent 63058fac10
commit 184fb13623
2 changed files with 196 additions and 130 deletions

File diff suppressed because it is too large Load Diff

View File

@@ -192,93 +192,103 @@ public:
// This is used by most of the subsequent functions
void attitude_controller_run_quat();
// Sets a desired attitude using a quaternion and body-frame angular velocity (rad/s).
// The desired quaternion is incrementally updated each timestep. Angular velocity is shaped by acceleration limits and feedforward.
// Sets an attitude target using a quaternion and a body-frame angular velocity input (rad/s).
// The desired quaternion is incrementally advanced each timestep using the (limited) angular velocity input.
// If body-frame rate feedforward shaping is enabled, rate/accel targets are generated with acceleration limits
// and input time constants; otherwise the targets are set directly.
virtual void input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_body_rads);
// Sets desired roll and pitch angles (in centidegrees) and yaw rate (in centidegrees/s).
// Sets the desired roll and pitch angles (in centidegrees) and yaw rate (in centidegrees/s).
// See input_euler_angle_roll_pitch_euler_rate_yaw_rad() for full details.
void input_euler_angle_roll_pitch_euler_rate_yaw_cd(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds);
// Sets desired roll and pitch angles (in radians) and yaw rate (in radians/s).
// Used when roll/pitch stabilization is needed with manual or autonomous yaw rate control.
// Applies acceleration-limited input shaping for smooth transitions and computes body-frame angular velocity targets.
// Sets the desired roll and pitch angle inputs (radians) and a yaw rate input (radians/s).
// Used when roll/pitch stabilization is required while yaw is controlled as a rate.
// If body-frame rate feedforward shaping is enabled, shapes Euler rate/acceleration targets
// with configured limits and time constants and converts them back to body-frame targets.
// Otherwise, updates the attitude target directly and zeros rate/accel feedforward targets.
virtual void input_euler_angle_roll_pitch_euler_rate_yaw_rad(float euler_roll_angle_rad, float euler_pitch_angle_rad, float euler_yaw_rate_rads);
// Sets desired roll, pitch, and yaw angles (in centidegrees).
// Sets the desired roll, pitch, and yaw angles (in centidegrees).
// See input_euler_angle_roll_pitch_yaw_rad() for full details.
void input_euler_angle_roll_pitch_yaw_cd(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw);
// Sets desired roll, pitch, and yaw angles (in radians).
// Used to follow an absolute attitude setpoint. Input shaping and yaw slew limits are applied.
// Outputs are passed to the rate controller via shaped angular velocity targets.
// Sets the desired roll, pitch, and yaw angle inputs (radians) to follow an absolute attitude setpoint.
// Optional yaw slew limiting constrains the rate of change of the yaw target.
// If body-frame rate feedforward shaping is enabled, shapes Euler rate/acceleration targets
// with configured limits and time constants and converts them back to body-frame targets.
// Otherwise, updates the attitude target directly (with optional yaw slew) and zeros rate/accel feedforward targets.
virtual void input_euler_angle_roll_pitch_yaw_rad(float euler_roll_angle_rad, float euler_pitch_angle_rad, float euler_yaw_angle_rad, bool slew_yaw);
// Sets desired roll, pitch, and yaw angular rates (in radians/s).
// This command is used to apply angular rate targets in the earth frame.
// The inputs are shaped using acceleration limits and time constants.
// Resulting targets are converted into body-frame angular velocities
// and passed to the rate controller.
// Sets the desired roll, pitch, and yaw Euler angle rate inputs (radians/s).
// If body-frame rate feedforward shaping is enabled, the inputs are shaped using acceleration limits
// and time constants to generate Euler rate/acceleration targets, which are then converted into
// body-frame angular velocity/acceleration targets for the rate controller.
// Otherwise, Euler angle targets are integrated directly from the rate inputs and feedforward targets are zeroed.
virtual void input_euler_rate_roll_pitch_yaw_rads(float euler_roll_rate_rads, float euler_pitch_rate_rads, float euler_yaw_rate_rads);
// Sets desired roll, pitch, and yaw angular rates (in centidegrees/s).
// Sets the desired roll, pitch, and yaw angular rates (in centidegrees/s).
// See input_rate_bf_roll_pitch_yaw_rads() for full details.
void input_rate_bf_roll_pitch_yaw_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds);
// Sets desired roll, pitch, and yaw angular rates in body-frame (in radians/s).
// This command is used by fully stabilized acro modes.
// It applies angular velocity targets in the body frame,
// shaped using acceleration limits and passed to the rate controller.
// Sets the desired roll, pitch, and yaw body-frame angular rate inputs (radians/s).
// Used by fully stabilized acro modes.
// If body-frame rate feedforward shaping is enabled, the inputs are shaped using acceleration limits
// and time constants to generate body-frame angular velocity/acceleration targets for the rate controller.
// Otherwise, the attitude target is incrementally rotated using the rate inputs and feedforward targets are zeroed.
virtual void input_rate_bf_roll_pitch_yaw_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads);
// Sets desired roll, pitch, and yaw angular rates in body-frame (in centidegrees/s).
// Sets the desired roll, pitch, and yaw angular rates in body-frame (in centidegrees/s).
// See input_rate_bf_roll_pitch_yaw_2_rads() for full details.
void input_rate_bf_roll_pitch_yaw_2_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds);
// Sets desired roll, pitch, and yaw angular rates in body-frame (in radians/s).
// Sets the desired roll, pitch, and yaw body-frame angular rate inputs (radians/s).
// Used by Copter's rate-only acro mode.
// Applies raw angular velocity targets directly to the rate controller with smoothing
// and no attitude feedback or stabilization.
// Shapes the body-frame rate inputs using acceleration limits and time constants to produce
// body-frame angular velocity/acceleration targets for the rate controller.
// Attitude targets are updated from the current AHRS attitude to keep target state coherent for mode transitions.
virtual void input_rate_bf_roll_pitch_yaw_2_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads);
// Sets desired roll, pitch, and yaw angular rates in body-frame (in centidegrees/s).
// Sets the desired roll, pitch, and yaw angular rates in body-frame (in centidegrees/s).
// See input_rate_bf_roll_pitch_yaw_3_rads() for full details.
void input_rate_bf_roll_pitch_yaw_3_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds);
// Sets desired roll, pitch, and yaw angular rates in body-frame (in radians/s).
// Sets the desired roll, pitch, and yaw body-frame angular rate inputs (radians/s).
// Used by Plane's acro mode with rate error integration.
// Integrates attitude error over time to generate target angular rates.
// Maintains an integrated attitude error quaternion using (target_rate - gyro) and combines it
// with shaped rate inputs to form the final body-frame angular velocity target for the rate controller.
virtual void input_rate_bf_roll_pitch_yaw_3_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads);
// Directly sets the body-frame angular rates without smoothing (in centidegrees/s).
// See input_rate_bf_roll_pitch_yaw_no_shaping_rads() for full details.
void input_rate_bf_roll_pitch_yaw_no_shaping_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds);
// Directly sets the body-frame angular rates without smoothing (in radians/s).
// This command is used when external control logic (e.g. fixed-wing controller)
// dictates VTOL rates. No smoothing or shaping is applied.
// Directly sets body-frame angular rate targets (radians/s) without shaping.
// Used when an external controller (e.g. fixed-wing controller) provides VTOL body rates.
// No smoothing, acceleration limiting, or input shaping is applied.
void input_rate_bf_roll_pitch_yaw_no_shaping_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads);
// Applies a one-time angular offset in body-frame roll/pitch/yaw angles (in radians).
// Used for initiating step responses during autotuning or manual test inputs.
virtual void input_angle_step_bf_roll_pitch_yaw_rad(float roll_angle_step_bf_rad, float pitch_angle_step_bf_rad, float yaw_angle_step_bf_rad);
// Applies a one-time angular velocity offset in body-frame roll/pitch/yaw (in radians/s).
// Used to apply discrete disturbances or step inputs for system identification.
// Applies a one-time body-frame angular rate step (radians/s) in roll, pitch, and yaw.
// Used to inject discrete disturbances or step inputs for system identification.
// This sets the body-frame rate command directly for this update; no shaping is applied.
virtual void input_rate_step_bf_roll_pitch_yaw_rads(float roll_rate_step_bf_rads, float pitch_rate_step_bf_rads, float yaw_rate_step_bf_rads);
// Sets desired thrust vector and heading rate (in radians/s).
// Sets the desired thrust vector and a yaw/heading rate input (radians/s).
// Used for tilt-based navigation with independent yaw control.
// The thrust vector defines the desired orientation (e.g., pointing direction for vertical thrust),
// while the heading rate adjusts yaw. The input is shaped by acceleration and slew limits.
// The thrust vector determines the desired tilt (attitude) while the heading rate commands yaw.
// Optional yaw slew limiting constrains the heading rate input.
virtual void input_thrust_vector_rate_heading_rads(const Vector3f& thrust_vector, float heading_rate_rads, bool slew_yaw = true);
// Sets desired thrust vector and heading (in radians) with heading rate (in radians/s).
// Used for advanced attitude control where thrust direction is separated from yaw orientation.
// Heading slew is constrained based on configured limits.
// Sets the desired thrust vector, heading angle (radians), and heading rate input (radians/s).
// Used when thrust direction (tilt) is commanded independently from yaw/heading.
// Heading rate is constrained using the configured yaw slew rate limit (0 disables limiting).
virtual void input_thrust_vector_heading_rad(const Vector3f& thrust_vector, float heading_angle_rad, float heading_rate_rads);
// Sets desired thrust vector and heading (in centidegrees), with zero heading rate.
// Sets the desired thrust vector and heading (in centidegrees), with zero heading rate.
// See input_thrust_vector_heading_rad() for full details.
void input_thrust_vector_heading_rad(const Vector3f& thrust_vector, float heading_rad) {input_thrust_vector_heading_rad(thrust_vector, heading_rad, 0.0f);}