2013-08-29 02:34:34 -03:00
/*
This program is free software : you can redistribute it and / or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation , either version 3 of the License , or
( at your option ) any later version .
2018-12-20 19:38:42 -04:00
2013-08-29 02:34:34 -03:00
This program is distributed in the hope that it will be useful ,
but WITHOUT ANY WARRANTY ; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE . See the
GNU General Public License for more details .
2018-12-20 19:38:42 -04:00
2013-08-29 02:34:34 -03:00
You should have received a copy of the GNU General Public License
along with this program . If not , see < http : //www.gnu.org/licenses/>.
*/
2012-08-21 23:08:14 -03:00
2013-04-23 08:02:18 -03:00
// Initial Code by Jon Challinger
// Modified by Paul Riseborough
2012-08-21 23:08:14 -03:00
2015-08-11 03:28:41 -03:00
# include <AP_HAL/AP_HAL.h>
2012-08-21 23:08:14 -03:00
# include "AP_PitchController.h"
2012-10-12 14:53:42 -03:00
extern const AP_HAL : : HAL & hal ;
2015-10-25 14:03:46 -03:00
const AP_Param : : GroupInfo AP_PitchController : : var_info [ ] = {
2013-05-05 03:07:05 -03:00
2013-05-31 02:31:25 -03:00
// @Param: TCONST
2013-05-13 08:10:55 -03:00
// @DisplayName: Pitch Time Constant
2018-12-20 19:38:42 -04:00
// @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.
2013-05-13 08:10:55 -03:00
// @Range: 0.4 1.0
2017-05-02 10:39:35 -03:00
// @Units: s
2013-05-05 03:07:05 -03:00
// @Increment: 0.1
// @User: Advanced
2014-04-12 01:11:33 -03:00
AP_GROUPINFO ( " TCONST " , 0 , AP_PitchController , gains . tau , 0.5f ) ,
2013-05-05 03:07:05 -03:00
2013-05-31 02:31:25 -03:00
// @Param: P
2013-05-13 08:10:55 -03:00
// @DisplayName: Proportional Gain
2018-12-20 19:38:42 -04:00
// @Description: Proportional gain from pitch angle demands to elevator. Higher values allow more servo response but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
2014-08-16 05:07:13 -03:00
// @Range: 0.1 3.0
2013-05-05 03:07:05 -03:00
// @Increment: 0.1
// @User: User
2018-08-17 04:01:56 -03:00
AP_GROUPINFO ( " P " , 1 , AP_PitchController , gains . P , 1.0f ) ,
2013-05-05 03:07:05 -03:00
2013-05-31 02:31:25 -03:00
// @Param: D
2013-05-13 08:10:55 -03:00
// @DisplayName: Damping Gain
2018-12-20 19:38:42 -04:00
// @Description: Damping gain from pitch acceleration to elevator. Higher values reduce pitching in turbulence, but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
// @Range: 0 0.2
2013-05-05 03:07:05 -03:00
// @Increment: 0.01
// @User: User
2018-09-13 18:31:33 -03:00
AP_GROUPINFO ( " D " , 2 , AP_PitchController , gains . D , 0.04f ) ,
2013-05-05 03:07:05 -03:00
2013-05-31 02:31:25 -03:00
// @Param: I
2013-05-13 08:10:55 -03:00
// @DisplayName: Integrator Gain
2018-12-20 19:38:42 -04:00
// @Description: Integrator gain from long-term pitch angle offsets to elevator. Higher values "trim" out offsets faster but can cause oscillations. Automatically set and adjusted by AUTOTUNE mode.
2013-05-13 08:10:55 -03:00
// @Range: 0 0.5
// @Increment: 0.05
2013-05-05 03:07:05 -03:00
// @User: User
2018-08-17 04:01:56 -03:00
AP_GROUPINFO ( " I " , 3 , AP_PitchController , gains . I , 0.3f ) ,
2013-05-05 03:07:05 -03:00
2013-05-31 02:31:25 -03:00
// @Param: RMAX_UP
2013-05-05 03:07:05 -03:00
// @DisplayName: Pitch up max rate
2018-12-20 19:38:42 -04:00
// @Description: Maximum pitch up rate that the pitch controller demands (degrees/sec) in ACRO mode.
2013-05-05 03:07:05 -03:00
// @Range: 0 100
2017-05-02 10:39:35 -03:00
// @Units: deg/s
2013-05-05 03:07:05 -03:00
// @Increment: 1
2013-05-13 08:10:55 -03:00
// @User: Advanced
2014-04-12 01:11:33 -03:00
AP_GROUPINFO ( " RMAX_UP " , 4 , AP_PitchController , gains . rmax , 0.0f ) ,
2013-05-05 03:07:05 -03:00
2013-05-31 02:31:25 -03:00
// @Param: RMAX_DN
2013-05-05 03:07:05 -03:00
// @DisplayName: Pitch down max rate
// @Description: This sets the maximum nose down pitch rate that the controller will demand (degrees/sec). Setting it to zero disables the limit.
// @Range: 0 100
2017-05-02 10:39:35 -03:00
// @Units: deg/s
2013-05-05 03:07:05 -03:00
// @Increment: 1
2013-05-13 08:10:55 -03:00
// @User: Advanced
2013-05-31 02:31:25 -03:00
AP_GROUPINFO ( " RMAX_DN " , 5 , AP_PitchController , _max_rate_neg , 0.0f ) ,
2013-05-05 03:07:05 -03:00
2013-05-31 02:31:25 -03:00
// @Param: RLL
2013-05-05 08:37:21 -03:00
// @DisplayName: Roll compensation
2018-12-20 19:38:42 -04:00
// @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.
2013-05-05 08:37:21 -03:00
// @Range: 0.7 1.5
2013-05-05 03:07:05 -03:00
// @Increment: 0.05
// @User: User
2013-05-31 02:31:25 -03:00
AP_GROUPINFO ( " RLL " , 6 , AP_PitchController , _roll_ff , 1.0f ) ,
2013-05-05 03:07:05 -03:00
2013-06-11 05:35:31 -03:00
// @Param: IMAX
// @DisplayName: Integrator limit
2018-12-20 19:38:42 -04:00
// @Description: Limit of pitch integrator gain in centi-degrees of servo travel. Servos are assumed to have +/- 4500 centi-degrees of travel, so a value of 3000 allows trim of up to 2/3 of servo travel range.
2013-06-11 05:35:31 -03:00
// @Range: 0 4500
// @Increment: 1
// @User: Advanced
2015-02-19 01:15:33 -04:00
AP_GROUPINFO ( " IMAX " , 7 , AP_PitchController , gains . imax , 3000 ) ,
2013-06-11 05:35:31 -03:00
2015-05-23 00:26:17 -03:00
// @Param: FF
// @DisplayName: Feed forward Gain
2018-12-20 19:38:42 -04:00
// @Description: Gain from demanded rate to elevator output.
2015-05-23 00:26:17 -03:00
// @Range: 0.1 4.0
// @Increment: 0.1
// @User: User
AP_GROUPINFO ( " FF " , 8 , AP_PitchController , gains . FF , 0.0f ) ,
2012-08-21 23:08:14 -03:00
AP_GROUPEND
} ;
2013-07-10 10:25:06 -03:00
/*
Function returns an equivalent elevator deflection in centi - degrees in the range from - 4500 to 4500
A positive demand is up
Inputs are :
2013-07-17 22:57:11 -03:00
1 ) demanded pitch rate in degrees / second
2013-07-10 10:25:06 -03:00
2 ) control gain scaler = scaling_speed / aspeed
3 ) boolean which is true when stabilise mode is active
4 ) minimum FBW airspeed ( metres / sec )
5 ) maximum FBW airspeed ( metres / sec )
*/
2013-08-02 08:54:48 -03:00
int32_t AP_PitchController : : _get_rate_out ( float desired_rate , float scaler , bool disable_integrator , float aspeed )
2012-08-21 23:08:14 -03:00
{
2015-11-19 23:05:52 -04:00
uint32_t tnow = AP_HAL : : millis ( ) ;
2012-08-21 23:08:14 -03:00
uint32_t dt = tnow - _last_t ;
if ( _last_t = = 0 | | dt > 1000 ) {
dt = 0 ;
}
_last_t = tnow ;
2013-05-05 07:12:27 -03:00
float delta_time = ( float ) dt * 0.001f ;
2012-08-21 23:08:14 -03:00
2013-07-10 10:25:06 -03:00
// Get body rate vector (radians/sec)
2013-08-14 01:56:18 -03:00
float omega_y = _ahrs . get_gyro ( ) . y ;
2013-07-10 10:25:06 -03:00
// Calculate the pitch rate error (deg/sec) and scale
2014-04-12 01:11:33 -03:00
float achieved_rate = ToDeg ( omega_y ) ;
float rate_error = ( desired_rate - achieved_rate ) * scaler ;
2013-07-10 10:25:06 -03:00
// Multiply pitch rate error by _ki_rate and integrate
2013-10-21 03:58:46 -03:00
// Scaler is applied before integrator so that integrator state relates directly to elevator deflection
// This means elevator trim offset doesn't change as the value of scaler changes with airspeed
2013-07-10 10:25:06 -03:00
// Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
2014-04-12 01:11:33 -03:00
if ( ! disable_integrator & & gains . I > 0 ) {
2016-03-24 19:49:12 -03:00
float k_I = gains . I ;
if ( is_zero ( gains . FF ) ) {
/*
if the user hasn ' t set a direct FF then assume they are
not doing sophisticated tuning . Set a minimum I value of
0.15 to ensure that the time constant for trimming in
pitch is not too long . We have had a lot of user issues
with very small I value leading to very slow pitch
trimming , which causes a lot of problems for TECS . A
value of 0.15 is still quite small , but a lot better
than what many users are running .
*/
k_I = MAX ( k_I , 0.15f ) ;
}
float ki_rate = k_I * gains . tau ;
2013-07-10 10:25:06 -03:00
//only integrate if gain and time step are positive and airspeed above min value.
2016-08-07 21:48:25 -03:00
if ( dt > 0 & & aspeed > 0.5f * float ( aparm . airspeed_min ) ) {
2013-10-21 03:58:46 -03:00
float integrator_delta = rate_error * ki_rate * delta_time * scaler ;
2013-07-10 10:25:06 -03:00
if ( _last_out < - 45 ) {
// prevent the integrator from increasing if surface defln demand is above the upper limit
2015-11-27 13:11:58 -04:00
integrator_delta = MAX ( integrator_delta , 0 ) ;
2013-07-10 10:25:06 -03:00
} else if ( _last_out > 45 ) {
// prevent the integrator from decreasing if surface defln demand is below the lower limit
2015-11-27 13:11:58 -04:00
integrator_delta = MIN ( integrator_delta , 0 ) ;
2013-07-10 10:25:06 -03:00
}
2015-05-22 18:39:38 -03:00
_pid_info . I + = integrator_delta ;
2013-07-10 10:25:06 -03:00
}
} else {
2015-05-22 18:39:38 -03:00
_pid_info . I = 0 ;
2013-07-10 10:25:06 -03:00
}
// Scale the integration limit
2014-04-12 01:11:33 -03:00
float intLimScaled = gains . imax * 0.01f ;
2013-07-10 10:25:06 -03:00
// Constrain the integrator state
2015-05-22 18:39:38 -03:00
_pid_info . I = constrain_float ( _pid_info . I , - intLimScaled , intLimScaled ) ;
2013-07-10 10:25:06 -03:00
2013-05-13 08:10:55 -03:00
// Calculate equivalent gains so that values for K_P and K_I can be taken across from the old PID law
// No conversion is required for K_D
2015-05-23 00:26:17 -03:00
float eas2tas = _ahrs . get_EAS2TAS ( ) ;
2015-11-27 13:11:58 -04:00
float kp_ff = MAX ( ( gains . P - gains . I * gains . tau ) * gains . tau - gains . D , 0 ) / eas2tas ;
2015-05-23 00:26:17 -03:00
float k_ff = gains . FF / eas2tas ;
2013-07-10 10:25:06 -03:00
// Calculate the demanded control surface deflection
// Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
// path, but want a 1/speed^2 scaler applied to the rate error path.
// This is because acceleration scales with speed^2, but rate scales with speed.
2015-05-23 00:26:17 -03:00
_pid_info . P = desired_rate * kp_ff * scaler ;
_pid_info . FF = desired_rate * k_ff * scaler ;
2015-05-22 18:39:38 -03:00
_pid_info . D = rate_error * gains . D * scaler ;
2015-05-23 00:26:17 -03:00
_last_out = _pid_info . D + _pid_info . FF + _pid_info . P ;
2019-06-27 06:31:52 -03:00
_pid_info . target = desired_rate ;
2019-01-27 01:42:16 -04:00
_pid_info . actual = achieved_rate ;
2014-04-12 01:11:33 -03:00
2016-08-07 21:48:25 -03:00
if ( autotune . running & & aspeed > aparm . airspeed_min ) {
2014-04-12 01:11:33 -03:00
// let autotune have a go at the values
// Note that we don't pass the integrator component so we get
// a better idea of how much the base PD controller
// contributed
autotune . update ( desired_rate , achieved_rate , _last_out ) ;
2014-04-13 09:11:57 -03:00
// set down rate to rate up when auto-tuning
_max_rate_neg . set_and_save_ifchanged ( gains . rmax ) ;
2014-04-12 01:11:33 -03:00
}
2015-05-22 18:39:38 -03:00
_last_out + = _pid_info . I ;
2016-06-23 09:41:32 -03:00
/*
when we are past the users defined roll limit for the
aircraft our priority should be to bring the aircraft back
within the roll limit . Using elevator for pitch control at
large roll angles is ineffective , and can be counter
productive as it induces earth - frame yaw which can reduce
the ability to roll . We linearly reduce elevator input when
beyond the configured roll limit , reducing to zero at 90
degrees
*/
2018-10-09 07:08:15 -03:00
float roll_wrapped = labs ( _ahrs . roll_sensor ) ;
2016-06-23 09:41:32 -03:00
if ( roll_wrapped > 9000 ) {
roll_wrapped = 18000 - roll_wrapped ;
}
if ( roll_wrapped > aparm . roll_limit_cd + 500 & & aparm . roll_limit_cd < 8500 & &
labs ( _ahrs . pitch_sensor ) < 7000 ) {
float roll_prop = ( roll_wrapped - ( aparm . roll_limit_cd + 500 ) ) / ( float ) ( 9000 - aparm . roll_limit_cd ) ;
_last_out * = ( 1 - roll_prop ) ;
}
2013-07-10 10:25:06 -03:00
// Convert to centi-degrees and constrain
return constrain_float ( _last_out * 100 , - 4500 , 4500 ) ;
}
/*
Function returns an equivalent elevator deflection in centi - degrees in the range from - 4500 to 4500
A positive demand is up
Inputs are :
1 ) demanded pitch rate in degrees / second
2 ) control gain scaler = scaling_speed / aspeed
3 ) boolean which is true when stabilise mode is active
4 ) minimum FBW airspeed ( metres / sec )
5 ) maximum FBW airspeed ( metres / sec )
*/
int32_t AP_PitchController : : get_rate_out ( float desired_rate , float scaler )
{
2013-10-04 08:52:47 -03:00
float aspeed ;
2020-01-06 20:47:35 -04:00
if ( ! _ahrs . airspeed_estimate ( aspeed ) ) {
2013-10-04 08:52:47 -03:00
// If no airspeed available use average of min and max
2016-08-07 21:48:25 -03:00
aspeed = 0.5f * ( float ( aparm . airspeed_min ) + float ( aparm . airspeed_max ) ) ;
2013-10-04 08:52:47 -03:00
}
return _get_rate_out ( desired_rate , scaler , false , aspeed ) ;
2013-07-10 10:25:06 -03:00
}
2013-05-13 08:10:55 -03:00
2013-07-17 22:57:11 -03:00
/*
get the rate offset in degrees / second needed for pitch in body frame
to maintain height in a coordinated turn .
2018-12-20 19:38:42 -04:00
2013-07-17 22:57:11 -03:00
Also returns the inverted flag and the estimated airspeed in m / s for
use by the rest of the pitch controller
*/
float AP_PitchController : : _get_coordination_rate_offset ( float & aspeed , bool & inverted ) const
2013-07-10 10:25:06 -03:00
{
2013-04-29 04:37:34 -03:00
float rate_offset ;
2013-08-14 01:56:18 -03:00
float bank_angle = _ahrs . roll ;
2013-06-01 09:27:01 -03:00
2013-04-29 04:37:34 -03:00
// limit bank angle between +- 80 deg if right way up
2013-05-05 07:12:27 -03:00
if ( fabsf ( bank_angle ) < radians ( 90 ) ) {
bank_angle = constrain_float ( bank_angle , - radians ( 80 ) , radians ( 80 ) ) ;
2013-07-17 22:57:11 -03:00
inverted = false ;
2013-05-05 07:12:27 -03:00
} else {
inverted = true ;
if ( bank_angle > 0.0f ) {
bank_angle = constrain_float ( bank_angle , radians ( 100 ) , radians ( 180 ) ) ;
} else {
bank_angle = constrain_float ( bank_angle , - radians ( 180 ) , - radians ( 100 ) ) ;
}
2013-04-29 04:37:34 -03:00
}
2020-01-06 20:47:35 -04:00
if ( ! _ahrs . airspeed_estimate ( aspeed ) ) {
2013-04-29 04:37:34 -03:00
// If no airspeed available use average of min and max
2016-08-07 21:48:25 -03:00
aspeed = 0.5f * ( float ( aparm . airspeed_min ) + float ( aparm . airspeed_max ) ) ;
2013-04-29 04:37:34 -03:00
}
2013-08-14 01:56:18 -03:00
if ( abs ( _ahrs . pitch_sensor ) > 7000 ) {
2013-07-13 07:27:48 -03:00
// don't do turn coordination handling when at very high pitch angles
rate_offset = 0 ;
} else {
2016-08-07 21:48:25 -03:00
rate_offset = cosf ( _ahrs . pitch ) * fabsf ( ToDeg ( ( GRAVITY_MSS / MAX ( ( aspeed * _ahrs . get_EAS2TAS ( ) ) , float ( aparm . airspeed_min ) ) ) * tanf ( bank_angle ) * sinf ( bank_angle ) ) ) * _roll_ff ;
2013-07-13 07:27:48 -03:00
}
2013-05-05 07:12:27 -03:00
if ( inverted ) {
rate_offset = - rate_offset ;
}
2013-07-17 22:57:11 -03:00
return rate_offset ;
}
// Function returns an equivalent elevator deflection in centi-degrees in the range from -4500 to 4500
// A positive demand is up
// Inputs are:
// 1) demanded pitch angle in centi-degrees
// 2) control gain scaler = scaling_speed / aspeed
// 3) boolean which is true when stabilise mode is active
// 4) minimum FBW airspeed (metres/sec)
// 5) maximum FBW airspeed (metres/sec)
//
2013-08-02 08:54:48 -03:00
int32_t AP_PitchController : : get_servo_out ( int32_t angle_err , float scaler , bool disable_integrator )
2013-07-17 22:57:11 -03:00
{
// Calculate offset to pitch rate demand required to maintain pitch angle whilst banking
// Calculate ideal turn rate from bank angle and airspeed assuming a level coordinated turn
// Pitch rate offset is the component of turn rate about the pitch axis
float aspeed ;
float rate_offset ;
bool inverted ;
2014-04-12 01:11:33 -03:00
if ( gains . tau < 0.1f ) {
gains . tau . set ( 0.1f ) ;
2013-07-17 22:57:11 -03:00
}
rate_offset = _get_coordination_rate_offset ( aspeed , inverted ) ;
2013-04-23 08:02:18 -03:00
// Calculate the desired pitch rate (deg/sec) from the angle error
2014-04-12 01:11:33 -03:00
float desired_rate = angle_err * 0.01f / gains . tau ;
2012-08-21 23:08:14 -03:00
2013-05-05 07:12:27 -03:00
// limit the maximum pitch rate demand. Don't apply when inverted
// as the rates will be tuned when upright, and it is common that
// much higher rates are needed inverted
if ( ! inverted ) {
if ( _max_rate_neg & & desired_rate < - _max_rate_neg ) {
desired_rate = - _max_rate_neg ;
2014-04-12 01:11:33 -03:00
} else if ( gains . rmax & & desired_rate > gains . rmax ) {
desired_rate = gains . rmax ;
2013-05-05 07:12:27 -03:00
}
}
2012-08-21 23:08:14 -03:00
2013-05-05 07:12:27 -03:00
if ( inverted ) {
desired_rate = - desired_rate ;
}
2013-04-23 16:22:17 -03:00
// Apply the turn correction offset
desired_rate = desired_rate + rate_offset ;
2013-08-02 08:54:48 -03:00
return _get_rate_out ( desired_rate , scaler , disable_integrator , aspeed ) ;
2012-08-21 23:08:14 -03:00
}
void AP_PitchController : : reset_I ( )
{
2015-05-22 18:39:38 -03:00
_pid_info . I = 0 ;
2019-01-27 01:42:16 -04:00
}