APM:Libraries
AP_Landing_Slope.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * AP_Landing_Slope.cpp - Landing logic handler for ArduPlane for STANDARD_GLIDE_SLOPE
18  */
19 
20 #include "AP_Landing.h"
21 #include <GCS_MAVLink/GCS.h>
22 #include <AP_HAL/AP_HAL.h>
23 
24 void AP_Landing::type_slope_do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude)
25 {
26  initial_slope = 0;
27  slope = 0;
28 
29  // once landed, post some landing statistics to the GCS
30  type_slope_flags.post_stats = false;
31 
33  gcs().send_text(MAV_SEVERITY_INFO, "Landing approach start at %.1fm", (double)relative_altitude);
34 }
35 
36 void AP_Landing::type_slope_verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed)
37 {
38  // when aborting a landing, mimic the verify_takeoff with steering hold. Once
39  // the altitude has been reached, restart the landing sequence
40  throttle_suppressed = false;
41  nav_controller->update_heading_hold(get_bearing_cd(prev_WP_loc, next_WP_loc));
42 }
43 
44 
45 /*
46  update navigation for landing. Called when on landing approach or
47  final flare
48  */
49 bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
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)
51 {
52  // we don't 'verify' landing in the sense that it never completes,
53  // so we don't verify command completion. Instead we use this to
54  // adjust final landing parameters
55 
56  // determine stage
58  const bool heading_lined_up = abs(nav_controller->bearing_error_cd()) < 1000 && !nav_controller->data_is_stale();
59  const bool on_flight_line = fabsf(nav_controller->crosstrack_error()) < 5.0f && !nav_controller->data_is_stale();
60  const bool below_prev_WP = current_loc.alt < prev_WP_loc.alt;
61  if ((mission.get_prev_nav_cmd_id() == MAV_CMD_NAV_LOITER_TO_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.5f)) {
66  }
67  }
68 
69 
70  /* Set land_complete (which starts the flare) under 3 conditions:
71  1) we are within LAND_FLARE_ALT meters of the landing altitude
72  2) we are within LAND_FLARE_SEC of the landing point vertically
73  by the calculated sink rate (if LAND_FLARE_SEC != 0)
74  3) we have gone past the landing point and don't have
75  rangefinder data (to prevent us keeping throttle on
76  after landing if we've had positive baro drift)
77  */
78 
79  // flare check:
80  // 1) below flare alt/sec requires approach stage check because if sec/alt are set too
81  // large, and we're on a hard turn to line up for approach, we'll prematurely flare by
82  // skipping approach phase and the extreme roll limits will make it hard to line up with runway
83  // 2) passed land point and don't have an accurate AGL
84  // 3) probably crashed (ensures motor gets turned off)
85 
86  const bool on_approach_stage = type_slope_is_on_approach();
87  const bool below_flare_alt = (height <= flare_alt);
88  const bool below_flare_sec = (flare_sec > 0 && height <= sink_rate * flare_sec);
89  const bool probably_crashed = (aparm.crash_detection_enable && fabsf(sink_rate) < 0.2f && !is_flying);
90 
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) ||
94  probably_crashed) {
95 
97  type_slope_flags.post_stats = true;
98  if (is_flying && (AP_HAL::millis()-last_flying_ms) > 3000) {
99  gcs().send_text(MAV_SEVERITY_CRITICAL, "Flare crash detected: speed=%.1f", (double)AP::gps().ground_speed());
100  } else {
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(),
104  (double)get_distance(current_loc, next_WP_loc));
105  }
107  }
108 
109 
110  if (AP::gps().ground_speed() < 3) {
111  // reload any airspeed or groundspeed parameters that may have
112  // been set for landing. We don't do this till ground
113  // speed drops below 3.0 m/s as otherwise we will change
114  // target speeds too early.
115  aparm.airspeed_cruise_cm.load();
116  aparm.min_gndspeed_cm.load();
117  aparm.throttle_cruise.load();
118  }
120  bool reached_pre_flare_alt = pre_flare_alt > 0 && (height <= pre_flare_alt);
121  bool reached_pre_flare_sec = pre_flare_sec > 0 && (height <= sink_rate * pre_flare_sec);
122  if (reached_pre_flare_alt || reached_pre_flare_sec) {
124  }
125  }
126 
127  /*
128  when landing we keep the L1 navigation waypoint 200m ahead. This
129  prevents sudden turns if we overshoot the landing point
130  */
131  struct Location land_WP_loc = next_WP_loc;
132  int32_t land_bearing_cd = get_bearing_cd(prev_WP_loc, next_WP_loc);
133  location_update(land_WP_loc,
134  land_bearing_cd*0.01f,
135  get_distance(prev_WP_loc, current_loc) + 200);
136  nav_controller->update_waypoint(prev_WP_loc, land_WP_loc);
137 
138  // once landed and stationary, post some statistics
139  // this is done before disarm_if_autoland_complete() so that it happens on the next loop after the disarm
140  if (type_slope_flags.post_stats && !is_armed) {
141  type_slope_flags.post_stats = false;
142  gcs().send_text(MAV_SEVERITY_INFO, "Distance from LAND point=%.2fm", (double)get_distance(current_loc, next_WP_loc));
143  }
144 
145  // check if we should auto-disarm after a confirmed landing
148  }
149 
150  /*
151  we return false as a landing mission item never completes
152 
153  we stay on this waypoint unless the GCS commands us to change
154  mission item, reset the mission, command a go-around or finish
155  a land_abort procedure.
156  */
157  return false;
158 }
159 
160 void AP_Landing::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 &current_loc, const float wp_distance, int32_t &target_altitude_offset_cm)
161 {
162  // check the rangefinder correction for a large change. When found, recalculate the glide slope. This is done by
163  // determining the slope from your current location to the land point then following that back up to the approach
164  // altitude and moving the prev_wp to that location. From there
165  float correction_delta = fabsf(rangefinder_state.last_stable_correction) - fabsf(rangefinder_state.correction);
166 
168  fabsf(correction_delta) < slope_recalc_shallow_threshold) {
169  return;
170  }
171 
172  rangefinder_state.last_stable_correction = rangefinder_state.correction;
173 
174  float corrected_alt_m = (adjusted_altitude_cm_fn() - next_WP_loc.alt)*0.01f - rangefinder_state.correction;
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;
178 
179  // re-calculate auto_state.land_slope with updated prev_WP_loc
180  setup_landing_glide_slope(prev_WP_loc, next_WP_loc, current_loc, target_altitude_offset_cm);
181 
182  if (rangefinder_state.correction >= 0) { // we're too low or object is below us
183  // correction positive means we're too low so we should continue on with
184  // the newly computed shallower slope instead of pitching/throttling up
185 
186  } else if (slope_recalc_steep_threshold_to_abort > 0 && !type_slope_flags.has_aborted_due_to_slope_recalc) {
187  // correction negative means we're too high and need to point down (and speed up) to re-align
188  // to land on target. A large negative correction means we would have to dive down a lot and will
189  // generating way too much speed that we can not bleed off in time. It is better to remember
190  // the large baro altitude offset and abort the landing to come around again with the correct altitude
191  // offset and "perfect" slope.
192 
193  // calculate projected slope with projected alt
194  float new_slope_deg = degrees(atanf(slope));
195  float initial_slope_deg = degrees(atanf(initial_slope));
196 
197  // is projected slope too steep?
198  if (new_slope_deg - initial_slope_deg > slope_recalc_steep_threshold_to_abort) {
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));
201  alt_offset = rangefinder_state.correction;
202  flags.commanded_go_around = true;
203  type_slope_flags.has_aborted_due_to_slope_recalc = true; // only allow this once.
204  Log();
205  }
206  }
207 }
208 
209 
211 {
212  flags.commanded_go_around = true;
213  return true;
214 }
215 
216 /*
217  a special glide slope calculation for the landing approach
218 
219  During the land approach use a linear glide slope to a point
220  projected through the landing point. We don't use the landing point
221  itself as that leads to discontinuities close to the landing point,
222  which can lead to erratic pitch control
223  */
224 
225 void AP_Landing::type_slope_setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location &current_loc, int32_t &target_altitude_offset_cm)
226 {
227  float total_distance = get_distance(prev_WP_loc, next_WP_loc);
228 
229  // If someone mistakenly puts all 0's in their LAND command then total_distance
230  // will be calculated as 0 and cause a divide by 0 error below. Lets avoid that.
231  if (total_distance < 1) {
232  total_distance = 1;
233  }
234 
235  // height we need to sink for this WP
236  float sink_height = (prev_WP_loc.alt - next_WP_loc.alt)*0.01f;
237 
238  // current ground speed
239  float groundspeed = ahrs.groundspeed();
240  if (groundspeed < 0.5f) {
241  groundspeed = 0.5f;
242  }
243 
244  // calculate time to lose the needed altitude
245  float sink_time = total_distance / groundspeed;
246  if (sink_time < 0.5f) {
247  sink_time = 0.5f;
248  }
249 
250  // find the sink rate needed for the target location
251  float sink_rate = sink_height / sink_time;
252 
253  // the height we aim for is the one to give us the right flare point
254  float aim_height = flare_sec * sink_rate;
255  if (aim_height <= 0) {
256  aim_height = flare_alt;
257  }
258 
259  // don't allow the aim height to be too far above LAND_FLARE_ALT
260  if (flare_alt > 0 && aim_height > flare_alt*2) {
261  aim_height = flare_alt*2;
262  }
263 
264  // calculate slope to landing point
265  bool is_first_calc = is_zero(slope);
266  slope = (sink_height - aim_height) / total_distance;
267  if (is_first_calc) {
268  gcs().send_text(MAV_SEVERITY_INFO, "Landing glide slope %.1f degrees", (double)degrees(atanf(slope)));
269  }
270 
271 
272  // time before landing that we will flare
273  float flare_time = aim_height / SpdHgt_Controller->get_land_sinkrate();
274 
275  // distance to flare is based on ground speed, adjusted as we
276  // get closer. This takes into account the wind
277  float flare_distance = groundspeed * flare_time;
278 
279  // don't allow the flare before half way along the final leg
280  if (flare_distance > total_distance/2) {
281  flare_distance = total_distance/2;
282  }
283 
284  // project a point 500 meters past the landing point, passing
285  // through the landing point
286  const float land_projection = 500;
287  int32_t land_bearing_cd = get_bearing_cd(prev_WP_loc, next_WP_loc);
288 
289  // now calculate our aim point, which is before the landing
290  // point and above it
291  Location loc = next_WP_loc;
292  location_update(loc, land_bearing_cd*0.01f, -flare_distance);
293  loc.alt += aim_height*100;
294 
295  // calculate point along that slope 500m ahead
296  location_update(loc, land_bearing_cd*0.01f, land_projection);
297  loc.alt -= slope * land_projection * 100;
298 
299  // setup the offset_cm for set_target_altitude_proportion()
300  target_altitude_offset_cm = loc.alt - prev_WP_loc.alt;
301 
302  // calculate the proportion we are to the target
303  float land_proportion = location_path_proportion(current_loc, prev_WP_loc, loc);
304 
305  // now setup the glide slope for landing
306  set_target_altitude_proportion_fn(loc, 1.0f - land_proportion);
307 
308  // stay within the range of the start and end locations in altitude
309  constrain_target_altitude_location_fn(loc, prev_WP_loc);
310 }
311 
313 
314  // we're landing, check for custom approach and
315  // pre-flare airspeeds. Also increase for head-winds
316 
317  const float land_airspeed = SpdHgt_Controller->get_land_airspeed();
318  int32_t target_airspeed_cm = aparm.airspeed_cruise_cm;
319 
320  switch (type_slope_stage) {
322  if (land_airspeed >= 0) {
323  target_airspeed_cm = land_airspeed * 100;
324  }
325  break;
326 
328  case SLOPE_STAGE_FINAL:
329  if (pre_flare_airspeed > 0) {
330  // if we just preflared then continue using the pre-flare airspeed during final flare
331  target_airspeed_cm = pre_flare_airspeed * 100;
332  } else if (land_airspeed >= 0) {
333  target_airspeed_cm = land_airspeed * 100;
334  }
335  break;
336 
337  default:
338  break;
339  }
340 
341  // when landing, add half of head-wind.
342  const int32_t head_wind_compensation_cm = head_wind() * 0.5f * 100;
343 
344  // Do not lower it or exceed cruise speed
345  return constrain_int32(target_airspeed_cm + head_wind_compensation_cm, target_airspeed_cm, aparm.airspeed_cruise_cm);
346 }
347 
348 int32_t AP_Landing::type_slope_constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd) {
350  return constrain_int32(desired_roll_cd, level_roll_limit_cd * -1, level_roll_limit_cd);
351  } else {
352  return desired_roll_cd;
353  }
354 }
355 
357 {
359 }
360 
361 
363 {
366 }
367 
369 {
372 }
373 
375 {
377 }
378 
380 {
381  // log to DataFlash
382  DataFlash_Class::instance()->Log_Write("LAND", "TimeUS,stage,f1,f2,slope,slopeInit,altO", "QBBBfff",
385  flags,
387  (double)slope,
388  (double)initial_slope,
389  (double)alt_offset);
390 }
391 
393 {
395 }
AP_Float slope_recalc_shallow_threshold
Definition: AP_Landing.h:147
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 &current_loc, const float wp_distance, int32_t &target_altitude_offset_cm)
AP_AHRS & ahrs
Definition: AP_Landing.h:125
void location_update(struct Location &loc, float bearing, float distance)
Definition: location.cpp:115
AP_Float flare_sec
Definition: AP_Landing.h:143
void setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location &current_loc, int32_t &target_altitude_offset_cm)
Definition: AP_Landing.cpp:388
void type_slope_setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc, const Location &current_loc, int32_t &target_altitude_offset_cm)
uint16_t get_prev_nav_cmd_id() const
Definition: AP_Mission.h:395
float location_path_proportion(const struct Location &location, const struct Location &point1, const struct Location &point2)
Definition: location.cpp:94
bool type_slope_is_on_approach(void) const
bool type_slope_verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_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
Definition: AP_Landing.h:144
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
Definition: AP_Landing.h:148
float get_distance(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:36
virtual float get_land_airspeed(void) const =0
enum AP_Landing::@125 type_slope_stage
GCS & gcs()
bool type_slope_is_complete(void) const
adjusted_altitude_cm_fn_t adjusted_altitude_cm_fn
Definition: AP_Landing.h:133
AP_Mission & mission
Definition: AP_Landing.h:124
AP_SpdHgtControl * SpdHgt_Controller
Definition: AP_Landing.h:126
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:56
virtual float crosstrack_error(void) const =0
AP_Float pre_flare_sec
Definition: AP_Landing.h:146
struct AP_Landing::@126 type_slope_flags
AP_Navigation * nav_controller
Definition: AP_Landing.h:127
AP_Int32 min_gndspeed_cm
Definition: AP_Vehicle.h:39
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
void Log(void) const
Definition: AP_Landing.cpp:577
AP_Int8 crash_detection_enable
Definition: AP_Vehicle.h:40
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
int32_t constrain_int32(const int32_t amt, const int32_t low, const int32_t high)
Definition: AP_Math.h:152
uint32_t millis()
Definition: system.cpp:157
virtual bool data_is_stale(void) const =0
AP_Float flare_alt
Definition: AP_Landing.h:142
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
uint64_t micros64()
Definition: system.cpp:162
struct AP_Landing::@124 flags
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
int32_t type_slope_constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd)
float slope
Definition: AP_Landing.h:122
bool type_slope_is_flaring(void) const
void type_slope_log(void) const
bool type_slope_is_expecting_impact(void) const
float alt_offset
Definition: AP_Landing.h:107
AP_Float pre_flare_alt
Definition: AP_Landing.h:145
set_target_altitude_proportion_fn_t set_target_altitude_proportion_fn
Definition: AP_Landing.h:131
bool type_slope_is_throttle_suppressed(void) const
int32_t type_slope_get_target_airspeed_cm(void)
AP_Vehicle::FixedWing & aparm
Definition: AP_Landing.h:129
float head_wind(void)
Definition: AP_Landing.cpp:497
void type_slope_verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed)
float groundspeed(void)
Definition: AP_AHRS.h:359
void type_slope_do_land(const AP_Mission::Mission_Command &cmd, const float relative_altitude)
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
#define degrees(x)
Definition: moduletest.c:23
virtual void update_heading_hold(int32_t navigation_heading_cd)=0
float initial_slope
Definition: AP_Landing.h:119
disarm_if_autoland_complete_fn_t disarm_if_autoland_complete_fn
Definition: AP_Landing.h:135
AP_Int32 airspeed_cruise_cm
Definition: AP_Vehicle.h:38
constrain_target_altitude_location_fn_t constrain_target_altitude_location_fn
Definition: AP_Landing.h:132