Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
Views: 1798
#include "AC_AttitudeControl.h"1#include <AP_HAL/AP_HAL.h>2#include <AP_Vehicle/AP_Vehicle_Type.h>3#include <AP_Scheduler/AP_Scheduler.h>45extern const AP_HAL::HAL& hal;67#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)8// default gains for Plane9# define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.2f // Soft10#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 5.0 // Min lean angle so that vehicle can maintain limited control11#define AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL 012#else13// default gains for Copter and Sub14# define AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT 0.15f // Medium15#define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN 10.0 // Min lean angle so that vehicle can maintain limited control16#define AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL 117#endif1819AC_AttitudeControl *AC_AttitudeControl::_singleton;2021// table of user settable parameters22const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {2324// 0, 1 were RATE_RP_MAX, RATE_Y_MAX2526// @Param: SLEW_YAW27// @DisplayName: Yaw target slew rate28// @Description: Maximum rate the yaw target can be updated in RTL and Auto flight modes29// @Units: cdeg/s30// @Range: 500 1800031// @Increment: 10032// @User: Advanced33AP_GROUPINFO("SLEW_YAW", 2, AC_AttitudeControl, _slew_yaw, AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS),3435// 3 was for ACCEL_RP_MAX3637// @Param: ACCEL_Y_MAX38// @DisplayName: Acceleration Max for Yaw39// @Description: Maximum acceleration in yaw axis40// @Units: cdeg/s/s41// @Range: 0 7200042// @Values: 0:Disabled, 9000:VerySlow, 18000:Slow, 36000:Medium, 54000:Fast43// @Increment: 100044// @User: Advanced45AP_GROUPINFO("ACCEL_Y_MAX", 4, AC_AttitudeControl, _accel_yaw_max, AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS),4647// @Param: RATE_FF_ENAB48// @DisplayName: Rate Feedforward Enable49// @Description: Controls whether body-frame rate feedforward is enabled or disabled50// @Values: 0:Disabled, 1:Enabled51// @User: Advanced52AP_GROUPINFO("RATE_FF_ENAB", 5, AC_AttitudeControl, _rate_bf_ff_enabled, AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT),5354// @Param: ACCEL_R_MAX55// @DisplayName: Acceleration Max for Roll56// @Description: Maximum acceleration in roll axis57// @Units: cdeg/s/s58// @Range: 0 18000059// @Increment: 100060// @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast61// @User: Advanced62AP_GROUPINFO("ACCEL_R_MAX", 6, AC_AttitudeControl, _accel_roll_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS),6364// @Param: ACCEL_P_MAX65// @DisplayName: Acceleration Max for Pitch66// @Description: Maximum acceleration in pitch axis67// @Units: cdeg/s/s68// @Range: 0 18000069// @Increment: 100070// @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast71// @User: Advanced72AP_GROUPINFO("ACCEL_P_MAX", 7, AC_AttitudeControl, _accel_pitch_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS),7374// IDs 8,9,10,11 RESERVED (in use on Solo)7576// @Param: ANGLE_BOOST77// @DisplayName: Angle Boost78// @Description: Angle Boost increases output throttle as the vehicle leans to reduce loss of altitude79// @Values: 0:Disabled, 1:Enabled80// @User: Advanced81AP_GROUPINFO("ANGLE_BOOST", 12, AC_AttitudeControl, _angle_boost_enabled, 1),8283// @Param: ANG_RLL_P84// @DisplayName: Roll axis angle controller P gain85// @Description: Roll axis angle controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate86// @Range: 3.000 12.00087// @Range{Sub}: 0.0 12.00088// @User: Standard89AP_SUBGROUPINFO(_p_angle_roll, "ANG_RLL_", 13, AC_AttitudeControl, AC_P),9091// @Param: ANG_PIT_P92// @DisplayName: Pitch axis angle controller P gain93// @Description: Pitch axis angle controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate94// @Range: 3.000 12.00095// @Range{Sub}: 0.0 12.00096// @User: Standard97AP_SUBGROUPINFO(_p_angle_pitch, "ANG_PIT_", 14, AC_AttitudeControl, AC_P),9899// @Param: ANG_YAW_P100// @DisplayName: Yaw axis angle controller P gain101// @Description: Yaw axis angle controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate102// @Range: 3.000 12.000103// @Range{Sub}: 0.0 6.000104// @User: Standard105AP_SUBGROUPINFO(_p_angle_yaw, "ANG_YAW_", 15, AC_AttitudeControl, AC_P),106107// @Param: ANG_LIM_TC108// @DisplayName: Angle Limit (to maintain altitude) Time Constant109// @Description: Angle Limit (to maintain altitude) Time Constant110// @Range: 0.5 10.0111// @User: Advanced112AP_GROUPINFO("ANG_LIM_TC", 16, AC_AttitudeControl, _angle_limit_tc, AC_ATTITUDE_CONTROL_ANGLE_LIMIT_TC_DEFAULT),113114// @Param: RATE_R_MAX115// @DisplayName: Angular Velocity Max for Roll116// @Description: Maximum angular velocity in roll axis117// @Units: deg/s118// @Range: 0 1080119// @Increment: 1120// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast121// @User: Advanced122AP_GROUPINFO("RATE_R_MAX", 17, AC_AttitudeControl, _ang_vel_roll_max, 0.0f),123124// @Param: RATE_P_MAX125// @DisplayName: Angular Velocity Max for Pitch126// @Description: Maximum angular velocity in pitch axis127// @Units: deg/s128// @Range: 0 1080129// @Increment: 1130// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast131// @User: Advanced132AP_GROUPINFO("RATE_P_MAX", 18, AC_AttitudeControl, _ang_vel_pitch_max, 0.0f),133134// @Param: RATE_Y_MAX135// @DisplayName: Angular Velocity Max for Yaw136// @Description: Maximum angular velocity in yaw axis137// @Units: deg/s138// @Range: 0 1080139// @Increment: 1140// @Values: 0:Disabled, 60:Slow, 180:Medium, 360:Fast141// @User: Advanced142AP_GROUPINFO("RATE_Y_MAX", 19, AC_AttitudeControl, _ang_vel_yaw_max, 0.0f),143144// @Param: INPUT_TC145// @DisplayName: Attitude control input time constant146// @Description: Attitude control input time constant. Low numbers lead to sharper response, higher numbers to softer response147// @Units: s148// @Range: 0 1149// @Increment: 0.01150// @Values: 0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp151// @User: Standard152AP_GROUPINFO("INPUT_TC", 20, AC_AttitudeControl, _input_tc, AC_ATTITUDE_CONTROL_INPUT_TC_DEFAULT),153154// @Param: LAND_R_MULT155// @DisplayName: Landed roll gain multiplier156// @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.157// @Range: 0.25 1.0158// @User: Advanced159AP_GROUPINFO("LAND_R_MULT", 21, AC_AttitudeControl, _land_roll_mult, 1.0),160161// @Param: LAND_P_MULT162// @DisplayName: Landed pitch gain multiplier163// @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.164// @Range: 0.25 1.0165// @User: Advanced166AP_GROUPINFO("LAND_P_MULT", 22, AC_AttitudeControl, _land_pitch_mult, 1.0),167168// @Param: LAND_Y_MULT169// @DisplayName: Landed yaw gain multiplier170// @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.171// @Range: 0.25 1.0172// @User: Advanced173AP_GROUPINFO("LAND_Y_MULT", 23, AC_AttitudeControl, _land_yaw_mult, 1.0),174175AP_GROUPEND176};177178constexpr Vector3f AC_AttitudeControl::VECTORF_111;179180// get the slew yaw rate limit in deg/s181float AC_AttitudeControl::get_slew_yaw_max_degs() const182{183if (!is_positive(_ang_vel_yaw_max)) {184return _slew_yaw * 0.01;185}186return MIN(_ang_vel_yaw_max, _slew_yaw * 0.01);187}188189// get the latest gyro for the purposes of attitude control190// Counter-inuitively the lowest latency for rate control is achieved by running rate control191// *before* attitude control. This is because you want rate control to run as close as possible192// to the time that a gyro sample was read to minimise jitter and control errors. Running rate193// control after attitude control might makes sense logically, but the overhead of attitude194// control calculations (and other updates) compromises the actual rate control.195//196// In the case of running rate control in a separate thread, the ordering between rate and attitude197// updates is less important, except that gyro sample used should be the latest198//199// Currently quadplane runs rate control after attitude control, necessitating the following code200// to minimise latency.201// However this code can be removed once quadplane updates it's structure to run the rate loops before202// the Attitude controller.203const Vector3f AC_AttitudeControl::get_latest_gyro() const204{205#if AC_ATTITUDE_CONTROL_AFTER_RATE_CONTROL206// rate updates happen before attitude updates so the last gyro value is the last rate gyro value207// this also allows a separate rate thread to be the source of gyro data208return _rate_gyro;209#else210// rate updates happen after attitude updates so the AHRS must be consulted for the last gyro value211return _ahrs.get_gyro_latest();212#endif213}214215// Ensure attitude controller have zero errors to relax rate controller output216void AC_AttitudeControl::relax_attitude_controllers()217{218// take a copy of the last gyro used by the rate controller before using it219Vector3f gyro = get_latest_gyro();220// Initialize the attitude variables to the current attitude221_ahrs.get_quat_body_to_ned(_attitude_target);222_attitude_target.to_euler(_euler_angle_target);223_attitude_ang_error.initialise();224225// Initialize the angular rate variables to the current rate226_ang_vel_target = gyro;227ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);228229// Initialize remaining variables230_thrust_error_angle = 0.0f;231232// Reset the PID filters233get_rate_roll_pid().reset_filter();234get_rate_pitch_pid().reset_filter();235get_rate_yaw_pid().reset_filter();236237// Reset the I terms238reset_rate_controller_I_terms();239// finally update the attitude target240_ang_vel_body = gyro;241}242243void AC_AttitudeControl::reset_rate_controller_I_terms()244{245get_rate_roll_pid().reset_I();246get_rate_pitch_pid().reset_I();247get_rate_yaw_pid().reset_I();248}249250// reset rate controller I terms smoothly to zero in 0.5 seconds251void AC_AttitudeControl::reset_rate_controller_I_terms_smoothly()252{253get_rate_roll_pid().relax_integrator(0.0, _dt, AC_ATTITUDE_RATE_RELAX_TC);254get_rate_pitch_pid().relax_integrator(0.0, _dt, AC_ATTITUDE_RATE_RELAX_TC);255get_rate_yaw_pid().relax_integrator(0.0, _dt, AC_ATTITUDE_RATE_RELAX_TC);256}257258// Reduce attitude control gains while landed to stop ground resonance259void AC_AttitudeControl::landed_gain_reduction(bool landed)260{261if (is_positive(_input_tc)) {262// use 2.0 x tc to match the response time to 86% commanded263const float spool_step = _dt / (2.0 * _input_tc);264if (landed) {265_landed_gain_ratio = MIN(1.0, _landed_gain_ratio + spool_step);266} else {267_landed_gain_ratio = MAX(0.0, _landed_gain_ratio - spool_step);268}269} else {270_landed_gain_ratio = landed ? 1.0 : 0.0;271}272Vector3f scale_mult = VECTORF_111 * (1.0 - _landed_gain_ratio) + Vector3f(_land_roll_mult, _land_pitch_mult, _land_yaw_mult) * _landed_gain_ratio;273set_PD_scale_mult(scale_mult);274set_angle_P_scale_mult(scale_mult);275}276277// The attitude controller works around the concept of the desired attitude, target attitude278// and measured attitude. The desired attitude is the attitude input into the attitude controller279// that expresses where the higher level code would like the aircraft to move to. The target attitude is moved280// to the desired attitude with jerk, acceleration, and velocity limits. The target angular velocities are fed281// directly into the rate controllers. The angular error between the measured attitude and the target attitude is282// fed into the angle controller and the output of the angle controller summed at the input of the rate controllers.283// By feeding the target angular velocity directly into the rate controllers the measured and target attitudes284// remain very close together.285//286// All input functions below follow the same procedure287// 1. define the desired attitude or attitude change based on the input variables288// 2. update the target attitude based on the angular velocity target and the time since the last loop289// 3. using the desired attitude and input variables, define the target angular velocity so that it should290// move the target attitude towards the desired attitude291// 4. if _rate_bf_ff_enabled is not being used then make the target attitude292// and target angular velocities equal to the desired attitude and desired angular velocities.293// 5. ensure _attitude_target, _euler_angle_target, _euler_rate_target and294// _ang_vel_target have been defined. This ensures input modes can be changed without discontinuity.295// 6. attitude_controller_run_quat is then run to pass the target angular velocities to the rate controllers and296// integrate them into the target attitude. Any errors between the target attitude and the measured attitude are297// corrected by first correcting the thrust vector until the angle between the target thrust vector measured298// trust vector drops below 2*AC_ATTITUDE_THRUST_ERROR_ANGLE. At this point the heading is also corrected.299300// Command a Quaternion attitude with feedforward and smoothing301// attitude_desired_quat: is updated on each time_step by the integral of the body frame angular velocity302void AC_AttitudeControl::input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_body)303{304// update attitude target305update_attitude_target();306307// Limit the angular velocity308ang_vel_limit(ang_vel_body, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));309Vector3f ang_vel_target = attitude_desired_quat * ang_vel_body;310311if (_rate_bf_ff_enabled) {312Quaternion attitude_error_quat = _attitude_target.inverse() * attitude_desired_quat;313Vector3f attitude_error_angle;314attitude_error_quat.to_axis_angle(attitude_error_angle);315316// When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler317// angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration318// and an exponential decay specified by _input_tc at the end.319_ang_vel_target.x = input_shaping_angle(wrap_PI(attitude_error_angle.x), _input_tc, get_accel_roll_max_radss(), _ang_vel_target.x, ang_vel_target.x, radians(_ang_vel_roll_max), _dt);320_ang_vel_target.y = input_shaping_angle(wrap_PI(attitude_error_angle.y), _input_tc, get_accel_pitch_max_radss(), _ang_vel_target.y, ang_vel_target.y, radians(_ang_vel_pitch_max), _dt);321_ang_vel_target.z = input_shaping_angle(wrap_PI(attitude_error_angle.z), _input_tc, get_accel_yaw_max_radss(), _ang_vel_target.z, ang_vel_target.z, radians(_ang_vel_yaw_max), _dt);322} else {323_attitude_target = attitude_desired_quat;324_ang_vel_target = ang_vel_target;325}326327// calculate the attitude target euler angles328_attitude_target.to_euler(_euler_angle_target);329330// Convert body-frame angular velocity into euler angle derivative of desired attitude331ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);332333// rotate target and normalize334Quaternion attitude_desired_update;335attitude_desired_update.from_axis_angle(ang_vel_target * _dt);336attitude_desired_quat = attitude_desired_quat * attitude_desired_update;337attitude_desired_quat.normalize();338339// Call quaternion attitude controller340attitude_controller_run_quat();341}342343// Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing344void AC_AttitudeControl::input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds)345{346// Convert from centidegrees on public interface to radians347float euler_roll_angle = radians(euler_roll_angle_cd * 0.01f);348float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f);349float euler_yaw_rate = radians(euler_yaw_rate_cds * 0.01f);350351// update attitude target352update_attitude_target();353354// calculate the attitude target euler angles355_attitude_target.to_euler(_euler_angle_target);356357// Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)358euler_roll_angle += get_roll_trim_rad();359360if (_rate_bf_ff_enabled) {361// translate the roll pitch and yaw acceleration limits to the euler axis362const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()});363364// When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler365// angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration366// and an exponential decay specified by smoothing_gain at the end.367_euler_rate_target.x = input_shaping_angle(wrap_PI(euler_roll_angle - _euler_angle_target.x), _input_tc, euler_accel.x, _euler_rate_target.x, _dt);368_euler_rate_target.y = input_shaping_angle(wrap_PI(euler_pitch_angle - _euler_angle_target.y), _input_tc, euler_accel.y, _euler_rate_target.y, _dt);369370// When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing371// the output rate towards the input rate.372_euler_rate_target.z = input_shaping_ang_vel(_euler_rate_target.z, euler_yaw_rate, euler_accel.z, _dt, _rate_y_tc);373374// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward375euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target);376// Limit the angular velocity377ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));378// Convert body-frame angular velocity into euler angle derivative of desired attitude379ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);380} else {381// When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.382_euler_angle_target.x = euler_roll_angle;383_euler_angle_target.y = euler_pitch_angle;384_euler_angle_target.z += euler_yaw_rate * _dt;385// Compute quaternion target attitude386_attitude_target.from_euler(_euler_angle_target.x, _euler_angle_target.y, _euler_angle_target.z);387388// Set rate feedforward requests to zero389_euler_rate_target.zero();390_ang_vel_target.zero();391}392393// Call quaternion attitude controller394attitude_controller_run_quat();395}396397// Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing398void AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw)399{400// Convert from centidegrees on public interface to radians401float euler_roll_angle = radians(euler_roll_angle_cd * 0.01f);402float euler_pitch_angle = radians(euler_pitch_angle_cd * 0.01f);403float euler_yaw_angle = radians(euler_yaw_angle_cd * 0.01f);404405// update attitude target406update_attitude_target();407408// calculate the attitude target euler angles409_attitude_target.to_euler(_euler_angle_target);410411// Add roll trim to compensate tail rotor thrust in heli (will return zero on multirotors)412euler_roll_angle += get_roll_trim_rad();413414const float slew_yaw_max_rads = get_slew_yaw_max_rads();415if (_rate_bf_ff_enabled) {416// translate the roll pitch and yaw acceleration limits to the euler axis417const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()});418419// When acceleration limiting and feedforward are enabled, the sqrt controller is used to compute an euler420// angular velocity that will cause the euler angle to smoothly stop at the input angle with limited deceleration421// and an exponential decay specified by _input_tc at the end.422_euler_rate_target.x = input_shaping_angle(wrap_PI(euler_roll_angle - _euler_angle_target.x), _input_tc, euler_accel.x, _euler_rate_target.x, _dt);423_euler_rate_target.y = input_shaping_angle(wrap_PI(euler_pitch_angle - _euler_angle_target.y), _input_tc, euler_accel.y, _euler_rate_target.y, _dt);424_euler_rate_target.z = input_shaping_angle(wrap_PI(euler_yaw_angle - _euler_angle_target.z), _input_tc, euler_accel.z, _euler_rate_target.z, _dt);425if (slew_yaw) {426_euler_rate_target.z = constrain_float(_euler_rate_target.z, -slew_yaw_max_rads, slew_yaw_max_rads);427}428429// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward430euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target);431// Limit the angular velocity432ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));433// Convert body-frame angular velocity into euler angle derivative of desired attitude434ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);435} else {436// When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.437_euler_angle_target.x = euler_roll_angle;438_euler_angle_target.y = euler_pitch_angle;439if (slew_yaw) {440// Compute constrained angle error441float angle_error = constrain_float(wrap_PI(euler_yaw_angle - _euler_angle_target.z), -slew_yaw_max_rads * _dt, slew_yaw_max_rads * _dt);442// Update attitude target from constrained angle error443_euler_angle_target.z = wrap_PI(angle_error + _euler_angle_target.z);444} else {445_euler_angle_target.z = euler_yaw_angle;446}447// Compute quaternion target attitude448_attitude_target.from_euler(_euler_angle_target.x, _euler_angle_target.y, _euler_angle_target.z);449450// Set rate feedforward requests to zero451_euler_rate_target.zero();452_ang_vel_target.zero();453}454455// Call quaternion attitude controller456attitude_controller_run_quat();457}458459// Command an euler roll, pitch, and yaw rate with angular velocity feedforward and smoothing460void AC_AttitudeControl::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds)461{462// Convert from centidegrees on public interface to radians463float euler_roll_rate = radians(euler_roll_rate_cds * 0.01f);464float euler_pitch_rate = radians(euler_pitch_rate_cds * 0.01f);465float euler_yaw_rate = radians(euler_yaw_rate_cds * 0.01f);466467// update attitude target468update_attitude_target();469470// calculate the attitude target euler angles471_attitude_target.to_euler(_euler_angle_target);472473if (_rate_bf_ff_enabled) {474// translate the roll pitch and yaw acceleration limits to the euler axis475const Vector3f euler_accel = euler_accel_limit(_attitude_target, Vector3f{get_accel_roll_max_radss(), get_accel_pitch_max_radss(), get_accel_yaw_max_radss()});476477// When acceleration limiting is enabled, the input shaper constrains angular acceleration, slewing478// the output rate towards the input rate.479_euler_rate_target.x = input_shaping_ang_vel(_euler_rate_target.x, euler_roll_rate, euler_accel.x, _dt, _rate_rp_tc);480_euler_rate_target.y = input_shaping_ang_vel(_euler_rate_target.y, euler_pitch_rate, euler_accel.y, _dt, _rate_rp_tc);481_euler_rate_target.z = input_shaping_ang_vel(_euler_rate_target.z, euler_yaw_rate, euler_accel.z, _dt, _rate_y_tc);482483// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward484euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target);485} else {486// When feedforward is not enabled, the target euler angle is input into the target and the feedforward rate is zeroed.487// Pitch angle is restricted to +- 85.0 degrees to avoid gimbal lock discontinuities.488_euler_angle_target.x = wrap_PI(_euler_angle_target.x + euler_roll_rate * _dt);489_euler_angle_target.y = constrain_float(_euler_angle_target.y + euler_pitch_rate * _dt, radians(-85.0f), radians(85.0f));490_euler_angle_target.z = wrap_2PI(_euler_angle_target.z + euler_yaw_rate * _dt);491492// Set rate feedforward requests to zero493_euler_rate_target.zero();494_ang_vel_target.zero();495496// Compute quaternion target attitude497_attitude_target.from_euler(_euler_angle_target.x, _euler_angle_target.y, _euler_angle_target.z);498}499500// Call quaternion attitude controller501attitude_controller_run_quat();502}503504// Fully stabilized acro505// Command an angular velocity with angular velocity feedforward and smoothing506void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)507{508// Convert from centidegrees on public interface to radians509float roll_rate_rads = radians(roll_rate_bf_cds * 0.01f);510float pitch_rate_rads = radians(pitch_rate_bf_cds * 0.01f);511float yaw_rate_rads = radians(yaw_rate_bf_cds * 0.01f);512513// update attitude target514update_attitude_target();515516// calculate the attitude target euler angles517_attitude_target.to_euler(_euler_angle_target);518519if (_rate_bf_ff_enabled) {520// Compute acceleration-limited body frame rates521// When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing522// the output rate towards the input rate.523_ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt, _rate_rp_tc);524_ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt, _rate_rp_tc);525_ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt, _rate_y_tc);526527// Convert body-frame angular velocity into euler angle derivative of desired attitude528ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);529} else {530// When feedforward is not enabled, the quaternion is calculated and is input into the target and the feedforward rate is zeroed.531Quaternion attitude_target_update;532attitude_target_update.from_axis_angle(Vector3f{roll_rate_rads, pitch_rate_rads, yaw_rate_rads} * _dt);533_attitude_target = _attitude_target * attitude_target_update;534_attitude_target.normalize();535536// Set rate feedforward requests to zero537_euler_rate_target.zero();538_ang_vel_target.zero();539}540541// Call quaternion attitude controller542attitude_controller_run_quat();543}544545// Rate-only acro with no attitude feedback - used only by Copter rate-only acro546// Command an angular velocity with angular velocity smoothing using rate loops only with no attitude loop stabilization547void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)548{549// Convert from centidegrees on public interface to radians550float roll_rate_rads = radians(roll_rate_bf_cds * 0.01f);551float pitch_rate_rads = radians(pitch_rate_bf_cds * 0.01f);552float yaw_rate_rads = radians(yaw_rate_bf_cds * 0.01f);553554// Compute acceleration-limited body frame rates555// When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing556// the output rate towards the input rate.557_ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt, _rate_rp_tc);558_ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt, _rate_rp_tc);559_ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt, _rate_y_tc);560561// Update the unused targets attitude based on current attitude to condition mode change562_ahrs.get_quat_body_to_ned(_attitude_target);563_attitude_target.to_euler(_euler_angle_target);564// Convert body-frame angular velocity into euler angle derivative of desired attitude565ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);566567// finally update the attitude target568_ang_vel_body = _ang_vel_target;569}570571// Acro with attitude feedback that does not rely on attitude - used only by Plane acro572// Command an angular velocity with angular velocity smoothing using rate loops only with integrated rate error stabilization573void AC_AttitudeControl::input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds)574{575// Convert from centidegrees on public interface to radians576float roll_rate_rads = radians(roll_rate_bf_cds * 0.01f);577float pitch_rate_rads = radians(pitch_rate_bf_cds * 0.01f);578float yaw_rate_rads = radians(yaw_rate_bf_cds * 0.01f);579580// Update attitude error581Vector3f attitude_error;582_attitude_ang_error.to_axis_angle(attitude_error);583584Quaternion attitude_ang_error_update_quat;585// limit the integrated error angle586float err_mag = attitude_error.length();587if (err_mag > AC_ATTITUDE_THRUST_ERROR_ANGLE) {588attitude_error *= AC_ATTITUDE_THRUST_ERROR_ANGLE / err_mag;589_attitude_ang_error.from_axis_angle(attitude_error);590}591592Vector3f gyro_latest = get_latest_gyro();593attitude_ang_error_update_quat.from_axis_angle((_ang_vel_target - gyro_latest) * _dt);594_attitude_ang_error = attitude_ang_error_update_quat * _attitude_ang_error;595_attitude_ang_error.normalize();596597// Compute acceleration-limited body frame rates598// When acceleration limiting is enabled, the input shaper constrains angular acceleration about the axis, slewing599// the output rate towards the input rate.600_ang_vel_target.x = input_shaping_ang_vel(_ang_vel_target.x, roll_rate_rads, get_accel_roll_max_radss(), _dt, _rate_rp_tc);601_ang_vel_target.y = input_shaping_ang_vel(_ang_vel_target.y, pitch_rate_rads, get_accel_pitch_max_radss(), _dt, _rate_rp_tc);602_ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, yaw_rate_rads, get_accel_yaw_max_radss(), _dt, _rate_y_tc);603604// Retrieve quaternion body attitude605Quaternion attitude_body;606_ahrs.get_quat_body_to_ned(attitude_body);607608// Update the unused targets attitude based on current attitude to condition mode change609_attitude_target = attitude_body * _attitude_ang_error;610_attitude_target.normalize();611612// calculate the attitude target euler angles613_attitude_target.to_euler(_euler_angle_target);614615// Convert body-frame angular velocity into euler angle derivative of desired attitude616ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);617618// Compute the angular velocity target from the integrated rate error619_attitude_ang_error.to_axis_angle(attitude_error);620Vector3f ang_vel_body = update_ang_vel_target_from_att_error(attitude_error);621ang_vel_body += _ang_vel_target;622623// finally update the attitude target624_ang_vel_body = ang_vel_body;625}626627// Command an angular step (i.e change) in body frame angle628// Used to command a step in angle without exciting the orthogonal axis during autotune629void AC_AttitudeControl::input_angle_step_bf_roll_pitch_yaw(float roll_angle_step_bf_cd, float pitch_angle_step_bf_cd, float yaw_angle_step_bf_cd)630{631// Convert from centidegrees on public interface to radians632float roll_step_rads = radians(roll_angle_step_bf_cd * 0.01f);633float pitch_step_rads = radians(pitch_angle_step_bf_cd * 0.01f);634float yaw_step_rads = radians(yaw_angle_step_bf_cd * 0.01f);635636// rotate attitude target by desired step637Quaternion attitude_target_update;638attitude_target_update.from_axis_angle(Vector3f{roll_step_rads, pitch_step_rads, yaw_step_rads});639_attitude_target = _attitude_target * attitude_target_update;640_attitude_target.normalize();641642// calculate the attitude target euler angles643_attitude_target.to_euler(_euler_angle_target);644645// Set rate feedforward requests to zero646_euler_rate_target.zero();647_ang_vel_target.zero();648649// Call quaternion attitude controller650attitude_controller_run_quat();651}652653// Command an rate step (i.e change) in body frame rate654// Used to command a step in rate without exciting the orthogonal axis during autotune655// Done as a single thread-safe function to avoid intermediate zero values being seen by the attitude controller656void AC_AttitudeControl::input_rate_step_bf_roll_pitch_yaw(float roll_rate_step_bf_cd, float pitch_rate_step_bf_cd, float yaw_rate_step_bf_cd)657{658// Update the unused targets attitude based on current attitude to condition mode change659_ahrs.get_quat_body_to_ned(_attitude_target);660_attitude_target.to_euler(_euler_angle_target);661// Set the target angular velocity to be zero to minimize target overshoot after the rate step finishes662_ang_vel_target.zero();663// Convert body-frame angular velocity into euler angle derivative of desired attitude664_euler_rate_target.zero();665666Vector3f ang_vel_body {roll_rate_step_bf_cd, pitch_rate_step_bf_cd, yaw_rate_step_bf_cd};667ang_vel_body = ang_vel_body * 0.01f * DEG_TO_RAD;668// finally update the attitude target669_ang_vel_body = ang_vel_body;670}671672// Command a thrust vector and heading rate673void AC_AttitudeControl::input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw)674{675// Convert from centidegrees on public interface to radians676float heading_rate = radians(heading_rate_cds * 0.01f);677if (slew_yaw) {678// a zero _angle_vel_yaw_max means that setting is disabled679const float slew_yaw_max_rads = get_slew_yaw_max_rads();680heading_rate = constrain_float(heading_rate, -slew_yaw_max_rads, slew_yaw_max_rads);681}682683// update attitude target684update_attitude_target();685686// calculate the attitude target euler angles687_attitude_target.to_euler(_euler_angle_target);688689// convert thrust vector to a quaternion attitude690Quaternion thrust_vec_quat = attitude_from_thrust_vector(thrust_vector, 0.0f);691692// calculate the angle error in x and y.693float thrust_vector_diff_angle;694Quaternion thrust_vec_correction_quat;695Vector3f attitude_error;696float returned_thrust_vector_angle;697thrust_vector_rotation_angles(thrust_vec_quat, _attitude_target, thrust_vec_correction_quat, attitude_error, returned_thrust_vector_angle, thrust_vector_diff_angle);698699if (_rate_bf_ff_enabled) {700// When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing701// the output rate towards the input rate.702_ang_vel_target.x = input_shaping_angle(attitude_error.x, _input_tc, get_accel_roll_max_radss(), _ang_vel_target.x, _dt);703_ang_vel_target.y = input_shaping_angle(attitude_error.y, _input_tc, get_accel_pitch_max_radss(), _ang_vel_target.y, _dt);704705// When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing706// the output rate towards the input rate.707_ang_vel_target.z = input_shaping_ang_vel(_ang_vel_target.z, heading_rate, get_accel_yaw_max_radss(), _dt, _rate_y_tc);708709// Limit the angular velocity710ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));711} else {712Quaternion yaw_quat;713yaw_quat.from_axis_angle(Vector3f{0.0f, 0.0f, heading_rate * _dt});714_attitude_target = _attitude_target * thrust_vec_correction_quat * yaw_quat;715716// Set rate feedforward requests to zero717_euler_rate_target.zero();718_ang_vel_target.zero();719}720721// Convert body-frame angular velocity into euler angle derivative of desired attitude722ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);723724// Call quaternion attitude controller725attitude_controller_run_quat();726}727728// Command a thrust vector, heading and heading rate729void AC_AttitudeControl::input_thrust_vector_heading(const Vector3f& thrust_vector, float heading_angle_cd, float heading_rate_cds)730{731// a zero _angle_vel_yaw_max means that setting is disabled732const float slew_yaw_max_rads = get_slew_yaw_max_rads();733734// Convert from centidegrees on public interface to radians735float heading_rate = constrain_float(radians(heading_rate_cds * 0.01f), -slew_yaw_max_rads, slew_yaw_max_rads);736float heading_angle = radians(heading_angle_cd * 0.01f);737738// update attitude target739update_attitude_target();740741// calculate the attitude target euler angles742_attitude_target.to_euler(_euler_angle_target);743744// convert thrust vector and heading to a quaternion attitude745const Quaternion desired_attitude_quat = attitude_from_thrust_vector(thrust_vector, heading_angle);746747if (_rate_bf_ff_enabled) {748// calculate the angle error in x and y.749Vector3f attitude_error;750float thrust_vector_diff_angle;751Quaternion thrust_vec_correction_quat;752float returned_thrust_vector_angle;753thrust_vector_rotation_angles(desired_attitude_quat, _attitude_target, thrust_vec_correction_quat, attitude_error, returned_thrust_vector_angle, thrust_vector_diff_angle);754755// When yaw acceleration limiting is enabled, the yaw input shaper constrains angular acceleration about the yaw axis, slewing756// the output rate towards the input rate.757_ang_vel_target.x = input_shaping_angle(attitude_error.x, _input_tc, get_accel_roll_max_radss(), _ang_vel_target.x, _dt);758_ang_vel_target.y = input_shaping_angle(attitude_error.y, _input_tc, get_accel_pitch_max_radss(), _ang_vel_target.y, _dt);759_ang_vel_target.z = input_shaping_angle(attitude_error.z, _input_tc, get_accel_yaw_max_radss(), _ang_vel_target.z, heading_rate, slew_yaw_max_rads, _dt);760761// Limit the angular velocity762ang_vel_limit(_ang_vel_target, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), slew_yaw_max_rads);763} else {764// set persisted quaternion target attitude765_attitude_target = desired_attitude_quat;766767// Set rate feedforward requests to zero768_euler_rate_target.zero();769_ang_vel_target.zero();770}771772// Convert body-frame angular velocity into euler angle derivative of desired attitude773ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);774775// Call quaternion attitude controller776attitude_controller_run_quat();777}778779// Command a thrust vector and heading rate780void AC_AttitudeControl::input_thrust_vector_heading(const Vector3f& thrust_vector, HeadingCommand heading)781{782switch (heading.heading_mode) {783case HeadingMode::Rate_Only:784input_thrust_vector_rate_heading(thrust_vector, heading.yaw_rate_cds);785break;786case HeadingMode::Angle_Only:787input_thrust_vector_heading(thrust_vector, heading.yaw_angle_cd, 0.0);788break;789case HeadingMode::Angle_And_Rate:790input_thrust_vector_heading(thrust_vector, heading.yaw_angle_cd, heading.yaw_rate_cds);791break;792}793}794795Quaternion AC_AttitudeControl::attitude_from_thrust_vector(Vector3f thrust_vector, float heading_angle) const796{797const Vector3f thrust_vector_up{0.0f, 0.0f, -1.0f};798799if (is_zero(thrust_vector.length_squared())) {800thrust_vector = thrust_vector_up;801} else {802thrust_vector.normalize();803}804805// the cross product of the desired and target thrust vector defines the rotation vector806Vector3f thrust_vec_cross = thrust_vector_up % thrust_vector;807808// the dot product is used to calculate the angle between the target and desired thrust vectors809const float thrust_vector_angle = acosf(constrain_float(thrust_vector_up * thrust_vector, -1.0f, 1.0f));810811// Normalize the thrust rotation vector812const float thrust_vector_length = thrust_vec_cross.length();813if (is_zero(thrust_vector_length) || is_zero(thrust_vector_angle)) {814thrust_vec_cross = thrust_vector_up;815} else {816thrust_vec_cross /= thrust_vector_length;817}818819Quaternion thrust_vec_quat;820thrust_vec_quat.from_axis_angle(thrust_vec_cross, thrust_vector_angle);821Quaternion yaw_quat;822yaw_quat.from_axis_angle(Vector3f{0.0f, 0.0f, 1.0f}, heading_angle);823return thrust_vec_quat*yaw_quat;824}825826// Calculates the body frame angular velocities to follow the target attitude827void AC_AttitudeControl::update_attitude_target()828{829// rotate target and normalize830Quaternion attitude_target_update;831attitude_target_update.from_axis_angle(_ang_vel_target * _dt);832_attitude_target *= attitude_target_update;833_attitude_target.normalize();834}835836// Calculates the body frame angular velocities to follow the target attitude837void AC_AttitudeControl::attitude_controller_run_quat()838{839// This represents a quaternion rotation in NED frame to the body840Quaternion attitude_body;841_ahrs.get_quat_body_to_ned(attitude_body);842843// This vector represents the angular error to rotate the thrust vector using x and y and heading using z844Vector3f attitude_error;845thrust_heading_rotation_angles(_attitude_target, attitude_body, attitude_error, _thrust_angle, _thrust_error_angle);846847// Compute the angular velocity corrections in the body frame from the attitude error848Vector3f ang_vel_body = update_ang_vel_target_from_att_error(attitude_error);849850// ensure angular velocity does not go over configured limits851ang_vel_limit(ang_vel_body, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), radians(_ang_vel_yaw_max));852853// rotation from the target frame to the body frame854Quaternion rotation_target_to_body = attitude_body.inverse() * _attitude_target;855856// target angle velocity vector in the body frame857Vector3f ang_vel_body_feedforward = rotation_target_to_body * _ang_vel_target;858Vector3f gyro = get_latest_gyro();859// Correct the thrust vector and smoothly add feedforward and yaw input860_feedforward_scalar = 1.0f;861if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE * 2.0f) {862ang_vel_body.z = gyro.z;863} else if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE) {864_feedforward_scalar = (1.0f - (_thrust_error_angle - AC_ATTITUDE_THRUST_ERROR_ANGLE) / AC_ATTITUDE_THRUST_ERROR_ANGLE);865ang_vel_body.x += ang_vel_body_feedforward.x * _feedforward_scalar;866ang_vel_body.y += ang_vel_body_feedforward.y * _feedforward_scalar;867ang_vel_body.z += ang_vel_body_feedforward.z;868ang_vel_body.z = gyro.z * (1.0 - _feedforward_scalar) + ang_vel_body.z * _feedforward_scalar;869} else {870ang_vel_body += ang_vel_body_feedforward;871}872873// Record error to handle EKF resets874_attitude_ang_error = attitude_body.inverse() * _attitude_target;875// finally update the attitude target876_ang_vel_body = ang_vel_body;877}878879// thrust_heading_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion.880// The maximum error in the yaw axis is limited based on static output saturation.881void AC_AttitudeControl::thrust_heading_rotation_angles(Quaternion& attitude_target, const Quaternion& attitude_body, Vector3f& attitude_error, float& thrust_angle, float& thrust_error_angle) const882{883Quaternion thrust_vector_correction;884thrust_vector_rotation_angles(attitude_target, attitude_body, thrust_vector_correction, attitude_error, thrust_angle, thrust_error_angle);885886// Todo: Limit roll an pitch error based on output saturation and maximum error.887888// Limit Yaw Error based to the maximum that would saturate the output when yaw rate is zero.889Quaternion heading_vec_correction_quat;890891float 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);892if (!is_zero(get_rate_yaw_pid().kP())) {893float 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);894if (!is_zero(_p_angle_yaw.kP()) && fabsf(attitude_error.z) > heading_error_max) {895attitude_error.z = constrain_float(wrap_PI(attitude_error.z), -heading_error_max, heading_error_max);896heading_vec_correction_quat.from_axis_angle(Vector3f{0.0f, 0.0f, attitude_error.z});897attitude_target = attitude_body * thrust_vector_correction * heading_vec_correction_quat;898}899}900}901902// thrust_vector_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion.903// The first rotation corrects the thrust vector and the second rotation corrects the heading vector.904void AC_AttitudeControl::thrust_vector_rotation_angles(const Quaternion& attitude_target, const Quaternion& attitude_body, Quaternion& thrust_vector_correction, Vector3f& attitude_error, float& thrust_angle, float& thrust_error_angle) const905{906// The direction of thrust is [0,0,-1] is any body-fixed frame, inc. body frame and target frame.907const Vector3f thrust_vector_up{0.0f, 0.0f, -1.0f};908909// attitude_target and attitude_body are passive rotations from target / body frames to the NED frame910911// Rotating [0,0,-1] by attitude_target expresses (gets a view of) the target thrust vector in the inertial frame912Vector3f att_target_thrust_vec = attitude_target * thrust_vector_up; // target thrust vector913914// Rotating [0,0,-1] by attitude_target expresses (gets a view of) the current thrust vector in the inertial frame915Vector3f att_body_thrust_vec = attitude_body * thrust_vector_up; // current thrust vector916917// the dot product is used to calculate the current lean angle for use of external functions918thrust_angle = acosf(constrain_float(thrust_vector_up * att_body_thrust_vec,-1.0f,1.0f));919920// the cross product of the desired and target thrust vector defines the rotation vector921Vector3f thrust_vec_cross = att_body_thrust_vec % att_target_thrust_vec;922923// the dot product is used to calculate the angle between the target and desired thrust vectors924thrust_error_angle = acosf(constrain_float(att_body_thrust_vec * att_target_thrust_vec, -1.0f, 1.0f));925926// Normalize the thrust rotation vector927float thrust_vector_length = thrust_vec_cross.length();928if (is_zero(thrust_vector_length) || is_zero(thrust_error_angle)) {929thrust_vec_cross = thrust_vector_up;930} else {931thrust_vec_cross /= thrust_vector_length;932}933934// thrust_vector_correction is defined relative to the body frame but its axis `thrust_vec_cross` was computed in935// the inertial frame. First rotate it by the inverse of attitude_body to express it back in the body frame936thrust_vec_cross = attitude_body.inverse() * thrust_vec_cross;937thrust_vector_correction.from_axis_angle(thrust_vec_cross, thrust_error_angle);938939// calculate the angle error in x and y.940Vector3f rotation;941thrust_vector_correction.to_axis_angle(rotation);942attitude_error.x = rotation.x;943attitude_error.y = rotation.y;944945// calculate the remaining rotation required after thrust vector is rotated transformed to the body frame946// heading_vector_correction947Quaternion heading_vec_correction_quat = thrust_vector_correction.inverse() * attitude_body.inverse() * attitude_target;948949// calculate the angle error in z (x and y should be zero here).950heading_vec_correction_quat.to_axis_angle(rotation);951attitude_error.z = rotation.z;952}953954// calculates the velocity correction from an angle error. The angular velocity has acceleration and955// deceleration limits including basic jerk limiting using _input_tc956float AC_AttitudeControl::input_shaping_angle(float error_angle, float input_tc, float accel_max, float target_ang_vel, float desired_ang_vel, float max_ang_vel, float dt)957{958// Calculate the velocity as error approaches zero with acceleration limited by accel_max_radss959desired_ang_vel += sqrt_controller(error_angle, 1.0f / MAX(input_tc, 0.01f), accel_max, dt);960if (is_positive(max_ang_vel)) {961desired_ang_vel = constrain_float(desired_ang_vel, -max_ang_vel, max_ang_vel);962}963964// Acceleration is limited directly to smooth the beginning of the curve.965return input_shaping_ang_vel(target_ang_vel, desired_ang_vel, accel_max, dt, 0.0f);966}967968// Shapes the velocity request based on a rate time constant. The angular acceleration and deceleration is limited.969float AC_AttitudeControl::input_shaping_ang_vel(float target_ang_vel, float desired_ang_vel, float accel_max, float dt, float input_tc)970{971if (is_positive(input_tc)) {972// Calculate the acceleration to smoothly achieve rate. Jerk is not limited.973float error_rate = desired_ang_vel - target_ang_vel;974float desired_ang_accel = sqrt_controller(error_rate, 1.0f / MAX(input_tc, 0.01f), 0.0f, dt);975desired_ang_vel = target_ang_vel + desired_ang_accel * dt;976}977// Acceleration is limited directly to smooth the beginning of the curve.978if (is_positive(accel_max)) {979float delta_ang_vel = accel_max * dt;980return constrain_float(desired_ang_vel, target_ang_vel - delta_ang_vel, target_ang_vel + delta_ang_vel);981} else {982return desired_ang_vel;983}984}985986// calculates the expected angular velocity correction from an angle error based on the AC_AttitudeControl settings.987// This function can be used to predict the delay associated with angle requests.988void AC_AttitudeControl::input_shaping_rate_predictor(const Vector2f &error_angle, Vector2f& target_ang_vel, float dt) const989{990if (_rate_bf_ff_enabled) {991// translate the roll pitch and yaw acceleration limits to the euler axis992target_ang_vel.x = input_shaping_angle(wrap_PI(error_angle.x), _input_tc, get_accel_roll_max_radss(), target_ang_vel.x, dt);993target_ang_vel.y = input_shaping_angle(wrap_PI(error_angle.y), _input_tc, get_accel_pitch_max_radss(), target_ang_vel.y, dt);994} else {995const float angleP_roll = _p_angle_roll.kP() * _angle_P_scale.x;996const float angleP_pitch = _p_angle_pitch.kP() * _angle_P_scale.y;997target_ang_vel.x = angleP_roll * wrap_PI(error_angle.x);998target_ang_vel.y = angleP_pitch * wrap_PI(error_angle.y);999}1000// Limit the angular velocity correction1001Vector3f ang_vel(target_ang_vel.x, target_ang_vel.y, 0.0f);1002ang_vel_limit(ang_vel, radians(_ang_vel_roll_max), radians(_ang_vel_pitch_max), 0.0f);10031004target_ang_vel.x = ang_vel.x;1005target_ang_vel.y = ang_vel.y;1006}10071008// limits angular velocity1009void AC_AttitudeControl::ang_vel_limit(Vector3f& euler_rad, float ang_vel_roll_max, float ang_vel_pitch_max, float ang_vel_yaw_max) const1010{1011if (is_zero(ang_vel_roll_max) || is_zero(ang_vel_pitch_max)) {1012if (!is_zero(ang_vel_roll_max)) {1013euler_rad.x = constrain_float(euler_rad.x, -ang_vel_roll_max, ang_vel_roll_max);1014}1015if (!is_zero(ang_vel_pitch_max)) {1016euler_rad.y = constrain_float(euler_rad.y, -ang_vel_pitch_max, ang_vel_pitch_max);1017}1018} else {1019Vector2f thrust_vector_ang_vel(euler_rad.x / ang_vel_roll_max, euler_rad.y / ang_vel_pitch_max);1020float thrust_vector_length = thrust_vector_ang_vel.length();1021if (thrust_vector_length > 1.0f) {1022euler_rad.x = thrust_vector_ang_vel.x * ang_vel_roll_max / thrust_vector_length;1023euler_rad.y = thrust_vector_ang_vel.y * ang_vel_pitch_max / thrust_vector_length;1024}1025}1026if (!is_zero(ang_vel_yaw_max)) {1027euler_rad.z = constrain_float(euler_rad.z, -ang_vel_yaw_max, ang_vel_yaw_max);1028}1029}10301031// translates body frame acceleration limits to the euler axis1032Vector3f AC_AttitudeControl::euler_accel_limit(const Quaternion &att, const Vector3f &euler_accel)1033{1034if (!is_positive(euler_accel.x) || !is_positive(euler_accel.y) || !is_positive(euler_accel.z)) {1035return Vector3f { euler_accel };1036}10371038const float phi = att.get_euler_roll();1039const float theta = att.get_euler_pitch();10401041const float sin_phi = constrain_float(fabsf(sinf(phi)), 0.1f, 1.0f);1042const float cos_phi = constrain_float(fabsf(cosf(phi)), 0.1f, 1.0f);1043const float sin_theta = constrain_float(fabsf(sinf(theta)), 0.1f, 1.0f);1044const float cos_theta = constrain_float(fabsf(cosf(theta)), 0.1f, 1.0f);10451046return Vector3f {1047euler_accel.x,1048MIN(euler_accel.y / cos_phi, euler_accel.z / sin_phi),1049MIN(MIN(euler_accel.x / sin_theta, euler_accel.y / (sin_phi * cos_theta)), euler_accel.z / (cos_phi * cos_theta))1050};1051}10521053// Sets attitude target to vehicle attitude and sets all rates to zero1054// If reset_rate is false rates are not reset to allow the rate controllers to run1055void AC_AttitudeControl::reset_target_and_rate(bool reset_rate)1056{1057// move attitude target to current attitude1058_ahrs.get_quat_body_to_ned(_attitude_target);1059_attitude_target.to_euler(_euler_angle_target);10601061if (reset_rate) {1062_ang_vel_target.zero();1063_euler_rate_target.zero();1064}1065}10661067// Sets yaw target to vehicle heading and sets yaw rate to zero1068// If reset_rate is false rates are not reset to allow the rate controllers to run1069void AC_AttitudeControl::reset_yaw_target_and_rate(bool reset_rate)1070{1071// move attitude target to current heading1072float yaw_shift = _ahrs.yaw - _euler_angle_target.z;1073Quaternion _attitude_target_update;1074_attitude_target_update.from_axis_angle(Vector3f{0.0f, 0.0f, yaw_shift});1075_attitude_target = _attitude_target_update * _attitude_target;10761077if (reset_rate) {1078// set yaw rate to zero1079_euler_rate_target.z = 0.0f;10801081// Convert euler angle derivative of desired attitude into a body-frame angular velocity vector for feedforward1082euler_rate_to_ang_vel(_attitude_target, _euler_rate_target, _ang_vel_target);1083}1084}10851086// Shifts the target attitude to maintain the current error in the event of an EKF reset1087void AC_AttitudeControl::inertial_frame_reset()1088{1089// Retrieve quaternion body attitude1090Quaternion attitude_body;1091_ahrs.get_quat_body_to_ned(attitude_body);10921093// Recalculate the target quaternion1094_attitude_target = attitude_body * _attitude_ang_error;10951096// calculate the attitude target euler angles1097_attitude_target.to_euler(_euler_angle_target);1098}10991100// Convert a 321-intrinsic euler angle derivative to an angular velocity vector1101void AC_AttitudeControl::euler_rate_to_ang_vel(const Quaternion& att, const Vector3f& euler_rate_rads, Vector3f& ang_vel_rads)1102{1103const float theta = att.get_euler_pitch();1104const float phi = att.get_euler_roll();11051106const float sin_theta = sinf(theta);1107const float cos_theta = cosf(theta);1108const float sin_phi = sinf(phi);1109const float cos_phi = cosf(phi);11101111ang_vel_rads.x = euler_rate_rads.x - sin_theta * euler_rate_rads.z;1112ang_vel_rads.y = cos_phi * euler_rate_rads.y + sin_phi * cos_theta * euler_rate_rads.z;1113ang_vel_rads.z = -sin_phi * euler_rate_rads.y + cos_theta * cos_phi * euler_rate_rads.z;1114}11151116// Convert an angular velocity vector to a 321-intrinsic euler angle derivative1117// Returns false if the vehicle is pitched 90 degrees up or down1118bool AC_AttitudeControl::ang_vel_to_euler_rate(const Quaternion& att, const Vector3f& ang_vel_rads, Vector3f& euler_rate_rads)1119{1120const float theta = att.get_euler_pitch();1121const float phi = att.get_euler_roll();11221123const float sin_theta = sinf(theta);1124const float cos_theta = cosf(theta);1125const float sin_phi = sinf(phi);1126const float cos_phi = cosf(phi);11271128// 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.1129if (is_zero(cos_theta)) {1130return false;1131}11321133euler_rate_rads.x = ang_vel_rads.x + sin_phi * (sin_theta / cos_theta) * ang_vel_rads.y + cos_phi * (sin_theta / cos_theta) * ang_vel_rads.z;1134euler_rate_rads.y = cos_phi * ang_vel_rads.y - sin_phi * ang_vel_rads.z;1135euler_rate_rads.z = (sin_phi / cos_theta) * ang_vel_rads.y + (cos_phi / cos_theta) * ang_vel_rads.z;1136return true;1137}11381139// Update rate_target_ang_vel using attitude_error_rot_vec_rad1140Vector3f AC_AttitudeControl::update_ang_vel_target_from_att_error(const Vector3f &attitude_error_rot_vec_rad)1141{1142Vector3f rate_target_ang_vel;11431144// Compute the roll angular velocity demand from the roll angle error1145const float angleP_roll = _p_angle_roll.kP() * _angle_P_scale.x;1146if (_use_sqrt_controller && !is_zero(get_accel_roll_max_radss())) {1147rate_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);1148} else {1149rate_target_ang_vel.x = angleP_roll * attitude_error_rot_vec_rad.x;1150}11511152// Compute the pitch angular velocity demand from the pitch angle error1153const float angleP_pitch = _p_angle_pitch.kP() * _angle_P_scale.y;1154if (_use_sqrt_controller && !is_zero(get_accel_pitch_max_radss())) {1155rate_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);1156} else {1157rate_target_ang_vel.y = angleP_pitch * attitude_error_rot_vec_rad.y;1158}11591160// Compute the yaw angular velocity demand from the yaw angle error1161const float angleP_yaw = _p_angle_yaw.kP() * _angle_P_scale.z;1162if (_use_sqrt_controller && !is_zero(get_accel_yaw_max_radss())) {1163rate_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);1164} else {1165rate_target_ang_vel.z = angleP_yaw * attitude_error_rot_vec_rad.z;1166}11671168// reset angle P scaling, saving used value1169_angle_P_scale_used = _angle_P_scale;1170_angle_P_scale = VECTORF_111;11711172return rate_target_ang_vel;1173}11741175// Enable or disable body-frame feed forward1176void AC_AttitudeControl::accel_limiting(bool enable_limits)1177{1178if (enable_limits) {1179// If enabling limits, reload from eeprom or set to defaults1180if (is_zero(_accel_roll_max)) {1181_accel_roll_max.load();1182}1183if (is_zero(_accel_pitch_max)) {1184_accel_pitch_max.load();1185}1186if (is_zero(_accel_yaw_max)) {1187_accel_yaw_max.load();1188}1189} else {1190_accel_roll_max.set(0.0f);1191_accel_pitch_max.set(0.0f);1192_accel_yaw_max.set(0.0f);1193}1194}11951196// Return tilt angle limit for pilot input that prioritises altitude hold over lean angle1197float AC_AttitudeControl::get_althold_lean_angle_max_cd() const1198{1199// convert to centi-degrees for public interface1200return MAX(ToDeg(_althold_lean_angle_max), AC_ATTITUDE_CONTROL_ANGLE_LIMIT_MIN) * 100.0f;1201}12021203// Return roll rate step size in centidegrees/s that results in maximum output after 4 time steps1204float AC_AttitudeControl::max_rate_step_bf_roll()1205{1206float dt_average = AP::scheduler().get_filtered_loop_time();1207float alpha = MIN(get_rate_roll_pid().get_filt_E_alpha(dt_average), get_rate_roll_pid().get_filt_D_alpha(dt_average));1208float alpha_remaining = 1 - alpha;1209// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max1210float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);1211float 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 + get_rate_roll_pid().kP());1212if (is_positive(_ang_vel_roll_max)) {1213rate_max = MIN(rate_max, get_ang_vel_roll_max_rads());1214}1215return rate_max;1216}12171218// Return pitch rate step size in centidegrees/s that results in maximum output after 4 time steps1219float AC_AttitudeControl::max_rate_step_bf_pitch()1220{1221float dt_average = AP::scheduler().get_filtered_loop_time();1222float alpha = MIN(get_rate_pitch_pid().get_filt_E_alpha(dt_average), get_rate_pitch_pid().get_filt_D_alpha(dt_average));1223float alpha_remaining = 1 - alpha;1224// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max1225float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);1226float 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 + get_rate_pitch_pid().kP());1227if (is_positive(_ang_vel_pitch_max)) {1228rate_max = MIN(rate_max, get_ang_vel_pitch_max_rads());1229}1230return rate_max;1231}12321233// Return yaw rate step size in centidegrees/s that results in maximum output after 4 time steps1234float AC_AttitudeControl::max_rate_step_bf_yaw()1235{1236float dt_average = AP::scheduler().get_filtered_loop_time();1237float alpha = MIN(get_rate_yaw_pid().get_filt_E_alpha(dt_average), get_rate_yaw_pid().get_filt_D_alpha(dt_average));1238float alpha_remaining = 1 - alpha;1239// todo: When a thrust_max is available we should replace 0.5f with 0.5f * _motors.thrust_max1240float throttle_hover = constrain_float(_motors.get_throttle_hover(), 0.1f, 0.5f);1241float 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 + get_rate_yaw_pid().kP());1242if (is_positive(_ang_vel_yaw_max)) {1243rate_max = MIN(rate_max, get_ang_vel_yaw_max_rads());1244}1245return rate_max;1246}12471248bool AC_AttitudeControl::pre_arm_checks(const char *param_prefix,1249char *failure_msg,1250const uint8_t failure_msg_len)1251{1252// validate AC_P members:1253const struct {1254const char *pid_name;1255AC_P &p;1256} ps[] = {1257{ "ANG_PIT", get_angle_pitch_p() },1258{ "ANG_RLL", get_angle_roll_p() },1259{ "ANG_YAW", get_angle_yaw_p() }1260};1261for (uint8_t i=0; i<ARRAY_SIZE(ps); i++) {1262// all AC_P's must have a positive P value:1263if (!is_positive(ps[i].p.kP())) {1264hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, ps[i].pid_name);1265return false;1266}1267}12681269// validate AC_PID members:1270const struct {1271const char *pid_name;1272AC_PID &pid;1273} pids[] = {1274{ "RAT_RLL", get_rate_roll_pid() },1275{ "RAT_PIT", get_rate_pitch_pid() },1276{ "RAT_YAW", get_rate_yaw_pid() },1277};1278for (uint8_t i=0; i<ARRAY_SIZE(pids); i++) {1279// if the PID has a positive FF then we just ensure kP and1280// kI aren't negative1281AC_PID &pid = pids[i].pid;1282const char *pid_name = pids[i].pid_name;1283if (is_positive(pid.ff())) {1284// kP and kI must be non-negative:1285if (is_negative(pid.kP())) {1286hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be >= 0", param_prefix, pid_name);1287return false;1288}1289if (is_negative(pid.kI())) {1290hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_I must be >= 0", param_prefix, pid_name);1291return false;1292}1293} else {1294// kP and kI must be positive:1295if (!is_positive(pid.kP())) {1296hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_P must be > 0", param_prefix, pid_name);1297return false;1298}1299if (!is_positive(pid.kI())) {1300hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_I must be > 0", param_prefix, pid_name);1301return false;1302}1303}1304// never allow a negative D term (but zero is allowed)1305if (is_negative(pid.kD())) {1306hal.util->snprintf(failure_msg, failure_msg_len, "%s_%s_D must be >= 0", param_prefix, pid_name);1307return false;1308}1309}1310return true;1311}13121313/*1314get the slew rate for roll, pitch and yaw, for oscillation1315detection in lua scripts1316*/1317void AC_AttitudeControl::get_rpy_srate(float &roll_srate, float &pitch_srate, float &yaw_srate)1318{1319roll_srate = get_rate_roll_pid().get_pid_info().slew_rate;1320pitch_srate = get_rate_pitch_pid().get_pid_info().slew_rate;1321yaw_srate = get_rate_yaw_pid().get_pid_info().slew_rate;1322}132313241325