Path: blob/master/libraries/APM_Control/AP_PitchController.cpp
9398 views
/*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>2223extern const AP_HAL::HAL& hal;2425const AP_Param::GroupInfo AP_PitchController::var_info[] = {2627// @Param: 2SRV_TCONST28// @DisplayName: Pitch Time Constant29// @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.30// @Range: 0.4 1.031// @Units: s32// @Increment: 0.133// @User: Advanced34AP_GROUPINFO("2SRV_TCONST", 0, AP_PitchController, gains.tau, 0.5f),3536// index 1 to 3 reserved for old PID values3738// @Param: 2SRV_RMAX_UP39// @DisplayName: Pitch up max rate40// @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.41// @Range: 0 10042// @Units: deg/s43// @Increment: 144// @User: Advanced45AP_GROUPINFO("2SRV_RMAX_UP", 4, AP_PitchController, gains.rmax_pos, 0.0f),4647// @Param: 2SRV_RMAX_DN48// @DisplayName: Pitch down max rate49// @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.50// @Range: 0 10051// @Units: deg/s52// @Increment: 153// @User: Advanced54AP_GROUPINFO("2SRV_RMAX_DN", 5, AP_PitchController, gains.rmax_neg, 0.0f),5556// @Param: 2SRV_RLL57// @DisplayName: Roll compensation58// @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.59// @Range: 0.7 1.560// @Increment: 0.0561// @User: Standard62AP_GROUPINFO("2SRV_RLL", 6, AP_PitchController, _roll_ff, 1.0f),6364// index 7, 8 reserved for old IMAX, FF6566// @Param: _RATE_P67// @DisplayName: Pitch axis rate controller P gain68// @Description: Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate69// @Range: 0.08 0.3570// @Increment: 0.00571// @User: Standard7273// @Param: _RATE_I74// @DisplayName: Pitch axis rate controller I gain75// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate76// @Range: 0.01 0.677// @Increment: 0.0178// @User: Standard7980// @Param: _RATE_IMAX81// @DisplayName: Pitch axis rate controller I gain maximum82// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output83// @Range: 0 184// @Increment: 0.0185// @User: Standard8687// @Param: _RATE_D88// @DisplayName: Pitch axis rate controller D gain89// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate90// @Range: 0.001 0.0391// @Increment: 0.00192// @User: Standard9394// @Param: _RATE_FF95// @DisplayName: Pitch axis rate controller feed forward96// @Description: Pitch axis rate controller feed forward97// @Range: 0 3.098// @Increment: 0.00199// @User: Standard100101// @Param: _RATE_FLTT102// @DisplayName: Pitch axis rate controller target frequency in Hz103// @Description: Pitch axis rate controller target frequency in Hz104// @Range: 2 50105// @Increment: 1106// @Units: Hz107// @User: Standard108109// @Param: _RATE_FLTE110// @DisplayName: Pitch axis rate controller error frequency in Hz111// @Description: Pitch axis rate controller error frequency in Hz112// @Range: 2 50113// @Increment: 1114// @Units: Hz115// @User: Standard116117// @Param: _RATE_FLTD118// @DisplayName: Pitch axis rate controller derivative frequency in Hz119// @Description: Pitch axis rate controller derivative frequency in Hz120// @Range: 0 50121// @Increment: 1122// @Units: Hz123// @User: Standard124125// @Param: _RATE_SMAX126// @DisplayName: Pitch slew rate limit127// @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.128// @Range: 0 200129// @Increment: 0.5130// @User: Advanced131132// @Param: _RATE_PDMX133// @DisplayName: Pitch axis rate controller PD sum maximum134// @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output135// @Range: 0 1136// @Increment: 0.01137138// @Param: _RATE_D_FF139// @DisplayName: Pitch Derivative FeedForward Gain140// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target141// @Range: 0 0.03142// @Increment: 0.001143// @User: Advanced144145// @Param: _RATE_NTF146// @DisplayName: Pitch Target notch filter index147// @Description: Pitch Target notch filter index148// @Range: 1 8149// @User: Advanced150151// @Param: _RATE_NEF152// @DisplayName: Pitch Error notch filter index153// @Description: Pitch Error notch filter index154// @Range: 1 8155// @User: Advanced156157AP_SUBGROUPINFO(rate_pid, "_RATE_", 11, AP_PitchController, AC_PID),158159AP_GROUPEND160};161162AP_PitchController::AP_PitchController(const AP_FixedWing &parms)163: AP_FW_Controller(parms,164AC_PID::Defaults{165.p = 0.04,166.i = 0.15,167.d = 0.0,168.ff = 0.345,169.imax = 0.666,170.filt_T_hz = 3.0,171.filt_E_hz = 0.0,172.filt_D_hz = 12.0,173.srmax = 150.0,174.srtau = 1.0175},176AP_AutoTune::ATType::AUTOTUNE_PITCH)177{178AP_Param::setup_object_defaults(this, var_info);179}180181float AP_PitchController::get_measured_rate() const182{183return AP::ahrs().get_gyro().y;184}185186float AP_PitchController::get_airspeed() const187{188float aspeed;189if (!AP::ahrs().airspeed_EAS(aspeed)) {190// If no airspeed available use average of min and max191aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max));192}193return aspeed;194}195196bool AP_PitchController::is_underspeed(const float aspeed) const197{198return aspeed <= 0.5*float(aparm.airspeed_min);199}200201/*202get the rate offset in degrees/second needed for pitch in body frame203to maintain height in a coordinated turn.204205Also returns the inverted flag and the estimated airspeed in m/s for206use by the rest of the pitch controller207*/208float AP_PitchController::_get_coordination_rate_offset(const float &aspeed, bool &inverted) const209{210float rate_offset;211float bank_angle = AP::ahrs().get_roll_rad();212213// limit bank angle between +- 80 deg if right way up214if (fabsf(bank_angle) < radians(90)) {215bank_angle = constrain_float(bank_angle,-radians(80),radians(80));216inverted = false;217} else {218inverted = true;219if (bank_angle > 0.0f) {220bank_angle = constrain_float(bank_angle,radians(100),radians(180));221} else {222bank_angle = constrain_float(bank_angle,-radians(180),-radians(100));223}224}225const AP_AHRS &_ahrs = AP::ahrs();226if (abs(_ahrs.pitch_sensor) > 7000) {227// don't do turn coordination handling when at very high pitch angles228rate_offset = 0;229} else {230rate_offset = cosf(_ahrs.get_pitch_rad())*fabsf(degrees((GRAVITY_MSS / MAX((aspeed * _ahrs.get_EAS2TAS()), MAX(aparm.airspeed_min, 1))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff;231}232if (inverted) {233rate_offset = -rate_offset;234}235return rate_offset;236}237238// Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500239// A positive demand is up240// Inputs are:241// 1) demanded pitch angle in centi-degrees242// 2) control gain scaler = scaling_speed / aspeed243// 3) boolean which is true when stabilise mode is active244// 4) minimum FBW airspeed (metres/sec)245// 5) maximum FBW airspeed (metres/sec)246//247float AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator, bool ground_mode)248{249// Calculate offset to pitch rate demand required to maintain pitch angle whilst banking250// Calculate ideal turn rate from bank angle and airspeed assuming a level coordinated turn251// Pitch rate offset is the component of turn rate about the pitch axis252float rate_offset;253bool inverted;254255if (gains.tau < 0.05f) {256gains.tau.set(0.05f);257}258259const float aspeed = get_airspeed();260261rate_offset = _get_coordination_rate_offset(aspeed, inverted);262263// Calculate the desired pitch rate (deg/sec) from the angle error264angle_err_deg = angle_err * 0.01;265float desired_rate = angle_err_deg / gains.tau;266267// limit the maximum pitch rate demand. Don't apply when inverted268// as the rates will be tuned when upright, and it is common that269// much higher rates are needed inverted270if (!inverted) {271desired_rate += rate_offset;272if (gains.rmax_neg && desired_rate < -gains.rmax_neg) {273desired_rate = -gains.rmax_neg;274} else if (gains.rmax_pos && desired_rate > gains.rmax_pos) {275desired_rate = gains.rmax_pos;276}277} else {278// Make sure not to invert the turn coordination offset279desired_rate = -desired_rate + rate_offset;280}281282/*283when we are past the users defined roll limit for the aircraft284our priority should be to bring the aircraft back within the285roll limit. Using elevator for pitch control at large roll286angles is ineffective, and can be counter productive as it287induces earth-frame yaw which can reduce the ability to roll. We288linearly reduce pitch demanded rate when beyond the configured289roll limit, reducing to zero at 90 degrees290*/291const AP_AHRS &_ahrs = AP::ahrs();292float roll_wrapped = labs(_ahrs.roll_sensor);293if (roll_wrapped > 9000) {294roll_wrapped = 18000 - roll_wrapped;295}296const float roll_limit_margin = MIN(aparm.roll_limit*100 + 500.0, 8500.0);297if (roll_wrapped > roll_limit_margin && labs(_ahrs.pitch_sensor) < 7000) {298float roll_prop = (roll_wrapped - roll_limit_margin) / (float)(9000 - roll_limit_margin);299desired_rate *= (1 - roll_prop);300}301302return _get_rate_out(desired_rate, scaler, disable_integrator, aspeed, ground_mode);303}304305/*306convert from old to new PIDs307this is a temporary conversion function during development308*/309void AP_PitchController::convert_pid()310{311AP_Float &ff = rate_pid.ff();312if (ff.configured()) {313return;314}315316float old_ff=0, old_p=1.0, old_i=0.3, old_d=0.08;317int16_t old_imax = 3000;318bool have_old = AP_Param::get_param_by_index(this, 1, AP_PARAM_FLOAT, &old_p);319have_old |= AP_Param::get_param_by_index(this, 3, AP_PARAM_FLOAT, &old_i);320have_old |= AP_Param::get_param_by_index(this, 2, AP_PARAM_FLOAT, &old_d);321have_old |= AP_Param::get_param_by_index(this, 8, AP_PARAM_FLOAT, &old_ff);322have_old |= AP_Param::get_param_by_index(this, 7, AP_PARAM_FLOAT, &old_imax);323if (!have_old) {324// none of the old gains were set325return;326}327328const float kp_ff = MAX((old_p - old_i * gains.tau) * gains.tau - old_d, 0);329rate_pid.ff().set_and_save(old_ff + kp_ff);330rate_pid.kI().set_and_save_ifchanged(old_i * gains.tau);331rate_pid.kP().set_and_save_ifchanged(old_d);332rate_pid.kD().set_and_save_ifchanged(0);333rate_pid.kIMAX().set_and_save_ifchanged(old_imax/4500.0);334}335336337