2016-11-16 21:05:37 -04:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <AP_Mission/AP_Mission.h>
|
2016-11-17 21:33:56 -04:00
|
|
|
#include <AP_Common/AP_Common.h>
|
2021-11-12 13:54:43 -04:00
|
|
|
#include <AP_TECS/AP_TECS.h>
|
2016-11-21 20:09:17 -04:00
|
|
|
#include <AP_Navigation/AP_Navigation.h>
|
2017-02-14 15:21:59 -04:00
|
|
|
#include "AP_Landing_Deepstall.h"
|
2019-04-05 03:11:26 -03:00
|
|
|
#include <AP_Common/Location.h>
|
2016-11-16 21:05:37 -04:00
|
|
|
|
|
|
|
/// @class AP_Landing
|
|
|
|
/// @brief Class managing ArduPlane landing methods
|
2017-08-30 16:05:07 -03:00
|
|
|
class AP_Landing {
|
2017-02-22 15:53:25 -04:00
|
|
|
friend class AP_Landing_Deepstall;
|
2016-11-16 21:05:37 -04:00
|
|
|
|
2017-08-30 16:05:07 -03:00
|
|
|
public:
|
2016-11-21 20:09:17 -04:00
|
|
|
FUNCTOR_TYPEDEF(set_target_altitude_proportion_fn_t, void, const Location&, float);
|
|
|
|
FUNCTOR_TYPEDEF(constrain_target_altitude_location_fn_t, void, const Location&, const Location&);
|
|
|
|
FUNCTOR_TYPEDEF(adjusted_altitude_cm_fn_t, int32_t);
|
|
|
|
FUNCTOR_TYPEDEF(adjusted_relative_altitude_cm_fn_t, int32_t);
|
|
|
|
FUNCTOR_TYPEDEF(disarm_if_autoland_complete_fn_t, void);
|
|
|
|
FUNCTOR_TYPEDEF(update_flight_stage_fn_t, void);
|
|
|
|
|
2022-09-29 20:10:40 -03:00
|
|
|
AP_Landing(AP_Mission &_mission, AP_AHRS &_ahrs, AP_TECS *_tecs_Controller, AP_Navigation *_nav_controller, AP_FixedWing &_aparm,
|
2017-02-22 15:53:25 -04:00
|
|
|
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,
|
2017-12-12 21:06:12 -04:00
|
|
|
update_flight_stage_fn_t _update_flight_stage_fn);
|
2017-08-30 16:05:07 -03:00
|
|
|
|
|
|
|
/* Do not allow copies */
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(AP_Landing);
|
2017-01-10 01:29:50 -04:00
|
|
|
|
|
|
|
|
|
|
|
// NOTE: make sure to update is_type_valid()
|
2016-12-05 20:15:20 -04:00
|
|
|
enum Landing_Type {
|
|
|
|
TYPE_STANDARD_GLIDE_SLOPE = 0,
|
2021-07-01 22:06:47 -03:00
|
|
|
#if HAL_LANDING_DEEPSTALL_ENABLED
|
2017-02-14 15:21:59 -04:00
|
|
|
TYPE_DEEPSTALL = 1,
|
2021-07-01 22:06:47 -03:00
|
|
|
#endif
|
2016-12-05 20:15:20 -04:00
|
|
|
// TODO: TYPE_PARACHUTE,
|
|
|
|
// TODO: TYPE_HELICAL,
|
|
|
|
};
|
|
|
|
|
2020-05-18 03:57:29 -03:00
|
|
|
// we support upto 32 boolean bits for users wanting to change landing behaviour.
|
|
|
|
enum OptionsMask {
|
|
|
|
ON_LANDING_FLARE_USE_THR_MIN = (1<<0), // If set then set trottle to thr_min instead of zero on final flare
|
2023-01-17 18:11:32 -04:00
|
|
|
ON_LANDING_USE_ARSPD_MAX = (1<<1), // If set then allow landing throttle constraint to be increased from trim airspeed to max airspeed (ARSPD_FBW_MAX)
|
2020-05-18 03:57:29 -03:00
|
|
|
};
|
|
|
|
|
2017-01-10 15:47:31 -04:00
|
|
|
void do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
|
2017-01-10 03:44:25 -04:00
|
|
|
bool verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, const Location ¤t_loc,
|
|
|
|
const int32_t auto_state_takeoff_altitude_rel_cm, bool &throttle_suppressed);
|
|
|
|
bool 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);
|
2022-09-29 20:10:40 -03:00
|
|
|
void adjust_landing_slope_for_rangefinder_bump(AP_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);
|
2016-11-21 20:09:17 -04:00
|
|
|
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);
|
2017-02-15 16:54:16 -04:00
|
|
|
bool override_servos(void);
|
2022-09-29 20:10:40 -03:00
|
|
|
void check_if_need_to_abort(const AP_FixedWing::Rangefinder_State &rangefinder_state);
|
2016-12-06 16:21:04 -04:00
|
|
|
bool request_go_around(void);
|
2017-01-10 01:29:50 -04:00
|
|
|
bool is_flaring(void) const;
|
|
|
|
bool is_on_approach(void) const;
|
2017-02-14 15:11:01 -04:00
|
|
|
bool is_ground_steering_allowed(void) const;
|
|
|
|
bool is_throttle_suppressed(void) const;
|
2017-05-15 15:35:05 -03:00
|
|
|
bool is_flying_forward(void) const;
|
2020-05-18 03:57:29 -03:00
|
|
|
bool use_thr_min_during_flare(void) const; //defaults to false, but _options bit zero enables it.
|
2023-01-17 18:11:32 -04:00
|
|
|
bool allow_max_airspeed_on_land(void) const; //defaults to false, but _options bit one enables it.
|
2017-01-11 02:18:09 -04:00
|
|
|
void handle_flight_stage_change(const bool _in_landing_stage);
|
2017-01-11 15:06:32 -04:00
|
|
|
int32_t constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd);
|
2017-02-14 15:11:01 -04:00
|
|
|
bool get_target_altitude_location(Location &location);
|
2017-04-13 03:57:10 -03:00
|
|
|
bool send_landing_message(mavlink_channel_t chan);
|
2016-11-16 21:05:37 -04:00
|
|
|
|
2017-07-25 14:58:11 -03:00
|
|
|
// terminate the flight with an immediate landing, returns false if unable to be used for termination
|
|
|
|
bool terminate(void);
|
|
|
|
|
2016-12-06 17:42:14 -04:00
|
|
|
// helper functions
|
|
|
|
bool restart_landing_sequence(void);
|
2016-11-30 14:05:25 -04:00
|
|
|
float wind_alignment(const float heading_deg);
|
|
|
|
float head_wind(void);
|
2017-01-10 15:46:51 -04:00
|
|
|
int32_t get_target_airspeed_cm(void);
|
2016-11-30 14:05:25 -04:00
|
|
|
|
2016-12-06 17:42:14 -04:00
|
|
|
// accessor functions for the params and states
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2017-02-22 15:53:25 -04:00
|
|
|
|
2016-11-23 06:17:34 -04:00
|
|
|
int16_t get_pitch_cd(void) const { return pitch_cd; }
|
|
|
|
float get_flare_sec(void) const { return flare_sec; }
|
|
|
|
int8_t get_disarm_delay(void) const { return disarm_delay; }
|
|
|
|
int8_t get_then_servos_neutral(void) const { return then_servos_neutral; }
|
|
|
|
int8_t get_abort_throttle_enable(void) const { return abort_throttle_enable; }
|
|
|
|
int8_t get_flap_percent(void) const { return flap_percent; }
|
|
|
|
int8_t get_throttle_slewrate(void) const { return throttle_slewrate; }
|
2017-01-26 17:05:45 -04:00
|
|
|
bool is_commanded_go_around(void) const { return flags.commanded_go_around; }
|
2017-01-12 19:59:11 -04:00
|
|
|
bool is_complete(void) const;
|
2017-01-10 01:29:50 -04:00
|
|
|
void set_initial_slope(void) { initial_slope = slope; }
|
|
|
|
bool is_expecting_impact(void) const;
|
2018-05-03 22:20:12 -03:00
|
|
|
void Log(void) const;
|
2022-03-03 23:29:46 -04:00
|
|
|
const AP_PIDInfo * get_pid_info(void) const;
|
2016-11-23 06:17:34 -04:00
|
|
|
|
2016-11-16 21:12:26 -04:00
|
|
|
// landing altitude offset (meters)
|
|
|
|
float alt_offset;
|
|
|
|
|
2016-11-23 06:17:34 -04:00
|
|
|
private:
|
2017-01-26 17:05:45 -04:00
|
|
|
struct {
|
2017-01-26 17:06:04 -04:00
|
|
|
// denotes if a go-around has been commanded for landing
|
2017-01-26 17:05:45 -04:00
|
|
|
bool commanded_go_around:1;
|
|
|
|
|
|
|
|
// are we in auto and flight_stage is LAND
|
|
|
|
bool in_progress:1;
|
|
|
|
} flags;
|
2016-12-06 16:21:04 -04:00
|
|
|
|
2020-05-18 03:57:29 -03:00
|
|
|
AP_Int16 _options; // user-configurable bitmask options, via a parameter, for landing
|
|
|
|
|
2016-12-06 21:30:10 -04:00
|
|
|
// same as land_slope but sampled once before a rangefinder changes the slope. This should be the original mission planned slope
|
|
|
|
float initial_slope;
|
|
|
|
|
2019-02-24 20:16:22 -04:00
|
|
|
// 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)
|
2016-12-06 21:30:10 -04:00
|
|
|
float slope;
|
|
|
|
|
2021-05-12 08:10:57 -03:00
|
|
|
float height_flare_log;
|
|
|
|
|
2016-11-23 06:17:34 -04:00
|
|
|
AP_Mission &mission;
|
|
|
|
AP_AHRS &ahrs;
|
2021-11-12 13:54:43 -04:00
|
|
|
AP_TECS *tecs_Controller;
|
2016-11-23 06:17:34 -04:00
|
|
|
AP_Navigation *nav_controller;
|
2017-02-22 15:53:25 -04:00
|
|
|
|
2022-09-29 20:10:40 -03:00
|
|
|
AP_FixedWing &aparm;
|
2016-11-18 18:05:45 -04:00
|
|
|
|
2016-12-05 20:15:20 -04:00
|
|
|
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;
|
|
|
|
|
2021-07-01 22:06:47 -03:00
|
|
|
#if HAL_LANDING_DEEPSTALL_ENABLED
|
2017-03-19 15:04:04 -03:00
|
|
|
// support for deepstall landings
|
|
|
|
AP_Landing_Deepstall deepstall;
|
2021-07-01 22:06:47 -03:00
|
|
|
#endif
|
2017-03-19 15:04:04 -03:00
|
|
|
|
2016-11-23 05:34:22 -04:00
|
|
|
AP_Int16 pitch_cd;
|
|
|
|
AP_Float flare_alt;
|
|
|
|
AP_Float flare_sec;
|
|
|
|
AP_Float pre_flare_airspeed;
|
|
|
|
AP_Float pre_flare_alt;
|
|
|
|
AP_Float pre_flare_sec;
|
|
|
|
AP_Float slope_recalc_shallow_threshold;
|
|
|
|
AP_Float slope_recalc_steep_threshold_to_abort;
|
2016-11-23 06:00:42 -04:00
|
|
|
AP_Int8 disarm_delay;
|
|
|
|
AP_Int8 then_servos_neutral;
|
|
|
|
AP_Int8 abort_throttle_enable;
|
|
|
|
AP_Int8 flap_percent;
|
|
|
|
AP_Int8 throttle_slewrate;
|
2016-11-23 21:26:06 -04:00
|
|
|
AP_Int8 type;
|
2021-12-03 03:06:16 -04:00
|
|
|
AP_Int8 flare_effectivness_pct;
|
2022-12-11 01:51:04 -04:00
|
|
|
AP_Float wind_comp;
|
2016-11-23 21:26:06 -04:00
|
|
|
|
|
|
|
// Land Type STANDARD GLIDE SLOPE
|
2017-01-26 17:05:45 -04:00
|
|
|
|
2022-11-29 02:29:35 -04:00
|
|
|
enum class SlopeStage {
|
|
|
|
NORMAL = 0,
|
|
|
|
APPROACH = 1,
|
|
|
|
PREFLARE = 2,
|
|
|
|
FINAL = 3,
|
2017-01-26 17:05:45 -04:00
|
|
|
} type_slope_stage;
|
|
|
|
|
|
|
|
struct {
|
|
|
|
// once landed, post some landing statistics to the GCS
|
|
|
|
bool post_stats:1;
|
2018-12-12 00:50:28 -04:00
|
|
|
|
2017-01-26 17:05:45 -04:00
|
|
|
bool has_aborted_due_to_slope_recalc:1;
|
|
|
|
} type_slope_flags;
|
|
|
|
|
2017-01-10 15:47:31 -04:00
|
|
|
void type_slope_do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
|
2017-01-10 03:44:25 -04:00
|
|
|
void type_slope_verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed);
|
|
|
|
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);
|
2016-11-23 21:26:06 -04:00
|
|
|
|
2022-09-29 20:10:40 -03:00
|
|
|
void type_slope_adjust_landing_slope_for_rangefinder_bump(AP_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);
|
2016-11-23 21:26:06 -04:00
|
|
|
|
|
|
|
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);
|
2017-01-10 15:46:51 -04:00
|
|
|
int32_t type_slope_get_target_airspeed_cm(void);
|
2022-09-29 20:10:40 -03:00
|
|
|
void type_slope_check_if_need_to_abort(const AP_FixedWing::Rangefinder_State &rangefinder_state);
|
2017-01-11 15:06:32 -04:00
|
|
|
int32_t type_slope_constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd);
|
2016-12-06 16:21:04 -04:00
|
|
|
bool type_slope_request_go_around(void);
|
2017-01-26 17:06:04 -04:00
|
|
|
void type_slope_log(void) const;
|
2017-01-12 19:59:11 -04:00
|
|
|
bool type_slope_is_complete(void) const;
|
2017-01-10 01:29:50 -04:00
|
|
|
bool type_slope_is_flaring(void) const;
|
|
|
|
bool type_slope_is_on_approach(void) const;
|
|
|
|
bool type_slope_is_expecting_impact(void) const;
|
2017-02-14 15:11:01 -04:00
|
|
|
bool type_slope_is_throttle_suppressed(void) const;
|
2016-11-16 21:05:37 -04:00
|
|
|
};
|