APM: added LAND_FLARE_ALT and LAND_FLARE_SEC

these allow you to configure the altitude and time before touchdown to
flare the plane and lock the heading. Useful on larger planes.
This commit is contained in:
Andrew Tridgell 2012-08-15 18:11:16 +10:00
parent 455e088c9f
commit efee2b1557
3 changed files with 25 additions and 5 deletions

View File

@ -71,6 +71,8 @@ public:
k_param_ins,
k_param_stick_mixing,
k_param_reset_mission_chan,
k_param_land_flare_alt,
k_param_land_flare_sec,
// 110: Telemetry control
//
@ -297,6 +299,8 @@ public:
AP_Int32 airspeed_cruise_cm;
AP_Int32 RTL_altitude_cm;
AP_Int16 land_pitch_cd;
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;

View File

@ -79,6 +79,22 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(land_pitch_cd, "LAND_PITCH_CD", 0),
// @Param: land_flare_alt
// @DisplayName: Landing flare altitude
// @Description: Altitude in autoland at which to lock heading and flare to the LAND_PITCH_CD pitch
// @Units: meters
// @Increment: 0.1
// @User: Advanced
GSCALAR(land_flare_alt, "LAND_FLARE_ALT", 3.0),
// @Param: land_flare_sec
// @DisplayName: Landing flare time
// @Description: Time before landing point at which to lock heading and flare to the LAND_PITCH_CD pitch
// @Units: seconds
// @Increment: 0.1
// @User: Advanced
GSCALAR(land_flare_sec, "LAND_FLARE_SEC", 2.0),
// @Param: XTRK_GAIN_SC
// @DisplayName: Crosstrack Gain
// @Description: The scale between distance off the line and angle to meet the line (in Degrees * 100)

View File

@ -317,14 +317,14 @@ static bool verify_land()
// Set land_complete if we are within 2 seconds distance or within
// 3 meters altitude of the landing point
if (((wp_distance > 0) && (wp_distance <= (2*g_gps->ground_speed/100)))
|| (current_loc.alt <= next_WP.alt + 300)){
if (((wp_distance > 0) && (wp_distance <= (g.land_flare_sec*g_gps->ground_speed*0.01)))
|| (current_loc.alt <= next_WP.alt + g.land_flare_alt*100)) {
land_complete = true;
if (hold_course == -1) {
// we have just reached the threshold of 2 seconds or 3
// meters to landing. We now don't want to do any radical
// we have just reached the threshold of to flare for landing.
// We now don't want to do any radical
// turns, as rolling could put the wings into the runway.
// To prevent further turns we set hold_course to the
// current heading. Previously we set this to
@ -333,7 +333,7 @@ static bool verify_land()
// sudden large roll correction which is very nasty at
// this point in the landing.
hold_course = ahrs.yaw_sensor;
gcs_send_text_fmt(PSTR("Holding course %ld"), hold_course);
gcs_send_text_fmt(PSTR("Land Complete - Hold course %ld"), hold_course);
}
// reload any airspeed or groundspeed parameters that may have