AC_PosControl_Sub.cpp 5.4 KB

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