APM:Libraries
AP_Landing.h
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 #pragma once
17 
18 #include <AP_Param/AP_Param.h>
19 #include <AP_Mission/AP_Mission.h>
20 #include <AP_Common/AP_Common.h>
23 #include <GCS_MAVLink/GCS.h>
24 #include "AP_Landing_Deepstall.h"
25 
28 class AP_Landing {
29  friend class AP_Landing_Deepstall;
30 
31 public:
32  FUNCTOR_TYPEDEF(set_target_altitude_proportion_fn_t, void, const Location&, float);
33  FUNCTOR_TYPEDEF(constrain_target_altitude_location_fn_t, void, const Location&, const Location&);
34  FUNCTOR_TYPEDEF(adjusted_altitude_cm_fn_t, int32_t);
35  FUNCTOR_TYPEDEF(adjusted_relative_altitude_cm_fn_t, int32_t);
36  FUNCTOR_TYPEDEF(disarm_if_autoland_complete_fn_t, void);
37  FUNCTOR_TYPEDEF(update_flight_stage_fn_t, void);
38 
39  AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_SpdHgtControl *_SpdHgt_Controller, AP_Navigation *_nav_controller, AP_Vehicle::FixedWing &_aparm,
40  set_target_altitude_proportion_fn_t _set_target_altitude_proportion_fn,
41  constrain_target_altitude_location_fn_t _constrain_target_altitude_location_fn,
42  adjusted_altitude_cm_fn_t _adjusted_altitude_cm_fn,
43  adjusted_relative_altitude_cm_fn_t _adjusted_relative_altitude_cm_fn,
44  disarm_if_autoland_complete_fn_t _disarm_if_autoland_complete_fn,
45  update_flight_stage_fn_t _update_flight_stage_fn);
46 
47  /* Do not allow copies */
48  AP_Landing(const AP_Landing &other) = delete;
49  AP_Landing &operator=(const AP_Landing&) = delete;
50 
51 
52  // NOTE: make sure to update is_type_valid()
53  enum Landing_Type {
56 // TODO: TYPE_PARACHUTE,
57 // TODO: TYPE_HELICAL,
58  };
59 
60  void do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
61  bool verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
62  const int32_t auto_state_takeoff_altitude_rel_cm, bool &throttle_suppressed);
63  bool verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
64  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);
65  void 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);
66  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);
67  bool override_servos(void);
69  bool request_go_around(void);
70  bool is_flaring(void) const;
71  bool is_on_approach(void) const;
72  bool is_ground_steering_allowed(void) const;
73  bool is_throttle_suppressed(void) const;
74  bool is_flying_forward(void) const;
75  void handle_flight_stage_change(const bool _in_landing_stage);
76  int32_t constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd);
78  bool send_landing_message(mavlink_channel_t chan);
79 
80  // terminate the flight with an immediate landing, returns false if unable to be used for termination
81  bool terminate(void);
82 
83  // helper functions
84  bool restart_landing_sequence(void);
85  float wind_alignment(const float heading_deg);
86  float head_wind(void);
87  int32_t get_target_airspeed_cm(void);
88 
89  // accessor functions for the params and states
90  static const struct AP_Param::GroupInfo var_info[];
91 
92  int16_t get_pitch_cd(void) const { return pitch_cd; }
93  float get_flare_sec(void) const { return flare_sec; }
94  int8_t get_disarm_delay(void) const { return disarm_delay; }
95  int8_t get_then_servos_neutral(void) const { return then_servos_neutral; }
96  int8_t get_abort_throttle_enable(void) const { return abort_throttle_enable; }
97  int8_t get_flap_percent(void) const { return flap_percent; }
98  int8_t get_throttle_slewrate(void) const { return throttle_slewrate; }
99  bool is_commanded_go_around(void) const { return flags.commanded_go_around; }
100  bool is_complete(void) const;
102  bool is_expecting_impact(void) const;
103  void Log(void) const;
104  const DataFlash_Class::PID_Info * get_pid_info(void) const;
105 
106  // landing altitude offset (meters)
107  float alt_offset;
108 
109 private:
110  struct {
111  // denotes if a go-around has been commanded for landing
113 
114  // are we in auto and flight_stage is LAND
115  bool in_progress:1;
116  } flags;
117 
118  // same as land_slope but sampled once before a rangefinder changes the slope. This should be the original mission planned slope
120 
121  // calculated approach slope during auto-landing: ((prev_WP_loc.alt - next_WP_loc.alt)*0.01f - flare_sec * sink_rate) / get_distance(prev_WP_loc, next_WP_loc)
122  float slope;
123 
128 
130 
131  set_target_altitude_proportion_fn_t set_target_altitude_proportion_fn;
132  constrain_target_altitude_location_fn_t constrain_target_altitude_location_fn;
133  adjusted_altitude_cm_fn_t adjusted_altitude_cm_fn;
134  adjusted_relative_altitude_cm_fn_t adjusted_relative_altitude_cm_fn;
135  disarm_if_autoland_complete_fn_t disarm_if_autoland_complete_fn;
136  update_flight_stage_fn_t update_flight_stage_fn;
137 
138  // support for deepstall landings
140 
141  AP_Int16 pitch_cd;
142  AP_Float flare_alt;
143  AP_Float flare_sec;
145  AP_Float pre_flare_alt;
146  AP_Float pre_flare_sec;
149  AP_Int8 disarm_delay;
152  AP_Int8 flap_percent;
154  AP_Int8 type;
155 
156  // Land Type STANDARD GLIDE SLOPE
157 
158  enum {
164 
165  struct {
166  // once landed, post some landing statistics to the GCS
167  bool post_stats:1;
168 
171 
172  void type_slope_do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
173  void type_slope_verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed);
174  bool type_slope_verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
175  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);
176 
177  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);
178 
179  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);
180  int32_t type_slope_get_target_airspeed_cm(void);
182  int32_t type_slope_constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd);
183  bool type_slope_request_go_around(void);
184  void type_slope_log(void) const;
185  bool type_slope_is_complete(void) const;
186  bool type_slope_is_flaring(void) const;
187  bool type_slope_is_on_approach(void) const;
188  bool type_slope_is_expecting_impact(void) const;
189  bool type_slope_is_throttle_suppressed(void) const;
190 };
AP_Int8 abort_throttle_enable
Definition: AP_Landing.h:151
void check_if_need_to_abort(const AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state)
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
bool verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc, const int32_t auto_state_takeoff_altitude_rel_cm, bool &throttle_suppressed)
Definition: AP_Landing.cpp:224
AP_Float flare_sec
Definition: AP_Landing.h:143
AP_Int8 then_servos_neutral
Definition: AP_Landing.h:150
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
int16_t get_pitch_cd(void) const
Definition: AP_Landing.h:92
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)
bool has_aborted_due_to_slope_recalc
Definition: AP_Landing.h:169
AP_Int8 disarm_delay
Definition: AP_Landing.h:149
bool send_landing_message(mavlink_channel_t chan)
Definition: AP_Landing.cpp:267
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)
FUNCTOR_TYPEDEF(set_target_altitude_proportion_fn_t, void, const Location &, float)
int8_t get_abort_throttle_enable(void) const
Definition: AP_Landing.h:96
float wind_alignment(const float heading_deg)
Definition: AP_Landing.cpp:487
void handle_flight_stage_change(const bool _in_landing_stage)
Definition: AP_Landing.cpp:554
bool type_slope_request_go_around(void)
AP_Float pre_flare_airspeed
Definition: AP_Landing.h:144
AP_Int16 pitch_cd
Definition: AP_Landing.h:141
Interface definition for the various Ground Control System.
Object managing Mission.
Definition: AP_Mission.h:45
bool is_commanded_go_around(void) const
Definition: AP_Landing.h:99
AP_Float slope_recalc_steep_threshold_to_abort
Definition: AP_Landing.h:148
enum AP_Landing::@125 type_slope_stage
bool type_slope_is_complete(void) const
adjusted_altitude_cm_fn_t adjusted_altitude_cm_fn
Definition: AP_Landing.h:133
bool post_stats
Definition: AP_Landing.h:167
AP_Mission & mission
Definition: AP_Landing.h:124
void set_initial_slope(void)
Definition: AP_Landing.h:101
AP_SpdHgtControl * SpdHgt_Controller
Definition: AP_Landing.h:126
A system for managing and storing variables that are of general interest to the system.
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
generic navigation controller interface
bool get_target_altitude_location(Location &location)
Definition: AP_Landing.cpp:466
generic speed & height controller interface
bool request_go_around(void)
Definition: AP_Landing.cpp:535
void Log(void) const
Definition: AP_Landing.cpp:577
Class managing Plane Deepstall landing methods.
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
AP_Float flare_alt
Definition: AP_Landing.h:142
bool is_ground_steering_allowed(void) const
Definition: AP_Landing.cpp:318
bool is_expecting_impact(void) const
Definition: AP_Landing.cpp:336
bool is_flying_forward(void) const
Definition: AP_Landing.cpp:613
struct AP_Landing::@124 flags
AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_SpdHgtControl *_SpdHgt_Controller, AP_Navigation *_nav_controller, AP_Vehicle::FixedWing &_aparm, set_target_altitude_proportion_fn_t _set_target_altitude_proportion_fn, constrain_target_altitude_location_fn_t _constrain_target_altitude_location_fn, adjusted_altitude_cm_fn_t _adjusted_altitude_cm_fn, adjusted_relative_altitude_cm_fn_t _adjusted_relative_altitude_cm_fn, disarm_if_autoland_complete_fn_t _disarm_if_autoland_complete_fn, update_flight_stage_fn_t _update_flight_stage_fn)
Definition: AP_Landing.cpp:149
int32_t get_target_airspeed_cm(void)
Definition: AP_Landing.cpp:511
AP_Int8 type
Definition: AP_Landing.h:154
bool override_servos(void)
Definition: AP_Landing.cpp:352
int32_t type_slope_constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd)
Class managing ArduPlane landing methods.
Definition: AP_Landing.h:28
float slope
Definition: AP_Landing.h:122
bool commanded_go_around
Definition: AP_Landing.h:112
bool type_slope_is_flaring(void) const
update_flight_stage_fn_t update_flight_stage_fn
Definition: AP_Landing.h:136
void type_slope_log(void) const
AP_Landing & operator=(const AP_Landing &)=delete
AP_Int8 throttle_slewrate
Definition: AP_Landing.h:153
bool type_slope_is_expecting_impact(void) const
Common definitions and utility routines for the ArduPilot libraries.
float alt_offset
Definition: AP_Landing.h:107
Vector2f location
Definition: location.cpp:16
bool is_complete(void) const
Definition: AP_Landing.cpp:565
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
void do_land(const AP_Mission::Mission_Command &cmd, const float relative_altitude)
Definition: AP_Landing.cpp:173
bool terminate(void)
Definition: AP_Landing.cpp:632
const DataFlash_Class::PID_Info * get_pid_info(void) const
Definition: AP_Landing.cpp:368
bool is_flaring(void) const
Definition: AP_Landing.cpp:281
bool 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)
Definition: AP_Landing.cpp:198
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
AP_Landing_Deepstall deepstall
Definition: AP_Landing.h:139
int32_t constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd)
Definition: AP_Landing.cpp:454
bool restart_landing_sequence(void)
Definition: AP_Landing.cpp:405
bool in_progress
Definition: AP_Landing.h:115
float get_flare_sec(void) const
Definition: AP_Landing.h:93
bool type_slope_is_throttle_suppressed(void) const
bool is_throttle_suppressed(void) const
Definition: AP_Landing.cpp:594
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)
void type_slope_do_land(const AP_Mission::Mission_Command &cmd, const float relative_altitude)
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Landing.h:90
AP_Int8 flap_percent
Definition: AP_Landing.h:152
int8_t get_flap_percent(void) const
Definition: AP_Landing.h:97
int8_t get_disarm_delay(void) const
Definition: AP_Landing.h:94
void 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)
Definition: AP_Landing.cpp:254
adjusted_relative_altitude_cm_fn_t adjusted_relative_altitude_cm_fn
Definition: AP_Landing.h:134
void type_slope_check_if_need_to_abort(const AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state)
float initial_slope
Definition: AP_Landing.h:119
bool is_on_approach(void) const
Definition: AP_Landing.cpp:301
disarm_if_autoland_complete_fn_t disarm_if_autoland_complete_fn
Definition: AP_Landing.h:135
int8_t get_then_servos_neutral(void) const
Definition: AP_Landing.h:95
int8_t get_throttle_slewrate(void) const
Definition: AP_Landing.h:98
constrain_target_altitude_location_fn_t constrain_target_altitude_location_fn
Definition: AP_Landing.h:132