96 const float height,
const float sink_rate,
const float wp_proportion,
const uint32_t last_flying_ms,
97 const bool is_armed,
const bool is_flying,
const bool rangefinder_state_in_range);
99 const Location ¤t_loc, int32_t &target_altitude_offset_cm);
108 void Log(
void)
const;
120 #define DEEPSTALL_LOITER_ALT_TOLERANCE 5.0f static const struct AP_Param::GroupInfo var_info[]
int32_t last_target_bearing
int32_t get_target_airspeed_cm(void) const
bool is_on_approach(void) const
float update_steering(void)
void verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed)
bool get_target_altitude_location(Location &location)
Generic PID algorithm, with EEPROM-backed storage of constants.
AP_Float handoff_lower_limit_airspeed
Interface definition for the various Ground Control System.
uint16_t initial_elevator_pwm
bool override_servos(void)
void build_approach_path(bool use_current_heading)
float predicted_travel_distance
void do_land(const AP_Mission::Mission_Command &cmd, const float relative_altitude)
AP_Landing_Deepstall(AP_Landing &_landing)
AP_Float handoff_airspeed
A system for managing and storing variables that are of general interest to the system.
float predict_travel_distance(const Vector3f wind, const float height, const bool print)
generic navigation controller interface
generic speed & height controller interface
Object managing one PID control.
bool request_go_around(void)
Class managing Plane Deepstall landing methods.
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
bool send_deepstall_message(mavlink_channel_t chan) const
bool verify_breakout(const Location ¤t_loc, const Location &target_loc, const float height_error) const
Class managing ArduPlane landing methods.
bool is_throttle_suppressed(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)
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL::AnalogSource * chan
float approach_alt_offset
Location extended_approach
uint32_t stall_entry_time
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_Float approach_extension
bool is_flying_forward(void) const
Location breakout_location
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
const DataFlash_Class::PID_Info & get_pid_info(void) const