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_Sub.cpp
Views: 1798
#include "AC_AttitudeControl_Sub.h"1#include <AP_HAL/AP_HAL.h>2#include <AP_Math/AP_Math.h>34// table of user settable parameters5const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = {6// parameters from parent vehicle7AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),89// @Param: RAT_RLL_P10// @DisplayName: Roll axis rate controller P gain11// @Description: Roll axis rate controller P gain. Corrects in proportion to the difference between the desired roll rate vs actual roll rate12// @Range: 0.0 0.3013// @Increment: 0.00514// @User: Standard1516// @Param: RAT_RLL_I17// @DisplayName: Roll axis rate controller I gain18// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate19// @Range: 0.0 0.520// @Increment: 0.0121// @User: Standard2223// @Param: RAT_RLL_IMAX24// @DisplayName: Roll axis rate controller I gain maximum25// @Description: Roll axis rate controller I gain maximum. Constrains the maximum that the I term will output26// @Range: 0 127// @Increment: 0.0128// @User: Standard2930// @Param: RAT_RLL_D31// @DisplayName: Roll axis rate controller D gain32// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate33// @Range: 0.0 0.0234// @Increment: 0.00135// @User: Standard3637// @Param: RAT_RLL_FF38// @DisplayName: Roll axis rate controller feed forward39// @Description: Roll axis rate controller feed forward40// @Range: 0 0.541// @Increment: 0.00142// @User: Standard4344// @Param: RAT_RLL_FLTT45// @DisplayName: Roll axis rate controller input frequency in Hz46// @Description: Roll axis rate controller input frequency in Hz47// @Range: 1 10048// @Increment: 149// @Units: Hz50// @User: Standard5152// @Param: RAT_RLL_FLTE53// @DisplayName: Roll axis rate controller input frequency in Hz54// @Description: Roll axis rate controller input frequency in Hz55// @Range: 1 10056// @Increment: 157// @Units: Hz58// @User: Standard5960// @Param: RAT_RLL_FLTD61// @DisplayName: Roll axis rate controller input frequency in Hz62// @Description: Roll axis rate controller input frequency in Hz63// @Range: 1 10064// @Increment: 165// @Units: Hz66// @User: Standard6768// @Param: RAT_RLL_SMAX69// @DisplayName: Roll slew rate limit70// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.71// @Range: 0 20072// @Increment: 0.573// @User: Advanced7475// @Param: RAT_RLL_PDMX76// @DisplayName: Roll axis rate controller PD sum maximum77// @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output78// @Range: 0 179// @Increment: 0.018081// @Param: RAT_RLL_D_FF82// @DisplayName: Roll Derivative FeedForward Gain83// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target84// @Range: 0 0.0285// @Increment: 0.000186// @User: Advanced8788// @Param: RAT_RLL_NTF89// @DisplayName: Roll Target notch filter index90// @Description: Roll Target notch filter index91// @Range: 1 892// @User: Advanced9394// @Param: RAT_RLL_NEF95// @DisplayName: Roll Error notch filter index96// @Description: Roll Error notch filter index97// @Range: 1 898// @User: Advanced99100AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Sub, AC_PID),101102// @Param: RAT_PIT_P103// @DisplayName: Pitch axis rate controller P gain104// @Description: Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate105// @Range: 0.0 0.30106// @Increment: 0.005107// @User: Standard108109// @Param: RAT_PIT_I110// @DisplayName: Pitch axis rate controller I gain111// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate112// @Range: 0.0 0.5113// @Increment: 0.01114// @User: Standard115116// @Param: RAT_PIT_IMAX117// @DisplayName: Pitch axis rate controller I gain maximum118// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output119// @Range: 0 1120// @Increment: 0.01121// @User: Standard122123// @Param: RAT_PIT_D124// @DisplayName: Pitch axis rate controller D gain125// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate126// @Range: 0.0 0.02127// @Increment: 0.001128// @User: Standard129130// @Param: RAT_PIT_FF131// @DisplayName: Pitch axis rate controller feed forward132// @Description: Pitch axis rate controller feed forward133// @Range: 0 0.5134// @Increment: 0.001135// @User: Standard136137// @Param: RAT_PIT_FLTT138// @DisplayName: Pitch axis rate controller input frequency in Hz139// @Description: Pitch axis rate controller input frequency in Hz140// @Range: 1 100141// @Increment: 1142// @Units: Hz143// @User: Standard144145// @Param: RAT_PIT_FLTE146// @DisplayName: Pitch axis rate controller input frequency in Hz147// @Description: Pitch axis rate controller input frequency in Hz148// @Range: 1 100149// @Increment: 1150// @Units: Hz151// @User: Standard152153// @Param: RAT_PIT_FLTD154// @DisplayName: Pitch axis rate controller input frequency in Hz155// @Description: Pitch axis rate controller input frequency in Hz156// @Range: 1 100157// @Increment: 1158// @Units: Hz159// @User: Standard160161// @Param: RAT_PIT_SMAX162// @DisplayName: Pitch slew rate limit163// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.164// @Range: 0 200165// @Increment: 0.5166// @User: Advanced167168// @Param: RAT_PIT_PDMX169// @DisplayName: Pitch axis rate controller PD sum maximum170// @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output171// @Range: 0 1172// @Increment: 0.01173174// @Param: RAT_PIT_D_FF175// @DisplayName: Pitch Derivative FeedForward Gain176// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target177// @Range: 0 0.02178// @Increment: 0.0001179// @User: Advanced180181// @Param: RAT_PIT_NTF182// @DisplayName: Pitch Target notch filter index183// @Description: Pitch Target notch filter index184// @Range: 1 8185// @User: Advanced186187// @Param: RAT_PIT_NEF188// @DisplayName: Pitch Error notch filter index189// @Description: Pitch Error notch filter index190// @Range: 1 8191// @User: Advanced192193AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Sub, AC_PID),194195// @Param: RAT_YAW_P196// @DisplayName: Yaw axis rate controller P gain197// @Description: Yaw axis rate controller P gain. Corrects in proportion to the difference between the desired yaw rate vs actual yaw rate198// @Range: 0.0 0.50199// @Increment: 0.005200// @User: Standard201202// @Param: RAT_YAW_I203// @DisplayName: Yaw axis rate controller I gain204// @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate205// @Range: 0.0 0.05206// @Increment: 0.01207// @User: Standard208209// @Param: RAT_YAW_IMAX210// @DisplayName: Yaw axis rate controller I gain maximum211// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum that the I term will output212// @Range: 0 1213// @Increment: 0.01214// @User: Standard215216// @Param: RAT_YAW_D217// @DisplayName: Yaw axis rate controller D gain218// @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate219// @Range: 0.000 0.02220// @Increment: 0.001221// @User: Standard222223// @Param: RAT_YAW_FF224// @DisplayName: Yaw axis rate controller feed forward225// @Description: Yaw axis rate controller feed forward226// @Range: 0 0.5227// @Increment: 0.001228// @User: Standard229230// @Param: RAT_YAW_FLTT231// @DisplayName: Yaw axis rate controller input frequency in Hz232// @Description: Yaw axis rate controller input frequency in Hz233// @Range: 1 100234// @Increment: 1235// @Units: Hz236// @User: Standard237238// @Param: RAT_YAW_FLTE239// @DisplayName: Yaw axis rate controller input frequency in Hz240// @Description: Yaw axis rate controller input frequency in Hz241// @Range: 1 100242// @Increment: 1243// @Units: Hz244// @User: Standard245246// @Param: RAT_YAW_FLTD247// @DisplayName: Yaw axis rate controller input frequency in Hz248// @Description: Yaw axis rate controller input frequency in Hz249// @Range: 1 100250// @Increment: 1251// @Units: Hz252// @User: Standard253254// @Param: RAT_YAW_SMAX255// @DisplayName: Yaw slew rate limit256// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.257// @Range: 0 200258// @Increment: 0.5259// @User: Advanced260261// @Param: RAT_YAW_PDMX262// @DisplayName: Yaw axis rate controller PD sum maximum263// @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output264// @Range: 0 1265// @Increment: 0.01266267// @Param: RAT_YAW_D_FF268// @DisplayName: Yaw Derivative FeedForward Gain269// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target270// @Range: 0 0.02271// @Increment: 0.0001272// @User: Advanced273274// @Param: RAT_YAW_NTF275// @DisplayName: Yaw Target notch filter index276// @Description: Yaw Target notch filter index277// @Range: 1 8278// @User: Advanced279280// @Param: RAT_YAW_NEF281// @DisplayName: Yaw Error notch filter index282// @Description: Yaw Error notch filter index283// @Range: 1 8284// @User: Advanced285286AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Sub, AC_PID),287288// @Param: THR_MIX_MIN289// @DisplayName: Throttle Mix Minimum290// @Description: Throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)291// @Range: 0.1 0.25292// @User: Advanced293AP_GROUPINFO("THR_MIX_MIN", 4, AC_AttitudeControl_Sub, _thr_mix_min, AC_ATTITUDE_CONTROL_MIN_DEFAULT),294295// @Param: THR_MIX_MAX296// @DisplayName: Throttle Mix Maximum297// @Description: Throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)298// @Range: 0.5 0.9299// @User: Advanced300AP_GROUPINFO("THR_MIX_MAX", 5, AC_AttitudeControl_Sub, _thr_mix_max, AC_ATTITUDE_CONTROL_MAX_DEFAULT),301302// @Param: THR_MIX_MAN303// @DisplayName: Throttle Mix Manual304// @Description: Throttle vs attitude control prioritisation used during manual flight (higher values mean we prioritise attitude control over throttle)305// @Range: 0.5 0.9306// @User: Advanced307AP_GROUPINFO("THR_MIX_MAN", 6, AC_AttitudeControl_Sub, _thr_mix_man, AC_ATTITUDE_CONTROL_MAN_DEFAULT),308309// @Param: RAT_RLL_FILT310// @DisplayName: Roll axis rate controller input frequency in Hz311// @Description: Roll axis rate controller input frequency in Hz312// @Range: 1 100313// @Increment: 1314// @Units: Hz315// @User: Standard316317// @Param: RAT_PIT_FILT318// @DisplayName: Pitch axis rate controller input frequency in Hz319// @Description: Pitch axis rate controller input frequency in Hz320// @Range: 1 100321// @Increment: 1322// @Units: Hz323// @User: Standard324325// @Param: RAT_YAW_FILT326// @DisplayName: Yaw axis rate controller input frequency in Hz327// @Description: Yaw axis rate controller input frequency in Hz328// @Range: 1 100329// @Increment: 1330// @Units: Hz331// @User: Standard332333AP_GROUPEND334};335336AC_AttitudeControl_Sub::AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors) :337AC_AttitudeControl(ahrs, aparm, motors),338_motors_multi(motors)339{340AP_Param::setup_object_defaults(this, var_info);341342// Sub-specific defaults for parent class343_p_angle_roll.kP().set_default(AC_ATC_SUB_ANGLE_P);344_p_angle_pitch.kP().set_default(AC_ATC_SUB_ANGLE_P);345_p_angle_yaw.kP().set_default(AC_ATC_SUB_ANGLE_P);346347_accel_yaw_max.set_default(AC_ATC_SUB_ACCEL_Y_MAX);348}349350// Update Alt_Hold angle maximum351void AC_AttitudeControl_Sub::update_althold_lean_angle_max(float throttle_in)352{353// calc maximum tilt angle based on throttle354float thr_max = _motors_multi.get_throttle_thrust_max();355356// divide by zero check357if (is_zero(thr_max)) {358_althold_lean_angle_max = 0.0f;359return;360}361362float althold_lean_angle_max = acosf(constrain_float(throttle_in/(AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max), 0.0f, 1.0f));363_althold_lean_angle_max = _althold_lean_angle_max + (_dt/(_dt+_angle_limit_tc))*(althold_lean_angle_max-_althold_lean_angle_max);364}365366void AC_AttitudeControl_Sub::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)367{368_throttle_in = throttle_in;369update_althold_lean_angle_max(throttle_in);370_motors.set_throttle_filter_cutoff(filter_cutoff);371_motors.set_throttle(throttle_in);372_motors.set_throttle_avg_max(get_throttle_avg_max(MAX(throttle_in, _throttle_in)));373}374375// returns a throttle including compensation for roll/pitch angle376// throttle value should be 0 ~ 1377float AC_AttitudeControl_Sub::get_throttle_boosted(float throttle_in)378{379if (!_angle_boost_enabled) {380_angle_boost = 0;381return throttle_in;382}383// inverted_factor is 1 for tilt angles below 60 degrees384// inverted_factor reduces from 1 to 0 for tilt angles between 60 and 90 degrees385386float cos_tilt = _ahrs.cos_pitch() * _ahrs.cos_roll();387float inverted_factor = constrain_float(2.0f*cos_tilt, 0.0f, 1.0f);388float boost_factor = 1.0f/constrain_float(cos_tilt, 0.5f, 1.0f);389390float throttle_out = throttle_in*inverted_factor*boost_factor;391_angle_boost = constrain_float(throttle_out - throttle_in,-1.0f,1.0f);392return throttle_out;393}394395// returns a throttle including compensation for roll/pitch angle396// throttle value should be 0 ~ 1397float AC_AttitudeControl_Sub::get_throttle_avg_max(float throttle_in)398{399throttle_in = constrain_float(throttle_in, 0.0f, 1.0f);400return MAX(throttle_in, throttle_in*MAX(0.0f,1.0f-_throttle_rpy_mix)+_motors.get_throttle_hover()*_throttle_rpy_mix);401}402403// update_throttle_rpy_mix - slew set_throttle_rpy_mix to requested value404void AC_AttitudeControl_Sub::update_throttle_rpy_mix()405{406// slew _throttle_rpy_mix to _throttle_rpy_mix_desired407if (_throttle_rpy_mix < _throttle_rpy_mix_desired) {408// increase quickly (i.e. from 0.1 to 0.9 in 0.4 seconds)409_throttle_rpy_mix += MIN(2.0f*_dt, _throttle_rpy_mix_desired-_throttle_rpy_mix);410} else if (_throttle_rpy_mix > _throttle_rpy_mix_desired) {411// reduce more slowly (from 0.9 to 0.1 in 1.6 seconds)412_throttle_rpy_mix -= MIN(0.5f*_dt, _throttle_rpy_mix-_throttle_rpy_mix_desired);413}414_throttle_rpy_mix = constrain_float(_throttle_rpy_mix, 0.1f, AC_ATTITUDE_CONTROL_MAX);415}416417void AC_AttitudeControl_Sub::rate_controller_run()418{419// move throttle vs attitude mixing towards desired (called from here because this is conveniently called on every iteration)420update_throttle_rpy_mix();421422_rate_gyro = _ahrs.get_gyro_latest();423_rate_gyro_time_us = AP_HAL::micros64();424425_motors.set_roll(get_rate_roll_pid().update_all(_ang_vel_body.x, _rate_gyro.x, _dt, _motors.limit.roll));426_motors.set_pitch(get_rate_pitch_pid().update_all(_ang_vel_body.y, _rate_gyro.y, _dt, _motors.limit.pitch));427_motors.set_yaw(get_rate_yaw_pid().update_all(_ang_vel_body.z, _rate_gyro.z, _dt, _motors.limit.yaw));428429control_monitor_update();430}431432// sanity check parameters. should be called once before takeoff433void AC_AttitudeControl_Sub::parameter_sanity_check()434{435// sanity check throttle mix parameters436if (_thr_mix_man < 0.1f || _thr_mix_man > AC_ATTITUDE_CONTROL_MAN_LIMIT) {437// parameter description recommends thr-mix-man be no higher than 0.9 but we allow up to 4.0438// which can be useful for very high powered copters with very low hover throttle439_thr_mix_man.set_and_save(constrain_float(_thr_mix_man, 0.1, AC_ATTITUDE_CONTROL_MAN_LIMIT));440}441if (_thr_mix_min < 0.1f || _thr_mix_min > AC_ATTITUDE_CONTROL_MIN_LIMIT) {442_thr_mix_min.set_and_save(constrain_float(_thr_mix_min, 0.1, AC_ATTITUDE_CONTROL_MIN_LIMIT));443}444if (_thr_mix_max < 0.5f || _thr_mix_max > AC_ATTITUDE_CONTROL_MAX) {445// parameter description recommends thr-mix-max be no higher than 0.9 but we allow up to 5.0446// which can be useful for very high powered copters with very low hover throttle447_thr_mix_max.set_and_save(constrain_float(_thr_mix_max, 0.5, AC_ATTITUDE_CONTROL_MAX));448}449if (_thr_mix_min > _thr_mix_max) {450_thr_mix_min.set_and_save(AC_ATTITUDE_CONTROL_MIN_DEFAULT);451_thr_mix_max.set_and_save(AC_ATTITUDE_CONTROL_MAX_DEFAULT);452}453}454455// This function ensures that the ROV reaches the target orientation with the desired yaw rate456void AC_AttitudeControl_Sub::input_euler_angle_roll_pitch_slew_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, float target_yaw_rate)457{458// Convert from centidegrees on public interface to radians459const float euler_yaw_angle = wrap_PI(radians(euler_yaw_angle_cd * 0.01f));460461const float current_yaw = AP::ahrs().get_yaw();462463// Compute angle error464const float yaw_error = wrap_PI(euler_yaw_angle - current_yaw);465466int direction = 0;467if (yaw_error < 0){468direction = -1;469} else {470direction = 1;471}472473target_yaw_rate *= direction;474475476if (fabsf(yaw_error) > MAX_YAW_ERROR) {477// rotate the rov with desired yaw rate towards the target yaw478input_euler_angle_roll_pitch_euler_rate_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, target_yaw_rate);479} else {480// holds the rov's angles481input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_angle_cd, true);482}483}484485void AC_AttitudeControl_Sub::set_notch_sample_rate(float sample_rate)486{487#if AP_FILTER_ENABLED488_pid_rate_roll.set_notch_sample_rate(sample_rate);489_pid_rate_pitch.set_notch_sample_rate(sample_rate);490_pid_rate_yaw.set_notch_sample_rate(sample_rate);491#endif492}493494