AP_MotorsHeli_Swash.cpp 9.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include <stdlib.h>
  14. #include <AP_HAL/AP_HAL.h>
  15. #include "AP_MotorsHeli_Swash.h"
  16. extern const AP_HAL::HAL& hal;
  17. const AP_Param::GroupInfo AP_MotorsHeli_Swash::var_info[] = {
  18. // @Param: TYPE
  19. // @DisplayName: Swashplate Type
  20. // @Description: H3 is generic, three-servo only. H3_120/H3_140 plates have Motor1 left side, Motor2 right side, Motor3 elevator in rear. HR3_120/HR3_140 have Motor1 right side, Motor2 left side, Motor3 elevator in front - use H3_120/H3_140 and reverse servo and collective directions as necessary. For all H3_90 swashplates use H4_90 and don't use servo output for the missing servo. For H4-90 Motors1&2 are left/right respectively, Motors3&4 are rear/front respectively. For H4-45 Motors1&2 are LF/RF, Motors3&4 are LR/RR
  21. // @Values: 0:H3 Generic,1:H1 non-CPPM,2:H3_140,3:H3_120,4:H4_90,5:H4_45
  22. // @User: Standard
  23. AP_GROUPINFO("TYPE", 1, AP_MotorsHeli_Swash, _swashplate_type, SWASHPLATE_TYPE_H3_120),
  24. // @Param: COL_DIR
  25. // @DisplayName: Collective Control Direction
  26. // @Description: Direction collective moves for positive pitch. 0 for Normal, 1 for Reversed
  27. // @Values: 0:Normal,1:Reversed
  28. // @User: Standard
  29. AP_GROUPINFO("COL_DIR", 2, AP_MotorsHeli_Swash, _swash_coll_dir, COLLECTIVE_DIRECTION_NORMAL),
  30. // @Param: LIN_SVO
  31. // @DisplayName: Linearize swashplate servo mechanical throw
  32. // @Description: This linearizes the swashplate servo's mechanical output to account for nonlinear output due to arm rotation. This requires a specific setup procedure to work properly. The servo arm must be centered on the mechanical throw at the servo trim position and the servo trim position kept as close to 1500 as possible. Leveling the swashplate can only be done through the pitch links. See the ardupilot wiki for more details on setup.
  33. // @Values: 0:Disabled,1:Enabled
  34. // @User: Standard
  35. AP_GROUPINFO("LIN_SVO", 3, AP_MotorsHeli_Swash, _linear_swash_servo, 0),
  36. // @Param: H3_ENABLE
  37. // @DisplayName: Enable generic H3 swashplate settings
  38. // @Description: Automatically set when H3 generic swash type is selected. Do not set manually.
  39. // @Values: 0:Disabled,1:Enabled
  40. // @User: Advanced
  41. AP_GROUPINFO_FLAGS("H3_ENABLE", 4, AP_MotorsHeli_Swash, enable, 0, AP_PARAM_FLAG_ENABLE),
  42. // @Param: H3_SV1_POS
  43. // @DisplayName: servo 1 position
  44. // @Description: Azimuth position on swashplate for servo 1 with the front of the heli being 0 deg
  45. // @Range: -180 180
  46. // @Units: deg
  47. // @User: Advanced
  48. AP_GROUPINFO("H3_SV1_POS", 5, AP_MotorsHeli_Swash, _servo1_pos, -60),
  49. // @Param: H3_SV2_POS
  50. // @DisplayName: servo 2 position
  51. // @Description: Azimuth position on swashplate for servo 2 with the front of the heli being 0 deg
  52. // @Range: -180 180
  53. // @Units: deg
  54. // @User: Advanced
  55. AP_GROUPINFO("H3_SV2_POS", 6, AP_MotorsHeli_Swash, _servo2_pos, 60),
  56. // @Param: H3_SV3_POS
  57. // @DisplayName: servo 3 position
  58. // @Description: Azimuth position on swashplate for servo 3 with the front of the heli being 0 deg
  59. // @Range: -180 180
  60. // @Units: deg
  61. // @User: Advanced
  62. AP_GROUPINFO("H3_SV3_POS", 7, AP_MotorsHeli_Swash, _servo3_pos, 180),
  63. // @Param: H3_PHANG
  64. // @DisplayName: Swashplate Phase Angle Compensation
  65. // @Description: Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
  66. // @Range: -30 30
  67. // @Units: deg
  68. // @User: Advanced
  69. // @Increment: 1
  70. AP_GROUPINFO("H3_PHANG", 8, AP_MotorsHeli_Swash, _phase_angle, 0),
  71. AP_GROUPEND
  72. };
  73. // configure - configure the swashplate settings for any updated parameters
  74. void AP_MotorsHeli_Swash::configure()
  75. {
  76. _swash_type = static_cast<SwashPlateType>(_swashplate_type.get());
  77. _collective_direction = static_cast<CollectiveDirection>(_swash_coll_dir.get());
  78. _make_servo_linear = _linear_swash_servo;
  79. if (_swash_type == SWASHPLATE_TYPE_H3) {
  80. enable = 1;
  81. } else {
  82. enable = 0;
  83. }
  84. }
  85. // CCPM Mixers - calculate mixing scale factors by swashplate type
  86. void AP_MotorsHeli_Swash::calculate_roll_pitch_collective_factors()
  87. {
  88. if (_swash_type == SWASHPLATE_TYPE_H1) {
  89. // CCPM mixing not used
  90. _collectiveFactor[CH_1] = 0;
  91. _collectiveFactor[CH_2] = 0;
  92. _collectiveFactor[CH_3] = 1;
  93. } else if ((_swash_type == SWASHPLATE_TYPE_H4_90) || (_swash_type == SWASHPLATE_TYPE_H4_45)) {
  94. // collective mixer for four-servo CCPM
  95. _collectiveFactor[CH_1] = 1;
  96. _collectiveFactor[CH_2] = 1;
  97. _collectiveFactor[CH_3] = 1;
  98. _collectiveFactor[CH_4] = 1;
  99. } else {
  100. // collective mixer for three-servo CCPM
  101. _collectiveFactor[CH_1] = 1;
  102. _collectiveFactor[CH_2] = 1;
  103. _collectiveFactor[CH_3] = 1;
  104. }
  105. if (_swash_type == SWASHPLATE_TYPE_H3) {
  106. // Three-servo roll/pitch mixer for adjustable servo position
  107. // can be any style swashplate, phase angle is adjustable
  108. _rollFactor[CH_1] = cosf(radians(_servo1_pos + 90 - _phase_angle));
  109. _rollFactor[CH_2] = cosf(radians(_servo2_pos + 90 - _phase_angle));
  110. _rollFactor[CH_3] = cosf(radians(_servo3_pos + 90 - _phase_angle));
  111. _pitchFactor[CH_1] = cosf(radians(_servo1_pos - _phase_angle));
  112. _pitchFactor[CH_2] = cosf(radians(_servo2_pos - _phase_angle));
  113. _pitchFactor[CH_3] = cosf(radians(_servo3_pos - _phase_angle));
  114. // defined swashplates, servo1 is always left, servo2 is right,
  115. // servo3 is elevator
  116. } else if (_swash_type == SWASHPLATE_TYPE_H3_140) { //
  117. // Three-servo roll/pitch mixer for H3-140
  118. // HR3-140 uses reversed servo and collective direction in heli setup
  119. // 1:1 pure input style, phase angle not adjustable
  120. _rollFactor[CH_1] = 1;
  121. _rollFactor[CH_2] = -1;
  122. _rollFactor[CH_3] = 0;
  123. _pitchFactor[CH_1] = 1;
  124. _pitchFactor[CH_2] = 1;
  125. _pitchFactor[CH_3] = -1;
  126. } else if (_swash_type == SWASHPLATE_TYPE_H3_120) {
  127. // three-servo roll/pitch mixer for H3-120
  128. // HR3-120 uses reversed servo and collective direction in heli setup
  129. // not a pure mixing swashplate, phase angle is adjustable
  130. _rollFactor[CH_1] = 0.866025f;
  131. _rollFactor[CH_2] = -0.866025f;
  132. _rollFactor[CH_3] = 0;
  133. _pitchFactor[CH_1] = 0.5f;
  134. _pitchFactor[CH_2] = 0.5f;
  135. _pitchFactor[CH_3] = -1;
  136. } else if (_swash_type == SWASHPLATE_TYPE_H4_90) {
  137. // four-servo roll/pitch mixer for H4-90
  138. // 1:1 pure input style, phase angle not adjustable
  139. // servos 3 & 7 are elevator
  140. // can also be used for all versions of 90 deg three-servo swashplates
  141. _rollFactor[CH_1] = 1;
  142. _rollFactor[CH_2] = -1;
  143. _rollFactor[CH_3] = 0;
  144. _rollFactor[CH_4] = 0;
  145. _pitchFactor[CH_1] = 0;
  146. _pitchFactor[CH_2] = 0;
  147. _pitchFactor[CH_3] = -1;
  148. _pitchFactor[CH_4] = 1;
  149. } else if (_swash_type == SWASHPLATE_TYPE_H4_45) {
  150. // four-servo roll/pitch mixer for H4-45
  151. // 1:1 pure input style, phase angle not adjustable
  152. // for 45 deg plates servos 1&2 are LF&RF, 3&7 are LR&RR.
  153. _rollFactor[CH_1] = 0.707107f;
  154. _rollFactor[CH_2] = -0.707107f;
  155. _rollFactor[CH_3] = 0.707107f;
  156. _rollFactor[CH_4] = -0.707107f;
  157. _pitchFactor[CH_1] = 0.707107f;
  158. _pitchFactor[CH_2] = 0.707107f;
  159. _pitchFactor[CH_3] = -0.707f;
  160. _pitchFactor[CH_4] = -0.707f;
  161. } else {
  162. // CCPM mixing not being used, so H1 straight outputs
  163. _rollFactor[CH_1] = 1;
  164. _rollFactor[CH_2] = 0;
  165. _rollFactor[CH_3] = 0;
  166. _pitchFactor[CH_1] = 0;
  167. _pitchFactor[CH_2] = 1;
  168. _pitchFactor[CH_3] = 0;
  169. }
  170. }
  171. // get_servo_out - calculates servo output
  172. float AP_MotorsHeli_Swash::get_servo_out(int8_t ch_num, float pitch, float roll, float collective) const
  173. {
  174. // Collective control direction. Swash moves up for negative collective pitch, down for positive collective pitch
  175. if (_collective_direction == COLLECTIVE_DIRECTION_REVERSED){
  176. collective = 1 - collective;
  177. }
  178. float servo = ((_rollFactor[ch_num] * roll) + (_pitchFactor[ch_num] * pitch))*0.45f + _collectiveFactor[ch_num] * collective;
  179. if (_swash_type == SWASHPLATE_TYPE_H1 && (ch_num == CH_1 || ch_num == CH_2)) {
  180. servo += 0.5f;
  181. }
  182. // rescale from -1..1, so we can use the pwm calc that includes trim
  183. servo = 2.0f * servo - 1.0f;
  184. if (_make_servo_linear == 1) {
  185. servo = get_linear_servo_output(servo);
  186. }
  187. return servo;
  188. }
  189. // set_linear_servo_out - sets swashplate servo output to be linear
  190. float AP_MotorsHeli_Swash::get_linear_servo_output(float input) const
  191. {
  192. input = constrain_float(input, -1.0f, 1.0f);
  193. //servo output is calculated by normalizing input to 50 deg arm rotation as full input for a linear throw
  194. return safe_asin(0.766044f * input) * 1.145916;
  195. }