1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159 |
- #include "AP_TECS.h"
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Baro/AP_Baro.h>
- #include <AP_Logger/AP_Logger.h>
- extern const AP_HAL::HAL& hal;
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- #include <stdio.h>
- # define Debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
- #else
- # define Debug(fmt, args ...)
- #endif
- const AP_Param::GroupInfo AP_TECS::var_info[] = {
-
-
-
-
-
-
- AP_GROUPINFO("CLMB_MAX", 0, AP_TECS, _maxClimbRate, 5.0f),
-
-
-
-
-
-
- AP_GROUPINFO("SINK_MIN", 1, AP_TECS, _minSinkRate, 2.0f),
-
-
-
-
-
-
- AP_GROUPINFO("TIME_CONST", 2, AP_TECS, _timeConst, 5.0f),
-
-
-
-
-
-
- AP_GROUPINFO("THR_DAMP", 3, AP_TECS, _thrDamp, 0.5f),
-
-
-
-
-
-
- AP_GROUPINFO("INTEG_GAIN", 4, AP_TECS, _integGain, 0.1f),
-
-
-
-
-
-
- AP_GROUPINFO("VERT_ACC", 5, AP_TECS, _vertAccLim, 7.0f),
-
-
-
-
-
-
- AP_GROUPINFO("HGT_OMEGA", 6, AP_TECS, _hgtCompFiltOmega, 3.0f),
-
-
-
-
-
-
- AP_GROUPINFO("SPD_OMEGA", 7, AP_TECS, _spdCompFiltOmega, 2.0f),
-
-
-
-
-
-
- AP_GROUPINFO("RLL2THR", 8, AP_TECS, _rollComp, 10.0f),
-
-
-
-
-
-
- AP_GROUPINFO("SPDWEIGHT", 9, AP_TECS, _spdWeight, 1.0f),
-
-
-
-
-
-
- AP_GROUPINFO("PTCH_DAMP", 10, AP_TECS, _ptchDamp, 0.0f),
-
-
-
-
-
-
- AP_GROUPINFO("SINK_MAX", 11, AP_TECS, _maxSinkRate, 5.0f),
-
-
-
-
-
-
- AP_GROUPINFO("LAND_ARSPD", 12, AP_TECS, _landAirspeed, -1),
-
-
-
-
-
-
- AP_GROUPINFO("LAND_THR", 13, AP_TECS, _landThrottle, -1),
-
-
-
-
-
-
- AP_GROUPINFO("LAND_SPDWGT", 14, AP_TECS, _spdWeightLand, -1.0f),
-
-
-
-
-
-
- AP_GROUPINFO("PITCH_MAX", 15, AP_TECS, _pitch_max, 15),
-
-
-
-
-
-
- AP_GROUPINFO("PITCH_MIN", 16, AP_TECS, _pitch_min, 0),
-
-
-
-
-
-
- AP_GROUPINFO("LAND_SINK", 17, AP_TECS, _land_sink, 0.25f),
-
-
-
-
-
-
- AP_GROUPINFO("LAND_TCONST", 18, AP_TECS, _landTimeConst, 2.0f),
-
-
-
-
-
-
- AP_GROUPINFO("LAND_DAMP", 19, AP_TECS, _landDamp, 0.5f),
-
-
-
-
-
-
- AP_GROUPINFO("LAND_PMAX", 20, AP_TECS, _land_pitch_max, 10),
-
-
-
-
-
-
-
- AP_GROUPINFO("APPR_SMAX", 21, AP_TECS, _maxSinkRate_approach, 0),
-
-
-
-
-
-
-
- AP_GROUPINFO("LAND_SRC", 22, AP_TECS, _land_sink_rate_change, 0),
-
-
-
-
-
-
- AP_GROUPINFO("LAND_TDAMP", 23, AP_TECS, _land_throttle_damp, 0),
-
-
-
-
-
-
- AP_GROUPINFO("LAND_IGAIN", 24, AP_TECS, _integGain_land, 0),
-
-
-
-
-
-
- AP_GROUPINFO("TKOFF_IGAIN", 25, AP_TECS, _integGain_takeoff, 0),
-
-
-
-
-
-
- AP_GROUPINFO("LAND_PDAMP", 26, AP_TECS, _land_pitch_damp, 0),
-
-
-
-
-
- AP_GROUPINFO("SYNAIRSPEED", 27, AP_TECS, _use_synthetic_airspeed, 0),
-
-
-
-
-
- AP_GROUPINFO("OPTIONS", 28, AP_TECS, _options, 0),
-
- AP_GROUPEND
- };
- void AP_TECS::update_50hz(void)
- {
-
-
-
-
-
-
-
-
- _ahrs.get_relative_position_D_home(_height);
- _height *= -1.0f;
-
- uint64_t now = AP_HAL::micros64();
- float DT = (now - _update_50hz_last_usec) * 1.0e-6f;
- if (DT > 1.0f) {
- _climb_rate = 0.0f;
- _height_filter.dd_height = 0.0f;
- DT = 0.02f;
-
- }
- _update_50hz_last_usec = now;
-
- Vector3f velned;
- if (_ahrs.get_velocity_NED(velned)) {
-
- _climb_rate = -velned.z;
- } else {
-
- const float baro_alt = AP::baro().get_altitude();
-
- float hgt_ddot_mea = -(_ahrs.get_accel_ef().z + GRAVITY_MSS);
-
-
- float omega2 = _hgtCompFiltOmega*_hgtCompFiltOmega;
- float hgt_err = baro_alt - _height_filter.height;
- float integ1_input = hgt_err * omega2 * _hgtCompFiltOmega;
- _height_filter.dd_height += integ1_input * DT;
- float integ2_input = _height_filter.dd_height + hgt_ddot_mea + hgt_err * omega2 * 3.0f;
- _climb_rate += integ2_input * DT;
- float integ3_input = _climb_rate + hgt_err * _hgtCompFiltOmega * 3.0f;
-
-
- if (DT > 1.0f) {
- _height_filter.height = _height;
- } else {
- _height_filter.height += integ3_input*DT;
- }
- }
-
-
- const Matrix3f &rotMat = _ahrs.get_rotation_body_to_ned();
-
- float temp = rotMat.c.x * GRAVITY_MSS + AP::ins().get_accel().x;
-
- _vel_dot = _vdot_filter.apply(temp);
- }
- void AP_TECS::_update_speed(float load_factor)
- {
-
- uint64_t now = AP_HAL::micros64();
- float DT = (now - _update_speed_last_usec) * 1.0e-6f;
- _update_speed_last_usec = now;
-
- float EAS2TAS = _ahrs.get_EAS2TAS();
- _TAS_dem = _EAS_dem * EAS2TAS;
- _TASmax = aparm.airspeed_max * EAS2TAS;
- _TASmin = aparm.airspeed_min * EAS2TAS;
- if (aparm.stall_prevention) {
-
-
- _TASmin *= load_factor;
- }
- if (_TASmax < _TASmin) {
- _TASmax = _TASmin;
- }
- if (_TASmin > _TAS_dem) {
- _TASmin = _TAS_dem;
- }
-
- if (DT > 1.0f) {
- _TAS_state = (_EAS * EAS2TAS);
- _integDTAS_state = 0.0f;
- DT = 0.1f;
-
- }
-
-
- bool use_airspeed = _use_synthetic_airspeed_once || _use_synthetic_airspeed.get() || _ahrs.airspeed_sensor_enabled();
- if (!use_airspeed || !_ahrs.airspeed_estimate(&_EAS)) {
-
- _EAS = 0.5f * (aparm.airspeed_min.get() + (float)aparm.airspeed_max.get());
- }
-
-
-
- float aspdErr = (_EAS * EAS2TAS) - _TAS_state;
- float integDTAS_input = aspdErr * _spdCompFiltOmega * _spdCompFiltOmega;
-
- if (_TAS_state < 3.1f) {
- integDTAS_input = MAX(integDTAS_input , 0.0f);
- }
- _integDTAS_state = _integDTAS_state + integDTAS_input * DT;
- float TAS_input = _integDTAS_state + _vel_dot + aspdErr * _spdCompFiltOmega * 1.4142f;
- _TAS_state = _TAS_state + TAS_input * DT;
-
- _TAS_state = MAX(_TAS_state, 3.0f);
- }
- void AP_TECS::_update_speed_demand(void)
- {
-
-
-
-
-
- if ((_flags.badDescent) || (_flags.underspeed))
- {
- _TAS_dem = _TASmin;
- }
-
- _TAS_dem = constrain_float(_TAS_dem, _TASmin, _TASmax);
-
-
-
- const float velRateMax = 0.5f * _STEdot_max / _TAS_state;
- const float velRateMin = 0.5f * _STEdot_min / _TAS_state;
- const float TAS_dem_previous = _TAS_dem_adj;
-
- const float dt = 0.1;
-
- if ((_TAS_dem - TAS_dem_previous) > (velRateMax * dt))
- {
- _TAS_dem_adj = TAS_dem_previous + velRateMax * dt;
- _TAS_rate_dem = velRateMax;
- }
- else if ((_TAS_dem - TAS_dem_previous) < (velRateMin * dt))
- {
- _TAS_dem_adj = TAS_dem_previous + velRateMin * dt;
- _TAS_rate_dem = velRateMin;
- }
- else
- {
- _TAS_rate_dem = (_TAS_dem - TAS_dem_previous) / dt;
- _TAS_dem_adj = _TAS_dem;
- }
-
- _TAS_dem_adj = constrain_float(_TAS_dem_adj, _TASmin, _TASmax);
- }
- void AP_TECS::_update_height_demand(void)
- {
-
- _hgt_dem = 0.5f * (_hgt_dem + _hgt_dem_in_old);
- _hgt_dem_in_old = _hgt_dem;
- float max_sink_rate = _maxSinkRate;
- if (_maxSinkRate_approach > 0 && _flags.is_doing_auto_land) {
-
-
-
-
-
- max_sink_rate = _maxSinkRate_approach;
- }
-
- if ((_hgt_dem - _hgt_dem_prev) > (_maxClimbRate * 0.1f))
- {
- _hgt_dem = _hgt_dem_prev + _maxClimbRate * 0.1f;
- }
- else if ((_hgt_dem - _hgt_dem_prev) < (-max_sink_rate * 0.1f))
- {
- _hgt_dem = _hgt_dem_prev - max_sink_rate * 0.1f;
- }
- _hgt_dem_prev = _hgt_dem;
-
- _hgt_dem_adj = 0.05f * _hgt_dem + 0.95f * _hgt_dem_adj_last;
-
-
-
- if (_landing.is_flaring()) {
- _integSEB_state = 0;
- if (_flare_counter == 0) {
- _hgt_rate_dem = _climb_rate;
- _land_hgt_dem = _hgt_dem_adj;
- }
-
- float land_sink_rate_adj = _land_sink + _land_sink_rate_change*_distance_beyond_land_wp;
-
- if (_flare_counter < 10) {
- _hgt_rate_dem = _hgt_rate_dem * 0.8f - 0.2f * land_sink_rate_adj;
- _flare_counter++;
- } else {
- _hgt_rate_dem = - land_sink_rate_adj;
- }
- _land_hgt_dem += 0.1f * _hgt_rate_dem;
- _hgt_dem_adj = _land_hgt_dem;
- } else {
- _hgt_rate_dem = (_hgt_dem_adj - _hgt_dem_adj_last) / 0.1f;
- _flare_counter = 0;
- }
-
-
-
-
-
- float new_hgt_dem = _hgt_dem_adj;
- if (_flags.is_doing_auto_land) {
- if (hgt_dem_lag_filter_slew < 1) {
- hgt_dem_lag_filter_slew += 0.1f;
- } else {
- hgt_dem_lag_filter_slew = 1;
- }
- new_hgt_dem += hgt_dem_lag_filter_slew*(_hgt_dem_adj - _hgt_dem_adj_last)*10.0f*(timeConstant()+1);
- } else {
- hgt_dem_lag_filter_slew = 0;
- }
- _hgt_dem_adj_last = _hgt_dem_adj;
- _hgt_dem_adj = new_hgt_dem;
- }
- void AP_TECS::_detect_underspeed(void)
- {
-
-
-
- if (_flags.underspeed &&
- _TAS_state >= _TASmin * 1.15f &&
- AP_HAL::millis() - _underspeed_start_ms > 3000U) {
- _flags.underspeed = false;
- }
- if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_VTOL) {
- _flags.underspeed = false;
- } else if (((_TAS_state < _TASmin * 0.9f) &&
- (_throttle_dem >= _THRmaxf * 0.95f) &&
- !_landing.is_flaring()) ||
- ((_height < _hgt_dem_adj) && _flags.underspeed))
- {
- _flags.underspeed = true;
- if (_TAS_state < _TASmin * 0.9f) {
-
- _underspeed_start_ms = AP_HAL::millis();
- }
- }
- else
- {
-
-
-
- _flags.underspeed = false;
- }
- }
- void AP_TECS::_update_energies(void)
- {
-
- _SPE_dem = _hgt_dem_adj * GRAVITY_MSS;
- _SKE_dem = 0.5f * _TAS_dem_adj * _TAS_dem_adj;
-
- _SPEdot_dem = _hgt_rate_dem * GRAVITY_MSS;
- _SKEdot_dem = _TAS_state * _TAS_rate_dem;
-
- _SPE_est = _height * GRAVITY_MSS;
- _SKE_est = 0.5f * _TAS_state * _TAS_state;
-
- _SPEdot = _climb_rate * GRAVITY_MSS;
- _SKEdot = _TAS_state * _vel_dot;
- }
- float AP_TECS::timeConstant(void) const
- {
- if (_flags.is_doing_auto_land) {
- if (_landTimeConst < 0.1f) {
- return 0.1f;
- }
- return _landTimeConst;
- }
- if (_timeConst < 0.1f) {
- return 0.1f;
- }
- return _timeConst;
- }
- void AP_TECS::_update_throttle_with_airspeed(void)
- {
-
- float SPE_err_max = 0.5f * _TASmax * _TASmax - _SKE_dem;
- float SPE_err_min = 0.5f * _TASmin * _TASmin - _SKE_dem;
- if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_VTOL) {
-
- SPE_err_max = SPE_err_min = 0;
- }
-
-
- _STE_error = constrain_float((_SPE_dem - _SPE_est), SPE_err_min, SPE_err_max) + _SKE_dem - _SKE_est;
- float STEdot_dem = constrain_float((_SPEdot_dem + _SKEdot_dem), _STEdot_min, _STEdot_max);
- float STEdot_error = STEdot_dem - _SPEdot - _SKEdot;
-
-
- STEdot_error = 0.2f*STEdot_error + 0.8f*_STEdotErrLast;
- _STEdotErrLast = STEdot_error;
-
-
- if (_flags.underspeed)
- {
- _throttle_dem = 1.0f;
- }
- else
- {
-
-
- float K_STE2Thr = 1 / (timeConstant() * (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf));
-
- float ff_throttle = 0;
- float nomThr = aparm.throttle_cruise * 0.01f;
- const Matrix3f &rotMat = _ahrs.get_rotation_body_to_ned();
-
-
-
- float cosPhi = sqrtf((rotMat.a.y*rotMat.a.y) + (rotMat.b.y*rotMat.b.y));
- STEdot_dem = STEdot_dem + _rollComp * (1.0f/constrain_float(cosPhi * cosPhi , 0.1f, 1.0f) - 1.0f);
- ff_throttle = nomThr + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf);
-
- float throttle_damp = _thrDamp;
- if (_flags.is_doing_auto_land && !is_zero(_land_throttle_damp)) {
- throttle_damp = _land_throttle_damp;
- }
- _throttle_dem = (_STE_error + STEdot_error * throttle_damp) * K_STE2Thr + ff_throttle;
-
- _throttle_dem = constrain_float(_throttle_dem, _THRminf, _THRmaxf);
- float THRminf_clipped_to_zero = constrain_float(_THRminf, 0, _THRmaxf);
-
-
- if (aparm.throttle_slewrate != 0) {
- float thrRateIncr = _DT * (_THRmaxf - THRminf_clipped_to_zero) * aparm.throttle_slewrate * 0.01f;
- _throttle_dem = constrain_float(_throttle_dem,
- _last_throttle_dem - thrRateIncr,
- _last_throttle_dem + thrRateIncr);
- _last_throttle_dem = _throttle_dem;
- }
-
-
-
- float maxAmp = 0.5f*(_THRmaxf - THRminf_clipped_to_zero);
- float integ_max = constrain_float((_THRmaxf - _throttle_dem + 0.1f),-maxAmp,maxAmp);
- float integ_min = constrain_float((_THRminf - _throttle_dem - 0.1f),-maxAmp,maxAmp);
-
-
- _integTHR_state = _integTHR_state + (_STE_error * _get_i_gain()) * _DT * K_STE2Thr;
- if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND)
- {
- if (!_flags.reached_speed_takeoff) {
-
- _throttle_dem = MAX(_throttle_dem, _THRmaxf - _integTHR_state);
- }
- _integTHR_state = integ_max;
- }
- else
- {
- _integTHR_state = constrain_float(_integTHR_state, integ_min, integ_max);
- }
-
- _throttle_dem = _throttle_dem + _integTHR_state;
- }
-
- _throttle_dem = constrain_float(_throttle_dem, _THRminf, _THRmaxf);
- }
- float AP_TECS::_get_i_gain(void)
- {
- float i_gain = _integGain;
- if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
- if (!is_zero(_integGain_takeoff)) {
- i_gain = _integGain_takeoff;
- }
- } else if (_flags.is_doing_auto_land) {
- if (!is_zero(_integGain_land)) {
- i_gain = _integGain_land;
- }
- }
- return i_gain;
- }
- void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge)
- {
-
- float nomThr;
-
-
- if (_flags.is_doing_auto_land && _landThrottle >= 0) {
- nomThr = (_landThrottle + throttle_nudge) * 0.01f;
- } else {
- nomThr = (aparm.throttle_cruise + throttle_nudge)* 0.01f;
- }
- if (_pitch_dem > 0.0f && _PITCHmaxf > 0.0f)
- {
- _throttle_dem = nomThr + (_THRmaxf - nomThr) * _pitch_dem / _PITCHmaxf;
- }
- else if (_pitch_dem < 0.0f && _PITCHminf < 0.0f)
- {
- _throttle_dem = nomThr + (_THRminf - nomThr) * _pitch_dem / _PITCHminf;
- }
- else
- {
- _throttle_dem = nomThr;
- }
-
- const Matrix3f &rotMat = _ahrs.get_rotation_body_to_ned();
-
-
-
- float cosPhi = sqrtf((rotMat.a.y*rotMat.a.y) + (rotMat.b.y*rotMat.b.y));
- float STEdot_dem = _rollComp * (1.0f/constrain_float(cosPhi * cosPhi , 0.1f, 1.0f) - 1.0f);
- _throttle_dem = _throttle_dem + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf);
- }
- void AP_TECS::_detect_bad_descent(void)
- {
-
-
-
-
-
-
-
-
-
-
-
-
- float STEdot = _SPEdot + _SKEdot;
- if ((!_flags.underspeed && (_STE_error > 200.0f) && (STEdot < 0.0f) && (_throttle_dem >= _THRmaxf * 0.9f)) || (_flags.badDescent && !_flags.underspeed && (_STE_error > 0.0f)))
- {
- _flags.badDescent = true;
- }
- else
- {
- _flags.badDescent = false;
- }
- }
- void AP_TECS::_update_pitch(void)
- {
-
-
-
-
-
-
- float SKE_weighting = constrain_float(_spdWeight, 0.0f, 2.0f);
- if (!_ahrs.airspeed_sensor_enabled()) {
- SKE_weighting = 0.0f;
- } else if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_VTOL) {
-
-
-
-
- SKE_weighting = 0.0f;
- } else if ( _flags.underspeed || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
- SKE_weighting = 2.0f;
- } else if (_flags.is_doing_auto_land) {
- if (_spdWeightLand < 0) {
-
- float scaled_weight = _spdWeight * (1.0f - constrain_float(_path_proportion,0,1));
- SKE_weighting = constrain_float(scaled_weight, 0.0f, 2.0f);
- } else {
- SKE_weighting = constrain_float(_spdWeightLand, 0.0f, 2.0f);
- }
- }
- logging.SKE_weighting = SKE_weighting;
-
- float SPE_weighting = 2.0f - SKE_weighting;
-
- float SEB_dem = _SPE_dem * SPE_weighting - _SKE_dem * SKE_weighting;
- float SEBdot_dem = _SPEdot_dem * SPE_weighting - _SKEdot_dem * SKE_weighting;
- float SEB_error = SEB_dem - (_SPE_est * SPE_weighting - _SKE_est * SKE_weighting);
- float SEBdot_error = SEBdot_dem - (_SPEdot * SPE_weighting - _SKEdot * SKE_weighting);
- logging.SKE_error = _SKE_dem - _SKE_est;
- logging.SPE_error = _SPE_dem - _SPE_est;
-
-
- float integSEB_input = SEB_error * _get_i_gain();
- if (_pitch_dem > _PITCHmaxf)
- {
- integSEB_input = MIN(integSEB_input, _PITCHmaxf - _pitch_dem);
- }
- else if (_pitch_dem < _PITCHminf)
- {
- integSEB_input = MAX(integSEB_input, _PITCHminf - _pitch_dem);
- }
- float integSEB_delta = integSEB_input * _DT;
- #if 0
- if (_landing.is_flaring() && fabsf(_climb_rate) > 0.2f) {
- ::printf("_hgt_rate_dem=%.1f _hgt_dem_adj=%.1f climb=%.1f _flare_counter=%u _pitch_dem=%.1f SEB_dem=%.2f SEBdot_dem=%.2f SEB_error=%.2f SEBdot_error=%.2f\n",
- _hgt_rate_dem, _hgt_dem_adj, _climb_rate, _flare_counter, degrees(_pitch_dem),
- SEB_dem, SEBdot_dem, SEB_error, SEBdot_error);
- }
- #endif
-
-
-
-
-
-
-
- float gainInv = (_TAS_state * timeConstant() * GRAVITY_MSS);
- float temp = SEB_error + SEBdot_dem * timeConstant();
- float pitch_damp = _ptchDamp;
- if (_landing.is_flaring()) {
- pitch_damp = _landDamp;
- } else if (!is_zero(_land_pitch_damp) && _flags.is_doing_auto_land) {
- pitch_damp = _land_pitch_damp;
- }
- temp += SEBdot_error * pitch_damp;
- if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
- temp += _PITCHminf * gainInv;
- }
- float integSEB_min = (gainInv * (_PITCHminf - 0.0783f)) - temp;
- float integSEB_max = (gainInv * (_PITCHmaxf + 0.0783f)) - temp;
- float integSEB_range = integSEB_max - integSEB_min;
- logging.SEB_delta = integSEB_delta;
-
-
-
-
- integSEB_delta = constrain_float(integSEB_delta, -integSEB_range*0.1f, integSEB_range*0.1f);
-
-
-
-
-
-
- integSEB_min = MIN(integSEB_min, _integSEB_state);
- integSEB_max = MAX(integSEB_max, _integSEB_state);
-
- _integSEB_state = constrain_float(_integSEB_state + integSEB_delta, integSEB_min, integSEB_max);
-
- _pitch_dem_unc = (temp + _integSEB_state) / gainInv;
-
- _pitch_dem = constrain_float(_pitch_dem_unc, _PITCHminf, _PITCHmaxf);
-
-
- float ptchRateIncr = _DT * _vertAccLim / _TAS_state;
- if ((_pitch_dem - _last_pitch_dem) > ptchRateIncr)
- {
- _pitch_dem = _last_pitch_dem + ptchRateIncr;
- }
- else if ((_pitch_dem - _last_pitch_dem) < -ptchRateIncr)
- {
- _pitch_dem = _last_pitch_dem - ptchRateIncr;
- }
-
- _pitch_dem = constrain_float(_pitch_dem, _PITCHminf, _PITCHmaxf);
- _last_pitch_dem = _pitch_dem;
- }
- void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe)
- {
-
- if (_DT > 1.0f)
- {
- _integTHR_state = 0.0f;
- _integSEB_state = 0.0f;
- _last_throttle_dem = aparm.throttle_cruise * 0.01f;
- _last_pitch_dem = _ahrs.pitch;
- _hgt_dem_adj_last = hgt_afe;
- _hgt_dem_adj = _hgt_dem_adj_last;
- _hgt_dem_prev = _hgt_dem_adj_last;
- _hgt_dem_in_old = _hgt_dem_adj_last;
- _TAS_dem_adj = _TAS_dem;
- _flags.underspeed = false;
- _flags.badDescent = false;
- _flags.reached_speed_takeoff = false;
- _DT = 0.1f;
-
- }
- else if (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND)
- {
- _PITCHminf = 0.000174533f * ptchMinCO_cd;
- _hgt_dem_adj_last = hgt_afe;
- _hgt_dem_adj = _hgt_dem_adj_last;
- _hgt_dem_prev = _hgt_dem_adj_last;
- _TAS_dem_adj = _TAS_dem;
- _flags.underspeed = false;
- _flags.badDescent = false;
- }
-
- if (_flight_stage != AP_Vehicle::FixedWing::FLIGHT_TAKEOFF && _flight_stage != AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
-
- _flags.reached_speed_takeoff = false;
- }
- }
- void AP_TECS::_update_STE_rate_lim(void)
- {
-
-
- _STEdot_max = _maxClimbRate * GRAVITY_MSS;
- _STEdot_min = - _minSinkRate * GRAVITY_MSS;
- }
- void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
- int32_t EAS_dem_cm,
- enum AP_Vehicle::FixedWing::FlightStage flight_stage,
- float distance_beyond_land_wp,
- int32_t ptchMinCO_cd,
- int16_t throttle_nudge,
- float hgt_afe,
- float load_factor,
- bool soaring_active)
- {
-
- uint64_t now = AP_HAL::micros64();
- _DT = (now - _update_pitch_throttle_last_usec) * 1.0e-6f;
- _update_pitch_throttle_last_usec = now;
- _flags.is_doing_auto_land = (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND);
- _distance_beyond_land_wp = distance_beyond_land_wp;
- _flight_stage = flight_stage;
-
- _hgt_dem = hgt_dem_cm * 0.01f;
- _EAS_dem = EAS_dem_cm * 0.01f;
-
- _update_speed(load_factor);
- if (aparm.takeoff_throttle_max != 0 &&
- (_flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || _flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND)) {
- _THRmaxf = aparm.takeoff_throttle_max * 0.01f;
- } else {
- _THRmaxf = aparm.throttle_max * 0.01f;
- }
- _THRminf = aparm.throttle_min * 0.01f;
-
- _THRmaxf = MAX(_THRmaxf, _THRminf+0.01);
-
-
-
-
- if (_pitch_max == 0) {
- _PITCHmaxf = aparm.pitch_limit_max_cd * 0.01f;
- } else {
- _PITCHmaxf = MIN(_pitch_max, aparm.pitch_limit_max_cd * 0.01f);
- }
- if (_pitch_min >= 0) {
- _PITCHminf = aparm.pitch_limit_min_cd * 0.01f;
- } else {
- _PITCHminf = MAX(_pitch_min, aparm.pitch_limit_min_cd * 0.01f);
- }
-
- if (_pitch_max_limit < 90) {
- _PITCHmaxf = constrain_float(_PITCHmaxf, -90, _pitch_max_limit);
- _PITCHminf = constrain_float(_PITCHminf, -_pitch_max_limit, _PITCHmaxf);
- _pitch_max_limit = 90;
- }
- if (!_landing.is_on_approach()) {
-
- _land_pitch_min = _PITCHminf;
- }
-
- if (_landing.is_flaring()) {
-
- _PITCHminf = MAX(_PITCHminf, _landing.get_pitch_cd() * 0.01f);
-
- if (_land_pitch_max != 0) {
-
- _PITCHmaxf = _land_pitch_max;
- }
-
- _THRminf = 0;
- } else if (_landing.is_on_approach() && (-_climb_rate) > _land_sink) {
-
-
-
- float time_to_flare = (- hgt_afe / _climb_rate) - _landing.get_flare_sec();
- if (time_to_flare < 0) {
-
- _PITCHminf = MAX(_PITCHminf, _landing.get_pitch_cd() * 0.01f);
- } else if (time_to_flare < timeConstant()*2) {
-
-
- float p = time_to_flare/(2*timeConstant());
- float pitch_limit_cd = p*aparm.pitch_limit_min_cd + (1-p)*_landing.get_pitch_cd();
- #if 0
- ::printf("ttf=%.1f hgt_afe=%.1f _PITCHminf=%.1f pitch_limit=%.1f climb=%.1f\n",
- time_to_flare, hgt_afe, _PITCHminf, pitch_limit_cd*0.01f, _climb_rate);
- #endif
- _PITCHminf = MAX(_PITCHminf, pitch_limit_cd*0.01f);
- }
- }
- if (_landing.is_on_approach()) {
-
-
-
-
- if (_land_pitch_min <= -90) {
- _land_pitch_min = _PITCHminf;
- }
- const float flare_pitch_range = 20;
- const float delta_per_loop = (flare_pitch_range/_landTimeConst) * _DT;
- _PITCHminf = MIN(_PITCHminf, _land_pitch_min+delta_per_loop);
- _land_pitch_min = MAX(_land_pitch_min, _PITCHminf);
- _PITCHminf = MAX(_land_pitch_min, _PITCHminf);
- }
- if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
- if (!_flags.reached_speed_takeoff && _TAS_state >= _TAS_dem_adj) {
-
-
- _flags.reached_speed_takeoff = true;
- }
- }
-
-
- _PITCHmaxf = radians(_PITCHmaxf);
- _PITCHminf = radians(_PITCHminf);
-
- _PITCHmaxf = MAX(_PITCHmaxf, _PITCHminf);
-
- _initialise_states(ptchMinCO_cd, hgt_afe);
-
- _update_STE_rate_lim();
-
- _update_speed_demand();
-
- _update_height_demand();
-
- _detect_underspeed();
-
- _update_energies();
-
-
-
-
-
- if (_ahrs.airspeed_sensor_enabled() || _use_synthetic_airspeed || _use_synthetic_airspeed_once) {
- _update_throttle_with_airspeed();
- _use_synthetic_airspeed_once = false;
- } else {
- _update_throttle_without_airspeed(throttle_nudge);
- }
-
- _detect_bad_descent();
-
- if (soaring_active || (_options & OPTION_GLIDER_ONLY)) {
- _flags.badDescent = false;
- }
-
- _update_pitch();
-
- AP::logger().Write(
- "TECS",
- "TimeUS,h,dh,hdem,dhdem,spdem,sp,dsp,ith,iph,th,ph,dspdem,w,f",
- "smnmnnnn----o--",
- "F0000000----0--",
- "QfffffffffffffB",
- now,
- (double)_height,
- (double)_climb_rate,
- (double)_hgt_dem_adj,
- (double)_hgt_rate_dem,
- (double)_TAS_dem_adj,
- (double)_TAS_state,
- (double)_vel_dot,
- (double)_integTHR_state,
- (double)_integSEB_state,
- (double)_throttle_dem,
- (double)_pitch_dem,
- (double)_TAS_rate_dem,
- (double)logging.SKE_weighting,
- _flags_byte);
- AP::logger().Write("TEC2", "TimeUS,pmax,pmin,KErr,PErr,EDelta,LF",
- "s------",
- "F------",
- "Qffffff",
- now,
- (double)degrees(_PITCHmaxf),
- (double)degrees(_PITCHminf),
- (double)logging.SKE_error,
- (double)logging.SPE_error,
- (double)logging.SEB_delta,
- (double)load_factor);
- }
|