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);
62 const int32_t auto_state_takeoff_altitude_rel_cm,
bool &throttle_suppressed);
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);
76 int32_t
constrain_roll(
const int32_t desired_roll_cd,
const int32_t level_roll_limit_cd);
103 void Log(
void)
const;
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);
AP_Int8 abort_throttle_enable
void check_if_need_to_abort(const AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state)
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)
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)
AP_Int8 then_servos_neutral
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)
int16_t get_pitch_cd(void) const
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)
bool has_aborted_due_to_slope_recalc
bool send_landing_message(mavlink_channel_t chan)
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)
FUNCTOR_TYPEDEF(set_target_altitude_proportion_fn_t, void, const Location &, float)
int8_t get_abort_throttle_enable(void) const
float wind_alignment(const float heading_deg)
void handle_flight_stage_change(const bool _in_landing_stage)
bool type_slope_request_go_around(void)
AP_Float pre_flare_airspeed
Interface definition for the various Ground Control System.
bool is_commanded_go_around(void) const
AP_Float slope_recalc_steep_threshold_to_abort
enum AP_Landing::@125 type_slope_stage
bool type_slope_is_complete(void) const
adjusted_altitude_cm_fn_t adjusted_altitude_cm_fn
void set_initial_slope(void)
AP_SpdHgtControl * SpdHgt_Controller
A system for managing and storing variables that are of general interest to the system.
struct AP_Landing::@126 type_slope_flags
AP_Navigation * nav_controller
generic navigation controller interface
bool get_target_altitude_location(Location &location)
generic speed & height controller interface
bool request_go_around(void)
Class managing Plane Deepstall landing methods.
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
bool is_ground_steering_allowed(void) const
bool is_expecting_impact(void) const
bool is_flying_forward(void) const
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)
int32_t get_target_airspeed_cm(void)
bool override_servos(void)
int32_t type_slope_constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd)
Class managing ArduPlane landing methods.
bool type_slope_is_flaring(void) const
update_flight_stage_fn_t update_flight_stage_fn
void type_slope_log(void) const
AP_Landing & operator=(const AP_Landing &)=delete
AP_Int8 throttle_slewrate
bool type_slope_is_expecting_impact(void) const
Common definitions and utility routines for the ArduPilot libraries.
bool is_complete(void) const
set_target_altitude_proportion_fn_t set_target_altitude_proportion_fn
void do_land(const AP_Mission::Mission_Command &cmd, const float relative_altitude)
const DataFlash_Class::PID_Info * get_pid_info(void) const
bool is_flaring(void) const
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)
AP_HAL::AnalogSource * chan
AP_Landing_Deepstall deepstall
int32_t constrain_roll(const int32_t desired_roll_cd, const int32_t level_roll_limit_cd)
bool restart_landing_sequence(void)
float get_flare_sec(void) const
bool type_slope_is_throttle_suppressed(void) const
bool 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)
static const struct AP_Param::GroupInfo var_info[]
int8_t get_flap_percent(void) const
int8_t get_disarm_delay(void) const
void 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)
adjusted_relative_altitude_cm_fn_t adjusted_relative_altitude_cm_fn
void type_slope_check_if_need_to_abort(const AP_Vehicle::FixedWing::Rangefinder_State &rangefinder_state)
bool is_on_approach(void) const
disarm_if_autoland_complete_fn_t disarm_if_autoland_complete_fn
int8_t get_then_servos_neutral(void) const
int8_t get_throttle_slewrate(void) const
constrain_target_altitude_location_fn_t constrain_target_altitude_location_fn