AP_Landing.h 8.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. #include <AP_Param/AP_Param.h>
  15. #include <AP_Mission/AP_Mission.h>
  16. #include <AP_Common/AP_Common.h>
  17. #include <AP_SpdHgtControl/AP_SpdHgtControl.h>
  18. #include <AP_Navigation/AP_Navigation.h>
  19. #include "AP_Landing_Deepstall.h"
  20. #include <AP_Common/Location.h>
  21. /// @class AP_Landing
  22. /// @brief Class managing ArduPlane landing methods
  23. class AP_Landing {
  24. friend class AP_Landing_Deepstall;
  25. public:
  26. FUNCTOR_TYPEDEF(set_target_altitude_proportion_fn_t, void, const Location&, float);
  27. FUNCTOR_TYPEDEF(constrain_target_altitude_location_fn_t, void, const Location&, const Location&);
  28. FUNCTOR_TYPEDEF(adjusted_altitude_cm_fn_t, int32_t);
  29. FUNCTOR_TYPEDEF(adjusted_relative_altitude_cm_fn_t, int32_t);
  30. FUNCTOR_TYPEDEF(disarm_if_autoland_complete_fn_t, void);
  31. FUNCTOR_TYPEDEF(update_flight_stage_fn_t, void);
  32. AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_SpdHgtControl *_SpdHgt_Controller, AP_Navigation *_nav_controller, AP_Vehicle::FixedWing &_aparm,
  33. set_target_altitude_proportion_fn_t _set_target_altitude_proportion_fn,
  34. constrain_target_altitude_location_fn_t _constrain_target_altitude_location_fn,
  35. adjusted_altitude_cm_fn_t _adjusted_altitude_cm_fn,
  36. adjusted_relative_altitude_cm_fn_t _adjusted_relative_altitude_cm_fn,
  37. disarm_if_autoland_complete_fn_t _disarm_if_autoland_complete_fn,
  38. update_flight_stage_fn_t _update_flight_stage_fn);
  39. /* Do not allow copies */
  40. AP_Landing(const AP_Landing &other) = delete;
  41. AP_Landing &operator=(const AP_Landing&) = delete;
  42. // NOTE: make sure to update is_type_valid()
  43. enum Landing_Type {
  44. TYPE_STANDARD_GLIDE_SLOPE = 0,
  45. TYPE_DEEPSTALL = 1,
  46. // TODO: TYPE_PARACHUTE,
  47. // TODO: TYPE_HELICAL,
  48. };
  49. void do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
  50. bool verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
  51. const int32_t auto_state_takeoff_altitude_rel_cm, bool &throttle_suppressed);
  52. bool verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
  53. 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);
  54. 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);
  55. 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);
  56. bool override_servos(void);
  57. void check_if_need_to_abort(const AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state);
  58. bool request_go_around(void);
  59. bool is_flaring(void) const;
  60. bool is_on_approach(void) const;
  61. bool is_ground_steering_allowed(void) const;
  62. bool is_throttle_suppressed(void) const;
  63. bool is_flying_forward(void) const;
  64. void handle_flight_stage_change(const bool _in_landing_stage);
  65. int32_t constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd);
  66. bool get_target_altitude_location(Location &location);
  67. bool send_landing_message(mavlink_channel_t chan);
  68. // terminate the flight with an immediate landing, returns false if unable to be used for termination
  69. bool terminate(void);
  70. // helper functions
  71. bool restart_landing_sequence(void);
  72. float wind_alignment(const float heading_deg);
  73. float head_wind(void);
  74. int32_t get_target_airspeed_cm(void);
  75. // accessor functions for the params and states
  76. static const struct AP_Param::GroupInfo var_info[];
  77. int16_t get_pitch_cd(void) const { return pitch_cd; }
  78. float get_flare_sec(void) const { return flare_sec; }
  79. int8_t get_disarm_delay(void) const { return disarm_delay; }
  80. int8_t get_then_servos_neutral(void) const { return then_servos_neutral; }
  81. int8_t get_abort_throttle_enable(void) const { return abort_throttle_enable; }
  82. int8_t get_flap_percent(void) const { return flap_percent; }
  83. int8_t get_throttle_slewrate(void) const { return throttle_slewrate; }
  84. bool is_commanded_go_around(void) const { return flags.commanded_go_around; }
  85. bool is_complete(void) const;
  86. void set_initial_slope(void) { initial_slope = slope; }
  87. bool is_expecting_impact(void) const;
  88. void Log(void) const;
  89. const AP_Logger::PID_Info * get_pid_info(void) const;
  90. // landing altitude offset (meters)
  91. float alt_offset;
  92. private:
  93. struct {
  94. // denotes if a go-around has been commanded for landing
  95. bool commanded_go_around:1;
  96. // are we in auto and flight_stage is LAND
  97. bool in_progress:1;
  98. } flags;
  99. // same as land_slope but sampled once before a rangefinder changes the slope. This should be the original mission planned slope
  100. float initial_slope;
  101. // calculated approach slope during auto-landing: ((prev_WP_loc.alt - next_WP_loc.alt)*0.01f - flare_sec * sink_rate) / prev_WP_loc.get_distance(next_WP_loc)
  102. float slope;
  103. AP_Mission &mission;
  104. AP_AHRS &ahrs;
  105. AP_SpdHgtControl *SpdHgt_Controller;
  106. AP_Navigation *nav_controller;
  107. AP_Vehicle::FixedWing &aparm;
  108. set_target_altitude_proportion_fn_t set_target_altitude_proportion_fn;
  109. constrain_target_altitude_location_fn_t constrain_target_altitude_location_fn;
  110. adjusted_altitude_cm_fn_t adjusted_altitude_cm_fn;
  111. adjusted_relative_altitude_cm_fn_t adjusted_relative_altitude_cm_fn;
  112. disarm_if_autoland_complete_fn_t disarm_if_autoland_complete_fn;
  113. update_flight_stage_fn_t update_flight_stage_fn;
  114. // support for deepstall landings
  115. AP_Landing_Deepstall deepstall;
  116. AP_Int16 pitch_cd;
  117. AP_Float flare_alt;
  118. AP_Float flare_sec;
  119. AP_Float pre_flare_airspeed;
  120. AP_Float pre_flare_alt;
  121. AP_Float pre_flare_sec;
  122. AP_Float slope_recalc_shallow_threshold;
  123. AP_Float slope_recalc_steep_threshold_to_abort;
  124. AP_Int8 disarm_delay;
  125. AP_Int8 then_servos_neutral;
  126. AP_Int8 abort_throttle_enable;
  127. AP_Int8 flap_percent;
  128. AP_Int8 throttle_slewrate;
  129. AP_Int8 type;
  130. // Land Type STANDARD GLIDE SLOPE
  131. enum {
  132. SLOPE_STAGE_NORMAL,
  133. SLOPE_STAGE_APPROACH,
  134. SLOPE_STAGE_PREFLARE,
  135. SLOPE_STAGE_FINAL
  136. } type_slope_stage;
  137. struct {
  138. // once landed, post some landing statistics to the GCS
  139. bool post_stats:1;
  140. bool has_aborted_due_to_slope_recalc:1;
  141. } type_slope_flags;
  142. void type_slope_do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
  143. void type_slope_verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed);
  144. bool type_slope_verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
  145. 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);
  146. 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);
  147. 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);
  148. int32_t type_slope_get_target_airspeed_cm(void);
  149. void type_slope_check_if_need_to_abort(const AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state);
  150. int32_t type_slope_constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd);
  151. bool type_slope_request_go_around(void);
  152. void type_slope_log(void) const;
  153. bool type_slope_is_complete(void) const;
  154. bool type_slope_is_flaring(void) const;
  155. bool type_slope_is_on_approach(void) const;
  156. bool type_slope_is_expecting_impact(void) const;
  157. bool type_slope_is_throttle_suppressed(void) const;
  158. };