AC_PosControl_Sub.cpp 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105
  1. #include "AC_PosControl_Sub.h"
  2. AC_PosControl_Sub::AC_PosControl_Sub(const AP_AHRS_View& ahrs, const AP_InertialNav& inav,
  3. const AP_Motors& motors, AC_AttitudeControl& attitude_control) :
  4. AC_PosControl(ahrs, inav, motors, attitude_control),
  5. _alt_max(0.0f),
  6. _alt_min(0.0f)
  7. {}
  8. /// set_alt_target_from_climb_rate - adjusts target up or down using a climb rate in cm/s
  9. /// should be called continuously (with dt set to be the expected time between calls)
  10. /// actual position target will be moved no faster than the speed_down and speed_up
  11. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  12. void AC_PosControl_Sub::set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
  13. {
  14. // adjust desired alt if motors have not hit their limits
  15. // To-Do: add check of _limit.pos_down?
  16. if ((climb_rate_cms<0 && (!_motors.limit.throttle_lower || force_descend)) || (climb_rate_cms>0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
  17. _pos_target.z += climb_rate_cms * dt;
  18. }
  19. // do not let target alt get above limit
  20. if (_alt_max < 100 && _pos_target.z > _alt_max) {
  21. _pos_target.z = _alt_max;
  22. _limit.pos_up = true;
  23. }
  24. // do not let target alt get below limit
  25. if (_alt_min < 0 && _alt_min < _alt_max && _pos_target.z < _alt_min) {
  26. _pos_target.z = _alt_min;
  27. _limit.pos_down = true;
  28. }
  29. // do not use z-axis desired velocity feed forward
  30. // vel_desired set to desired climb rate for reporting and land-detector
  31. _flags.use_desvel_ff_z = false;
  32. _vel_desired.z = climb_rate_cms;
  33. }
  34. /// set_alt_target_from_climb_rate_ff - adjusts target up or down using a climb rate in cm/s using feed-forward
  35. /// should be called continuously (with dt set to be the expected time between calls)
  36. /// actual position target will be moved no faster than the speed_down and speed_up
  37. /// target will also be stopped if the motors hit their limits or leash length is exceeded
  38. /// set force_descend to true during landing to allow target to move low enough to slow the motors
  39. void AC_PosControl_Sub::set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
  40. {
  41. // calculated increased maximum acceleration if over speed
  42. float accel_z_cms = _accel_z_cms;
  43. if (_vel_desired.z < _speed_down_cms && !is_zero(_speed_down_cms)) {
  44. accel_z_cms *= POSCONTROL_OVERSPEED_GAIN_Z * _vel_desired.z / _speed_down_cms;
  45. }
  46. if (_vel_desired.z > _speed_up_cms && !is_zero(_speed_up_cms)) {
  47. accel_z_cms *= POSCONTROL_OVERSPEED_GAIN_Z * _vel_desired.z / _speed_up_cms;
  48. }
  49. accel_z_cms = constrain_float(accel_z_cms, 0.0f, 750.0f);
  50. // jerk_z is calculated to reach full acceleration in 1000ms.
  51. float jerk_z = accel_z_cms * POSCONTROL_JERK_RATIO;
  52. float accel_z_max = MIN(accel_z_cms, safe_sqrt(2.0f*fabsf(_vel_desired.z - climb_rate_cms)*jerk_z));
  53. _accel_last_z_cms += jerk_z * dt;
  54. _accel_last_z_cms = MIN(accel_z_max, _accel_last_z_cms);
  55. float vel_change_limit = _accel_last_z_cms * dt;
  56. _vel_desired.z = constrain_float(climb_rate_cms, _vel_desired.z-vel_change_limit, _vel_desired.z+vel_change_limit);
  57. _flags.use_desvel_ff_z = true;
  58. // adjust desired alt if motors have not hit their limits
  59. // To-Do: add check of _limit.pos_down?
  60. if ((_vel_desired.z<0 && (!_motors.limit.throttle_lower || force_descend)) || (_vel_desired.z>0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
  61. _pos_target.z += _vel_desired.z * dt;
  62. }
  63. // do not let target alt get above limit
  64. if (_alt_max < 100 && _pos_target.z > _alt_max) {
  65. _pos_target.z = _alt_max;
  66. _limit.pos_up = true;
  67. // decelerate feed forward to zero
  68. _vel_desired.z = constrain_float(0.0f, _vel_desired.z-vel_change_limit, _vel_desired.z+vel_change_limit);
  69. }
  70. // do not let target alt get below limit
  71. if (_alt_min < 0 && _alt_min < _alt_max && _pos_target.z < _alt_min) {
  72. _pos_target.z = _alt_min;
  73. _limit.pos_down = true;
  74. // decelerate feed forward to zero
  75. _vel_desired.z = constrain_float(0.0f, _vel_desired.z-vel_change_limit, _vel_desired.z+vel_change_limit);
  76. }
  77. }
  78. /// relax_alt_hold_controllers - set all desired and targets to measured
  79. void AC_PosControl_Sub::relax_alt_hold_controllers()
  80. {
  81. _pos_target.z = _inav.get_altitude();
  82. _vel_desired.z = 0.0f;
  83. _flags.use_desvel_ff_z = false;
  84. _vel_target.z = _inav.get_velocity_z();
  85. _vel_last.z = _inav.get_velocity_z();
  86. _accel_desired.z = 0.0f;
  87. _accel_last_z_cms = 0.0f;
  88. _flags.reset_rate_to_accel_z = true;
  89. _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
  90. _pid_accel_z.reset_filter();
  91. }