150 set_target_altitude_proportion_fn_t _set_target_altitude_proportion_fn,
151 constrain_target_altitude_location_fn_t _constrain_target_altitude_location_fn,
152 adjusted_altitude_cm_fn_t _adjusted_altitude_cm_fn,
153 adjusted_relative_altitude_cm_fn_t _adjusted_relative_altitude_cm_fn,
154 disarm_if_autoland_complete_fn_t _disarm_if_autoland_complete_fn,
155 update_flight_stage_fn_t _update_flight_stage_fn) :
158 ,SpdHgt_Controller(_SpdHgt_Controller)
159 ,nav_controller(_nav_controller)
161 ,set_target_altitude_proportion_fn(_set_target_altitude_proportion_fn)
162 ,constrain_target_altitude_location_fn(_constrain_target_altitude_location_fn)
163 ,adjusted_altitude_cm_fn(_adjusted_altitude_cm_fn)
164 ,adjusted_relative_altitude_cm_fn(_adjusted_relative_altitude_cm_fn)
165 ,disarm_if_autoland_complete_fn(_disarm_if_autoland_complete_fn)
166 ,update_flight_stage_fn(_update_flight_stage_fn)
177 flags.commanded_go_around =
false;
199 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)
206 height, sink_rate, wp_proportion, last_flying_ms, is_armed, is_flying, rangefinder_state_in_range);
210 height, sink_rate, wp_proportion, last_flying_ms, is_armed, is_flying, rangefinder_state_in_range);
215 gcs().
send_text(MAV_SEVERITY_CRITICAL,
"Landing configuration error, invalid LAND_TYPE");
225 const int32_t auto_state_takeoff_altitude_rel_cm,
bool &throttle_suppressed)
240 next_WP_loc = current_loc;
268 if (!
flags.in_progress) {
283 if (!
flags.in_progress) {
303 if (!
flags.in_progress) {
320 if (!
flags.in_progress) {
338 if (!
flags.in_progress) {
353 if (!
flags.in_progress) {
413 bool success =
false;
418 cmd.
id == MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT &&
419 (cmd.
p1 == 0 || cmd.
p1 == 1) &&
426 else if (do_land_start_index != 0 &&
430 gcs().
send_text(MAV_SEVERITY_NOTICE,
"Restarted landing via DO_LAND_START: %d",do_land_start_index);
438 gcs().
send_text(MAV_SEVERITY_NOTICE,
"Restarted landing sequence at waypoint %d", prev_cmd_with_wp_index);
441 gcs().
send_text(MAV_SEVERITY_WARNING,
"Unable to restart landing sequence");
461 return desired_roll_cd;
468 if (!
flags.in_progress) {
490 const float wind_heading_rad = atan2f(-wind.
y, -wind.
x);
491 return cosf(wind_heading_rad -
radians(heading_deg));
501 if (alignment <= 0) {
513 if (!
flags.in_progress) {
537 bool success =
false;
557 flags.in_progress = _in_landing_stage;
558 flags.commanded_go_around =
false;
596 if (!
flags.in_progress) {
615 if (!
flags.in_progress) {
int32_t get_target_airspeed_cm(void) const
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)
bool is_on_approach(void) const
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)
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 send_landing_message(mavlink_channel_t chan)
void verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed)
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)
bool get_target_altitude_location(Location &location)
float wind_alignment(const float heading_deg)
void handle_flight_stage_change(const bool _in_landing_stage)
bool type_slope_request_go_around(void)
Interface definition for the various Ground Control System.
uint16_t get_current_nav_index() const
virtual Vector3f wind_estimate(void) const =0
#define AP_GROUPINFO(name, idx, clazz, element, def)
bool override_servos(void)
bool type_slope_is_complete(void) const
void do_land(const AP_Mission::Mission_Command &cmd, const float relative_altitude)
const Mission_Command & get_current_nav_cmd() const
get_current_nav_cmd - returns the current "navigation" command
AP_SpdHgtControl * SpdHgt_Controller
bool read_cmd_from_storage(uint16_t index, Mission_Command &cmd) const
void stop()
stop - stops mission execution. subsequent calls to update() will have no effect until the mission is...
bool get_target_altitude_location(Location &location)
bool request_go_around(void)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
bool request_go_around(void)
Class managing Plane Deepstall landing methods.
bool send_deepstall_message(mavlink_channel_t chan) const
bool is_ground_steering_allowed(void) const
bool is_expecting_impact(void) const
uint16_t get_prev_nav_cmd_with_wp_index() 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)
bool set_current_cmd(uint16_t index)
uint16_t get_landing_sequence_start()
int32_t get_target_airspeed_cm(void)
bool override_servos(void)
void send_text(MAV_SEVERITY severity, const char *fmt,...)
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
bool is_throttle_suppressed(void) const
bool type_slope_is_expecting_impact(void) const
bool is_complete(void) const
void do_land(const AP_Mission::Mission_Command &cmd, const float relative_altitude)
static constexpr float radians(float deg)
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)
#define AP_MISSION_CMD_INDEX_NONE
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)
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)
virtual float get_target_airspeed(void) const =0
static const struct AP_Param::GroupInfo var_info[]
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)
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)
bool is_flying_forward(void) const
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
adjusted_relative_altitude_cm_fn_t adjusted_relative_altitude_cm_fn
bool is_on_approach(void) const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
AP_Int32 airspeed_cruise_cm
const DataFlash_Class::PID_Info & get_pid_info(void) const