AC_AutoTune.h 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. support for autotune of multirotors. Based on original autotune code from ArduCopter, written by Leonard Hall
  15. Converted to a library by Andrew Tridgell
  16. */
  17. #pragma once
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AC_AttitudeControl/AC_AttitudeControl_Multi.h>
  20. #include <AC_AttitudeControl/AC_PosControl.h>
  21. class AC_AutoTune {
  22. public:
  23. // constructor
  24. AC_AutoTune();
  25. // main run loop
  26. virtual void run();
  27. // save gained, called on disarm
  28. void save_tuning_gains();
  29. // stop tune, reverting gains
  30. void stop();
  31. // reset Autotune so that gains are not saved again and autotune can be run again.
  32. void reset() {
  33. mode = UNINITIALISED;
  34. axes_completed = 0;
  35. }
  36. // var_info for holding Parameter information
  37. static const struct AP_Param::GroupInfo var_info[];
  38. protected:
  39. // methods that must be supplied by the vehicle specific subclass
  40. virtual bool init(void) = 0;
  41. // get pilot input for desired cimb rate
  42. virtual float get_pilot_desired_climb_rate_cms(void) const = 0;
  43. // get pilot input for designed roll and pitch, and yaw rate
  44. virtual void get_pilot_desired_rp_yrate_cd(float &roll_cd, float &pitch_cd, float &yaw_rate_cds) = 0;
  45. // init pos controller Z velocity and accel limits
  46. virtual void init_z_limits() = 0;
  47. // log PIDs at full rate for during twitch
  48. virtual void log_pids() = 0;
  49. // start tune - virtual so that vehicle code can add additional pre-conditions
  50. virtual bool start(void);
  51. // return true if we have a good position estimate
  52. virtual bool position_ok();
  53. enum at_event {
  54. EVENT_AUTOTUNE_INITIALISED = 0,
  55. EVENT_AUTOTUNE_OFF = 1,
  56. EVENT_AUTOTUNE_RESTART = 2,
  57. EVENT_AUTOTUNE_SUCCESS = 3,
  58. EVENT_AUTOTUNE_FAILED = 4,
  59. EVENT_AUTOTUNE_REACHED_LIMIT = 5,
  60. EVENT_AUTOTUNE_PILOT_TESTING = 6,
  61. EVENT_AUTOTUNE_SAVEDGAINS = 7
  62. };
  63. // write a log event
  64. virtual void Log_Write_Event(enum at_event id) = 0;
  65. // internal init function, should be called from init()
  66. bool init_internals(bool use_poshold,
  67. AC_AttitudeControl_Multi *attitude_control,
  68. AC_PosControl *pos_control,
  69. AP_AHRS_View *ahrs_view,
  70. AP_InertialNav *inertial_nav);
  71. private:
  72. void control_attitude();
  73. void backup_gains_and_initialise();
  74. void load_orig_gains();
  75. void load_tuned_gains();
  76. void load_intra_test_gains();
  77. void load_twitch_gains();
  78. void update_gcs(uint8_t message_id);
  79. bool roll_enabled();
  80. bool pitch_enabled();
  81. bool yaw_enabled();
  82. void twitching_test_rate(float rate, float rate_target, float &meas_rate_min, float &meas_rate_max);
  83. void twitching_abort_rate(float angle, float rate, float angle_max, float meas_rate_min);
  84. void twitching_test_angle(float angle, float rate, float angle_target, float &meas_angle_min, float &meas_angle_max, float &meas_rate_min, float &meas_rate_max);
  85. void twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max);
  86. void updating_rate_d_up(float &tune_d, float tune_d_min, float tune_d_max, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max);
  87. void updating_rate_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max);
  88. void updating_rate_p_up_d_down(float &tune_d, float tune_d_min, float tune_d_step_ratio, float &tune_p, float tune_p_min, float tune_p_max, float tune_p_step_ratio, float rate_target, float meas_rate_min, float meas_rate_max);
  89. void updating_angle_p_down(float &tune_p, float tune_p_min, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max);
  90. void updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max);
  91. void get_poshold_attitude(float &roll_cd, float &pitch_cd, float &yaw_cd);
  92. void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt);
  93. void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds);
  94. void send_step_string();
  95. const char *level_issue_string() const;
  96. const char * type_string() const;
  97. void announce_state_to_gcs();
  98. void do_gcs_announcements();
  99. enum struct LevelIssue {
  100. NONE,
  101. ANGLE_ROLL,
  102. ANGLE_PITCH,
  103. ANGLE_YAW,
  104. RATE_ROLL,
  105. RATE_PITCH,
  106. RATE_YAW,
  107. };
  108. bool check_level(const enum LevelIssue issue, const float current, const float maximum);
  109. bool currently_level();
  110. // autotune modes (high level states)
  111. enum TuneMode {
  112. UNINITIALISED = 0, // autotune has never been run
  113. TUNING = 1, // autotune is testing gains
  114. SUCCESS = 2, // tuning has completed, user is flight testing the new gains
  115. FAILED = 3, // tuning has failed, user is flying on original gains
  116. };
  117. // steps performed while in the tuning mode
  118. enum StepType {
  119. WAITING_FOR_LEVEL = 0, // autotune is waiting for vehicle to return to level before beginning the next twitch
  120. TWITCHING = 1, // autotune has begun a twitch and is watching the resulting vehicle movement
  121. UPDATE_GAINS = 2 // autotune has completed a twitch and is updating the gains based on the results
  122. };
  123. // things that can be tuned
  124. enum AxisType {
  125. ROLL = 0, // roll axis is being tuned (either angle or rate)
  126. PITCH = 1, // pitch axis is being tuned (either angle or rate)
  127. YAW = 2, // pitch axis is being tuned (either angle or rate)
  128. };
  129. // mini steps performed while in Tuning mode, Testing step
  130. enum TuneType {
  131. RD_UP = 0, // rate D is being tuned up
  132. RD_DOWN = 1, // rate D is being tuned down
  133. RP_UP = 2, // rate P is being tuned up
  134. SP_DOWN = 3, // angle P is being tuned down
  135. SP_UP = 4 // angle P is being tuned up
  136. };
  137. // type of gains to load
  138. enum GainType {
  139. GAIN_ORIGINAL = 0,
  140. GAIN_TWITCH = 1,
  141. GAIN_INTRA_TEST = 2,
  142. GAIN_TUNED = 3,
  143. };
  144. enum GainType current_gain_type;
  145. void load_gains(enum GainType gain_type);
  146. TuneMode mode : 2; // see TuneMode for what modes are allowed
  147. bool pilot_override : 1; // true = pilot is overriding controls so we suspend tuning temporarily
  148. AxisType axis : 2; // see AxisType for which things can be tuned
  149. bool positive_direction : 1; // false = tuning in negative direction (i.e. left for roll), true = positive direction (i.e. right for roll)
  150. StepType step : 2; // see StepType for what steps are performed
  151. TuneType tune_type : 3; // see TuneType
  152. bool ignore_next : 1; // true = ignore the next test
  153. bool twitch_first_iter : 1; // true on first iteration of a twitch (used to signal we must step the attitude or rate target)
  154. bool use_poshold : 1; // true = enable position hold
  155. bool have_position : 1; // true = start_position is value
  156. Vector3f start_position;
  157. uint8_t axes_completed; // bitmask of completed axes
  158. // variables
  159. uint32_t override_time; // the last time the pilot overrode the controls
  160. float test_rate_min; // the minimum angular rate achieved during TESTING_RATE step
  161. float test_rate_max; // the maximum angular rate achieved during TESTING_RATE step
  162. float test_angle_min; // the minimum angle achieved during TESTING_ANGLE step
  163. float test_angle_max; // the maximum angle achieved during TESTING_ANGLE step
  164. uint32_t step_start_time_ms; // start time of current tuning step (used for timeout checks)
  165. uint32_t level_start_time_ms; // start time of waiting for level
  166. uint32_t step_time_limit_ms; // time limit of current autotune process
  167. int8_t counter; // counter for tuning gains
  168. float target_rate, start_rate; // target and start rate
  169. float target_angle, start_angle; // target and start angles
  170. float desired_yaw_cd; // yaw heading during tune
  171. float rate_max, test_accel_max; // maximum acceleration variables
  172. float step_scaler; // scaler to reduce maximum target step
  173. float abort_angle; // Angle that test is aborted
  174. LowPassFilterFloat rotation_rate_filt; // filtered rotation rate in radians/second
  175. // backup of currently being tuned parameter values
  176. float orig_roll_rp, orig_roll_ri, orig_roll_rd, orig_roll_rff, orig_roll_sp, orig_roll_accel;
  177. float orig_pitch_rp, orig_pitch_ri, orig_pitch_rd, orig_pitch_rff, orig_pitch_sp, orig_pitch_accel;
  178. float orig_yaw_rp, orig_yaw_ri, orig_yaw_rd, orig_yaw_rff, orig_yaw_rLPF, orig_yaw_sp, orig_yaw_accel;
  179. bool orig_bf_feedforward;
  180. // currently being tuned parameter values
  181. float tune_roll_rp, tune_roll_rd, tune_roll_sp, tune_roll_accel;
  182. float tune_pitch_rp, tune_pitch_rd, tune_pitch_sp, tune_pitch_accel;
  183. float tune_yaw_rp, tune_yaw_rLPF, tune_yaw_sp, tune_yaw_accel;
  184. uint32_t announce_time;
  185. float lean_angle;
  186. float rotation_rate;
  187. float roll_cd, pitch_cd;
  188. uint32_t last_pilot_override_warning;
  189. struct {
  190. LevelIssue issue{LevelIssue::NONE};
  191. float maximum;
  192. float current;
  193. } level_problem;
  194. AP_Int8 axis_bitmask;
  195. AP_Float aggressiveness;
  196. AP_Float min_d;
  197. // copies of object pointers to make code a bit clearer
  198. AC_AttitudeControl_Multi *attitude_control;
  199. AC_PosControl *pos_control;
  200. AP_AHRS_View *ahrs_view;
  201. AP_InertialNav *inertial_nav;
  202. AP_Motors *motors;
  203. };