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_Multi.cpp
Views: 1798
#include "AC_AttitudeControl_Multi.h"1#include <AP_HAL/AP_HAL.h>2#include <AP_Math/AP_Math.h>3#include <AC_PID/AC_PID.h>4#include <AP_Scheduler/AP_Scheduler.h>56// table of user settable parameters7const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {8// parameters from parent vehicle9AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),1011// @Param: RAT_RLL_P12// @DisplayName: Roll axis rate controller P gain13// @Description: Roll axis rate controller P gain. Corrects in proportion to the difference between the desired roll rate vs actual roll rate14// @Range: 0.01 0.515// @Increment: 0.00516// @User: Standard1718// @Param: RAT_RLL_I19// @DisplayName: Roll axis rate controller I gain20// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate21// @Range: 0.01 2.022// @Increment: 0.0123// @User: Standard2425// @Param: RAT_RLL_IMAX26// @DisplayName: Roll axis rate controller I gain maximum27// @Description: Roll axis rate controller I gain maximum. Constrains the maximum that the I term will output28// @Range: 0 129// @Increment: 0.0130// @User: Standard3132// @Param: RAT_RLL_D33// @DisplayName: Roll axis rate controller D gain34// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate35// @Range: 0.0 0.0536// @Increment: 0.00137// @User: Standard3839// @Param: RAT_RLL_FF40// @DisplayName: Roll axis rate controller feed forward41// @Description: Roll axis rate controller feed forward42// @Range: 0 0.543// @Increment: 0.00144// @User: Standard4546// @Param: RAT_RLL_FLTT47// @DisplayName: Roll axis rate controller target frequency in Hz48// @Description: Roll axis rate controller target frequency in Hz49// @Range: 5 10050// @Increment: 151// @Units: Hz52// @User: Standard5354// @Param: RAT_RLL_FLTE55// @DisplayName: Roll axis rate controller error frequency in Hz56// @Description: Roll axis rate controller error frequency in Hz57// @Range: 0 10058// @Increment: 159// @Units: Hz60// @User: Standard6162// @Param: RAT_RLL_FLTD63// @DisplayName: Roll axis rate controller derivative frequency in Hz64// @Description: Roll axis rate controller derivative frequency in Hz65// @Range: 5 10066// @Increment: 167// @Units: Hz68// @User: Standard6970// @Param: RAT_RLL_SMAX71// @DisplayName: Roll slew rate limit72// @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.73// @Range: 0 20074// @Increment: 0.575// @User: Advanced7677// @Param: RAT_RLL_PDMX78// @DisplayName: Roll axis rate controller PD sum maximum79// @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output80// @Range: 0 181// @Increment: 0.018283// @Param: RAT_RLL_D_FF84// @DisplayName: Roll Derivative FeedForward Gain85// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target86// @Range: 0 0.0287// @Increment: 0.000188// @User: Advanced8990// @Param: RAT_RLL_NTF91// @DisplayName: Roll Target notch filter index92// @Description: Roll Target notch filter index93// @Range: 1 894// @User: Advanced9596// @Param: RAT_RLL_NEF97// @DisplayName: Roll Error notch filter index98// @Description: Roll Error notch filter index99// @Range: 1 8100// @User: Advanced101102AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Multi, AC_PID),103104// @Param: RAT_PIT_P105// @DisplayName: Pitch axis rate controller P gain106// @Description: Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate output107// @Range: 0.01 0.50108// @Increment: 0.005109// @User: Standard110111// @Param: RAT_PIT_I112// @DisplayName: Pitch axis rate controller I gain113// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate114// @Range: 0.01 2.0115// @Increment: 0.01116// @User: Standard117118// @Param: RAT_PIT_IMAX119// @DisplayName: Pitch axis rate controller I gain maximum120// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output121// @Range: 0 1122// @Increment: 0.01123// @User: Standard124125// @Param: RAT_PIT_D126// @DisplayName: Pitch axis rate controller D gain127// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate128// @Range: 0.0 0.05129// @Increment: 0.001130// @User: Standard131132// @Param: RAT_PIT_FF133// @DisplayName: Pitch axis rate controller feed forward134// @Description: Pitch axis rate controller feed forward135// @Range: 0 0.5136// @Increment: 0.001137// @User: Standard138139// @Param: RAT_PIT_FLTT140// @DisplayName: Pitch axis rate controller target frequency in Hz141// @Description: Pitch axis rate controller target frequency in Hz142// @Range: 5 100143// @Increment: 1144// @Units: Hz145// @User: Standard146147// @Param: RAT_PIT_FLTE148// @DisplayName: Pitch axis rate controller error frequency in Hz149// @Description: Pitch axis rate controller error frequency in Hz150// @Range: 0 100151// @Increment: 1152// @Units: Hz153// @User: Standard154155// @Param: RAT_PIT_FLTD156// @DisplayName: Pitch axis rate controller derivative frequency in Hz157// @Description: Pitch axis rate controller derivative frequency in Hz158// @Range: 5 100159// @Increment: 1160// @Units: Hz161// @User: Standard162163// @Param: RAT_PIT_SMAX164// @DisplayName: Pitch slew rate limit165// @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.166// @Range: 0 200167// @Increment: 0.5168// @User: Advanced169170// @Param: RAT_PIT_PDMX171// @DisplayName: Pitch axis rate controller PD sum maximum172// @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output173// @Range: 0 1174// @Increment: 0.01175176// @Param: RAT_PIT_D_FF177// @DisplayName: Pitch Derivative FeedForward Gain178// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target179// @Range: 0 0.02180// @Increment: 0.0001181// @User: Advanced182183// @Param: RAT_PIT_NTF184// @DisplayName: Pitch Target notch filter index185// @Description: Pitch Target notch filter index186// @Range: 1 8187// @User: Advanced188189// @Param: RAT_PIT_NEF190// @DisplayName: Pitch Error notch filter index191// @Description: Pitch Error notch filter index192// @Range: 1 8193// @User: Advanced194195AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Multi, AC_PID),196197// @Param: RAT_YAW_P198// @DisplayName: Yaw axis rate controller P gain199// @Description: Yaw axis rate controller P gain. Corrects in proportion to the difference between the desired yaw rate vs actual yaw rate200// @Range: 0.10 2.50201// @Increment: 0.005202// @User: Standard203204// @Param: RAT_YAW_I205// @DisplayName: Yaw axis rate controller I gain206// @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate207// @Range: 0.010 1.0208// @Increment: 0.01209// @User: Standard210211// @Param: RAT_YAW_IMAX212// @DisplayName: Yaw axis rate controller I gain maximum213// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum that the I term will output214// @Range: 0 1215// @Increment: 0.01216// @User: Standard217218// @Param: RAT_YAW_D219// @DisplayName: Yaw axis rate controller D gain220// @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate221// @Range: 0.000 0.02222// @Increment: 0.001223// @User: Standard224225// @Param: RAT_YAW_FF226// @DisplayName: Yaw axis rate controller feed forward227// @Description: Yaw axis rate controller feed forward228// @Range: 0 0.5229// @Increment: 0.001230// @User: Standard231232// @Param: RAT_YAW_FLTT233// @DisplayName: Yaw axis rate controller target frequency in Hz234// @Description: Yaw axis rate controller target frequency in Hz235// @Range: 1 50236// @Increment: 1237// @Units: Hz238// @User: Standard239240// @Param: RAT_YAW_FLTE241// @DisplayName: Yaw axis rate controller error frequency in Hz242// @Description: Yaw axis rate controller error frequency in Hz243// @Range: 0 20244// @Increment: 1245// @Units: Hz246// @User: Standard247248// @Param: RAT_YAW_FLTD249// @DisplayName: Yaw axis rate controller derivative frequency in Hz250// @Description: Yaw axis rate controller derivative frequency in Hz251// @Range: 5 50252// @Increment: 1253// @Units: Hz254// @User: Standard255256// @Param: RAT_YAW_SMAX257// @DisplayName: Yaw slew rate limit258// @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.259// @Range: 0 200260// @Increment: 0.5261// @User: Advanced262263// @Param: RAT_YAW_PDMX264// @DisplayName: Yaw axis rate controller PD sum maximum265// @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output266// @Range: 0 1267// @Increment: 0.01268269// @Param: RAT_YAW_D_FF270// @DisplayName: Yaw Derivative FeedForward Gain271// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target272// @Range: 0 0.02273// @Increment: 0.0001274// @User: Advanced275276// @Param: RAT_YAW_NTF277// @DisplayName: Yaw Target notch filter index278// @Description: Yaw Target notch filter index279// @Range: 1 8280// @Units: Hz281// @User: Advanced282283// @Param: RAT_YAW_NEF284// @DisplayName: Yaw Error notch filter index285// @Description: Yaw Error notch filter index286// @Range: 1 8287// @User: Advanced288289AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Multi, AC_PID),290291// @Param: THR_MIX_MIN292// @DisplayName: Throttle Mix Minimum293// @Description: Throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)294// @Range: 0.1 0.25295// @User: Advanced296AP_GROUPINFO("THR_MIX_MIN", 4, AC_AttitudeControl_Multi, _thr_mix_min, AC_ATTITUDE_CONTROL_MIN_DEFAULT),297298// @Param: THR_MIX_MAX299// @DisplayName: Throttle Mix Maximum300// @Description: Throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)301// @Range: 0.5 0.9302// @User: Advanced303AP_GROUPINFO("THR_MIX_MAX", 5, AC_AttitudeControl_Multi, _thr_mix_max, AC_ATTITUDE_CONTROL_MAX_DEFAULT),304305// @Param: THR_MIX_MAN306// @DisplayName: Throttle Mix Manual307// @Description: Throttle vs attitude control prioritisation used during manual flight (higher values mean we prioritise attitude control over throttle)308// @Range: 0.1 0.9309// @User: Advanced310AP_GROUPINFO("THR_MIX_MAN", 6, AC_AttitudeControl_Multi, _thr_mix_man, AC_ATTITUDE_CONTROL_MAN_DEFAULT),311312// @Param: THR_G_BOOST313// @DisplayName: Throttle-gain boost314// @Description: Throttle-gain boost ratio. A value of 0 means no boosting is applied, a value of 1 means full boosting is applied. Describes the ratio increase that is applied to angle P and PD on pitch and roll.315// @Range: 0 1316// @User: Advanced317AP_GROUPINFO("THR_G_BOOST", 7, AC_AttitudeControl_Multi, _throttle_gain_boost, 0.0f),318319AP_GROUPEND320};321322AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors) :323AC_AttitudeControl(ahrs, aparm, motors),324_motors_multi(motors)325{326AP_Param::setup_object_defaults(this, var_info);327328#if AP_FILTER_ENABLED329set_notch_sample_rate(AP::scheduler().get_loop_rate_hz());330#endif331}332333// Update Alt_Hold angle maximum334void AC_AttitudeControl_Multi::update_althold_lean_angle_max(float throttle_in)335{336// calc maximum tilt angle based on throttle337float thr_max = _motors_multi.get_throttle_thrust_max();338339// divide by zero check340if (is_zero(thr_max)) {341_althold_lean_angle_max = 0.0f;342return;343}344345float althold_lean_angle_max = acosf(constrain_float(throttle_in / (AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX * thr_max), 0.0f, 1.0f));346_althold_lean_angle_max = _althold_lean_angle_max + (_dt / (_dt + _angle_limit_tc)) * (althold_lean_angle_max - _althold_lean_angle_max);347}348349void AC_AttitudeControl_Multi::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)350{351_throttle_in = throttle_in;352update_althold_lean_angle_max(throttle_in);353_motors.set_throttle_filter_cutoff(filter_cutoff);354if (apply_angle_boost) {355// Apply angle boost356throttle_in = get_throttle_boosted(throttle_in);357} else {358// Clear angle_boost for logging purposes359_angle_boost = 0.0f;360}361_motors.set_throttle(throttle_in);362_motors.set_throttle_avg_max(get_throttle_avg_max(MAX(throttle_in, _throttle_in)));363}364365void AC_AttitudeControl_Multi::set_throttle_mix_max(float ratio)366{367ratio = constrain_float(ratio, 0.0f, 1.0f);368_throttle_rpy_mix_desired = (1.0f - ratio) * _thr_mix_min + ratio * _thr_mix_max;369}370371// returns a throttle including compensation for roll/pitch angle372// throttle value should be 0 ~ 1373float AC_AttitudeControl_Multi::get_throttle_boosted(float throttle_in)374{375if (!_angle_boost_enabled) {376_angle_boost = 0;377return throttle_in;378}379// inverted_factor is 1 for tilt angles below 60 degrees380// inverted_factor reduces from 1 to 0 for tilt angles between 60 and 90 degrees381382float cos_tilt = _ahrs.cos_pitch() * _ahrs.cos_roll();383float inverted_factor = constrain_float(10.0f * cos_tilt, 0.0f, 1.0f);384float cos_tilt_target = cosf(_thrust_angle);385float boost_factor = 1.0f / constrain_float(cos_tilt_target, 0.1f, 1.0f);386387float throttle_out = throttle_in * inverted_factor * boost_factor;388_angle_boost = constrain_float(throttle_out - throttle_in, -1.0f, 1.0f);389return throttle_out;390}391392// returns a throttle including compensation for roll/pitch angle393// throttle value should be 0 ~ 1394float AC_AttitudeControl_Multi::get_throttle_avg_max(float throttle_in)395{396throttle_in = constrain_float(throttle_in, 0.0f, 1.0f);397return MAX(throttle_in, throttle_in * MAX(0.0f, 1.0f - _throttle_rpy_mix) + _motors.get_throttle_hover() * _throttle_rpy_mix);398}399400// update_throttle_gain_boost - boost angle_p/pd each cycle on high throttle slew401void AC_AttitudeControl_Multi::update_throttle_gain_boost()402{403// Boost PD and Angle P on very rapid throttle changes404if (_motors.get_throttle_slew_rate() > AC_ATTITUDE_CONTROL_THR_G_BOOST_THRESH) {405const float pd_boost = constrain_float(_throttle_gain_boost + 1.0f, 1.0, 2.0);406set_PD_scale_mult(Vector3f(pd_boost, pd_boost, 1.0f));407408const float angle_p_boost = constrain_float((_throttle_gain_boost + 1.0f) * (_throttle_gain_boost + 1.0f), 1.0, 4.0);409set_angle_P_scale_mult(Vector3f(angle_p_boost, angle_p_boost, 1.0f));410}411}412413// update_throttle_rpy_mix - slew set_throttle_rpy_mix to requested value414void AC_AttitudeControl_Multi::update_throttle_rpy_mix()415{416// slew _throttle_rpy_mix to _throttle_rpy_mix_desired417if (_throttle_rpy_mix < _throttle_rpy_mix_desired) {418// increase quickly (i.e. from 0.1 to 0.9 in 0.4 seconds)419_throttle_rpy_mix += MIN(2.0f * _dt, _throttle_rpy_mix_desired - _throttle_rpy_mix);420} else if (_throttle_rpy_mix > _throttle_rpy_mix_desired) {421// reduce more slowly (from 0.9 to 0.1 in 1.6 seconds)422_throttle_rpy_mix -= MIN(0.5f * _dt, _throttle_rpy_mix - _throttle_rpy_mix_desired);423424// if the mix is still higher than that being used, reset immediately425const float throttle_hover = _motors.get_throttle_hover();426const float throttle_in = _motors.get_throttle();427const float throttle_out = MAX(_motors.get_throttle_out(), throttle_in);428float mix_used;429// since throttle_out >= throttle_in at this point we don't need to check throttle_in < throttle_hover430if (throttle_out < throttle_hover) {431mix_used = (throttle_out - throttle_in) / (throttle_hover - throttle_in);432} else {433mix_used = throttle_out / throttle_hover;434}435436_throttle_rpy_mix = MIN(_throttle_rpy_mix, MAX(mix_used, _throttle_rpy_mix_desired));437}438_throttle_rpy_mix = constrain_float(_throttle_rpy_mix, 0.1f, AC_ATTITUDE_CONTROL_MAX);439}440441void AC_AttitudeControl_Multi::rate_controller_run_dt(const Vector3f& gyro, float dt)442{443// take a copy of the target so that it can't be changed from under us.444Vector3f ang_vel_body = _ang_vel_body;445446// boost angle_p/pd each cycle on high throttle slew447update_throttle_gain_boost();448449// move throttle vs attitude mixing towards desired (called from here because this is conveniently called on every iteration)450update_throttle_rpy_mix();451452ang_vel_body += _sysid_ang_vel_body;453454_rate_gyro = gyro;455_rate_gyro_time_us = AP_HAL::micros64();456457_motors.set_roll(get_rate_roll_pid().update_all(ang_vel_body.x, gyro.x, dt, _motors.limit.roll, _pd_scale.x) + _actuator_sysid.x);458_motors.set_roll_ff(get_rate_roll_pid().get_ff());459460_motors.set_pitch(get_rate_pitch_pid().update_all(ang_vel_body.y, gyro.y, dt, _motors.limit.pitch, _pd_scale.y) + _actuator_sysid.y);461_motors.set_pitch_ff(get_rate_pitch_pid().get_ff());462463_motors.set_yaw(get_rate_yaw_pid().update_all(ang_vel_body.z, gyro.z, dt, _motors.limit.yaw, _pd_scale.z) + _actuator_sysid.z);464_motors.set_yaw_ff(get_rate_yaw_pid().get_ff()*_feedforward_scalar);465466_pd_scale_used = _pd_scale;467468control_monitor_update();469}470471// reset the rate controller target loop updates472void AC_AttitudeControl_Multi::rate_controller_target_reset()473{474_sysid_ang_vel_body.zero();475_actuator_sysid.zero();476_pd_scale = VECTORF_111;477}478479// run the rate controller using the configured _dt and latest gyro480void AC_AttitudeControl_Multi::rate_controller_run()481{482Vector3f gyro_latest = _ahrs.get_gyro_latest();483rate_controller_run_dt(gyro_latest, _dt);484}485486// sanity check parameters. should be called once before takeoff487void AC_AttitudeControl_Multi::parameter_sanity_check()488{489// sanity check throttle mix parameters490if (_thr_mix_man < 0.1f || _thr_mix_man > AC_ATTITUDE_CONTROL_MAN_LIMIT) {491// parameter description recommends thr-mix-man be no higher than 0.9 but we allow up to 4.0492// which can be useful for very high powered copters with very low hover throttle493_thr_mix_man.set_and_save(constrain_float(_thr_mix_man, 0.1, AC_ATTITUDE_CONTROL_MAN_LIMIT));494}495if (_thr_mix_min < 0.1f || _thr_mix_min > AC_ATTITUDE_CONTROL_MIN_LIMIT) {496_thr_mix_min.set_and_save(constrain_float(_thr_mix_min, 0.1, AC_ATTITUDE_CONTROL_MIN_LIMIT));497}498if (_thr_mix_max < 0.5f || _thr_mix_max > AC_ATTITUDE_CONTROL_MAX) {499// parameter description recommends thr-mix-max be no higher than 0.9 but we allow up to 5.0500// which can be useful for very high powered copters with very low hover throttle501_thr_mix_max.set_and_save(constrain_float(_thr_mix_max, 0.5, AC_ATTITUDE_CONTROL_MAX));502}503if (_thr_mix_min > _thr_mix_max) {504_thr_mix_min.set_and_save(AC_ATTITUDE_CONTROL_MIN_DEFAULT);505_thr_mix_max.set_and_save(AC_ATTITUDE_CONTROL_MAX_DEFAULT);506}507}508509void AC_AttitudeControl_Multi::set_notch_sample_rate(float sample_rate)510{511#if AP_FILTER_ENABLED512_pid_rate_roll.set_notch_sample_rate(sample_rate);513_pid_rate_pitch.set_notch_sample_rate(sample_rate);514_pid_rate_yaw.set_notch_sample_rate(sample_rate);515#endif516}517518519