Path: blob/master/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
9381 views
#include "AC_AttitudeControl.h"1#include <AP_HAL/AP_HAL.h>2#include <AP_Vehicle/AP_Vehicle.h>3#include <AP_Scheduler/AP_Scheduler.h>4#include <AP_Vehicle/AP_Vehicle_Type.h>56extern const AP_HAL::HAL& hal;78#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)9// default gains for Plane10# define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.2f // Soft11#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 5.0 // Min lean angle so that vehicle can maintain limited control12#define AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL 013#else14// default gains for Copter and Sub15# define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium16#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 10.0 // Min lean angle so that vehicle can maintain limited control17#define AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL 118#endif1920// lean angle max (in degrees) for all vehicles21#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MAX 80.0 // lean angle max in degrees2223// default angle max for all vehicles24#ifndef AC_ATTITUDE_CONTROL_ANGLE_MAX_DEFAULT25# define AC_ATTITUDE_CONTROL_ANGLE_MAX_DEFAULT 30.0f // default max lean angle in degrees26#endif2728AC_AttitudeControl *AC_AttitudeControl::_singleton;2930// table of user settable parameters31const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {3233// 0, 1 were RATE_RP_MAX, RATE_Y_MAX3435// @Param: SLEW_YAW36// @DisplayName: Yaw target slew rate37// @Description: Maximum rate the yaw target can be updated in RTL and Auto flight modes38// @Units: cdeg/s39// @Range: 500 1800040// @Increment: 10041// @User: Advanced42AP_GROUPINFO("SLEW_YAW", 2, AC_AttitudeControl, _slew_yaw_cds, AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS),4344// 3 was for ACCEL_RP_MAX4546// @Param: ACCEL_Y_MAX47// @DisplayName: Acceleration Max for Yaw48// @Description: Maximum acceleration in yaw axis49// @Units: cdeg/s/s50// @Range: 0 7200051// @Values: 0:Disabled, 9000:VerySlow, 18000:Slow, 36000:Medium, 54000:Fast52// @Increment: 100053// @User: Advanced54AP_GROUPINFO("ACCEL_Y_MAX", 4, AC_AttitudeControl, _accel_yaw_max_cdss, AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS),5556// @Param: RATE_FF_ENAB57// @DisplayName: Rate Feedforward Enable58// @Description: Controls whether body-frame rate feedforward is enabled or disabled59// @Values: 0:Disabled, 1:Enabled60// @User: Advanced61AP_GROUPINFO("RATE_FF_ENAB", 5, AC_AttitudeControl, _rate_bf_ff_enabled, AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT),6263// @Param: ACCEL_R_MAX64// @DisplayName: Acceleration Max for Roll65// @Description: Maximum acceleration in roll axis66// @Units: cdeg/s/s67// @Range: 0 18000068// @Increment: 100069// @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast70// @User: Advanced71AP_GROUPINFO("ACCEL_R_MAX", 6, AC_AttitudeControl, _accel_roll_max_cdss, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS),7273// @Param: ACCEL_P_MAX74// @DisplayName: Acceleration Max for Pitch75// @Description: Maximum acceleration in pitch axis76// @Units: cdeg/s/s77// @Range: 0 18000078// @Increment: 100079// @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast80// @User: Advanced81AP_GROUPINFO("ACCEL_P_MAX", 7, AC_AttitudeControl, _accel_pitch_max_cdss, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS),8283// IDs 8,9,10,11 RESERVED (in use on Solo)8485// @Param: ANGLE_BOOST86// @DisplayName: Angle Boost87// @Description: Angle Boost increases output throttle as the vehicle leans to reduce loss of altitude88// @Values: 0:Disabled, 1:Enabled89// @User: Advanced90AP_GROUPINFO("ANGLE_BOOST", 12, AC_AttitudeControl, _angle_boost_enabled, 1),9192// @Param: ANG_RLL_P93// @DisplayName: Roll axis angle controller P gain94// @Description: Roll axis angle controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate95// @Range: 3.000 12.00096// @Range{Sub}: 0.0 12.00097// @Increment: 0.0198// @User: Standard99AP_SUBGROUPINFO(_p_angle_roll, "ANG_RLL_", 13, AC_AttitudeControl, AC_P),100101// @Param: ANG_PIT_P102// @DisplayName: Pitch axis angle controller P gain103// @Description: Pitch axis angle controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate104// @Range: 3.000 12.000105// @Range{Sub}: 0.0 12.000106// @Increment: 0.01107// @User: Standard108AP_SUBGROUPINFO(_p_angle_pitch, "ANG_PIT_", 14, AC_AttitudeControl, AC_P),109110// @Param: ANG_YAW_P111// @DisplayName: Yaw axis angle controller P gain112// @Description: Yaw axis angle controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate113// @Range: 3.000 12.000114// @Range{Sub}: 0.0 6.000115// @Increment: 0.01116// @User: Standard117AP_SUBGROUPINFO(_p_angle_yaw, "ANG_YAW_", 15, AC_AttitudeControl, AC_P),118119// @Param: ANG_LIM_TC120// @DisplayName: Angle Limit (to maintain altitude) Time Constant121// @Description: Angle Limit (to maintain altitude) Time Constant122// @Range: 0.5 10.0123// @User: Advanced124AP_GROUPINFO("ANG_LIM_TC", 16, AC_AttitudeControl, _angle_limit_tc, AC_ATTITUDE_CONTROL_ANGLE_LIMIT_TC_DEFAULT),125126// @Param: RATE_R_MAX127// @DisplayName: Angular Velocity Max for Roll128// @Description: Maximum angular velocity in roll axis129// @Units: deg/s130// @Range: 0 1080131// @Increment: 1132// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast133// @User: Advanced134AP_GROUPINFO("RATE_R_MAX", 17, AC_AttitudeControl, _ang_vel_roll_max_degs, 0.0f),135136// @Param: RATE_P_MAX137// @DisplayName: Angular Velocity Max for Pitch138// @Description: Maximum angular velocity in pitch axis139// @Units: deg/s140// @Range: 0 1080141// @Increment: 1142// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast143// @User: Advanced144AP_GROUPINFO("RATE_P_MAX", 18, AC_AttitudeControl, _ang_vel_pitch_max_degs, 0.0f),145146// @Param: RATE_Y_MAX147// @DisplayName: Angular Velocity Max for Yaw148// @Description: Maximum angular velocity in yaw axis149// @Units: deg/s150// @Range: 0 1080151// @Increment: 1152// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast153// @User: Advanced154AP_GROUPINFO("RATE_Y_MAX", 19, AC_AttitudeControl, _ang_vel_yaw_max_degs, 0.0f),155156// @Param: INPUT_TC157// @DisplayName: Attitude control input time constant158// @Description: Attitude control input time constant. Low numbers lead to sharper response, higher numbers to softer response159// @Units: s160// @Range: 0 1161// @Increment: 0.01162// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp163// @User: Standard164AP_GROUPINFO("INPUT_TC", 20, AC_AttitudeControl, _input_tc, AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT),165166// @Param: LAND_R_MULT167// @DisplayName: Landed roll gain multiplier168// @Description: Roll gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the roll axis.169// @Range: 0.25 1.0170// @User: Advanced171AP_GROUPINFO("LAND_R_MULT", 21, AC_AttitudeControl, _land_roll_mult, 1.0),172173// @Param: LAND_P_MULT174// @DisplayName: Landed pitch gain multiplier175// @Description: Pitch gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the pitch axis.176// @Range: 0.25 1.0177// @User: Advanced178AP_GROUPINFO("LAND_P_MULT", 22, AC_AttitudeControl, _land_pitch_mult, 1.0),179180// @Param: LAND_Y_MULT181// @DisplayName: Landed yaw gain multiplier182// @Description: Yaw gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the yaw axis.183// @Range: 0.25 1.0184// @User: Advanced185AP_GROUPINFO("LAND_Y_MULT", 23, AC_AttitudeControl, _land_yaw_mult, 1.0),186187// @Param: ANGLE_MAX188// @DisplayName: Angle Max189// @Description: Maximum lean angle in all flight modes190// @Units: deg191// @Increment: 0.1192// @Range: 10.0 80.0193// @User: Standard194AP_GROUPINFO("ANGLE_MAX", 24, AC_AttitudeControl, _angle_max_deg, AC_ATTITUDE_CONTROL_ANGLE_MAX_DEFAULT),195196AP_GROUPEND197};198199constexpr Vector3f AC_AttitudeControl::VECTORF_111;200201// get the slew yaw rate limit in rad/s202float AC_AttitudeControl::get_slew_yaw_max_rads() const203{204if (!is_positive(_ang_vel_yaw_max_degs)) {205return cd_to_rad(_slew_yaw_cds);206}207return MIN(radians(_ang_vel_yaw_max_degs), cd_to_rad(_slew_yaw_cds));208}209210// get the latest gyro for the purposes of attitude control211// Counter-inuitively the lowest latency for rate control is achieved by running rate control212// *before* attitude control. This is because you want rate control to run as close as possible213// to the time that a gyro sample was read to minimise jitter and control errors. Running rate214// control after attitude control might makes sense logically, but the overhead of attitude215// control calculations (and other updates) compromises the actual rate control.216//217// In the case of running rate control in a separate thread, the ordering between rate and attitude218// updates is less important, except that gyro sample used should be the latest219//220// Currently quadplane runs rate control after attitude control, necessitating the following code221// to minimise latency.222// However this code can be removed once quadplane updates it's structure to run the rate loops before223// the Attitude controller.224const Vector3f AC_AttitudeControl::get_latest_gyro() const225{226#if AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL227// rate updates happen before attitude updates so the last gyro value is the last rate gyro value228// this also allows a separate rate thread to be the source of gyro data229return _rate_gyro_rads;230#else231// rate updates happen after attitude updates so the AHRS must be consulted for the last gyro value232return _ahrs.get_gyro_latest();233#endif234}235236// Ensure attitude controller have zero errors to relax rate controller output237void AC_AttitudeControl::relax_attitude_controllers()238{239// take a copy of the last gyro used by the rate controller before using it240Vector3f gyro = get_latest_gyro();241// Initialize the attitude variables to the current attitude242_ahrs.get_quat_body_to_ned(_attitude_target);243_attitude_target.to_euler(_euler_angle_target_rad);244_attitude_ang_error.initialise();245246// Initialize the angular rate variables to the current rate247_ang_vel_target_rads = gyro;248body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);249250// Initialize remaining variables251_thrust_error_angle_rad = 0.0f;252253// Reset the PID filters254get_rate_roll_pid().reset_filter();255get_rate_pitch_pid().reset_filter();256get_rate_yaw_pid().reset_filter();257258// Reset the I terms259reset_rate_controller_I_terms();260// finally update the attitude target261_ang_vel_body_rads = gyro;262}263264void AC_AttitudeControl::reset_rate_controller_I_terms()265{266get_rate_roll_pid().reset_I();267get_rate_pitch_pid().reset_I();268get_rate_yaw_pid().reset_I();269}270271// reset rate controller I terms smoothly to zero in 0.5 seconds272void AC_AttitudeControl::reset_rate_controller_I_terms_smoothly()273{274get_rate_roll_pid().relax_integrator(0.0, _dt_s, AC_ATTITUDE_RATE_RELAX_TC);275get_rate_pitch_pid().relax_integrator(0.0, _dt_s, AC_ATTITUDE_RATE_RELAX_TC);276get_rate_yaw_pid().relax_integrator(0.0, _dt_s, AC_ATTITUDE_RATE_RELAX_TC);277}278279// Reduce attitude control gains while landed to stop ground resonance280void AC_AttitudeControl::landed_gain_reduction(bool landed)281{282if (is_positive(_input_tc)) {283// use 2.0 x tc to match the response time to 86% commanded284const float spool_step = _dt_s / (2.0 * _input_tc);285if (landed) {286_landed_gain_ratio = MIN(1.0, _landed_gain_ratio + spool_step);287} else {288_landed_gain_ratio = MAX(0.0, _landed_gain_ratio - spool_step);289}290} else {291_landed_gain_ratio = landed ? 1.0 : 0.0;292}293Vector3f scale_mult = VECTORF_111 * (1.0 - _landed_gain_ratio) + Vector3f{_land_roll_mult, _land_pitch_mult, _land_yaw_mult} * _landed_gain_ratio;294set_PD_scale_mult(scale_mult);295set_angle_P_scale_mult(scale_mult);296}297298// The attitude controller works around the concept of the desired attitude, target attitude299// and measured attitude. The desired attitude is the attitude input into the attitude controller300// that expresses where the higher level code would like the aircraft to move to. The target attitude is moved301// to the desired attitude with jerk, acceleration, and velocity limits. The target angular velocities are fed302// directly into the rate controllers. The angular error between the measured attitude and the target attitude is303// fed into the angle controller and the output of the angle controller summed at the input of the rate controllers.304// By feeding the target angular velocity directly into the rate controllers the measured and target attitudes305// remain very close together.306//307// All input functions below follow the same procedure308// 1. define the desired attitude or attitude change based on the input variables309// 2. update the target attitude based on the angular velocity target and the time since the last loop310// 3. using the desired attitude and input variables, define the target angular velocity so that it should311// move the target attitude towards the desired attitude312// 4. if _rate_bf_ff_enabled is not being used then make the target attitude313// and target angular velocities equal to the desired attitude and desired angular velocities.314// 5. ensure _attitude_target, _euler_angle_target_rad, _euler_rate_target_rads and315// _ang_vel_target_rads have been defined. This ensures input modes can be changed without discontinuity.316// 6. attitude_controller_run_quat is then run to pass the target angular velocities to the rate controllers and317// integrate them into the target attitude. Any errors between the target attitude and the measured attitude are318// corrected by first correcting the thrust vector until the angle between the target thrust vector measured319// trust vector drops below 2*AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD. At this point the heading is also corrected.320321// Sets an attitude target using a quaternion and a body-frame angular velocity input (rad/s).322// The desired quaternion is incrementally advanced each timestep using the (limited) angular velocity input.323// If body-frame rate feedforward shaping is enabled, rate/accel targets are generated with acceleration limits324// and input time constants; otherwise the targets are set directly.325void AC_AttitudeControl::input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_body_rads)326{327// Update internal attitude target state328update_attitude_target();329330// Limit the body-frame angular velocity input331ang_vel_limit(ang_vel_body_rads, radians(_ang_vel_roll_max_degs), radians(_ang_vel_pitch_max_degs), radians(_ang_vel_yaw_max_degs));332333// Convert the limited body-frame angular velocity input into the frame used for quaternion integration334Vector3f ang_vel_target = attitude_desired_quat * ang_vel_body_rads;335336if (_rate_bf_ff_enabled) {337// Compute attitude error (target -> desired) and express as a small-axis-angle vector338Quaternion attitude_error_quat = _attitude_target.inverse() * attitude_desired_quat;339Vector3f attitude_error_angle;340attitude_error_quat.to_axis_angle(attitude_error_angle);341342// Shape the attitude error into angular velocity and acceleration targets with configured343// rate and acceleration limits and time constants (roll/pitch use _input_tc, yaw uses _rate_y_tc).344attitude_command_model(wrap_PI(attitude_error_angle.x), 0.0, _ang_vel_target_rads.x, _ang_accel_target_rads.x, radians(_ang_vel_roll_max_degs), get_accel_roll_max_radss(), _input_tc, _dt_s);345attitude_command_model(wrap_PI(attitude_error_angle.y), 0.0, _ang_vel_target_rads.y, _ang_accel_target_rads.y, radians(_ang_vel_pitch_max_degs), get_accel_pitch_max_radss(), _input_tc, _dt_s);346attitude_command_model(wrap_PI(attitude_error_angle.z), 0.0, _ang_vel_target_rads.z, _ang_accel_target_rads.z, radians(_ang_vel_yaw_max_degs), get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);347} else {348// No shaping: directly set attitude and angular velocity targets349_attitude_target = attitude_desired_quat;350_ang_vel_target_rads = ang_vel_target;351}352353// Update stored Euler-angle representation of the attitude target354_attitude_target.to_euler(_euler_angle_target_rad);355356// Convert body-frame angular velocity into euler angle derivative of desired attitude357body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);358359// Incrementally advance the desired quaternion using the (limited) angular velocity input360Quaternion attitude_desired_update;361attitude_desired_update.from_axis_angle(ang_vel_target * _dt_s);362attitude_desired_quat = attitude_desired_quat * attitude_desired_update;363attitude_desired_quat.normalize();364365// Run quaternion attitude controller366attitude_controller_run_quat();367}368369// Sets the desired roll and pitch angles (in centidegrees) and yaw rate (in centidegrees/s).370// See input_euler_angle_roll_pitch_euler_rate_yaw_rad() for full details.371void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw_cd(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)372{373// Convert from centidegrees on public interface to radians374const float euler_roll_angle_rad = cd_to_rad(euler_roll_angle_cd);375const float euler_pitch_angle_rad = cd_to_rad(euler_pitch_angle_cd);376const float euler_yaw_rate_rads = cd_to_rad(euler_yaw_rate_cds);377input_euler_angle_roll_pitch_euler_rate_yaw_rad(euler_roll_angle_rad, euler_pitch_angle_rad, euler_yaw_rate_rads);378}379380// Sets the desired roll and pitch angle inputs (radians) and a yaw rate input (radians/s).381// Used when roll/pitch stabilization is required while yaw is controlled as a rate.382// If body-frame rate feedforward shaping is enabled, shapes Euler rate/acceleration targets383// with configured limits and time constants and converts them back to body-frame targets.384// Otherwise, updates the attitude target directly and zeros rate/accel feedforward targets.385void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw_rad(float euler_roll_angle_rad, float euler_pitch_angle_rad, float euler_yaw_rate_rads)386{387// update attitude target388update_attitude_target();389390// calculate the attitude target euler angles391_attitude_target.to_euler(_euler_angle_target_rad);392393// Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)394euler_roll_angle_rad += get_roll_trim_rad();395396if (_rate_bf_ff_enabled) {397// Convert body-frame angular acceleration limits (roll, pitch, yaw) into equivalent398// Euler-angle acceleration limits for the current attitude target.399const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()});400const Vector3f euler_rate_max_rads = euler_accel_limit(_attitude_target, Vector3f{radians(_ang_vel_roll_max_degs), radians(_ang_vel_pitch_max_degs), radians(_ang_vel_yaw_max_degs)});401402// Convert the body-frame angular acceleration target into an equivalent Euler-angle403// acceleration target for the current attitude target.404Vector3f euler_accel_target_rads;405body_to_euler_derivative(_attitude_target, _ang_accel_target_rads, euler_accel_target_rads);406407// Shape Euler roll/pitch angle error into Euler rate/acceleration targets.408// The shaper applies Euler rate/acceleration limits and the configured input time constant.409attitude_command_model(wrap_PI(euler_roll_angle_rad - _euler_angle_target_rad.x), 0.0, _euler_rate_target_rads.x, euler_accel_target_rads.x, fabsf(euler_rate_max_rads.x), euler_accel.x, _input_tc, _dt_s);410attitude_command_model(wrap_PI(euler_pitch_angle_rad - _euler_angle_target_rad.y), 0.0, _euler_rate_target_rads.y, euler_accel_target_rads.y, fabsf(euler_rate_max_rads.y), euler_accel.y, _input_tc, _dt_s);411412// Shape yaw rate input into Euler yaw rate/acceleration targets, applying the configured yaw rate time constant413// and limiting Euler acceleration about the yaw axis.414attitude_command_model(0.0, euler_yaw_rate_rads, _euler_rate_target_rads.z, euler_accel_target_rads.z, fabsf(euler_rate_max_rads.z), euler_accel.z, _rate_y_tc, _dt_s);415416// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward417euler_derivative_to_body(_attitude_target, _euler_rate_target_rads, _ang_vel_target_rads);418419// Convert euler angle derivative of desired attitude into a body-frame angular acceleration vector for feedforward420euler_derivative_to_body(_attitude_target, euler_accel_target_rads, _ang_accel_target_rads);421} else {422// No shaping/feedforward: directly update roll/pitch attitude targets and integrate yaw target from yaw rate.423_euler_angle_target_rad.x = euler_roll_angle_rad;424_euler_angle_target_rad.y = euler_pitch_angle_rad;425_euler_angle_target_rad.z += euler_yaw_rate_rads * _dt_s;426427// Compute quaternion target attitude428_attitude_target.from_euler(_euler_angle_target_rad.x, _euler_angle_target_rad.y, _euler_angle_target_rad.z);429430// Zero rate and acceleration feedforward targets431_euler_rate_target_rads.zero();432_ang_vel_target_rads.zero();433_ang_accel_target_rads.zero();434}435436// Call quaternion attitude controller437attitude_controller_run_quat();438}439440// Sets the desired roll, pitch, and yaw angles (in centidegrees).441// See input_euler_angle_roll_pitch_yaw_rad() for full details.442void AC_AttitudeControl::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)443{444// Convert from centidegrees on public interface to radians445const float euler_roll_angle_rad = cd_to_rad(euler_roll_angle_cd);446const float euler_pitch_angle_rad = cd_to_rad(euler_pitch_angle_cd);447const float euler_yaw_angle_rad = cd_to_rad(euler_yaw_angle_cd);448449input_euler_angle_roll_pitch_yaw_rad(euler_roll_angle_rad, euler_pitch_angle_rad, euler_yaw_angle_rad, slew_yaw);450}451452// Sets the desired roll, pitch, and yaw angle inputs (radians) to follow an absolute attitude setpoint.453// Optional yaw slew limiting constrains the rate of change of the yaw target.454// If body-frame rate feedforward shaping is enabled, shapes Euler rate/acceleration targets455// with configured limits and time constants and converts them back to body-frame targets.456// Otherwise, updates the attitude target directly (with optional yaw slew) and zeros rate/accel feedforward targets.457void AC_AttitudeControl::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)458{459// update attitude target460update_attitude_target();461462// calculate the attitude target euler angles463_attitude_target.to_euler(_euler_angle_target_rad);464465// Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)466euler_roll_angle_rad += get_roll_trim_rad();467468const float slew_yaw_max_rads = get_slew_yaw_max_rads();469470if (_rate_bf_ff_enabled) {471// Convert body-frame angular acceleration limits (roll, pitch, yaw) into equivalent472// Euler-angle acceleration limits for the current attitude target.473const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()});474475float yaw_rate_max_rads = radians(_ang_vel_yaw_max_degs);476if (slew_yaw) {477yaw_rate_max_rads = MIN(yaw_rate_max_rads, slew_yaw_max_rads);478}479const Vector3f euler_rate_max_rads = euler_accel_limit(_attitude_target, Vector3f{radians(_ang_vel_roll_max_degs), radians(_ang_vel_pitch_max_degs), yaw_rate_max_rads});480481Vector3f euler_accel_target_rads;482body_to_euler_derivative(_attitude_target, _ang_accel_target_rads, euler_accel_target_rads);483attitude_command_model(wrap_PI(euler_roll_angle_rad - _euler_angle_target_rad.x), 0.0, _euler_rate_target_rads.x, euler_accel_target_rads.x, fabsf(euler_rate_max_rads.x), euler_accel.x, _input_tc, _dt_s);484attitude_command_model(wrap_PI(euler_pitch_angle_rad - _euler_angle_target_rad.y), 0.0, _euler_rate_target_rads.y, euler_accel_target_rads.y, fabsf(euler_rate_max_rads.y), euler_accel.y, _input_tc, _dt_s);485attitude_command_model(wrap_PI(euler_yaw_angle_rad - _euler_angle_target_rad.z), 0.0, _euler_rate_target_rads.z, euler_accel_target_rads.z, fabsf(euler_rate_max_rads.z), euler_accel.z, _input_tc, _dt_s);486487// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward488euler_derivative_to_body(_attitude_target, _euler_rate_target_rads, _ang_vel_target_rads);489490// Convert euler angle derivative of desired attitude into a body-frame angular acceleration vector for feedforward491euler_derivative_to_body(_attitude_target, euler_accel_target_rads, _ang_accel_target_rads);492} else {493// No shaping/feedforward: directly update roll/pitch attitude targets and update yaw target494// with optional slew limiting, then zero rate/accel feedforward targets.495_euler_angle_target_rad.x = euler_roll_angle_rad;496_euler_angle_target_rad.y = euler_pitch_angle_rad;497498if (slew_yaw) {499// Constrain yaw target change to the configured slew rate.500const float yaw_error = wrap_PI(euler_yaw_angle_rad - _euler_angle_target_rad.z);501const float yaw_step = constrain_float(yaw_error, -slew_yaw_max_rads * _dt_s, slew_yaw_max_rads * _dt_s);502_euler_angle_target_rad.z = wrap_PI(_euler_angle_target_rad.z + yaw_step);503} else {504_euler_angle_target_rad.z = euler_yaw_angle_rad;505}506507// Compute quaternion target attitude508_attitude_target.from_euler(_euler_angle_target_rad.x, _euler_angle_target_rad.y, _euler_angle_target_rad.z);509510// Zero rate and acceleration feedforward targets511_euler_rate_target_rads.zero();512_ang_vel_target_rads.zero();513_ang_accel_target_rads.zero();514}515516// Call quaternion attitude controller517attitude_controller_run_quat();518}519520// Sets the desired roll, pitch, and yaw Euler angle rate inputs (radians/s).521// If body-frame rate feedforward shaping is enabled, the inputs are shaped using acceleration limits522// and time constants to generate Euler rate/acceleration targets, which are then converted into523// body-frame angular velocity/acceleration targets for the rate controller.524// Otherwise, Euler angle targets are integrated directly from the rate inputs and feedforward targets are zeroed.525void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw_rads(float euler_roll_rate_rads, float euler_pitch_rate_rads, float euler_yaw_rate_rads)526{527// update attitude target528update_attitude_target();529530// calculate the attitude target euler angles531_attitude_target.to_euler(_euler_angle_target_rad);532533if (_rate_bf_ff_enabled) {534// Convert body-frame angular acceleration limits (roll, pitch, yaw) into535// equivalent Euler-angle acceleration limits for the current attitude target.536const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()});537538// Convert the body-frame angular acceleration target into an equivalent Euler-angle539// acceleration target for the current attitude target.540Vector3f euler_accel_target_rads;541body_to_euler_derivative(_attitude_target, _ang_accel_target_rads, euler_accel_target_rads);542543// Shape Euler rate inputs into Euler rate/acceleration targets, applying acceleration limits and time constants.544attitude_command_model(0.0, euler_roll_rate_rads, _euler_rate_target_rads.x, euler_accel_target_rads.x, 0.0, euler_accel.x, _rate_rp_tc, _dt_s);545attitude_command_model(0.0, euler_pitch_rate_rads, _euler_rate_target_rads.y, euler_accel_target_rads.y, 0.0, euler_accel.y, _rate_rp_tc, _dt_s);546attitude_command_model(0.0, euler_yaw_rate_rads, _euler_rate_target_rads.z, euler_accel_target_rads.z, 0.0, euler_accel.z, _rate_y_tc, _dt_s);547548// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward549euler_derivative_to_body(_attitude_target, _euler_rate_target_rads, _ang_vel_target_rads);550551// Convert euler angle derivative of desired attitude into a body-frame angular acceleration vector for feedforward552euler_derivative_to_body(_attitude_target, euler_accel_target_rads, _ang_accel_target_rads);553} else {554// No shaping/feedforward: integrate Euler angle targets from Euler rate inputs.555// Pitch is constrained to ±85 degrees to avoid gimbal lock discontinuities.556_euler_angle_target_rad.x = wrap_PI(_euler_angle_target_rad.x + euler_roll_rate_rads * _dt_s);557_euler_angle_target_rad.y = constrain_float(_euler_angle_target_rad.y + euler_pitch_rate_rads * _dt_s, radians(-85.0f), radians(85.0f));558_euler_angle_target_rad.z = wrap_2PI(_euler_angle_target_rad.z + euler_yaw_rate_rads * _dt_s);559560// Zero rate and acceleration feedforward targets561_euler_rate_target_rads.zero();562_ang_vel_target_rads.zero();563_ang_accel_target_rads.zero();564565// Compute quaternion target attitude566_attitude_target.from_euler(_euler_angle_target_rad.x, _euler_angle_target_rad.y, _euler_angle_target_rad.z);567}568569// Call quaternion attitude controller570attitude_controller_run_quat();571}572573// Fully stabilized acro574// Sets the desired roll, pitch, and yaw angular rates (in centidegrees/s).575// See input_rate_bf_roll_pitch_yaw_rads() for full details.576void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)577{578// Convert from centidegrees on public interface to radians579const float roll_rate_bf_rads = cd_to_rad(roll_rate_bf_cds);580const float pitch_rate_bf_rads = cd_to_rad(pitch_rate_bf_cds);581const float yaw_rate_bf_rads = cd_to_rad(yaw_rate_bf_cds);582583input_rate_bf_roll_pitch_yaw_rads(roll_rate_bf_rads, pitch_rate_bf_rads, yaw_rate_bf_rads);584}585586// Sets the desired roll, pitch, and yaw body-frame angular rate inputs (radians/s).587// Used by fully stabilized acro modes.588// If body-frame rate feedforward shaping is enabled, the inputs are shaped using acceleration limits589// and time constants to generate body-frame angular velocity/acceleration targets for the rate controller.590// Otherwise, the attitude target is incrementally rotated using the rate inputs and feedforward targets are zeroed.591void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads)592{593// update attitude target594update_attitude_target();595596// calculate the attitude target euler angles597_attitude_target.to_euler(_euler_angle_target_rad);598599if (_rate_bf_ff_enabled) {600// Shape body-frame rate inputs into body-frame angular velocity/acceleration targets,601// applying acceleration limits and configured time constants.602attitude_command_model(0.0, roll_rate_bf_rads, _ang_vel_target_rads.x, _ang_accel_target_rads.x, 0.0, get_accel_roll_max_radss(), _rate_rp_tc, _dt_s);603attitude_command_model(0.0, pitch_rate_bf_rads, _ang_vel_target_rads.y, _ang_accel_target_rads.y, 0.0, get_accel_pitch_max_radss(), _rate_rp_tc, _dt_s);604attitude_command_model(0.0, yaw_rate_bf_rads, _ang_vel_target_rads.z, _ang_accel_target_rads.z, 0.0, get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);605606// Convert body-frame angular velocity into euler angle derivative of desired attitude607body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);608} else {609// No shaping/feedforward: incrementally rotate the attitude target using the body-frame rate inputs.610Quaternion attitude_target_update;611attitude_target_update.from_axis_angle(Vector3f{roll_rate_bf_rads, pitch_rate_bf_rads, yaw_rate_bf_rads} * _dt_s);612_attitude_target = _attitude_target * attitude_target_update;613_attitude_target.normalize();614615// Zero rate and acceleration feedforward targets616_euler_rate_target_rads.zero();617_ang_vel_target_rads.zero();618_ang_accel_target_rads.zero();619}620621// Call quaternion attitude controller622attitude_controller_run_quat();623}624625// Sets the desired roll, pitch, and yaw angular rates in body-frame (in centidegrees/s).626// See input_rate_bf_roll_pitch_yaw_2_rads() for full details.627void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)628{629// Convert from centidegrees on public interface to radians630const float roll_rate_bf_rads = cd_to_rad(roll_rate_bf_cds);631const float pitch_rate_bf_rads = cd_to_rad(pitch_rate_bf_cds);632const float yaw_rate_bf_rads = cd_to_rad(yaw_rate_bf_cds);633634input_rate_bf_roll_pitch_yaw_2_rads(roll_rate_bf_rads, pitch_rate_bf_rads, yaw_rate_bf_rads);635}636637// Sets the desired roll, pitch, and yaw body-frame angular rate inputs (radians/s).638// Used by Copter's rate-only acro mode.639// Shapes the body-frame rate inputs using acceleration limits and time constants to produce640// body-frame angular velocity/acceleration targets for the rate controller.641// Attitude targets are updated from the current AHRS attitude to keep target state coherent for mode transitions.642void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads)643{644// Shape body-frame rate inputs into body-frame angular velocity/acceleration targets,645// applying acceleration limits and configured time constants.646attitude_command_model(0.0, roll_rate_bf_rads, _ang_vel_target_rads.x, _ang_accel_target_rads.x, 0.0, get_accel_roll_max_radss(), _rate_rp_tc, _dt_s);647attitude_command_model(0.0, pitch_rate_bf_rads, _ang_vel_target_rads.y, _ang_accel_target_rads.y, 0.0, get_accel_pitch_max_radss(), _rate_rp_tc, _dt_s);648attitude_command_model(0.0, yaw_rate_bf_rads, _ang_vel_target_rads.z, _ang_accel_target_rads.z, 0.0, get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);649650// Update attitude and Euler targets from the current vehicle attitude (used for conditioning mode transitions).651_ahrs.get_quat_body_to_ned(_attitude_target);652_attitude_target.to_euler(_euler_angle_target_rad);653// Convert body-frame angular velocity into euler angle derivative of desired attitude654body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);655656// Update body-frame angular velocity target used by the rate controller.657_ang_vel_body_rads = _ang_vel_target_rads;658}659660// Sets the desired roll, pitch, and yaw angular rates in body-frame (in centidegrees/s).661// See input_rate_bf_roll_pitch_yaw_3_rads() for full details.662void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)663{664// Convert from centidegrees on public interface to radians665const float roll_rate_bf_rads = cd_to_rad(roll_rate_bf_cds);666const float pitch_rate_bf_rads = cd_to_rad(pitch_rate_bf_cds);667const float yaw_rate_bf_rads = cd_to_rad(yaw_rate_bf_cds);668669input_rate_bf_roll_pitch_yaw_3_rads(roll_rate_bf_rads, pitch_rate_bf_rads, yaw_rate_bf_rads);670}671672// Sets the desired roll, pitch, and yaw body-frame angular rate inputs (radians/s).673// Used by Plane's acro mode with rate error integration.674// Maintains an integrated attitude error quaternion using (target_rate - gyro) and combines it675// with shaped rate inputs to form the final body-frame angular velocity target for the rate controller.676void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads)677{678// Extract current integrated attitude error as axis-angle679Vector3f attitude_error;680_attitude_ang_error.to_axis_angle(attitude_error);681682Quaternion attitude_ang_error_update_quat;683684// Limit the magnitude of the integrated attitude error (prevents windup)685float err_mag = attitude_error.length();686if (err_mag > AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD) {687attitude_error *= AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD / err_mag;688_attitude_ang_error.from_axis_angle(attitude_error);689}690691// Integrate attitude error using rate error: (target body rates - measured gyro)692Vector3f gyro_latest = get_latest_gyro();693attitude_ang_error_update_quat.from_axis_angle((_ang_vel_target_rads - gyro_latest) * _dt_s);694_attitude_ang_error = attitude_ang_error_update_quat * _attitude_ang_error;695_attitude_ang_error.normalize();696697// Shape body-frame rate inputs into body-frame angular velocity/acceleration targets,698// applying acceleration limits and configured time constants.699attitude_command_model(0.0, roll_rate_bf_rads, _ang_vel_target_rads.x, _ang_accel_target_rads.x, 0.0, get_accel_roll_max_radss(), _rate_rp_tc, _dt_s);700attitude_command_model(0.0, pitch_rate_bf_rads, _ang_vel_target_rads.y, _ang_accel_target_rads.y, 0.0, get_accel_pitch_max_radss(), _rate_rp_tc, _dt_s);701attitude_command_model(0.0, yaw_rate_bf_rads, _ang_vel_target_rads.z, _ang_accel_target_rads.z, 0.0, get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);702703// Retrieve current vehicle attitude (body to NED)704Quaternion attitude_body;705_ahrs.get_quat_body_to_ned(attitude_body);706707// Update attitude target by applying the integrated attitude error to the current attitude708_attitude_target = attitude_body * _attitude_ang_error;709_attitude_target.normalize();710711// Update stored Euler-angle representation of the attitude target712_attitude_target.to_euler(_euler_angle_target_rad);713714// Convert body-frame angular velocity into euler angle derivative of desired attitude715body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);716717// Compute body-frame angular velocity correction from integrated attitude error and add shaped rate input718_attitude_ang_error.to_axis_angle(attitude_error);719Vector3f ang_vel_body_rads = update_ang_vel_target_from_att_error(attitude_error);720ang_vel_body_rads += _ang_vel_target_rads;721722// Update body-frame angular velocity target used by the rate controller723_ang_vel_body_rads = ang_vel_body_rads;724}725726/*727set the body frame target rates to the specified rates, used by the728quadplane code when we want to slave the VTOL controller rates to729the fixed wing rates730*/731732// Directly sets the body-frame angular rates without smoothing (in centidegrees/s).733// See input_rate_bf_roll_pitch_yaw_no_shaping_rads() for full details.734void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_no_shaping_cds(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)735{736// Convert from centidegrees on public interface to radians737const float roll_rate_bf_rads = cd_to_rad(roll_rate_bf_cds);738const float pitch_rate_bf_rads = cd_to_rad(pitch_rate_bf_cds);739const float yaw_rate_bf_rads = cd_to_rad(yaw_rate_bf_cds);740741input_rate_bf_roll_pitch_yaw_no_shaping_rads(roll_rate_bf_rads, pitch_rate_bf_rads, yaw_rate_bf_rads);742}743744// Directly sets body-frame angular rate targets (radians/s) without shaping.745// Used when an external controller (e.g. fixed-wing controller) provides VTOL body rates.746// No smoothing, acceleration limiting, or input shaping is applied.747void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_no_shaping_rads(float roll_rate_bf_rads, float pitch_rate_bf_rads, float yaw_rate_bf_rads)748{749// Set body-frame angular velocity targets directly from inputs750_ang_vel_target_rads.x = roll_rate_bf_rads;751_ang_vel_target_rads.y = pitch_rate_bf_rads;752_ang_vel_target_rads.z = yaw_rate_bf_rads;753754// Update attitude and Euler targets from the current vehicle attitude755// (used for mode transitions / logging / target state consistency).756_ahrs.get_quat_body_to_ned(_attitude_target);757_attitude_target.to_euler(_euler_angle_target_rad);758759// Convert body-frame angular velocity into euler angle derivative of desired attitude760body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);761762// Update body-frame angular velocity target used by the rate controller.763_ang_vel_body_rads = _ang_vel_target_rads;764}765766// Applies a one-time angular offset to the attitude target using body-frame roll, pitch,767// and yaw angles (radians).768// Used for step-response excitation during autotuning or manual test inputs.769// The offset is applied instantaneously; no rate or acceleration shaping is performed.770void AC_AttitudeControl::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)771{772// Apply the requested body-frame angular step to the attitude target773Quaternion attitude_target_update;774attitude_target_update.from_axis_angle(Vector3f{roll_angle_step_bf_rad, pitch_angle_step_bf_rad, yaw_angle_step_bf_rad});775_attitude_target = _attitude_target * attitude_target_update;776_attitude_target.normalize();777778// Update stored Euler-angle representation of the attitude target779_attitude_target.to_euler(_euler_angle_target_rad);780781// Zero rate and acceleration feedforward targets (pure attitude step)782_euler_rate_target_rads.zero();783_ang_vel_target_rads.zero();784_ang_accel_target_rads.zero();785786// Run quaternion attitude controller787attitude_controller_run_quat();788}789790// Applies a one-time body-frame angular rate step (radians/s) in roll, pitch, and yaw.791// Used to inject discrete disturbances or step inputs for system identification.792// This sets the body-frame rate command directly for this update; no shaping is applied.793void AC_AttitudeControl::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)794{795// Update attitude and Euler targets from the current vehicle attitude796// (used for mode transitions / logging / target state consistency).797_ahrs.get_quat_body_to_ned(_attitude_target);798_attitude_target.to_euler(_euler_angle_target_rad);799800// Zero rate and acceleration feedforward targets so the controller cleanly returns to zero rate801// after the step input is removed.802_ang_vel_target_rads.zero();803_ang_accel_target_rads.zero();804_euler_rate_target_rads.zero();805806// Apply the requested body-frame angular rate step directly to the rate controller input.807_ang_vel_body_rads = Vector3f{roll_rate_step_bf_rads, pitch_rate_step_bf_rads, yaw_rate_step_bf_rads};808}809810// Sets the desired thrust vector and a yaw/heading rate input (radians/s).811// Used for tilt-based navigation with independent yaw control.812// The thrust vector determines the desired tilt (attitude) while the heading rate commands yaw.813// Optional yaw slew limiting constrains the heading rate input.814void AC_AttitudeControl::input_thrust_vector_rate_heading_rads(const Vector3f& thrust_vector, float heading_rate_rads, bool slew_yaw)815{816if (slew_yaw) {817// Constrain heading rate input using the configured yaw slew rate limit (0 disables limiting).818const float slew_yaw_max_rads = get_slew_yaw_max_rads();819heading_rate_rads = constrain_float(heading_rate_rads, -slew_yaw_max_rads, slew_yaw_max_rads);820}821822// update attitude target823update_attitude_target();824825// calculate the attitude target euler angles826_attitude_target.to_euler(_euler_angle_target_rad);827828// Convert thrust vector to an attitude quaternion (zero yaw; yaw is commanded separately).829Quaternion thrust_vec_quat = attitude_from_thrust_vector(thrust_vector, 0.0f);830831// Compute the attitude correction required to align the current target attitude with the thrust vector.832float thrust_vector_diff_angle;833Quaternion thrust_vec_correction_quat;834Vector3f attitude_error;835float returned_thrust_vector_angle;836thrust_vector_rotation_angles(thrust_vec_quat, _attitude_target, thrust_vec_correction_quat, attitude_error, returned_thrust_vector_angle, thrust_vector_diff_angle);837838if (_rate_bf_ff_enabled) {839// Shape roll/pitch attitude error into body-frame angular velocity/acceleration targets,840// applying configured rate/acceleration limits and input time constant.841attitude_command_model(attitude_error.x, 0.0, _ang_vel_target_rads.x, _ang_accel_target_rads.x, radians(_ang_vel_roll_max_degs), get_accel_roll_max_radss(), _input_tc, _dt_s);842attitude_command_model(attitude_error.y, 0.0, _ang_vel_target_rads.y, _ang_accel_target_rads.y, radians(_ang_vel_pitch_max_degs), get_accel_pitch_max_radss(), _input_tc, _dt_s);843844// Shape yaw rate input into yaw angular velocity/acceleration targets, applying yaw limits and time constant.845attitude_command_model(0.0, heading_rate_rads, _ang_vel_target_rads.z, _ang_accel_target_rads.z, radians(_ang_vel_yaw_max_degs), get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);846} else {847// No shaping/feedforward: directly update the attitude target using the thrust-vector correction and yaw increment.848Quaternion yaw_quat;849yaw_quat.from_axis_angle(Vector3f{0.0f, 0.0f, heading_rate_rads * _dt_s});850_attitude_target = _attitude_target * thrust_vec_correction_quat * yaw_quat;851_attitude_target.normalize();852853// Zero rate and acceleration feedforward targets854_euler_rate_target_rads.zero();855_ang_vel_target_rads.zero();856_ang_accel_target_rads.zero();857}858859// Convert body-frame angular velocity into euler angle derivative of desired attitude860body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);861862// Call quaternion attitude controller863attitude_controller_run_quat();864}865866// Sets the desired thrust vector, heading angle (radians), and heading rate input (radians/s).867// Used when thrust direction (tilt) is commanded independently from yaw/heading.868// Heading rate is constrained using the configured yaw slew rate limit (0 disables limiting).869void AC_AttitudeControl::input_thrust_vector_heading_rad(const Vector3f& thrust_vector, float heading_angle_rad, float heading_rate_rads)870{871// Constrain heading rate input using the configured yaw slew rate limit.872const float slew_yaw_max_rads = get_slew_yaw_max_rads();873heading_rate_rads = constrain_float(heading_rate_rads, -slew_yaw_max_rads, slew_yaw_max_rads);874875// update attitude target876update_attitude_target();877878// calculate the attitude target euler angles879_attitude_target.to_euler(_euler_angle_target_rad);880881// Convert thrust vector and heading into a desired attitude quaternion.882const Quaternion desired_attitude_quat = attitude_from_thrust_vector(thrust_vector, heading_angle_rad);883884if (_rate_bf_ff_enabled) {885// Compute attitude error required to move from the current target attitude to the desired attitude.886Vector3f attitude_error;887float thrust_vector_diff_angle;888Quaternion thrust_vec_correction_quat;889float returned_thrust_vector_angle;890thrust_vector_rotation_angles(desired_attitude_quat, _attitude_target, thrust_vec_correction_quat, attitude_error, returned_thrust_vector_angle, thrust_vector_diff_angle);891892// Shape attitude error and heading rate into body-frame angular velocity/acceleration targets,893// applying configured rate/acceleration limits and time constants (roll/pitch use _input_tc, yaw uses _rate_y_tc).894attitude_command_model(attitude_error.x, 0.0, _ang_vel_target_rads.x, _ang_accel_target_rads.x, radians(_ang_vel_roll_max_degs), get_accel_roll_max_radss(), _input_tc, _dt_s);895attitude_command_model(attitude_error.y, 0.0, _ang_vel_target_rads.y, _ang_accel_target_rads.y, radians(_ang_vel_pitch_max_degs), get_accel_pitch_max_radss(), _input_tc, _dt_s);896attitude_command_model(attitude_error.z, heading_rate_rads, _ang_vel_target_rads.z, _ang_accel_target_rads.z, radians(_ang_vel_yaw_max_degs), get_accel_yaw_max_radss(), _rate_y_tc, _dt_s);897} else {898// No shaping/feedforward: directly set the attitude target to the desired attitude.899_attitude_target = desired_attitude_quat;900901// Zero rate and acceleration feedforward targets902_euler_rate_target_rads.zero();903_ang_vel_target_rads.zero();904_ang_accel_target_rads.zero();905}906907// Convert body-frame angular velocity into euler angle derivative of desired attitude908body_to_euler_derivative(_attitude_target, _ang_vel_target_rads, _euler_rate_target_rads);909910// Call quaternion attitude controller911attitude_controller_run_quat();912}913914// Command a thrust vector and heading rate915void AC_AttitudeControl::input_thrust_vector_heading(const Vector3f& thrust_vector, HeadingCommand heading)916{917switch (heading.heading_mode) {918case HeadingMode::Rate_Only:919input_thrust_vector_rate_heading_rads(thrust_vector, heading.yaw_rate_rads);920break;921case HeadingMode::Angle_Only:922input_thrust_vector_heading_rad(thrust_vector, heading.yaw_angle_rad, 0.0);923break;924case HeadingMode::Angle_And_Rate:925input_thrust_vector_heading_rad(thrust_vector, heading.yaw_angle_rad, heading.yaw_rate_rads);926break;927}928}929930Quaternion AC_AttitudeControl::attitude_from_thrust_vector(Vector3f thrust_vector, float heading_angle_rad) const931{932const Vector3f thrust_vector_up{0.0f, 0.0f, -1.0f};933934if (is_zero(thrust_vector.length_squared())) {935thrust_vector = thrust_vector_up;936} else {937thrust_vector.normalize();938}939940// the cross product of the desired and target thrust vector defines the rotation vector941Vector3f thrust_vec_cross = thrust_vector_up % thrust_vector;942943// the dot product is used to calculate the angle between the target and desired thrust vectors944const float thrust_vector_angle = acosf(constrain_float(thrust_vector_up * thrust_vector, -1.0f, 1.0f));945946// Normalize the thrust rotation vector947const float thrust_vector_length = thrust_vec_cross.length();948if (is_zero(thrust_vector_length) || is_zero(thrust_vector_angle)) {949thrust_vec_cross = thrust_vector_up;950} else {951thrust_vec_cross /= thrust_vector_length;952}953954Quaternion thrust_vec_quat;955thrust_vec_quat.from_axis_angle(thrust_vec_cross, thrust_vector_angle);956Quaternion yaw_quat;957yaw_quat.from_axis_angle(Vector3f{0.0f, 0.0f, 1.0f}, heading_angle_rad);958return thrust_vec_quat*yaw_quat;959}960961// Calculates the body frame angular velocities to follow the target attitude962void AC_AttitudeControl::update_attitude_target()963{964// rotate target and normalize965Quaternion attitude_target_update;966attitude_target_update.from_axis_angle(_ang_vel_target_rads * _dt_s);967_attitude_target *= attitude_target_update;968_attitude_target.normalize();969}970971// Calculates the body frame angular velocities to follow the target attitude972void AC_AttitudeControl::attitude_controller_run_quat()973{974// This represents a quaternion rotation in NED frame to the body975Quaternion attitude_body;976_ahrs.get_quat_body_to_ned(attitude_body);977978// This vector represents the angular error to rotate the thrust vector using x and y and heading using z979Vector3f attitude_error;980thrust_heading_rotation_angles(_attitude_target, attitude_body, attitude_error, _thrust_angle_rad, _thrust_error_angle_rad);981982// Compute the angular velocity corrections in the body frame from the attitude error983Vector3f ang_vel_body_rads = update_ang_vel_target_from_att_error(attitude_error);984985// ensure angular velocity does not go over configured limits986ang_vel_limit(ang_vel_body_rads, radians(_ang_vel_roll_max_degs), radians(_ang_vel_pitch_max_degs), radians(_ang_vel_yaw_max_degs));987988// rotation from the target frame to the body frame989Quaternion rotation_target_to_body = attitude_body.inverse() * _attitude_target;990991// target angle velocity vector in the body frame992Vector3f ang_vel_body_feedforward = rotation_target_to_body * _ang_vel_target_rads;993Vector3f gyro = get_latest_gyro();994// Correct the thrust vector and smoothly add feedforward and yaw input995_feedforward_scalar = 1.0f;996if (_thrust_error_angle_rad > AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD * 2.0f) {997ang_vel_body_rads.z = gyro.z;998} else if (_thrust_error_angle_rad > AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD) {999_feedforward_scalar = (1.0f - (_thrust_error_angle_rad - AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD) / AC_ATTITUDE_THRUST_ERROR_ANGLE_RAD);1000ang_vel_body_rads.x += ang_vel_body_feedforward.x * _feedforward_scalar;1001ang_vel_body_rads.y += ang_vel_body_feedforward.y * _feedforward_scalar;1002ang_vel_body_rads.z += ang_vel_body_feedforward.z;1003ang_vel_body_rads.z = gyro.z * (1.0 - _feedforward_scalar) + ang_vel_body_rads.z * _feedforward_scalar;1004} else {1005ang_vel_body_rads += ang_vel_body_feedforward;1006}10071008// Record error to handle EKF resets1009_attitude_ang_error = attitude_body.inverse() * _attitude_target;1010// finally update the attitude target1011_ang_vel_body_rads = ang_vel_body_rads;1012}10131014// thrust_heading_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion.1015// The maximum error in the yaw axis is limited based on static output saturation.1016void AC_AttitudeControl::thrust_heading_rotation_angles(Quaternion& attitude_target, const Quaternion& attitude_body, Vector3f& attitude_error_rad, float& thrust_angle_rad, float& thrust_error_angle_rad) const1017{1018Quaternion thrust_vector_correction;1019thrust_vector_rotation_angles(attitude_target, attitude_body, thrust_vector_correction, attitude_error_rad, thrust_angle_rad, thrust_error_angle_rad);10201021// Todo: Limit roll an pitch error based on output saturation and maximum error.10221023// Limit Yaw Error based to the maximum that would saturate the output when yaw rate is zero.1024Quaternion heading_vec_correction_quat;10251026float heading_accel_max = constrain_float(get_accel_yaw_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS);1027if (!is_zero(get_rate_yaw_pid().kP())) {1028float heading_error_max = MIN(inv_sqrt_controller(1.0 / get_rate_yaw_pid().kP(), _p_angle_yaw.kP(), heading_accel_max), AC_ATTITUDE_YAW_MAX_ERROR_ANGLE_RAD);1029if (!is_zero(_p_angle_yaw.kP()) && fabsf(attitude_error_rad.z) > heading_error_max) {1030attitude_error_rad.z = constrain_float(wrap_PI(attitude_error_rad.z), -heading_error_max, heading_error_max);1031heading_vec_correction_quat.from_axis_angle(Vector3f{0.0f, 0.0f, attitude_error_rad.z});1032attitude_target = attitude_body * thrust_vector_correction * heading_vec_correction_quat;1033}1034}1035}10361037// thrust_vector_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion.1038// The first rotation corrects the thrust vector and the second rotation corrects the heading vector.1039void AC_AttitudeControl::thrust_vector_rotation_angles(const Quaternion& attitude_target, const Quaternion& attitude_body, Quaternion& thrust_vector_correction, Vector3f& attitude_error_rad, float& thrust_angle_rad, float& thrust_error_angle_rad) const1040{1041// The direction of thrust is [0,0,-1] is any body-fixed frame, inc. body frame and target frame.1042const Vector3f thrust_vector_up{0.0f, 0.0f, -1.0f};10431044// attitude_target and attitude_body are passive rotations from target / body frames to the NED frame10451046// Rotating [0,0,-1] by attitude_target expresses (gets a view of) the target thrust vector in the inertial frame1047const Vector3f att_target_thrust_vec = attitude_target * thrust_vector_up; // target thrust vector10481049// Rotating [0,0,-1] by attitude_target expresses (gets a view of) the current thrust vector in the inertial frame1050const Vector3f att_body_thrust_vec = attitude_body * thrust_vector_up; // current thrust vector10511052// the dot product is used to calculate the current lean angle for use of external functions1053thrust_angle_rad = acosf(constrain_float(thrust_vector_up * att_body_thrust_vec,-1.0f,1.0f));10541055// the cross product of the desired and target thrust vector defines the rotation vector1056Vector3f thrust_vec_cross = att_body_thrust_vec % att_target_thrust_vec;10571058// the dot product is used to calculate the angle between the target and desired thrust vectors1059thrust_error_angle_rad = acosf(constrain_float(att_body_thrust_vec * att_target_thrust_vec, -1.0f, 1.0f));10601061// Normalize the thrust rotation vector1062float thrust_vector_length = thrust_vec_cross.length();1063if (is_zero(thrust_vector_length) || is_zero(thrust_error_angle_rad)) {1064thrust_vec_cross = thrust_vector_up;1065} else {1066thrust_vec_cross /= thrust_vector_length;1067}10681069// thrust_vector_correction is defined relative to the body frame but its axis `thrust_vec_cross` was computed in1070// the inertial frame. First rotate it by the inverse of attitude_body to express it back in the body frame1071thrust_vec_cross = attitude_body.inverse() * thrust_vec_cross;1072thrust_vector_correction.from_axis_angle(thrust_vec_cross, thrust_error_angle_rad);10731074// calculate the angle error in x and y.1075Vector3f rotation_rad;1076thrust_vector_correction.to_axis_angle(rotation_rad);1077attitude_error_rad.x = rotation_rad.x;1078attitude_error_rad.y = rotation_rad.y;10791080// calculate the remaining rotation required after thrust vector is rotated transformed to the body frame1081// heading_vector_correction1082Quaternion heading_vec_correction_quat = thrust_vector_correction.inverse() * attitude_body.inverse() * attitude_target;10831084// calculate the angle error in z (x and y should be zero here).1085heading_vec_correction_quat.to_axis_angle(rotation_rad);1086attitude_error_rad.z = rotation_rad.z;1087}10881089// calculates the velocity correction from an angle error. The angular velocity has acceleration and1090// deceleration limits including basic jerk limiting using _input_tc1091void AC_AttitudeControl::attitude_command_model(float error_angle, float desired_ang_vel, float& target_ang_vel, float& target_ang_accel, float max_ang_vel, float accel_max, float input_tc, float dt) const1092{1093if (!is_positive(dt)) {1094return;1095}10961097// protect against divide by zero1098if (!is_positive(accel_max)) {1099// no acceleration set so default to 1800 degrees/s²1100accel_max = radians(1800);1101}11021103if (!is_positive(input_tc)) {1104// no acceleration set so default to achieve maximum acceleration in 10 clock cycles1105input_tc = dt * 10.0;1106}11071108shape_angle_vel_accel( error_angle, desired_ang_vel, 0.0,11090.0, target_ang_vel, target_ang_accel,1110-max_ang_vel, max_ang_vel, accel_max,1111accel_max / input_tc, dt, false);1112target_ang_vel += target_ang_accel * dt;1113}11141115// calculates the expected angular velocity correction from an angle error based on the AC_AttitudeControl settings.1116// This function can be used to predict the delay associated with angle requests.1117void AC_AttitudeControl::command_model_rate_predictor(const Vector2f &error_angle_rad, Vector2f& target_ang_vel_rads, Vector2f& target_ang_accel_rads, float dt) const1118{1119if (_rate_bf_ff_enabled) {1120// translate the roll pitch and yaw acceleration limits to the euler axis1121attitude_command_model(wrap_PI(error_angle_rad.x), 0.0, target_ang_vel_rads.x, target_ang_accel_rads.x, radians(_ang_vel_roll_max_degs), get_accel_roll_max_radss(), _input_tc, _dt_s);1122attitude_command_model(wrap_PI(error_angle_rad.y), 0.0, target_ang_vel_rads.y, target_ang_accel_rads.y, radians(_ang_vel_pitch_max_degs), get_accel_pitch_max_radss(), _input_tc, _dt_s);1123} else {1124const float angleP_roll = _p_angle_roll.kP() * _angle_P_scale.x;1125const float angleP_pitch = _p_angle_pitch.kP() * _angle_P_scale.y;1126target_ang_vel_rads.x = angleP_roll * wrap_PI(error_angle_rad.x);1127target_ang_vel_rads.y = angleP_pitch * wrap_PI(error_angle_rad.y);1128}1129// Limit the angular velocity correction1130Vector3f ang_vel_rads(target_ang_vel_rads.x, target_ang_vel_rads.y, 0.0f);1131ang_vel_limit(ang_vel_rads, radians(_ang_vel_roll_max_degs), radians(_ang_vel_pitch_max_degs), 0.0f);11321133target_ang_vel_rads.x = ang_vel_rads.x;1134target_ang_vel_rads.y = ang_vel_rads.y;1135}11361137// scale I to represent the current angle P1138void AC_AttitudeControl::scale_I_to_angle_P()1139{1140Vector3f i_scale{1141_p_angle_roll.kP() * _angle_P_scale.x,1142_p_angle_pitch.kP() * _angle_P_scale.y,1143_p_angle_yaw.kP() * _angle_P_scale.z1144};1145set_I_scale_mult(i_scale);1146}11471148// perform any required parameter conversions1149void AC_AttitudeControl::convert_parameters()1150{1151// PARAMETER_CONVERSION - Added: Jan-2026 for 4.711521153// return immediately if no conversion is needed1154if (_angle_max_deg.configured()) {1155return;1156}11571158#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)1159static const AP_Param::ConversionInfo conversion_info_001[] = {1160{ 205, 10, AP_PARAM_INT16, "Q_A_ANGLE_MAX" }, // ANGLE_MAX moved to Q_A_ANGLE_MAX1161};1162#elif APM_BUILD_TYPE(APM_BUILD_ArduSub)1163static const AP_Param::ConversionInfo conversion_info_001[] = {1164{ 167, 0, AP_PARAM_INT16, "ATC_ANGLE_MAX" }, // ANGLE_MAX moved to ATC_ANGLE_MAX1165};1166#else1167static const AP_Param::ConversionInfo conversion_info_001[] = {1168{ 34, 0, AP_PARAM_INT16, "ATC_ANGLE_MAX" }, // ANGLE_MAX moved to ATC_ANGLE_MAX1169};1170#endif1171AP_Param::convert_old_parameters_scaled(conversion_info_001, ARRAY_SIZE(conversion_info_001), 0.01, 0);1172}11731174// limits angular velocity1175void AC_AttitudeControl::ang_vel_limit(Vector3f& euler_rad, float ang_vel_roll_max_rads, float ang_vel_pitch_max_rads, float ang_vel_yaw_max_rads) const1176{1177if (is_zero(ang_vel_roll_max_rads) || is_zero(ang_vel_pitch_max_rads)) {1178if (!is_zero(ang_vel_roll_max_rads)) {1179euler_rad.x = constrain_float(euler_rad.x, -ang_vel_roll_max_rads, ang_vel_roll_max_rads);1180}1181if (!is_zero(ang_vel_pitch_max_rads)) {1182euler_rad.y = constrain_float(euler_rad.y, -ang_vel_pitch_max_rads, ang_vel_pitch_max_rads);1183}1184} else {1185const Vector2f thrust_vector_ang_vel(euler_rad.x / ang_vel_roll_max_rads, euler_rad.y / ang_vel_pitch_max_rads);1186float thrust_vector_length = thrust_vector_ang_vel.length();1187if (thrust_vector_length > 1.0f) {1188euler_rad.x = thrust_vector_ang_vel.x * ang_vel_roll_max_rads / thrust_vector_length;1189euler_rad.y = thrust_vector_ang_vel.y * ang_vel_pitch_max_rads / thrust_vector_length;1190}1191}1192if (!is_zero(ang_vel_yaw_max_rads)) {1193euler_rad.z = constrain_float(euler_rad.z, -ang_vel_yaw_max_rads, ang_vel_yaw_max_rads);1194}1195}11961197// translates body frame acceleration limits to the euler axis1198Vector3f AC_AttitudeControl::euler_accel_limit(const Quaternion &att, const Vector3f &euler_accel)1199{1200if (!is_positive(euler_accel.x) || !is_positive(euler_accel.y) || !is_positive(euler_accel.z)) {1201return Vector3f { euler_accel };1202}12031204const float phi = att.get_euler_roll();1205const float theta = att.get_euler_pitch();12061207const float sin_phi = constrain_float(fabsf(sinf(phi)), 0.1f, 1.0f);1208const float cos_phi = constrain_float(fabsf(cosf(phi)), 0.1f, 1.0f);1209const float sin_theta = constrain_float(fabsf(sinf(theta)), 0.1f, 1.0f);1210const float cos_theta = constrain_float(fabsf(cosf(theta)), 0.1f, 1.0f);12111212return Vector3f {1213euler_accel.x,1214MIN(euler_accel.y / cos_phi, euler_accel.z / sin_phi),1215MIN(MIN(euler_accel.x / sin_theta, euler_accel.y / (sin_phi * cos_theta)), euler_accel.z / (cos_phi * cos_theta))1216};1217}12181219// Sets attitude target to vehicle attitude and sets all rates to zero1220// If reset_rate is false rates are not reset to allow the rate controllers to run1221void AC_AttitudeControl::reset_target_and_rate(bool reset_rate)1222{1223// move attitude target to current attitude1224_ahrs.get_quat_body_to_ned(_attitude_target);1225_attitude_target.to_euler(_euler_angle_target_rad);12261227if (reset_rate) {1228_ang_vel_target_rads.zero();1229_ang_accel_target_rads.zero();1230_euler_rate_target_rads.zero();1231}1232}12331234// Sets yaw target to vehicle heading and sets yaw rate to zero1235// If reset_rate is false rates are not reset to allow the rate controllers to run1236void AC_AttitudeControl::reset_yaw_target_and_rate(bool reset_rate)1237{1238// move attitude target to current heading1239float yaw_shift = _ahrs.yaw - _euler_angle_target_rad.z;1240Quaternion _attitude_target_update;1241_attitude_target_update.from_axis_angle(Vector3f{0.0f, 0.0f, yaw_shift});1242_attitude_target = _attitude_target_update * _attitude_target;12431244if (reset_rate) {1245// set yaw rate to zero1246_euler_rate_target_rads.z = 0.0f;1247_ang_accel_target_rads.z = 0.0;12481249// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward1250euler_derivative_to_body(_attitude_target, _euler_rate_target_rads, _ang_vel_target_rads);1251}1252}12531254// Shifts the target attitude to maintain the current error in the event of an EKF reset1255void AC_AttitudeControl::inertial_frame_reset()1256{1257// Retrieve quaternion body attitude1258Quaternion attitude_body;1259_ahrs.get_quat_body_to_ned(attitude_body);12601261// Recalculate the target quaternion1262_attitude_target = attitude_body * _attitude_ang_error;12631264// calculate the attitude target euler angles1265_attitude_target.to_euler(_euler_angle_target_rad);1266}12671268// euler_derivative_to_body - transform euler angle derivative to body-frame1269// Converts euler derivatives (rate, acceleration, etc.) to body-frame equivalents.1270// The same transformation applies regardless of derivative order.1271// Uses the kinematic relationship for 321 (yaw-pitch-roll) euler sequence.1272void AC_AttitudeControl::euler_derivative_to_body(const Quaternion& att, const Vector3f& euler_derivative_rads, Vector3f& body_derivative_rads)1273{1274const float theta = att.get_euler_pitch();1275const float phi = att.get_euler_roll();12761277const float sin_theta = sinf(theta);1278const float cos_theta = cosf(theta);1279const float sin_phi = sinf(phi);1280const float cos_phi = cosf(phi);12811282body_derivative_rads.x = euler_derivative_rads.x - sin_theta * euler_derivative_rads.z;1283body_derivative_rads.y = cos_phi * euler_derivative_rads.y + sin_phi * cos_theta * euler_derivative_rads.z;1284body_derivative_rads.z = -sin_phi * euler_derivative_rads.y + cos_theta * cos_phi * euler_derivative_rads.z;1285}12861287// body_to_euler_derivative - transform body-frame derivative to euler angle derivative1288// Converts body-frame derivatives (rate, acceleration, etc.) to euler equivalents.1289// The same transformation applies regardless of derivative order.1290// Uses the kinematic relationship for 321 (yaw-pitch-roll) euler sequence.1291// Returns false if the vehicle is pitched 90 degrees up or down (gimbal lock)1292bool AC_AttitudeControl::body_to_euler_derivative(const Quaternion& att, const Vector3f& body_derivative_rads, Vector3f& euler_derivative_rads)1293{1294const float theta = att.get_euler_pitch();1295const float phi = att.get_euler_roll();12961297const float sin_theta = sinf(theta);1298const float cos_theta = cosf(theta);1299const float sin_phi = sinf(phi);1300const float cos_phi = cosf(phi);13011302// When the vehicle pitches all the way up or all the way down, the euler angles become discontinuous. In this case, we just return false.1303if (is_zero(cos_theta)) {1304return false;1305}13061307euler_derivative_rads.x = body_derivative_rads.x + sin_phi * (sin_theta / cos_theta) * body_derivative_rads.y + cos_phi * (sin_theta / cos_theta) * body_derivative_rads.z;1308euler_derivative_rads.y = cos_phi * body_derivative_rads.y - sin_phi * body_derivative_rads.z;1309euler_derivative_rads.z = (sin_phi / cos_theta) * body_derivative_rads.y + (cos_phi / cos_theta) * body_derivative_rads.z;1310return true;1311}13121313// Update rate_target_ang_vel using attitude_error_rot_vec_rad1314Vector3f AC_AttitudeControl::update_ang_vel_target_from_att_error(const Vector3f &attitude_error_rot_vec_rad)1315{1316Vector3f rate_target_ang_vel;13171318// Compute the roll angular velocity demand from the roll angle error1319const float angleP_roll = _p_angle_roll.kP() * _angle_P_scale.x;1320if (_use_sqrt_controller && !is_zero(get_accel_roll_max_radss())) {1321rate_target_ang_vel.x = sqrt_controller(attitude_error_rot_vec_rad.x, angleP_roll, constrain_float(get_accel_roll_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt_s);1322} else {1323rate_target_ang_vel.x = angleP_roll * attitude_error_rot_vec_rad.x;1324}13251326// Compute the pitch angular velocity demand from the pitch angle error1327const float angleP_pitch = _p_angle_pitch.kP() * _angle_P_scale.y;1328if (_use_sqrt_controller && !is_zero(get_accel_pitch_max_radss())) {1329rate_target_ang_vel.y = sqrt_controller(attitude_error_rot_vec_rad.y, angleP_pitch, constrain_float(get_accel_pitch_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS), _dt_s);1330} else {1331rate_target_ang_vel.y = angleP_pitch * attitude_error_rot_vec_rad.y;1332}13331334// Compute the yaw angular velocity demand from the yaw angle error1335const float angleP_yaw = _p_angle_yaw.kP() * _angle_P_scale.z;1336if (_use_sqrt_controller && !is_zero(get_accel_yaw_max_radss())) {1337rate_target_ang_vel.z = sqrt_controller(attitude_error_rot_vec_rad.z, angleP_yaw, constrain_float(get_accel_yaw_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS), _dt_s);1338} else {1339rate_target_ang_vel.z = angleP_yaw * attitude_error_rot_vec_rad.z;1340}13411342return rate_target_ang_vel;1343}13441345// Enable or disable body-frame feed forward1346void AC_AttitudeControl::accel_limiting(bool enable_limits)1347{1348if (enable_limits) {1349// If enabling limits, reload from eeprom or set to defaults1350if (is_zero(_accel_roll_max_cdss)) {1351_accel_roll_max_cdss.load();1352}1353if (is_zero(_accel_pitch_max_cdss)) {1354_accel_pitch_max_cdss.load();1355}1356if (is_zero(_accel_yaw_max_cdss)) {1357_accel_yaw_max_cdss.load();1358}1359} else {1360_accel_roll_max_cdss.set(0.0f);1361_accel_pitch_max_cdss.set(0.0f);1362_accel_yaw_max_cdss.set(0.0f);1363}1364}13651366// Returns maximum allowable tilt angle (in centidegrees) for pilot input when in altitude hold mode.1367// See get_althold_lean_angle_max_rad() for full details.1368float AC_AttitudeControl::get_althold_lean_angle_max_cd() const1369{1370// convert to centi-degrees for public interface1371return rad_to_cd(get_althold_lean_angle_max_rad());1372}13731374// Returns maximum allowable tilt angle (in radians) for pilot input when in altitude hold mode.1375// Used to limit lean angle based on available thrust margin, prioritising altitude stability.1376float AC_AttitudeControl::get_althold_lean_angle_max_rad() const1377{1378return MAX(_althold_lean_angle_max_rad, radians(AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN));1379}13801381// Return configured tilt angle limit in centidegrees1382float AC_AttitudeControl::lean_angle_max_cd() const1383{1384return constrain_float(_angle_max_deg.get(), AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN, AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MAX) * 100;1385}13861387// Return configured tilt angle limit in radians1388float AC_AttitudeControl::lean_angle_max_rad() const1389{1390return radians(constrain_float(_angle_max_deg.get(), AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN, AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MAX));1391}13921393// Return roll rate step size in centidegrees/s that results in maximum output after 4 time steps1394float AC_AttitudeControl::max_rate_step_bf_roll()1395{1396float dt_average = AP::scheduler().get_filtered_loop_time();1397float alpha = MIN(get_rate_roll_pid().get_filt_E_alpha(dt_average), get_rate_roll_pid().get_filt_D_alpha(dt_average));1398float alpha_remaining = 1 - alpha;1399// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max1400float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);1401float rate_max = 2.0f * throttle_hover * AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX / ((alpha_remaining * alpha_remaining * alpha_remaining * alpha * get_rate_roll_pid().kD()) / _dt_s + get_rate_roll_pid().kP());1402if (is_positive(_ang_vel_roll_max_degs)) {1403rate_max = MIN(rate_max, get_ang_vel_roll_max_rads());1404}1405return rate_max;1406}14071408// Return pitch rate step size in centidegrees/s that results in maximum output after 4 time steps1409float AC_AttitudeControl::max_rate_step_bf_pitch()1410{1411const float dt_average = AP::scheduler().get_filtered_loop_time();1412const float alpha = MIN(get_rate_pitch_pid().get_filt_E_alpha(dt_average), get_rate_pitch_pid().get_filt_D_alpha(dt_average));1413const float alpha_remaining = 1 - alpha;1414// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max1415const float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);1416float rate_max = 2.0f * throttle_hover * AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX / ((alpha_remaining * alpha_remaining * alpha_remaining * alpha * get_rate_pitch_pid().kD()) / _dt_s + get_rate_pitch_pid().kP());1417if (is_positive(_ang_vel_pitch_max_degs)) {1418rate_max = MIN(rate_max, get_ang_vel_pitch_max_rads());1419}1420return rate_max;1421}14221423// Return yaw rate step size in centidegrees/s that results in maximum output after 4 time steps1424float AC_AttitudeControl::max_rate_step_bf_yaw()1425{1426const float dt_average = AP::scheduler().get_filtered_loop_time();1427const float alpha = MIN(get_rate_yaw_pid().get_filt_E_alpha(dt_average), get_rate_yaw_pid().get_filt_D_alpha(dt_average));1428const float alpha_remaining = 1 - alpha;1429// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max1430const float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);1431float rate_max = 2.0f * throttle_hover * AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX / ((alpha_remaining * alpha_remaining * alpha_remaining * alpha * get_rate_yaw_pid().kD()) / _dt_s + get_rate_yaw_pid().kP());1432if (is_positive(_ang_vel_yaw_max_degs)) {1433rate_max = MIN(rate_max, get_ang_vel_yaw_max_rads());1434}1435return rate_max;1436}14371438bool AC_AttitudeControl::pre_arm_checks(const char *param_prefix,1439char *failure_msg,1440const uint8_t failure_msg_len)1441{1442// validate AC_P members:1443const struct {1444const char *pid_name;1445AC_P &p;1446} ps[] = {1447{ "ANG_PIT", get_angle_pitch_p() },1448{ "ANG_RLL", get_angle_roll_p() },1449{ "ANG_YAW", get_angle_yaw_p() }1450};1451for (uint8_t i=0; i<ARRAY_SIZE(ps); i++) {1452// all AC_P's must have a positive P value:1453if (!is_positive(ps[i].p.kP())) {1454hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, ps[i].pid_name);1455return false;1456}1457}14581459// validate AC_PID members:1460const struct {1461const char *pid_name;1462AC_PID &pid;1463} pids[] = {1464{ "RAT_RLL", get_rate_roll_pid() },1465{ "RAT_PIT", get_rate_pitch_pid() },1466{ "RAT_YAW", get_rate_yaw_pid() },1467};1468for (uint8_t i=0; i<ARRAY_SIZE(pids); i++) {1469// if the PID has a positive FF then we just ensure kP and1470// kI aren't negative1471AC_PID &pid = pids[i].pid;1472const char *pid_name = pids[i].pid_name;1473if (is_positive(pid.ff())) {1474// kP and kI must be non-negative:1475if (is_negative(pid.kP())) {1476hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be >= 0", param_prefix, pid_name);1477return false;1478}1479if (is_negative(pid.kI())) {1480hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_I must be >= 0", param_prefix, pid_name);1481return false;1482}1483} else {1484// kP and kI must be positive:1485if (!is_positive(pid.kP())) {1486hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, pid_name);1487return false;1488}1489if (!is_positive(pid.kI())) {1490hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_I must be > 0", param_prefix, pid_name);1491return false;1492}1493}1494// never allow a negative D term (but zero is allowed)1495if (is_negative(pid.kD())) {1496hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_D must be >= 0", param_prefix, pid_name);1497return false;1498}1499}15001501// validate ANGLE_MAX1502if (_angle_max_deg.get() < 10 || _angle_max_deg.get() > 80) {1503hal.util->snprintf(failure_msg, failure_msg_len, "%s_ANGLE_MAX must be >= 10 and <= 80", param_prefix);1504return false;1505}15061507return true;1508}15091510/*1511get the slew rate for roll, pitch and yaw, for oscillation1512detection in lua scripts1513*/1514void AC_AttitudeControl::get_rpy_srate(float &roll_srate, float &pitch_srate, float &yaw_srate)1515{1516roll_srate = get_rate_roll_pid().get_pid_info().slew_rate;1517pitch_srate = get_rate_pitch_pid().get_pid_info().slew_rate;1518yaw_srate = get_rate_yaw_pid().get_pid_info().slew_rate;1519}152015211522