AP_L1_Control.h 4.1 KB

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