APM:Libraries
AP_Landing_Deepstall.h
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #pragma once
17 
18 #include <AP_Param/AP_Param.h>
19 #include <AP_Mission/AP_Mission.h>
20 #include <AP_Common/AP_Common.h>
23 #include <GCS_MAVLink/GCS.h>
24 #include <PID/PID.h>
25 
26 class AP_Landing;
27 
31 {
32 private:
33  friend class AP_Landing;
34 
35  // constructor
37  landing(_landing)
38  {
40  }
41 
43 
44  static const struct AP_Param::GroupInfo var_info[];
45 
46  // deepstall members
48  DEEPSTALL_STAGE_FLY_TO_LANDING, // fly to the deepstall landing point
49  DEEPSTALL_STAGE_ESTIMATE_WIND, // loiter until we have a decent estimate of the wind for the target altitude
50  DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT, // wait until the aircraft is aligned for the optimal breakout
51  DEEPSTALL_STAGE_FLY_TO_ARC, // fly to the start of the arc
52  DEEPSTALL_STAGE_ARC, // fly the arc
53  DEEPSTALL_STAGE_APPROACH, // fly the approach in, and prepare to deepstall when close
54  DEEPSTALL_STAGE_LAND, // the aircraft will stall torwards the ground while targeting a given point
55  };
56 
57  AP_Float forward_speed;
58  AP_Float slope_a;
59  AP_Float slope_b;
61  AP_Float down_speed;
62  AP_Float slew_speed;
63  AP_Int16 elevator_pwm;
64  AP_Float handoff_airspeed;
66  AP_Float L1_period;
67  AP_Float L1_i;
68  AP_Float yaw_rate_limit;
69  AP_Float time_constant;
70  AP_Float min_abort_alt;
71  AP_Float aileron_scalar;
72  int32_t loiter_sum_cd; // used for tracking the progress on loitering
80  float target_heading_deg; // target heading for the deepstall in degrees
81  uint32_t stall_entry_time; // time when the aircrafted enter the stall (in millis)
82  uint16_t initial_elevator_pwm; // PWM to start slewing the elevator up from
83  uint32_t last_time; // last time the controller ran
84  float L1_xtrack_i; // L1 integrator for navigation
86  int32_t last_target_bearing; // used for tracking the progress on loitering
87  float crosstrack_error; // current crosstrack error
88  float predicted_travel_distance; // distance the aircraft is perdicted to travel during deepstall
89  bool hold_level; // locks the target yaw rate of the aircraft to 0, serves to hold the aircraft level at all times
90  float approach_alt_offset; // approach altitude offset
91 
92  //public AP_Landing interface
93  void do_land(const AP_Mission::Mission_Command& cmd, const float relative_altitude);
94  void verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed);
95  bool verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_loc,
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);
98  void setup_landing_glide_slope(const Location &prev_WP_loc, const Location &next_WP_loc,
99  const Location &current_loc, int32_t &target_altitude_offset_cm);
100  bool override_servos(void);
101  bool request_go_around(void);
103  int32_t get_target_airspeed_cm(void) const;
104  bool is_throttle_suppressed(void) const;
105  bool is_flying_forward(void) const;
106  bool is_on_approach(void) const;
107  bool terminate(void);
108  void Log(void) const;
109 
110  bool send_deepstall_message(mavlink_channel_t chan) const;
111 
112  const DataFlash_Class::PID_Info& get_pid_info(void) const;
113 
114  //private helpers
115  void build_approach_path(bool use_current_heading);
116  float predict_travel_distance(const Vector3f wind, const float height, const bool print);
117  bool verify_breakout(const Location &current_loc, const Location &target_loc, const float height_error) const;
118  float update_steering(void);
119 
120  #define DEEPSTALL_LOITER_ALT_TOLERANCE 5.0f
121 };
static const struct AP_Param::GroupInfo var_info[]
int32_t get_target_airspeed_cm(void) const
bool is_on_approach(void) const
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.
Interface definition for the various Ground Control System.
void build_approach_path(bool use_current_heading)
void do_land(const AP_Mission::Mission_Command &cmd, const float relative_altitude)
AP_Landing_Deepstall(AP_Landing &_landing)
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.
Definition: PID.h:13
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 &current_loc, const Location &target_loc, const float height_error) const
Class managing ArduPlane landing methods.
Definition: AP_Landing.h:28
bool is_throttle_suppressed(void) const
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)
Common definitions and utility routines for the ArduPilot libraries.
Vector2f location
Definition: location.cpp:16
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
bool verify_land(const Location &prev_WP_loc, Location &next_WP_loc, const Location &current_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 is_flying_forward(void) const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
const DataFlash_Class::PID_Info & get_pid_info(void) const