33 gcs().
send_text(MAV_SEVERITY_INFO,
"Landing approach start at %.1fm", (
double)relative_altitude);
40 throttle_suppressed =
false;
50 const float height,
const float sink_rate,
const float wp_proportion,
const uint32_t last_flying_ms,
const bool is_armed,
const bool is_flying,
const bool rangefinder_state_in_range)
60 const bool below_prev_WP = current_loc.
alt < prev_WP_loc.
alt;
62 (wp_proportion >= 0 && heading_lined_up && on_flight_line) ||
63 (wp_proportion > 0.15f && heading_lined_up && below_prev_WP) ||
64 (wp_proportion > 0.5
f)) {
87 const bool below_flare_alt = (height <=
flare_alt);
91 if ((on_approach_stage && below_flare_alt) ||
92 (on_approach_stage && below_flare_sec && (wp_proportion > 0.5)) ||
93 (!rangefinder_state_in_range && wp_proportion >= 1) ||
99 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"Flare crash detected: speed=%.1f", (
double)
AP::gps().ground_speed());
101 gcs().
send_text(MAV_SEVERITY_INFO,
"Flare %.1fm sink=%.2f speed=%.1f dist=%.1f",
102 (
double)height, (
double)sink_rate,
103 (
double)
AP::gps().ground_speed(),
110 if (
AP::gps().ground_speed() < 3) {
122 if (reached_pre_flare_alt || reached_pre_flare_sec) {
131 struct Location land_WP_loc = next_WP_loc;
132 int32_t land_bearing_cd =
get_bearing_cd(prev_WP_loc, next_WP_loc);
134 land_bearing_cd*0.01
f,
142 gcs().
send_text(MAV_SEVERITY_INFO,
"Distance from LAND point=%.2fm", (
double)
get_distance(current_loc, next_WP_loc));
175 float total_distance_m =
get_distance(prev_WP_loc, next_WP_loc);
176 float top_of_glide_slope_alt_m = total_distance_m * corrected_alt_m / wp_distance;
177 prev_WP_loc.
alt = top_of_glide_slope_alt_m*100 + next_WP_loc.
alt;
199 gcs().
send_text(MAV_SEVERITY_INFO,
"Landing slope too steep, aborting (%.0fm %.1fdeg)",
200 (
double)rangefinder_state.
correction, (
double)(new_slope_deg - initial_slope_deg));
202 flags.commanded_go_around =
true;
212 flags.commanded_go_around =
true;
227 float total_distance =
get_distance(prev_WP_loc, next_WP_loc);
231 if (total_distance < 1) {
236 float sink_height = (prev_WP_loc.
alt - next_WP_loc.
alt)*0.01
f;
240 if (groundspeed < 0.5
f) {
245 float sink_time = total_distance / groundspeed;
246 if (sink_time < 0.5
f) {
251 float sink_rate = sink_height / sink_time;
254 float aim_height =
flare_sec * sink_rate;
255 if (aim_height <= 0) {
266 slope = (sink_height - aim_height) / total_distance;
277 float flare_distance = groundspeed * flare_time;
280 if (flare_distance > total_distance/2) {
281 flare_distance = total_distance/2;
286 const float land_projection = 500;
287 int32_t land_bearing_cd =
get_bearing_cd(prev_WP_loc, next_WP_loc);
293 loc.
alt += aim_height*100;
297 loc.
alt -=
slope * land_projection * 100;
300 target_altitude_offset_cm = loc.
alt - prev_WP_loc.
alt;
322 if (land_airspeed >= 0) {
323 target_airspeed_cm = land_airspeed * 100;
332 }
else if (land_airspeed >= 0) {
333 target_airspeed_cm = land_airspeed * 100;
342 const int32_t head_wind_compensation_cm =
head_wind() * 0.5f * 100;
350 return constrain_int32(desired_roll_cd, level_roll_limit_cd * -1, level_roll_limit_cd);
352 return desired_roll_cd;
AP_Float slope_recalc_shallow_threshold
void type_slope_adjust_landing_slope_for_rangefinder_bump(AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state, Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float wp_distance, int32_t &target_altitude_offset_cm)
void location_update(struct Location &loc, float bearing, float distance)
void setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location ¤t_loc, int32_t &target_altitude_offset_cm)
void type_slope_setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location ¤t_loc, int32_t &target_altitude_offset_cm)
uint16_t get_prev_nav_cmd_id() const
float location_path_proportion(const struct Location &location, const struct Location &point1, const struct Location &point2)
float last_stable_correction
bool type_slope_is_on_approach(void) const
bool type_slope_verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc, const float height, const float sink_rate, const float wp_proportion, const uint32_t last_flying_ms, const bool is_armed, const bool is_flying, const bool rangefinder_state_in_range)
virtual float get_land_sinkrate(void) const =0
virtual int32_t bearing_error_cd(void) const =0
bool type_slope_request_go_around(void)
AP_Float pre_flare_airspeed
Interface definition for the various Ground Control System.
virtual void update_waypoint(const struct Location &prev_WP, const struct Location &next_WP, float dist_min=0.0f)=0
AP_Float slope_recalc_steep_threshold_to_abort
float get_distance(const struct Location &loc1, const struct Location &loc2)
virtual float get_land_airspeed(void) const =0
enum AP_Landing::@125 type_slope_stage
bool type_slope_is_complete(void) const
adjusted_altitude_cm_fn_t adjusted_altitude_cm_fn
AP_SpdHgtControl * SpdHgt_Controller
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
virtual float crosstrack_error(void) const =0
struct AP_Landing::@126 type_slope_flags
AP_Navigation * nav_controller
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
void Log_Write(const char *name, const char *labels, const char *fmt,...)
AP_Int8 crash_detection_enable
bool is_zero(const T fVal1)
int32_t constrain_int32(const int32_t amt, const int32_t low, const int32_t high)
virtual bool data_is_stale(void) const =0
static DataFlash_Class * instance(void)
struct AP_Landing::@124 flags
void send_text(MAV_SEVERITY severity, const char *fmt,...)
int32_t type_slope_constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd)
bool type_slope_is_flaring(void) const
void type_slope_log(void) const
bool type_slope_is_expecting_impact(void) const
set_target_altitude_proportion_fn_t set_target_altitude_proportion_fn
bool type_slope_is_throttle_suppressed(void) const
int32_t type_slope_get_target_airspeed_cm(void)
AP_Vehicle::FixedWing & aparm
void type_slope_verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed)
void type_slope_do_land(const AP_Mission::Mission_Command &cmd, const float relative_altitude)
virtual void update_heading_hold(int32_t navigation_heading_cd)=0
disarm_if_autoland_complete_fn_t disarm_if_autoland_complete_fn
AP_Int32 airspeed_cruise_cm
constrain_target_altitude_location_fn_t constrain_target_altitude_location_fn