mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_TECS: migrate aparm "LAND_" params from plane to AP_Landing
This commit is contained in:
parent
15ec551990
commit
9035dcbbc5
@ -981,7 +981,7 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
||||
|
||||
if (flight_stage == FLIGHT_LAND_FINAL) {
|
||||
// in flare use min pitch from LAND_PITCH_CD
|
||||
_PITCHminf = MAX(_PITCHminf, aparm.land_pitch_cd * 0.01f);
|
||||
_PITCHminf = MAX(_PITCHminf, _landing.pitch_cd * 0.01f);
|
||||
|
||||
// and use max pitch from TECS_LAND_PMAX
|
||||
if (_land_pitch_max != 0) {
|
||||
@ -994,15 +994,15 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
||||
// constrain the pitch in landing as we get close to the flare
|
||||
// point. Use a simple linear limit from 15 meters after the
|
||||
// landing point
|
||||
float time_to_flare = (- hgt_afe / _climb_rate) - aparm.land_flare_sec;
|
||||
float time_to_flare = (- hgt_afe / _climb_rate) - _landing.flare_sec;
|
||||
if (time_to_flare < 0) {
|
||||
// we should be flaring already
|
||||
_PITCHminf = MAX(_PITCHminf, aparm.land_pitch_cd * 0.01f);
|
||||
_PITCHminf = MAX(_PITCHminf, _landing.pitch_cd * 0.01f);
|
||||
} else if (time_to_flare < timeConstant()*2) {
|
||||
// smoothly move the min pitch to the flare min pitch over
|
||||
// twice the time constant
|
||||
float p = time_to_flare/(2*timeConstant());
|
||||
float pitch_limit_cd = p*aparm.pitch_limit_min_cd + (1-p)*aparm.land_pitch_cd;
|
||||
float pitch_limit_cd = p*aparm.pitch_limit_min_cd + (1-p)*_landing.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);
|
||||
|
@ -24,12 +24,14 @@
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include <AP_SpdHgtControl/AP_SpdHgtControl.h>
|
||||
#include <DataFlash/DataFlash.h>
|
||||
#include <AP_Landing/AP_Landing.h>
|
||||
|
||||
class AP_TECS : public AP_SpdHgtControl {
|
||||
public:
|
||||
AP_TECS(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms) :
|
||||
AP_TECS(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms, const AP_Landing &landing) :
|
||||
_ahrs(ahrs),
|
||||
aparm(parms)
|
||||
aparm(parms),
|
||||
_landing(landing)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
}
|
||||
@ -123,6 +125,9 @@ private:
|
||||
// reference to the AHRS object
|
||||
AP_AHRS &_ahrs;
|
||||
|
||||
// reference to const AP_Landing to access it's params
|
||||
const AP_Landing &_landing;
|
||||
|
||||
const AP_Vehicle::FixedWing &aparm;
|
||||
|
||||
// TECS tuning parameters
|
||||
|
Loading…
Reference in New Issue
Block a user