AR_AttitudeControl.h 9.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190
  1. #pragma once
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #include <AP_Common/AP_Common.h>
  4. #include <AC_PID/AC_PID.h>
  5. #include <AC_PID/AC_P.h>
  6. // attitude control default definition
  7. #define AR_ATTCONTROL_STEER_ANG_P 2.50f
  8. #define AR_ATTCONTROL_STEER_RATE_FF 0.20f
  9. #define AR_ATTCONTROL_STEER_RATE_P 0.20f
  10. #define AR_ATTCONTROL_STEER_RATE_I 0.20f
  11. #define AR_ATTCONTROL_STEER_RATE_IMAX 1.00f
  12. #define AR_ATTCONTROL_STEER_RATE_D 0.00f
  13. #define AR_ATTCONTROL_STEER_RATE_FILT 10.00f
  14. #define AR_ATTCONTROL_STEER_RATE_MAX 360.0f
  15. #define AR_ATTCONTROL_STEER_ACCEL_MAX 180.0f
  16. #define AR_ATTCONTROL_THR_SPEED_P 0.20f
  17. #define AR_ATTCONTROL_THR_SPEED_I 0.20f
  18. #define AR_ATTCONTROL_THR_SPEED_IMAX 1.00f
  19. #define AR_ATTCONTROL_THR_SPEED_D 0.00f
  20. #define AR_ATTCONTROL_THR_SPEED_FILT 10.00f
  21. #define AR_ATTCONTROL_PITCH_THR_P 1.80f
  22. #define AR_ATTCONTROL_PITCH_THR_I 1.50f
  23. #define AR_ATTCONTROL_PITCH_THR_D 0.03f
  24. #define AR_ATTCONTROL_PITCH_THR_IMAX 1.0f
  25. #define AR_ATTCONTROL_PITCH_THR_FILT 10.0f
  26. #define AR_ATTCONTROL_BAL_SPEED_FF 1.0f
  27. #define AR_ATTCONTROL_DT 0.02f
  28. #define AR_ATTCONTROL_TIMEOUT_MS 200
  29. #define AR_ATTCONTROL_HEEL_SAIL_P 1.0f
  30. #define AR_ATTCONTROL_HEEL_SAIL_I 0.1f
  31. #define AR_ATTCONTROL_HEEL_SAIL_D 0.0f
  32. #define AR_ATTCONTROL_HEEL_SAIL_IMAX 1.0f
  33. #define AR_ATTCONTROL_HEEL_SAIL_FILT 10.0f
  34. #define AR_ATTCONTROL_DT 0.02f
  35. // throttle/speed control maximum acceleration/deceleration (in m/s) (_ACCEL_MAX parameter default)
  36. #define AR_ATTCONTROL_THR_ACCEL_MAX 2.00f
  37. // minimum speed in m/s
  38. #define AR_ATTCONTROL_STEER_SPEED_MIN 1.0f
  39. // speed (in m/s) at or below which vehicle is considered stopped (_STOP_SPEED parameter default)
  40. #define AR_ATTCONTROL_STOP_SPEED_DEFAULT 0.1f
  41. class AR_AttitudeControl {
  42. public:
  43. // constructor
  44. AR_AttitudeControl(AP_AHRS &ahrs);
  45. //
  46. // steering controller
  47. //
  48. // return a steering servo output given a desired lateral acceleration rate in m/s/s.
  49. // positive lateral acceleration is to the right. dt should normally be the main loop rate.
  50. // return value is normally in range -1.0 to +1.0 but can be higher or lower
  51. float get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt);
  52. // return a steering servo output given a heading in radians
  53. // set rate_max_rads to a non-zero number to apply a limit on the desired turn rate
  54. // return value is normally in range -1.0 to +1.0 but can be higher or lower
  55. float get_steering_out_heading(float heading_rad, float rate_max_rads, bool motor_limit_left, bool motor_limit_right, float dt);
  56. // return a desired turn-rate given a desired heading in radians
  57. // normally the results are later passed into get_steering_out_rate
  58. float get_turn_rate_from_heading(float heading_rad, float rate_max_rads) const;
  59. // return a steering servo output given a desired yaw rate in radians/sec.
  60. // positive yaw is to the right
  61. // return value is normally in range -1.0 to +1.0 but can be higher or lower
  62. float get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt);
  63. // get latest desired turn rate in rad/sec recorded during calls to get_steering_out_rate. For reporting purposes only
  64. float get_desired_turn_rate() const;
  65. // get latest desired lateral acceleration in m/s/s recorded during calls to get_steering_out_lat_accel. For reporting purposes only
  66. float get_desired_lat_accel() const;
  67. // get actual lateral acceleration in m/s/s. returns true on success. For reporting purposes only
  68. bool get_lat_accel(float &lat_accel) const;
  69. // calculate the turn rate in rad/sec given a lateral acceleration (in m/s/s) and speed (in m/s)
  70. float get_turn_rate_from_lat_accel(float lat_accel, float speed) const;
  71. //
  72. // throttle / speed controller
  73. //
  74. // set limits used by throttle controller
  75. // forward/back acceleration max in m/s/s
  76. // forward/back deceleartion max in m/s/s
  77. void set_throttle_limits(float throttle_accel_max, float throttle_decel_max);
  78. // return a throttle output from -1 to +1 given a desired speed in m/s (use negative speeds to travel backwards)
  79. // desired_speed argument should already have been passed through get_desired_speed_accel_limited function
  80. // motor_limit should be true if motors have hit their upper or lower limits
  81. // cruise speed should be in m/s, cruise throttle should be a number from -1 to +1
  82. float get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt);
  83. // return a throttle output from -1 to +1 to perform a controlled stop. stopped is set to true once stop has been completed
  84. float get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt, bool &stopped);
  85. // balancebot pitch to throttle controller
  86. // returns a throttle output from -100 to +100 given a desired pitch angle and vehicle's current speed (from wheel encoders)
  87. // desired_pitch is in radians, veh_speed_pct is supplied as a percentage (-100 to +100) of vehicle's top speed
  88. float get_throttle_out_from_pitch(float desired_pitch, float veh_speed_pct, bool motor_limit_low, bool motor_limit_high, float dt);
  89. // get latest desired pitch in radians for reporting purposes
  90. float get_desired_pitch() const;
  91. // Sailboat heel(roll) angle contorller, release sail to keep at maximum heel angle
  92. float get_sail_out_from_heel(float desired_heel, float dt);
  93. // low level control accessors for reporting and logging
  94. AC_P& get_steering_angle_p() { return _steer_angle_p; }
  95. AC_PID& get_steering_rate_pid() { return _steer_rate_pid; }
  96. AC_PID& get_throttle_speed_pid() { return _throttle_speed_pid; }
  97. AC_PID& get_pitch_to_throttle_pid() { return _pitch_to_throttle_pid; }
  98. AC_PID& get_sailboat_heel_pid() { return _sailboat_heel_pid; }
  99. // get forward speed in m/s (earth-frame horizontal velocity but only along vehicle x-axis). returns true on success
  100. bool get_forward_speed(float &speed) const;
  101. // get throttle/speed controller maximum acceleration (also used for deceleration)
  102. float get_accel_max() const { return MAX(_throttle_accel_max, 0.0f); }
  103. // get throttle/speed controller maximum deceleration
  104. float get_decel_max() const;
  105. // check if speed controller active
  106. bool speed_control_active() const;
  107. // get latest desired speed recorded during call to get_throttle_out_speed. For reporting purposes only
  108. float get_desired_speed() const;
  109. // get acceleration limited desired speed
  110. float get_desired_speed_accel_limited(float desired_speed, float dt) const;
  111. // get minimum stopping distance (in meters) given a speed (in m/s)
  112. float get_stopping_distance(float speed) const;
  113. // relax I terms of throttle and steering controllers
  114. void relax_I();
  115. // parameter var table
  116. static const struct AP_Param::GroupInfo var_info[];
  117. private:
  118. // external references
  119. const AP_AHRS &_ahrs;
  120. // parameters
  121. AC_P _steer_angle_p; // steering angle controller
  122. AC_PID _steer_rate_pid; // steering rate controller
  123. AC_PID _throttle_speed_pid; // throttle speed controller
  124. AC_PID _pitch_to_throttle_pid;// balancebot pitch controller
  125. AP_Float _pitch_to_throttle_speed_ff; // balancebot feed forward from speed
  126. AP_Float _throttle_accel_max; // speed/throttle control acceleration (and deceleration) maximum in m/s/s. 0 to disable limits
  127. AP_Float _throttle_decel_max; // speed/throttle control deceleration maximum in m/s/s. 0 to use ATC_ACCEL_MAX for deceleration
  128. AP_Int8 _brake_enable; // speed control brake enable/disable. if set to 1 a reversed output to the motors to slow the vehicle.
  129. AP_Float _stop_speed; // speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
  130. AP_Float _steer_accel_max; // steering angle acceleration max in deg/s/s
  131. AP_Float _steer_rate_max; // steering rate control maximum rate in deg/s
  132. // steering control
  133. uint32_t _steer_lat_accel_last_ms; // system time of last call to lateral acceleration controller (i.e. get_steering_out_lat_accel)
  134. uint32_t _steer_turn_last_ms; // system time of last call to steering rate controller
  135. float _desired_lat_accel; // desired lateral acceleration (in m/s/s) from latest call to get_steering_out_lat_accel (for reporting purposes)
  136. float _desired_turn_rate; // desired turn rate (in radians/sec) either from external caller or from lateral acceleration controller
  137. // throttle control
  138. uint32_t _speed_last_ms; // system time of last call to get_throttle_out_speed
  139. float _desired_speed; // last recorded desired speed
  140. uint32_t _stop_last_ms; // system time the vehicle was at a complete stop
  141. bool _throttle_limit_low; // throttle output was limited from going too low (used to reduce i-term buildup)
  142. bool _throttle_limit_high; // throttle output was limited from going too high (used to reduce i-term buildup)
  143. // balancebot pitch control
  144. uint32_t _balance_last_ms = 0;
  145. // Sailboat heel control
  146. AC_PID _sailboat_heel_pid; // Sailboat heel angle pid controller
  147. uint32_t _heel_controller_last_ms = 0;
  148. };