Plane: 3/3 new param TECS_LAND_SRC for Land Sink Rate Change

// @Description: When zero, the flare sink rate (TECS_LAND_SINK) is a fixed sink demand. With this enabled the flare sinkrate will increase/decrease the flare sink demand as you get further beyond the LAND waypoint. Has no effect before the waypoint. This value is added to TECS_LAND_SINK proportional to distance traveled after wp. With an increasing sink rate you can still land in a given distance if you're traveling too fast and cruise passed the land point. A positive value will force the plane to land sooner proportional to distance passed land point. A negative number will tell the plane to slowly climb allowing for a pitched-up stall landing. Recommend 0.2 as initial value.
This commit is contained in:
Tom Pittenger 2016-02-12 11:39:27 -08:00
parent b38e27cadc
commit c837fbca2f

View File

@ -877,11 +877,17 @@ void Plane::update_alt()
update_flight_stage();
bool is_doing_auto_land = (control_mode == AUTO) && (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND);
float distance_beyond_land_wp = 0;
if (is_doing_auto_land && location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
distance_beyond_land_wp = get_distance(current_loc, next_WP_loc);
}
if (auto_throttle_mode && !throttle_suppressed) {
SpdHgt_Controller->update_pitch_throttle(relative_target_altitude_cm(),
target_airspeed_cm,
flight_stage,
is_doing_auto_land,
distance_beyond_land_wp,
auto_state.takeoff_pitch_cd,
throttle_nudge,
tecs_hgt_afe(),