Plane: support much smoother flare transitions
provide the height above the ground to TECS so it can make a smarter pre-flare transition
This commit is contained in:
parent
8fc58d1cbe
commit
1c1798fb11
@ -892,7 +892,7 @@ static void update_speed_height(void)
|
||||
// Call TECS 50Hz update. Note that we call this regardless of
|
||||
// throttle suppressed, as this needs to be running for
|
||||
// takeoff detection
|
||||
SpdHgt_Controller->update_50hz(relative_altitude());
|
||||
SpdHgt_Controller->update_50hz(tecs_hgt_afe());
|
||||
}
|
||||
}
|
||||
|
||||
@ -1519,7 +1519,7 @@ static void update_flight_stage(void)
|
||||
flight_stage,
|
||||
auto_state.takeoff_pitch_cd,
|
||||
throttle_nudge,
|
||||
relative_altitude(),
|
||||
tecs_hgt_afe(),
|
||||
aerodynamic_load_factor);
|
||||
if (should_log(MASK_LOG_TECS)) {
|
||||
Log_Write_TECS_Tuning();
|
||||
|
@ -437,7 +437,6 @@ public:
|
||||
AP_Int32 airspeed_cruise_cm;
|
||||
AP_Int32 RTL_altitude_cm;
|
||||
AP_Float land_flare_alt;
|
||||
AP_Float land_flare_sec;
|
||||
AP_Int32 min_gndspeed_cm;
|
||||
AP_Int16 pitch_trim_cd;
|
||||
AP_Int16 FBWB_min_altitude_cm;
|
||||
|
@ -230,7 +230,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Units: seconds
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
GSCALAR(land_flare_sec, "LAND_FLARE_SEC", 2.0),
|
||||
ASCALAR(land_flare_sec, "LAND_FLARE_SEC", 2.0),
|
||||
|
||||
// @Param: NAV_CONTROLLER
|
||||
// @DisplayName: Navigation controller selection
|
||||
|
@ -51,7 +51,7 @@ static bool verify_land()
|
||||
after landing if we've had positive baro drift)
|
||||
*/
|
||||
if (height <= g.land_flare_alt ||
|
||||
height <= auto_state.land_sink_rate * g.land_flare_sec ||
|
||||
height <= auto_state.land_sink_rate * aparm.land_flare_sec ||
|
||||
(!rangefinder_state.in_range && location_passed_point(current_loc, prev_WP_loc, next_WP_loc))) {
|
||||
|
||||
if (!auto_state.land_complete) {
|
||||
@ -129,7 +129,7 @@ static void setup_landing_glide_slope(void)
|
||||
float sink_rate = sink_height / sink_time;
|
||||
|
||||
// the height we aim for is the one to give us the right flare point
|
||||
float aim_height = g.land_flare_sec * sink_rate;
|
||||
float aim_height = aparm.land_flare_sec * sink_rate;
|
||||
|
||||
// don't allow the aim height to be too far above LAND_FLARE_ALT
|
||||
if (g.land_flare_alt > 0 && aim_height > g.land_flare_alt*2) {
|
||||
@ -198,3 +198,27 @@ static bool jump_to_landing_sequence(void)
|
||||
gcs_send_text_P(SEVERITY_HIGH, PSTR("Unable to start landing sequence."));
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
the height above field elevation that we pass to TECS
|
||||
*/
|
||||
static float tecs_hgt_afe(void)
|
||||
{
|
||||
/*
|
||||
pass the height above field elevation as the height above
|
||||
the ground when in landing, which means that TECS gets the
|
||||
rangefinder information and thus can know when the flare is
|
||||
coming.
|
||||
*/
|
||||
float hgt_afe;
|
||||
if (flight_stage == AP_SpdHgtControl::FLIGHT_LAND_FINAL ||
|
||||
flight_stage == AP_SpdHgtControl::FLIGHT_LAND_APPROACH) {
|
||||
hgt_afe = height_above_target();
|
||||
hgt_afe -= rangefinder_correction();
|
||||
} else {
|
||||
// when in normal flight we pass the hgt_afe as relative
|
||||
// altitude to home
|
||||
hgt_afe = relative_altitude();
|
||||
}
|
||||
return hgt_afe;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user