AC_InputManager_Heli.cpp 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122
  1. #include "AC_InputManager_Heli.h"
  2. #include <AP_Math/AP_Math.h>
  3. #include <AP_HAL/AP_HAL.h>
  4. extern const AP_HAL::HAL& hal;
  5. const AP_Param::GroupInfo AC_InputManager_Heli::var_info[] = {
  6. // parameters from parent vehicle
  7. AP_NESTEDGROUPINFO(AC_InputManager, 0),
  8. // @Param: STAB_COL_1
  9. // @DisplayName: Stabilize Mode Collective Point 1
  10. // @Description: Helicopter's minimum collective pitch setting at zero throttle input in Stabilize mode
  11. // @Range: 0 500
  12. // @Units: d%
  13. // @Increment: 1
  14. // @User: Standard
  15. AP_GROUPINFO("STAB_COL_1", 1, AC_InputManager_Heli, _heli_stab_col_min, AC_ATTITUDE_HELI_STAB_COLLECTIVE_MIN_DEFAULT),
  16. // @Param: STAB_COL_2
  17. // @DisplayName: Stabilize Mode Collective Point 2
  18. // @Description: Helicopter's collective pitch setting at mid-low throttle input in Stabilize mode
  19. // @Range: 0 500
  20. // @Units: d%
  21. // @Increment: 1
  22. // @User: Standard
  23. AP_GROUPINFO("STAB_COL_2", 2, AC_InputManager_Heli, _heli_stab_col_low, AC_ATTITUDE_HELI_STAB_COLLECTIVE_LOW_DEFAULT),
  24. // @Param: STAB_COL_3
  25. // @DisplayName: Stabilize Mode Collective Point 3
  26. // @Description: Helicopter's collective pitch setting at mid-high throttle input in Stabilize mode
  27. // @Range: 500 1000
  28. // @Units: d%
  29. // @Increment: 1
  30. // @User: Standard
  31. AP_GROUPINFO("STAB_COL_3", 3, AC_InputManager_Heli, _heli_stab_col_high, AC_ATTITUDE_HELI_STAB_COLLECTIVE_HIGH_DEFAULT),
  32. // @Param: STAB_COL_4
  33. // @DisplayName: Stabilize Mode Collective Point 4
  34. // @Description: Helicopter's maximum collective pitch setting at full throttle input in Stabilize mode
  35. // @Range: 500 1000
  36. // @Units: d%
  37. // @Increment: 1
  38. // @User: Standard
  39. AP_GROUPINFO("STAB_COL_4", 4, AC_InputManager_Heli, _heli_stab_col_max, AC_ATTITUDE_HELI_STAB_COLLECTIVE_MAX_DEFAULT),
  40. // @Param: ACRO_COL_EXP
  41. // @DisplayName: Acro Mode Collective Expo
  42. // @Description: Used to soften collective pitch inputs near center point in Acro mode.
  43. // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
  44. // @User: Advanced
  45. AP_GROUPINFO("ACRO_COL_EXP", 5, AC_InputManager_Heli, _acro_col_expo, 0),
  46. AP_GROUPEND
  47. };
  48. // get_pilot_desired_collective - rescale's pilot collective pitch input in Stabilize and Acro modes
  49. float AC_InputManager_Heli::get_pilot_desired_collective(int16_t control_in)
  50. {
  51. float slope_low, slope_high, slope_range, slope_run, scalar;
  52. float stab_col_out, acro_col_out;
  53. // calculate stabilize collective value which scales pilot input to reduced collective range
  54. // code implements a 3-segment curve with knee points at 40% and 60% throttle input
  55. if (control_in < 400){
  56. slope_low = _heli_stab_col_min / 1000.0f;
  57. slope_high = _heli_stab_col_low / 1000.0f;
  58. slope_range = 0.4f;
  59. slope_run = control_in / 1000.0f;
  60. } else if(control_in <600){
  61. slope_low = _heli_stab_col_low / 1000.0f;
  62. slope_high = _heli_stab_col_high / 1000.0f;
  63. slope_range = 0.2f;
  64. slope_run = (control_in - 400) / 1000.0f;
  65. } else {
  66. slope_low = _heli_stab_col_high / 1000.0f;
  67. slope_high = _heli_stab_col_max / 1000.0f;
  68. slope_range = 0.4f;
  69. slope_run = (control_in - 600) / 1000.0f;
  70. }
  71. scalar = (slope_high - slope_low)/slope_range;
  72. stab_col_out = slope_low + slope_run * scalar;
  73. stab_col_out = constrain_float(stab_col_out, 0.0f, 1.0f);
  74. //
  75. // calculate expo-scaled acro collective
  76. // range check expo
  77. if (_acro_col_expo > 1.0f) {
  78. _acro_col_expo = 1.0f;
  79. }
  80. if (_acro_col_expo <= 0.0f) {
  81. acro_col_out = control_in / 1000.0f;
  82. } else {
  83. // expo variables
  84. float col_in, col_in3, col_out;
  85. col_in = (float)(control_in-500)/500.0f;
  86. col_in3 = col_in*col_in*col_in;
  87. col_out = (_acro_col_expo * col_in3) + ((1.0f-_acro_col_expo)*col_in);
  88. acro_col_out = 0.5f + col_out*0.5f;
  89. }
  90. acro_col_out = constrain_float(acro_col_out, 0.0f, 1.0f);
  91. // ramp to and from stab col over 1/2 second
  92. if (_im_flags_heli.use_stab_col && (_stab_col_ramp < 1.0f)){
  93. _stab_col_ramp += 2.0f/(float)_loop_rate;
  94. } else if(!_im_flags_heli.use_stab_col && (_stab_col_ramp > 0.0f)){
  95. _stab_col_ramp -= 2.0f/(float)_loop_rate;
  96. }
  97. _stab_col_ramp = constrain_float(_stab_col_ramp, 0.0f, 1.0f);
  98. // scale collective output smoothly between acro and stab col
  99. float collective_out;
  100. collective_out = (float)((1.0f-_stab_col_ramp)*acro_col_out + _stab_col_ramp*stab_col_out);
  101. collective_out = constrain_float(collective_out, 0.0f, 1.0f);
  102. return collective_out;
  103. }