123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340 |
- #include <AP_HAL/AP_HAL.h>
- #include "AP_PitchController.h"
- extern const AP_HAL::HAL& hal;
- const AP_Param::GroupInfo AP_PitchController::var_info[] = {
-
-
-
-
-
-
-
- AP_GROUPINFO("TCONST", 0, AP_PitchController, gains.tau, 0.5f),
-
-
-
-
-
-
- AP_GROUPINFO("P", 1, AP_PitchController, gains.P, 1.0f),
-
-
-
-
-
-
- AP_GROUPINFO("D", 2, AP_PitchController, gains.D, 0.04f),
-
-
-
-
-
-
- AP_GROUPINFO("I", 3, AP_PitchController, gains.I, 0.3f),
-
-
-
-
-
-
-
- AP_GROUPINFO("RMAX_UP", 4, AP_PitchController, gains.rmax, 0.0f),
-
-
-
-
-
-
-
- AP_GROUPINFO("RMAX_DN", 5, AP_PitchController, _max_rate_neg, 0.0f),
-
-
-
-
-
-
- AP_GROUPINFO("RLL", 6, AP_PitchController, _roll_ff, 1.0f),
-
-
-
-
-
-
- AP_GROUPINFO("IMAX", 7, AP_PitchController, gains.imax, 3000),
-
-
-
-
-
-
- AP_GROUPINFO("FF", 8, AP_PitchController, gains.FF, 0.0f),
- AP_GROUPEND
- };
- int32_t AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool disable_integrator, float aspeed)
- {
- uint32_t tnow = AP_HAL::millis();
- uint32_t dt = tnow - _last_t;
-
- if (_last_t == 0 || dt > 1000) {
- dt = 0;
- }
- _last_t = tnow;
-
- float delta_time = (float)dt * 0.001f;
-
-
- float omega_y = _ahrs.get_gyro().y;
-
-
- float achieved_rate = ToDeg(omega_y);
- float rate_error = (desired_rate - achieved_rate) * scaler;
-
-
-
-
-
- if (!disable_integrator && gains.I > 0) {
- float k_I = gains.I;
- if (is_zero(gains.FF)) {
-
- k_I = MAX(k_I, 0.15f);
- }
- float ki_rate = k_I * gains.tau;
-
- if (dt > 0 && aspeed > 0.5f*float(aparm.airspeed_min)) {
- float integrator_delta = rate_error * ki_rate * delta_time * scaler;
- if (_last_out < -45) {
-
- integrator_delta = MAX(integrator_delta , 0);
- } else if (_last_out > 45) {
-
- integrator_delta = MIN(integrator_delta , 0);
- }
- _pid_info.I += integrator_delta;
- }
- } else {
- _pid_info.I = 0;
- }
-
- float intLimScaled = gains.imax * 0.01f;
-
- _pid_info.I = constrain_float(_pid_info.I, -intLimScaled, intLimScaled);
-
-
- float eas2tas = _ahrs.get_EAS2TAS();
- float kp_ff = MAX((gains.P - gains.I * gains.tau) * gains.tau - gains.D , 0) / eas2tas;
- float k_ff = gains.FF / eas2tas;
-
-
-
-
-
- _pid_info.P = desired_rate * kp_ff * scaler;
- _pid_info.FF = desired_rate * k_ff * scaler;
- _pid_info.D = rate_error * gains.D * scaler;
- _last_out = _pid_info.D + _pid_info.FF + _pid_info.P;
- _pid_info.target = desired_rate;
- _pid_info.actual = achieved_rate;
- if (autotune.running && aspeed > aparm.airspeed_min) {
-
-
-
-
- autotune.update(desired_rate, achieved_rate, _last_out);
-
-
- _max_rate_neg.set_and_save_ifchanged(gains.rmax);
- }
- _last_out += _pid_info.I;
-
- float roll_wrapped = labs(_ahrs.roll_sensor);
- 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);
- }
-
-
- return constrain_float(_last_out * 100, -4500, 4500);
- }
- int32_t AP_PitchController::get_rate_out(float desired_rate, float scaler)
- {
- float aspeed;
- if (!_ahrs.airspeed_estimate(&aspeed)) {
-
- aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max));
- }
- return _get_rate_out(desired_rate, scaler, false, aspeed);
- }
- float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inverted) const
- {
- float rate_offset;
- float bank_angle = _ahrs.roll;
-
- if (fabsf(bank_angle) < radians(90)) {
- bank_angle = constrain_float(bank_angle,-radians(80),radians(80));
- inverted = false;
- } 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));
- }
- }
- if (!_ahrs.airspeed_estimate(&aspeed)) {
-
- aspeed = 0.5f*(float(aparm.airspeed_min) + float(aparm.airspeed_max));
- }
- if (abs(_ahrs.pitch_sensor) > 7000) {
-
- rate_offset = 0;
- } else {
- 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;
- }
- if (inverted) {
- rate_offset = -rate_offset;
- }
- return rate_offset;
- }
- int32_t AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
- {
-
-
-
- float aspeed;
- float rate_offset;
- bool inverted;
- if (gains.tau < 0.1f) {
- gains.tau.set(0.1f);
- }
- rate_offset = _get_coordination_rate_offset(aspeed, inverted);
-
-
- float desired_rate = angle_err * 0.01f / gains.tau;
-
-
-
-
- if (!inverted) {
- if (_max_rate_neg && desired_rate < -_max_rate_neg) {
- desired_rate = -_max_rate_neg;
- } else if (gains.rmax && desired_rate > gains.rmax) {
- desired_rate = gains.rmax;
- }
- }
-
- if (inverted) {
- desired_rate = -desired_rate;
- }
-
- desired_rate = desired_rate + rate_offset;
- return _get_rate_out(desired_rate, scaler, disable_integrator, aspeed);
- }
- void AP_PitchController::reset_I()
- {
- _pid_info.I = 0;
- }
|