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/APM_Control/AP_PitchController.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415// Initial Code by Jon Challinger16// Modified by Paul Riseborough1718#include <AP_HAL/AP_HAL.h>19#include "AP_PitchController.h"20#include <AP_AHRS/AP_AHRS.h>21#include <AP_Scheduler/AP_Scheduler.h>22#include <GCS_MAVLink/GCS.h>2324extern const AP_HAL::HAL& hal;2526const AP_Param::GroupInfo AP_PitchController::var_info[] = {2728// @Param: 2SRV_TCONST29// @DisplayName: Pitch Time Constant30// @Description: Time constant in seconds from demanded to achieved pitch angle. Most models respond well to 0.5. May be reduced for faster responses, but setting lower than a model can achieve will not help.31// @Range: 0.4 1.032// @Units: s33// @Increment: 0.134// @User: Advanced35AP_GROUPINFO("2SRV_TCONST", 0, AP_PitchController, gains.tau, 0.5f),3637// index 1 to 3 reserved for old PID values3839// @Param: 2SRV_RMAX_UP40// @DisplayName: Pitch up max rate41// @Description: This sets the maximum nose up pitch rate that the attitude controller will demand (degrees/sec) in angle stabilized modes. Setting it to zero disables the limit.42// @Range: 0 10043// @Units: deg/s44// @Increment: 145// @User: Advanced46AP_GROUPINFO("2SRV_RMAX_UP", 4, AP_PitchController, gains.rmax_pos, 0.0f),4748// @Param: 2SRV_RMAX_DN49// @DisplayName: Pitch down max rate50// @Description: This sets the maximum nose down pitch rate that the attitude controller will demand (degrees/sec) in angle stabilized modes. Setting it to zero disables the limit.51// @Range: 0 10052// @Units: deg/s53// @Increment: 154// @User: Advanced55AP_GROUPINFO("2SRV_RMAX_DN", 5, AP_PitchController, gains.rmax_neg, 0.0f),5657// @Param: 2SRV_RLL58// @DisplayName: Roll compensation59// @Description: Gain added to pitch to keep aircraft from descending or ascending in turns. Increase in increments of 0.05 to reduce altitude loss. Decrease for altitude gain.60// @Range: 0.7 1.561// @Increment: 0.0562// @User: Standard63AP_GROUPINFO("2SRV_RLL", 6, AP_PitchController, _roll_ff, 1.0f),6465// index 7, 8 reserved for old IMAX, FF6667// @Param: _RATE_P68// @DisplayName: Pitch axis rate controller P gain69// @Description: Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate70// @Range: 0.08 0.3571// @Increment: 0.00572// @User: Standard7374// @Param: _RATE_I75// @DisplayName: Pitch axis rate controller I gain76// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate77// @Range: 0.01 0.678// @Increment: 0.0179// @User: Standard8081// @Param: _RATE_IMAX82// @DisplayName: Pitch axis rate controller I gain maximum83// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output84// @Range: 0 185// @Increment: 0.0186// @User: Standard8788// @Param: _RATE_D89// @DisplayName: Pitch axis rate controller D gain90// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate91// @Range: 0.001 0.0392// @Increment: 0.00193// @User: Standard9495// @Param: _RATE_FF96// @DisplayName: Pitch axis rate controller feed forward97// @Description: Pitch axis rate controller feed forward98// @Range: 0 3.099// @Increment: 0.001100// @User: Standard101102// @Param: _RATE_FLTT103// @DisplayName: Pitch axis rate controller target frequency in Hz104// @Description: Pitch axis rate controller target frequency in Hz105// @Range: 2 50106// @Increment: 1107// @Units: Hz108// @User: Standard109110// @Param: _RATE_FLTE111// @DisplayName: Pitch axis rate controller error frequency in Hz112// @Description: Pitch axis rate controller error frequency in Hz113// @Range: 2 50114// @Increment: 1115// @Units: Hz116// @User: Standard117118// @Param: _RATE_FLTD119// @DisplayName: Pitch axis rate controller derivative frequency in Hz120// @Description: Pitch axis rate controller derivative frequency in Hz121// @Range: 0 50122// @Increment: 1123// @Units: Hz124// @User: Standard125126// @Param: _RATE_SMAX127// @DisplayName: Pitch slew rate limit128// @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.129// @Range: 0 200130// @Increment: 0.5131// @User: Advanced132133// @Param: _RATE_PDMX134// @DisplayName: Pitch axis rate controller PD sum maximum135// @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output136// @Range: 0 1137// @Increment: 0.01138139// @Param: _RATE_D_FF140// @DisplayName: Pitch Derivative FeedForward Gain141// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target142// @Range: 0 0.03143// @Increment: 0.001144// @User: Advanced145146// @Param: _RATE_NTF147// @DisplayName: Pitch Target notch filter index148// @Description: Pitch Target notch filter index149// @Range: 1 8150// @User: Advanced151152// @Param: _RATE_NEF153// @DisplayName: Pitch Error notch filter index154// @Description: Pitch Error notch filter index155// @Range: 1 8156// @User: Advanced157158AP_SUBGROUPINFO(rate_pid, "_RATE_", 11, AP_PitchController, AC_PID),159160AP_GROUPEND161};162163AP_PitchController::AP_PitchController(const AP_FixedWing &parms)164: aparm(parms)165{166AP_Param::setup_object_defaults(this, var_info);167rate_pid.set_slew_limit_scale(45);168}169170/*171AC_PID based rate controller172*/173float AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed, bool ground_mode)174{175const float dt = AP::scheduler().get_loop_period_s();176177const AP_AHRS &_ahrs = AP::ahrs();178179const float eas2tas = _ahrs.get_EAS2TAS();180bool limit_I = fabsf(_last_out) >= 45;181float rate_y = _ahrs.get_gyro().y;182float old_I = rate_pid.get_i();183184bool underspeed = aspeed <= 0.5*float(aparm.airspeed_min);185if (underspeed) {186limit_I = true;187}188189// the P and I elements are scaled by sq(scaler). To use an190// unmodified AC_PID object we scale the inputs and calculate FF separately191//192// note that we run AC_PID in radians so that the normal scaling193// range for IMAX in AC_PID applies (usually an IMAX value less than 1.0)194rate_pid.update_all(radians(desired_rate) * scaler * scaler, rate_y * scaler * scaler, dt, limit_I);195196if (underspeed) {197// when underspeed we lock the integrator198rate_pid.set_integrator(old_I);199}200201// FF should be scaled by scaler/eas2tas, but since we have scaled202// the AC_PID target above by scaler*scaler we need to instead203// divide by scaler*eas2tas to get the right scaling204const float ff = degrees(ff_scale * rate_pid.get_ff() / (scaler * eas2tas));205ff_scale = 1.0;206207if (disable_integrator) {208rate_pid.reset_I();209}210211// convert AC_PID info object to same scale as old controller212_pid_info = rate_pid.get_pid_info();213auto &pinfo = _pid_info;214215const float deg_scale = degrees(1);216pinfo.FF = ff;217pinfo.P *= deg_scale;218pinfo.I *= deg_scale;219pinfo.D *= deg_scale;220pinfo.DFF *= deg_scale;221222// fix the logged target and actual values to not have the scalers applied223pinfo.target = desired_rate;224pinfo.actual = degrees(rate_y);225226// sum components227float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D + pinfo.DFF;228if (ground_mode) {229// when on ground suppress D and half P term to prevent oscillations230out -= pinfo.D + 0.5*pinfo.P;231}232233// remember the last output to trigger the I limit234_last_out = out;235236if (autotune != nullptr && autotune->running && aspeed > aparm.airspeed_min) {237// let autotune have a go at the values238autotune->update(pinfo, scaler, angle_err_deg);239}240241// output is scaled to notional centidegrees of deflection242return constrain_float(out * 100, -4500, 4500);243}244245/*246Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500247A positive demand is up248Inputs are:2491) demanded pitch rate in degrees/second2502) control gain scaler = scaling_speed / aspeed2513) boolean which is true when stabilise mode is active2524) minimum FBW airspeed (metres/sec)2535) maximum FBW airspeed (metres/sec)254*/255float AP_PitchController::get_rate_out(float desired_rate, float scaler)256{257float aspeed;258if (!AP::ahrs().airspeed_estimate(aspeed)) {259// If no airspeed available use average of min and max260aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max));261}262return _get_rate_out(desired_rate, scaler, false, aspeed, false);263}264265/*266get the rate offset in degrees/second needed for pitch in body frame267to maintain height in a coordinated turn.268269Also returns the inverted flag and the estimated airspeed in m/s for270use by the rest of the pitch controller271*/272float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inverted) const273{274float rate_offset;275float bank_angle = AP::ahrs().get_roll();276277// limit bank angle between +- 80 deg if right way up278if (fabsf(bank_angle) < radians(90)) {279bank_angle = constrain_float(bank_angle,-radians(80),radians(80));280inverted = false;281} else {282inverted = true;283if (bank_angle > 0.0f) {284bank_angle = constrain_float(bank_angle,radians(100),radians(180));285} else {286bank_angle = constrain_float(bank_angle,-radians(180),-radians(100));287}288}289const AP_AHRS &_ahrs = AP::ahrs();290if (!_ahrs.airspeed_estimate(aspeed)) {291// If no airspeed available use average of min and max292aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max));293}294if (abs(_ahrs.pitch_sensor) > 7000) {295// don't do turn coordination handling when at very high pitch angles296rate_offset = 0;297} else {298rate_offset = cosf(_ahrs.get_pitch())*fabsf(ToDeg((GRAVITY_MSS / MAX((aspeed * _ahrs.get_EAS2TAS()), MAX(aparm.airspeed_min, 1))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff;299}300if (inverted) {301rate_offset = -rate_offset;302}303return rate_offset;304}305306// Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500307// A positive demand is up308// Inputs are:309// 1) demanded pitch angle in centi-degrees310// 2) control gain scaler = scaling_speed / aspeed311// 3) boolean which is true when stabilise mode is active312// 4) minimum FBW airspeed (metres/sec)313// 5) maximum FBW airspeed (metres/sec)314//315float AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode)316{317// Calculate offset to pitch rate demand required to maintain pitch angle whilst banking318// Calculate ideal turn rate from bank angle and airspeed assuming a level coordinated turn319// Pitch rate offset is the component of turn rate about the pitch axis320float aspeed;321float rate_offset;322bool inverted;323324if (gains.tau < 0.05f) {325gains.tau.set(0.05f);326}327328rate_offset = _get_coordination_rate_offset(aspeed, inverted);329330// Calculate the desired pitch rate (deg/sec) from the angle error331angle_err_deg = angle_err * 0.01;332float desired_rate = angle_err_deg / gains.tau;333334// limit the maximum pitch rate demand. Don't apply when inverted335// as the rates will be tuned when upright, and it is common that336// much higher rates are needed inverted337if (!inverted) {338desired_rate += rate_offset;339if (gains.rmax_neg && desired_rate < -gains.rmax_neg) {340desired_rate = -gains.rmax_neg;341} else if (gains.rmax_pos && desired_rate > gains.rmax_pos) {342desired_rate = gains.rmax_pos;343}344} else {345// Make sure not to invert the turn coordination offset346desired_rate = -desired_rate + rate_offset;347}348349/*350when we are past the users defined roll limit for the aircraft351our priority should be to bring the aircraft back within the352roll limit. Using elevator for pitch control at large roll353angles is ineffective, and can be counter productive as it354induces earth-frame yaw which can reduce the ability to roll. We355linearly reduce pitch demanded rate when beyond the configured356roll limit, reducing to zero at 90 degrees357*/358const AP_AHRS &_ahrs = AP::ahrs();359float roll_wrapped = labs(_ahrs.roll_sensor);360if (roll_wrapped > 9000) {361roll_wrapped = 18000 - roll_wrapped;362}363const float roll_limit_margin = MIN(aparm.roll_limit*100 + 500.0, 8500.0);364if (roll_wrapped > roll_limit_margin && labs(_ahrs.pitch_sensor) < 7000) {365float roll_prop = (roll_wrapped - roll_limit_margin) / (float)(9000 - roll_limit_margin);366desired_rate *= (1 - roll_prop);367}368369return _get_rate_out(desired_rate, scaler, disable_integrator, aspeed, ground_mode);370}371372void AP_PitchController::reset_I()373{374rate_pid.reset_I();375}376377/*378convert from old to new PIDs379this is a temporary conversion function during development380*/381void AP_PitchController::convert_pid()382{383AP_Float &ff = rate_pid.ff();384if (ff.configured()) {385return;386}387388float old_ff=0, old_p=1.0, old_i=0.3, old_d=0.08;389int16_t old_imax = 3000;390bool have_old = AP_Param::get_param_by_index(this, 1, AP_PARAM_FLOAT, &old_p);391have_old |= AP_Param::get_param_by_index(this, 3, AP_PARAM_FLOAT, &old_i);392have_old |= AP_Param::get_param_by_index(this, 2, AP_PARAM_FLOAT, &old_d);393have_old |= AP_Param::get_param_by_index(this, 8, AP_PARAM_FLOAT, &old_ff);394have_old |= AP_Param::get_param_by_index(this, 7, AP_PARAM_FLOAT, &old_imax);395if (!have_old) {396// none of the old gains were set397return;398}399400const float kp_ff = MAX((old_p - old_i * gains.tau) * gains.tau - old_d, 0);401rate_pid.ff().set_and_save(old_ff + kp_ff);402rate_pid.kI().set_and_save_ifchanged(old_i * gains.tau);403rate_pid.kP().set_and_save_ifchanged(old_d);404rate_pid.kD().set_and_save_ifchanged(0);405rate_pid.kIMAX().set_and_save_ifchanged(old_imax/4500.0);406}407408/*409start an autotune410*/411void AP_PitchController::autotune_start(void)412{413if (autotune == nullptr) {414autotune = NEW_NOTHROW AP_AutoTune(gains, AP_AutoTune::AUTOTUNE_PITCH, aparm, rate_pid);415if (autotune == nullptr) {416if (!failed_autotune_alloc) {417GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "AutoTune: failed pitch allocation");418}419failed_autotune_alloc = true;420}421}422if (autotune != nullptr) {423autotune->start();424}425}426427/*428restore autotune gains429*/430void AP_PitchController::autotune_restore(void)431{432if (autotune != nullptr) {433autotune->stop();434}435}436437438