APM:Libraries
AP_L1_Control.h
Go to the documentation of this file.
1 #pragma once
2 
6 
7 /*
8  * Originally written by Brandon Jones 2013
9  *
10  * Modified by Paul Riseborough 2013 to provide:
11  * - Explicit control over frequency and damping
12  * - Explicit control over track capture angle
13  * - Ability to use loiter radius smaller than L1 length
14  */
15 
16 #include <AP_Math/AP_Math.h>
17 #include <AP_AHRS/AP_AHRS.h>
18 #include <AP_Param/AP_Param.h>
21 
22 class AP_L1_Control : public AP_Navigation {
23 public:
24  AP_L1_Control(AP_AHRS &ahrs, const AP_SpdHgtControl *spdHgtControl)
25  : _ahrs(ahrs)
26  , _spdHgtControl(spdHgtControl)
27  {
29  }
30 
31  /* Do not allow copies */
32  AP_L1_Control(const AP_L1_Control &other) = delete;
33  AP_L1_Control &operator=(const AP_L1_Control&) = delete;
34 
35  /* see AP_Navigation.h for the definitions and units of these
36  * functions */
37  int32_t nav_roll_cd(void) const;
38  float lateral_acceleration(void) const;
39 
40  // return the desired track heading angle(centi-degrees)
41  int32_t nav_bearing_cd(void) const;
42 
43  // return the heading error angle (centi-degrees) +ve to left of track
44  int32_t bearing_error_cd(void) const;
45 
46  float crosstrack_error(void) const { return _crosstrack_error; }
47  float crosstrack_error_integrator(void) const { return _L1_xtrack_i; }
48 
49  int32_t target_bearing_cd(void) const;
50  float turn_distance(float wp_radius) const;
51  float turn_distance(float wp_radius, float turn_angle) const;
52  float loiter_radius (const float loiter_radius) const;
53  void update_waypoint(const struct Location &prev_WP, const struct Location &next_WP, float dist_min = 0.0f);
54  void update_loiter(const struct Location &center_WP, float radius, int8_t loiter_direction);
55  void update_heading_hold(int32_t navigation_heading_cd);
56  void update_level_flight(void);
57  bool reached_loiter_target(void);
58 
59  // set the default NAVL1_PERIOD
60  void set_default_period(float period) {
61  _L1_period.set_default(period);
62  }
63 
64  void set_data_is_stale(void) {
65  _data_is_stale = true;
66  }
67  bool data_is_stale(void) const {
68  return _data_is_stale;
69  }
70 
71  // this supports the NAVl1_* user settable parameters
72  static const struct AP_Param::GroupInfo var_info[];
73 
74  void set_reverse(bool reverse) {
75  _reverse = reverse;
76  }
77 
78 private:
79  // reference to the AHRS object
81 
82  // pointer to the SpdHgtControl object
84 
85  // lateral acceration in m/s required to fly to the
86  // L1 reference point (+ve to right)
87  float _latAccDem;
88 
89  // L1 tracking distance in meters which is dynamically updated
90  float _L1_dist;
91 
92  // Status which is true when the vehicle has started circling the WP
93  bool _WPcircle;
94 
95  // bearing angle (radians) to L1 point
96  float _nav_bearing;
97 
98  // bearing error angle (radians) +ve to left of track
100 
101  // crosstrack error in meters
103 
104  // target bearing in centi-degrees from last update
106 
107  // L1 tracking loop period (sec)
108  AP_Float _L1_period;
109  // L1 tracking loop damping ratio
110  AP_Float _L1_damping;
111 
112  // previous value of cross-track velocity
113  float _last_Nu;
114 
115  // prevent indecision in waypoint tracking
116  void _prevent_indecision(float &Nu);
117 
118  // integral feedback to correct crosstrack error. Used to ensure xtrack converges to zero.
119  // For tuning purposes it's helpful to clear the integrator when it changes so a _prev is used
120  float _L1_xtrack_i = 0;
124  bool _data_is_stale = true;
125 
127 
128  bool _reverse = false;
129  float get_yaw();
130  float get_yaw_sensor();
131 };
void update_heading_hold(int32_t navigation_heading_cd)
float crosstrack_error(void) const
Definition: AP_L1_Control.h:46
uint32_t _last_update_waypoint_us
AP_L1_Control & operator=(const AP_L1_Control &)=delete
float get_yaw_sensor()
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
AP_AHRS & _ahrs
Definition: AP_L1_Control.h:80
void set_default_period(float period)
Definition: AP_L1_Control.h:60
float _nav_bearing
Definition: AP_L1_Control.h:96
void update_level_flight(void)
int32_t nav_bearing_cd(void) const
int32_t bearing_error_cd(void) const
AP_Float _L1_xtrack_i_gain
AP_Float _L1_period
bool data_is_stale(void) const
Definition: AP_L1_Control.h:67
float turn_distance(float wp_radius) const
AP_L1_Control(AP_AHRS &ahrs, const AP_SpdHgtControl *spdHgtControl)
Definition: AP_L1_Control.h:24
float _bearing_error
Definition: AP_L1_Control.h:99
A system for managing and storing variables that are of general interest to the system.
const AP_SpdHgtControl * _spdHgtControl
Definition: AP_L1_Control.h:83
generic navigation controller interface
int32_t nav_roll_cd(void) const
generic speed & height controller interface
AP_Float _L1_damping
void set_reverse(bool reverse)
Definition: AP_L1_Control.h:74
#define f(i)
void update_loiter(const struct Location &center_WP, float radius, int8_t loiter_direction)
int32_t target_bearing_cd(void) const
float crosstrack_error_integrator(void) const
Definition: AP_L1_Control.h:47
float _crosstrack_error
bool reached_loiter_target(void)
int32_t _target_bearing_cd
float lateral_acceleration(void) const
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_L1_Control.h:72
AP_Float _loiter_bank_limit
void _prevent_indecision(float &Nu)
float loiter_radius(const float loiter_radius) const
void update_waypoint(const struct Location &prev_WP, const struct Location &next_WP, float dist_min=0.0f)
float _L1_xtrack_i_gain_prev
void set_data_is_stale(void)
Definition: AP_L1_Control.h:64
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214