AC_Loiter.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AC_Loiter.h"
  3. extern const AP_HAL::HAL& hal;
  4. #define LOITER_SPEED_DEFAULT 1250.0f // default loiter speed in cm/s
  5. #define LOITER_SPEED_MIN 20.0f // minimum loiter speed in cm/s
  6. #define LOITER_ACCEL_MAX_DEFAULT 500.0f // default acceleration in loiter mode
  7. #define LOITER_BRAKE_ACCEL_DEFAULT 250.0f // minimum acceleration in loiter mode
  8. #define LOITER_BRAKE_JERK_DEFAULT 500.0f // maximum jerk in cm/s/s/s in loiter mode
  9. #define LOITER_BRAKE_START_DELAY_DEFAULT 1.0f // delay (in seconds) before loiter braking begins after sticks are released
  10. #define LOITER_VEL_CORRECTION_MAX 200.0f // max speed used to correct position errors in loiter
  11. #define LOITER_POS_CORRECTION_MAX 200.0f // max position error in loiter
  12. #define LOITER_ACTIVE_TIMEOUT_MS 200 // loiter controller is considered active if it has been called within the past 200ms (0.2 seconds)
  13. const AP_Param::GroupInfo AC_Loiter::var_info[] = {
  14. // @Param: ANG_MAX
  15. // @DisplayName: Loiter Angle Max
  16. // @Description: Loiter maximum lean angle. Set to zero for 2/3 of PSC_ANGLE_MAX or ANGLE_MAX
  17. // @Units: deg
  18. // @Range: 0 45
  19. // @Increment: 1
  20. // @User: Advanced
  21. AP_GROUPINFO("ANG_MAX", 1, AC_Loiter, _angle_max, 0.0f),
  22. // @Param: SPEED
  23. // @DisplayName: Loiter Horizontal Maximum Speed
  24. // @Description: Defines the maximum speed in cm/s which the aircraft will travel horizontally while in loiter mode
  25. // @Units: cm/s
  26. // @Range: 20 2000
  27. // @Increment: 50
  28. // @User: Standard
  29. AP_GROUPINFO("SPEED", 2, AC_Loiter, _speed_cms, LOITER_SPEED_DEFAULT),
  30. // @Param: ACC_MAX
  31. // @DisplayName: Loiter maximum correction acceleration
  32. // @Description: Loiter maximum correction acceleration in cm/s/s. Higher values cause the copter to correct position errors more aggressively.
  33. // @Units: cm/s/s
  34. // @Range: 100 981
  35. // @Increment: 1
  36. // @User: Advanced
  37. AP_GROUPINFO("ACC_MAX", 3, AC_Loiter, _accel_cmss, LOITER_ACCEL_MAX_DEFAULT),
  38. // @Param: BRK_ACCEL
  39. // @DisplayName: Loiter braking acceleration
  40. // @Description: Loiter braking acceleration in cm/s/s. Higher values stop the copter more quickly when the stick is centered.
  41. // @Units: cm/s/s
  42. // @Range: 25 250
  43. // @Increment: 1
  44. // @User: Advanced
  45. AP_GROUPINFO("BRK_ACCEL", 4, AC_Loiter, _brake_accel_cmss, LOITER_BRAKE_ACCEL_DEFAULT),
  46. // @Param: BRK_JERK
  47. // @DisplayName: Loiter braking jerk
  48. // @Description: Loiter braking jerk in cm/s/s/s. Higher values will remove braking faster if the pilot moves the sticks during a braking maneuver.
  49. // @Units: cm/s/s/s
  50. // @Range: 500 5000
  51. // @Increment: 1
  52. // @User: Advanced
  53. AP_GROUPINFO("BRK_JERK", 5, AC_Loiter, _brake_jerk_max_cmsss, LOITER_BRAKE_JERK_DEFAULT),
  54. // @Param: BRK_DELAY
  55. // @DisplayName: Loiter brake start delay (in seconds)
  56. // @Description: Loiter brake start delay (in seconds)
  57. // @Units: s
  58. // @Range: 0 2
  59. // @Increment: 0.1
  60. // @User: Advanced
  61. AP_GROUPINFO("BRK_DELAY", 6, AC_Loiter, _brake_delay, LOITER_BRAKE_START_DELAY_DEFAULT),
  62. AP_GROUPEND
  63. };
  64. // Default constructor.
  65. // Note that the Vector/Matrix constructors already implicitly zero
  66. // their values.
  67. //
  68. AC_Loiter::AC_Loiter(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control) :
  69. _inav(inav),
  70. _ahrs(ahrs),
  71. _pos_control(pos_control),
  72. _attitude_control(attitude_control)
  73. {
  74. AP_Param::setup_object_defaults(this, var_info);
  75. }
  76. /// init_target to a position in cm from ekf origin
  77. void AC_Loiter::init_target(const Vector3f& position)
  78. {
  79. sanity_check_params();
  80. // initialise pos controller speed, acceleration
  81. _pos_control.set_max_speed_xy(LOITER_VEL_CORRECTION_MAX);
  82. _pos_control.set_max_accel_xy(_accel_cmss);
  83. // initialise desired acceleration and angles to zero to remain on station
  84. _predicted_accel.zero();
  85. _desired_accel = _predicted_accel;
  86. _predicted_euler_angle.zero();
  87. // set target position
  88. _pos_control.set_xy_target(position.x, position.y);
  89. // set vehicle velocity and acceleration to zero
  90. _pos_control.set_desired_velocity_xy(0.0f,0.0f);
  91. _pos_control.set_desired_accel_xy(0.0f,0.0f);
  92. // initialise position controller if not already active
  93. if (!_pos_control.is_active_xy()) {
  94. _pos_control.init_xy_controller();
  95. }
  96. }
  97. /// initialize's position and feed-forward velocity from current pos and velocity
  98. void AC_Loiter::init_target()
  99. {
  100. const Vector3f& curr_pos = _inav.get_position();
  101. const Vector3f& curr_vel = _inav.get_velocity();
  102. sanity_check_params();
  103. // initialise pos controller speed and acceleration
  104. _pos_control.set_max_speed_xy(LOITER_VEL_CORRECTION_MAX);
  105. _pos_control.set_max_accel_xy(_accel_cmss);
  106. _pos_control.set_leash_length_xy(LOITER_POS_CORRECTION_MAX);
  107. _predicted_accel = _desired_accel;
  108. // update angle targets that will be passed to stabilize controller
  109. float roll_cd, pitch_cd;
  110. _pos_control.accel_to_lean_angles(_predicted_accel.x, _predicted_accel.y, roll_cd, pitch_cd);
  111. _predicted_euler_angle.x = radians(roll_cd*0.01f);
  112. _predicted_euler_angle.y = radians(pitch_cd*0.01f);
  113. // set target position
  114. _pos_control.set_xy_target(curr_pos.x, curr_pos.y);
  115. // set vehicle velocity and acceleration to current state
  116. _pos_control.set_desired_velocity_xy(curr_vel.x, curr_vel.y);
  117. _pos_control.set_desired_accel_xy(_desired_accel.x, _desired_accel.y);
  118. // initialise position controller
  119. _pos_control.init_xy_controller();
  120. }
  121. /// reduce response for landing
  122. void AC_Loiter::soften_for_landing()
  123. {
  124. const Vector3f& curr_pos = _inav.get_position();
  125. // set target position to current position
  126. _pos_control.set_xy_target(curr_pos.x, curr_pos.y);
  127. // also prevent I term build up in xy velocity controller. Note
  128. // that this flag is reset on each loop, in run_xy_controller()
  129. _pos_control.set_limit_accel_xy();
  130. }
  131. /// set pilot desired acceleration in centi-degrees
  132. // dt should be the time (in seconds) since the last call to this function
  133. void AC_Loiter::set_pilot_desired_acceleration(float euler_roll_angle_cd, float euler_pitch_angle_cd, float dt)
  134. {
  135. // Convert from centidegrees on public interface to radians
  136. const float euler_roll_angle = radians(euler_roll_angle_cd*0.01f);
  137. const float euler_pitch_angle = radians(euler_pitch_angle_cd*0.01f);
  138. // convert our desired attitude to an acceleration vector assuming we are hovering
  139. const float pilot_cos_pitch_target = constrain_float(cosf(euler_pitch_angle), 0.5f, 1.0f);
  140. const float pilot_accel_rgt_cms = GRAVITY_MSS*100.0f * tanf(euler_roll_angle)/pilot_cos_pitch_target;
  141. const float pilot_accel_fwd_cms = -GRAVITY_MSS*100.0f * tanf(euler_pitch_angle);
  142. // rotate acceleration vectors input to lat/lon frame
  143. _desired_accel.x = (pilot_accel_fwd_cms*_ahrs.cos_yaw() - pilot_accel_rgt_cms*_ahrs.sin_yaw());
  144. _desired_accel.y = (pilot_accel_fwd_cms*_ahrs.sin_yaw() + pilot_accel_rgt_cms*_ahrs.cos_yaw());
  145. // difference between where we think we should be and where we want to be
  146. Vector2f angle_error(wrap_PI(euler_roll_angle - _predicted_euler_angle.x), wrap_PI(euler_pitch_angle - _predicted_euler_angle.y));
  147. // calculate the angular velocity that we would expect given our desired and predicted attitude
  148. _attitude_control.input_shaping_rate_predictor(angle_error, _predicted_euler_rate, dt);
  149. // update our predicted attitude based on our predicted angular velocity
  150. _predicted_euler_angle += _predicted_euler_rate * dt;
  151. // convert our predicted attitude to an acceleration vector assuming we are hovering
  152. const float pilot_predicted_cos_pitch_target = cosf(_predicted_euler_angle.y);
  153. const float pilot_predicted_accel_rgt_cms = GRAVITY_MSS*100.0f * tanf(_predicted_euler_angle.x)/pilot_predicted_cos_pitch_target;
  154. const float pilot_predicted_accel_fwd_cms = -GRAVITY_MSS*100.0f * tanf(_predicted_euler_angle.y);
  155. // rotate acceleration vectors input to lat/lon frame
  156. _predicted_accel.x = (pilot_predicted_accel_fwd_cms*_ahrs.cos_yaw() - pilot_predicted_accel_rgt_cms*_ahrs.sin_yaw());
  157. _predicted_accel.y = (pilot_predicted_accel_fwd_cms*_ahrs.sin_yaw() + pilot_predicted_accel_rgt_cms*_ahrs.cos_yaw());
  158. }
  159. /// get vector to stopping point based on a horizontal position and velocity
  160. void AC_Loiter::get_stopping_point_xy(Vector3f& stopping_point) const
  161. {
  162. _pos_control.get_stopping_point_xy(stopping_point);
  163. }
  164. /// get maximum lean angle when using loiter
  165. float AC_Loiter::get_angle_max_cd() const
  166. {
  167. if (is_zero(_angle_max)) {
  168. return MIN(_attitude_control.lean_angle_max(), _pos_control.get_lean_angle_max_cd()) * (2.0f/3.0f);
  169. }
  170. return MIN(_angle_max*100.0f, _pos_control.get_lean_angle_max_cd());
  171. }
  172. /// run the loiter controller
  173. void AC_Loiter::update()
  174. {
  175. // calculate dt
  176. float dt = _pos_control.time_since_last_xy_update();
  177. if (dt >= 0.2f) {
  178. dt = 0.0f;
  179. }
  180. // initialise pos controller speed and acceleration
  181. _pos_control.set_max_speed_xy(_speed_cms);
  182. _pos_control.set_max_accel_xy(_accel_cmss);
  183. calc_desired_velocity(dt);
  184. _pos_control.update_xy_controller();
  185. }
  186. // sanity check parameters
  187. void AC_Loiter::sanity_check_params()
  188. {
  189. _speed_cms = MAX(_speed_cms, LOITER_SPEED_MIN);
  190. _accel_cmss = MIN(_accel_cmss, GRAVITY_MSS * 100.0f * tanf(ToRad(_attitude_control.lean_angle_max() * 0.01f)));
  191. }
  192. /// calc_desired_velocity - updates desired velocity (i.e. feed forward) with pilot requested acceleration and fake wind resistance
  193. /// updated velocity sent directly to position controller
  194. void AC_Loiter::calc_desired_velocity(float nav_dt)
  195. {
  196. float ekfGndSpdLimit, ekfNavVelGainScaler;
  197. AP::ahrs_navekf().getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
  198. // calculate a loiter speed limit which is the minimum of the value set by the LOITER_SPEED
  199. // parameter and the value set by the EKF to observe optical flow limits
  200. float gnd_speed_limit_cms = MIN(_speed_cms, ekfGndSpdLimit*100.0f);
  201. gnd_speed_limit_cms = MAX(gnd_speed_limit_cms, LOITER_SPEED_MIN);
  202. float pilot_acceleration_max = GRAVITY_MSS*100.0f * tanf(radians(get_angle_max_cd()*0.01f));
  203. // range check nav_dt
  204. if (nav_dt < 0) {
  205. return;
  206. }
  207. _pos_control.set_max_speed_xy(gnd_speed_limit_cms);
  208. _pos_control.set_max_accel_xy(_accel_cmss);
  209. _pos_control.set_leash_length_xy(LOITER_POS_CORRECTION_MAX);
  210. // get loiters desired velocity from the position controller where it is being stored.
  211. const Vector3f &desired_vel_3d = _pos_control.get_desired_velocity();
  212. Vector2f desired_vel(desired_vel_3d.x,desired_vel_3d.y);
  213. // update the desired velocity using our predicted acceleration
  214. desired_vel.x += _predicted_accel.x * nav_dt;
  215. desired_vel.y += _predicted_accel.y * nav_dt;
  216. Vector2f loiter_accel_brake;
  217. float desired_speed = desired_vel.length();
  218. if (!is_zero(desired_speed)) {
  219. Vector2f desired_vel_norm = desired_vel/desired_speed;
  220. // TODO: consider using a velocity squared relationship like
  221. // pilot_acceleration_max*(desired_speed/gnd_speed_limit_cms)^2;
  222. // the drag characteristic of a multirotor should be examined to generate a curve
  223. // we could add a expo function here to fine tune it
  224. // calculate a drag acceleration based on the desired speed.
  225. float drag_decel = pilot_acceleration_max*desired_speed/gnd_speed_limit_cms;
  226. // calculate a braking acceleration if sticks are at zero
  227. float loiter_brake_accel = 0.0f;
  228. if (_desired_accel.is_zero()) {
  229. if ((AP_HAL::millis()-_brake_timer) > _brake_delay * 1000.0f) {
  230. float brake_gain = _pos_control.get_vel_xy_pid().kP() * 0.5f;
  231. loiter_brake_accel = constrain_float(AC_AttitudeControl::sqrt_controller(desired_speed, brake_gain, _brake_jerk_max_cmsss, nav_dt), 0.0f, _brake_accel_cmss);
  232. }
  233. } else {
  234. loiter_brake_accel = 0.0f;
  235. _brake_timer = AP_HAL::millis();
  236. }
  237. _brake_accel += constrain_float(loiter_brake_accel-_brake_accel, -_brake_jerk_max_cmsss*nav_dt, _brake_jerk_max_cmsss*nav_dt);
  238. loiter_accel_brake = desired_vel_norm*_brake_accel;
  239. // update the desired velocity using the drag and braking accelerations
  240. desired_speed = MAX(desired_speed-(drag_decel+_brake_accel)*nav_dt,0.0f);
  241. desired_vel = desired_vel_norm*desired_speed;
  242. }
  243. // add braking to the desired acceleration
  244. _desired_accel -= loiter_accel_brake;
  245. // Apply EKF limit to desired velocity - this limit is calculated by the EKF and adjusted as required to ensure certain sensor limits are respected (eg optical flow sensing)
  246. float horizSpdDem = desired_vel.length();
  247. if (horizSpdDem > gnd_speed_limit_cms) {
  248. desired_vel.x = desired_vel.x * gnd_speed_limit_cms / horizSpdDem;
  249. desired_vel.y = desired_vel.y * gnd_speed_limit_cms / horizSpdDem;
  250. }
  251. // Limit the velocity to prevent fence violations
  252. // TODO: We need to also limit the _desired_accel
  253. AC_Avoid *_avoid = AP::ac_avoid();
  254. if (_avoid != nullptr) {
  255. _avoid->adjust_velocity(_pos_control.get_pos_xy_p().kP(), _accel_cmss, desired_vel, nav_dt);
  256. }
  257. // send adjusted feed forward acceleration and velocity back to the Position Controller
  258. _pos_control.set_desired_accel_xy(_desired_accel.x, _desired_accel.y);
  259. _pos_control.set_desired_velocity_xy(desired_vel.x, desired_vel.y);
  260. }