AP_MotorsHeli_RSC.cpp 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396
  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_RSC.h"
  16. extern const AP_HAL::HAL& hal;
  17. const AP_Param::GroupInfo AP_MotorsHeli_RSC::var_info[] = {
  18. // @Param: SETPOINT
  19. // @DisplayName: External Motor Governor Setpoint
  20. // @Description: Throttle (HeliRSC Servo) output in percent to the external motor governor when motor interlock enabled (throttle hold off).
  21. // @Range: 0 100
  22. // @Units: %
  23. // @Increment: 1
  24. // @User: Standard
  25. AP_GROUPINFO("SETPOINT", 1, AP_MotorsHeli_RSC, _rsc_setpoint, AP_MOTORS_HELI_RSC_SETPOINT),
  26. // @Param: MODE
  27. // @DisplayName: Rotor Speed Control Mode
  28. // @Description: Selects the type of rotor speed control used to determine throttle output to the HeliRSC servo channel when motor interlock is enabled (throttle hold off). RC Passthrough sends the input from the RC Motor Interlock channel as throttle output. External Gov SetPoint sends the RSC SetPoint parameter value as throttle output. Throttle Curve uses the 5 point throttle curve to determine throttle output based on the collective output. Governor is ArduCopter's built-in governor that uses the throttle curve for a feed forward throttle command to determine throttle output.
  29. // @Values: 1:RC Passthrough, 2:External Gov SetPoint, 3:Throttle Curve, 4:Governor
  30. // @User: Standard
  31. AP_GROUPINFO("MODE", 2, AP_MotorsHeli_RSC, _rsc_mode, (int8_t)ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH),
  32. // @Param: RAMP_TIME
  33. // @DisplayName: RSC Throttle Output Ramp Time
  34. // @Description: Time in seconds for throttle output (HeliRSC servo) to ramp from ground idle (RSC_IDLE) to flight idle throttle setting when motor interlock is enabled (throttle hold off).
  35. // @Range: 0 60
  36. // @Units: s
  37. // @User: Standard
  38. AP_GROUPINFO("RAMP_TIME", 3, AP_MotorsHeli_RSC, _ramp_time, AP_MOTORS_HELI_RSC_RAMP_TIME),
  39. // @Param: RUNUP_TIME
  40. // @DisplayName: Rotor Runup Time
  41. // @Description: Actual time in seconds for the main rotor to reach full speed after motor interlock is enabled (throttle hold off). Must be at least one second longer than the Throttle Ramp Time that is set with RSC_RAMP_TIME.
  42. // @Range: 0 60
  43. // @Units: s
  44. // @User: Standard
  45. AP_GROUPINFO("RUNUP_TIME", 4, AP_MotorsHeli_RSC, _runup_time, AP_MOTORS_HELI_RSC_RUNUP_TIME),
  46. // @Param: CRITICAL
  47. // @DisplayName: Critical Rotor Speed
  48. // @Description: Percentage of normal rotor speed where flight is no longer possible. However currently the rotor runup/rundown is estimated using the RSC_RUNUP_TIME parameter. Estimated rotor speed increases/decreases between 0 (rotor stopped) to 1 (rotor at normal speed) in the RSC_RUNUP_TIME in seconds. This parameter should be set so that the estimated rotor speed goes below critical in approximately 3 seconds. So if you had a 10 second runup time then set RSC_CRITICAL to 70%.
  49. // @Range: 0 100
  50. // @Units: %
  51. // @Increment: 1
  52. // @User: Standard
  53. AP_GROUPINFO("CRITICAL", 5, AP_MotorsHeli_RSC, _critical_speed, AP_MOTORS_HELI_RSC_CRITICAL),
  54. // @Param: IDLE
  55. // @DisplayName: RSC Throttle Output at Idle
  56. // @Description: Throttle output (HeliRSC Servo) in percent while armed but motor interlock is disabled (throttle hold on). FOR COMBUSTION ENGINES. Sets the engine ground idle throttle percentage with clutch disengaged. This must be set to zero for electric helicopters under most situations. If the ESC has an autorotation window this can be set to keep the autorotation window open in the ESC. Consult the operating manual for your ESC to set it properly for this purpose
  57. // @Range: 0 50
  58. // @Units: %
  59. // @Increment: 1
  60. // @User: Standard
  61. AP_GROUPINFO("IDLE", 6, AP_MotorsHeli_RSC, _idle_output, AP_MOTORS_HELI_RSC_IDLE_DEFAULT),
  62. // @Param: SLEWRATE
  63. // @DisplayName: RSC Throttle Output Slew Rate
  64. // @Description: This controls the maximum rate at which the throttle output (HeliRSC servo) can change, as a percentage per second. A value of 100 means the throttle can change over its full range in one second. A value of zero gives unlimited slew rate.
  65. // @Range: 0 500
  66. // @Increment: 10
  67. // @User: Standard
  68. AP_GROUPINFO("SLEWRATE", 7, AP_MotorsHeli_RSC, _power_slewrate, 0),
  69. // @Param: THRCRV_0
  70. // @DisplayName: RSC Throttle Output at 0% collective
  71. // @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at the minimum collective pitch position. The 0 percent collective is defined by H_COL_MIN. Example: if the setup has -2 degree to +10 degree collective pitch setup, this setting would correspond to -2 degree of pitch.
  72. // @Range: 0 100
  73. // @Units: %
  74. // @Increment: 1
  75. // @User: Standard
  76. AP_GROUPINFO("THRCRV_0", 8, AP_MotorsHeli_RSC, _thrcrv[0], AP_MOTORS_HELI_RSC_THRCRV_0_DEFAULT),
  77. // @Param: THRCRV_25
  78. // @DisplayName: RSC Throttle Output at 25% collective
  79. // @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 25% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 25% of 12 degrees is 3 degrees, so this setting would correspond to +1 degree of pitch.
  80. // @Range: 0 100
  81. // @Units: %
  82. // @Increment: 1
  83. // @User: Standard
  84. AP_GROUPINFO("THRCRV_25", 9, AP_MotorsHeli_RSC, _thrcrv[1], AP_MOTORS_HELI_RSC_THRCRV_25_DEFAULT),
  85. // @Param: THRCRV_50
  86. // @DisplayName: RSC Throttle Output at 50% collective
  87. // @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 50% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 50% of 12 degrees is 6 degrees, so this setting would correspond to +4 degree of pitch.
  88. // @Range: 0 100
  89. // @Units: %
  90. // @Increment: 1
  91. // @User: Standard
  92. AP_GROUPINFO("THRCRV_50", 10, AP_MotorsHeli_RSC, _thrcrv[2], AP_MOTORS_HELI_RSC_THRCRV_50_DEFAULT),
  93. // @Param: THRCRV_75
  94. // @DisplayName: RSC Throttle Output at 75% collective
  95. // @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 75% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 75% of 12 degrees is 9 degrees, so this setting would correspond to +7 degree of pitch.
  96. // @Range: 0 100
  97. // @Units: %
  98. // @Increment: 1
  99. // @User: Standard
  100. AP_GROUPINFO("THRCRV_75", 11, AP_MotorsHeli_RSC, _thrcrv[3], AP_MOTORS_HELI_RSC_THRCRV_75_DEFAULT),
  101. // @Param: THRCRV_100
  102. // @DisplayName: RSC Throttle Output at 100% collective
  103. // @Description: Sets the throttle output (HeliRSC servo) in percent for the throttle curve at the minimum collective pitch position. The 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, this setting would correspond to +10 degree of pitch.
  104. // @Range: 0 100
  105. // @Units: %
  106. // @Increment: 1
  107. // @User: Standard
  108. AP_GROUPINFO("THRCRV_100", 12, AP_MotorsHeli_RSC, _thrcrv[4], AP_MOTORS_HELI_RSC_THRCRV_100_DEFAULT),
  109. // @Param: GOV_SETPNT
  110. // @DisplayName: Main Rotor Governor RPM Setpoint
  111. // @Description: Main rotor rpm setting that governor maintains when engaged. Set to the rotor rpm your helicopter runs in flight. When a speed sensor is installed the rotor governor maintains this speed. For governor operation this should be set 10 rpm higher than the actual desired headspeed to allow for governor droop
  112. // @Range: 800 3500
  113. // @Units: RPM
  114. // @Increment: 10
  115. // @User: Standard
  116. AP_GROUPINFO("GOV_SETPNT", 13, AP_MotorsHeli_RSC, _governor_reference, AP_MOTORS_HELI_RSC_GOVERNOR_SETPNT_DEFAULT),
  117. // @Param: GOV_DISGAG
  118. // @DisplayName: Throttle Percentage for Governor Disengage
  119. // @Description: Percentage of throttle where the governor will disengage to allow return to flight idle power. Typically should be set to the same value as flight idle throttle (the very lowest throttle setting on the throttle curve). The governor disengage can be disabled by setting this value to zero and using the pull-down from the governor TCGAIN to reduce power to flight idle with the collective at it's lowest throttle setting on the throttle curve.
  120. // @Range: 0 50
  121. // @Units: %
  122. // @Increment: 1
  123. // @User: Standard
  124. AP_GROUPINFO("GOV_DISGAG", 14, AP_MotorsHeli_RSC, _governor_disengage, AP_MOTORS_HELI_RSC_GOVERNOR_DISENGAGE_DEFAULT),
  125. // @Param: GOV_DROOP
  126. // @DisplayName: Governor Droop Response Setting
  127. // @Description: Governor droop response under load, normal settings of 0-100%. Higher value is quicker response but may cause surging. Setting to zero disables the governor. Adjust this to be as aggressive as possible without getting surging or over-run on headspeed when the governor engages. Setting over 100% is allowable for some two-stage turbine engines to provide scheduling of the gas generator for proper torque response of the N2 spool
  128. // @Range: 0 150
  129. // @Units: %
  130. // @Increment: 1
  131. // @User: Standard
  132. AP_GROUPINFO("GOV_DROOP", 15, AP_MotorsHeli_RSC, _governor_droop_response, AP_MOTORS_HELI_RSC_GOVERNOR_DROOP_DEFAULT),
  133. // @Param: GOV_TCGAIN
  134. // @DisplayName: Governor Throttle Curve Gain
  135. // @Description: Percentage of throttle curve gain in governor output. This provides a type of feedforward response to sudden loading or unloading of the engine. If headspeed drops excessively during sudden heavy load, increase the throttle curve gain. If the governor runs with excessive droop more than 15 rpm lower than the speed setting, increase this setting until the governor runs at 8-10 rpm droop from the speed setting. The throttle curve must be properly tuned to fly the helicopter without the governor for this setting to work properly.
  136. // @Range: 50 100
  137. // @Units: %
  138. // @Increment: 1
  139. // @User: Standard
  140. AP_GROUPINFO("GOV_TCGAIN", 16, AP_MotorsHeli_RSC, _governor_tcgain, AP_MOTORS_HELI_RSC_GOVERNOR_TCGAIN_DEFAULT),
  141. // @Param: GOV_RANGE
  142. // @DisplayName: Governor Operational Range
  143. // @Description: RPM range +/- governor rpm reference setting where governor is operational. If speed sensor fails or rpm falls outside of this range, the governor will disengage and return to throttle curve. Recommended range is 100
  144. // @Range: 50 200
  145. // @Units: RPM
  146. // @Increment: 10
  147. // @User: Standard
  148. AP_GROUPINFO("GOV_RANGE", 17, AP_MotorsHeli_RSC, _governor_range, AP_MOTORS_HELI_RSC_GOVERNOR_RANGE_DEFAULT),
  149. AP_GROUPEND
  150. };
  151. // init_servo - servo initialization on start-up
  152. void AP_MotorsHeli_RSC::init_servo()
  153. {
  154. // setup RSC on specified channel by default
  155. SRV_Channels::set_aux_channel_default(_aux_fn, _default_channel);
  156. // set servo range
  157. SRV_Channels::set_range(SRV_Channels::get_motor_function(_aux_fn), 1000);
  158. }
  159. // set_power_output_range
  160. // TODO: Look at possibly calling this at a slower rate. Doesn't need to be called every cycle.
  161. void AP_MotorsHeli_RSC::set_throttle_curve()
  162. {
  163. float thrcrv[5];
  164. // Ensure user inputs are within parameter limits
  165. // Scale throttle curve parameters
  166. for (uint8_t i = 0; i < 5; i++) {
  167. thrcrv[i] = constrain_float(_thrcrv[i] * 0.01f, 0.0f, 1.0f);
  168. }
  169. // Calculate the spline polynomials for the throttle curve
  170. splinterp5(thrcrv,_thrcrv_poly);
  171. }
  172. // output - update value to send to ESC/Servo
  173. void AP_MotorsHeli_RSC::output(RotorControlState state)
  174. {
  175. float dt;
  176. uint64_t now = AP_HAL::micros64();
  177. float last_control_output = _control_output;
  178. if (_last_update_us == 0) {
  179. _last_update_us = now;
  180. dt = 0.001f;
  181. } else {
  182. dt = 1.0e-6f * (now - _last_update_us);
  183. _last_update_us = now;
  184. }
  185. switch (state){
  186. case ROTOR_CONTROL_STOP:
  187. // set rotor ramp to decrease speed to zero, this happens instantly inside update_rotor_ramp()
  188. update_rotor_ramp(0.0f, dt);
  189. // control output forced to zero
  190. _control_output = 0.0f;
  191. break;
  192. case ROTOR_CONTROL_IDLE:
  193. // set rotor ramp to decrease speed to zero
  194. update_rotor_ramp(0.0f, dt);
  195. // set rotor control speed to idle speed parameter, this happens instantly and ignore ramping
  196. _control_output = get_idle_output();
  197. break;
  198. case ROTOR_CONTROL_ACTIVE:
  199. // set main rotor ramp to increase to full speed
  200. update_rotor_ramp(1.0f, dt);
  201. if ((_control_mode == ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH) || (_control_mode == ROTOR_CONTROL_MODE_SPEED_SETPOINT)) {
  202. // set control rotor speed to ramp slewed value between idle and desired speed
  203. _control_output = get_idle_output() + (_rotor_ramp_output * (_desired_speed - get_idle_output()));
  204. } else if (_control_mode == ROTOR_CONTROL_MODE_OPEN_LOOP_POWER_OUTPUT) {
  205. // throttle output from throttle curve based on collective position
  206. float desired_throttle = calculate_desired_throttle(_collective_in);
  207. _control_output = get_idle_output() + (_rotor_ramp_output * (desired_throttle - get_idle_output()));
  208. } else if (_control_mode == ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT) {
  209. // governor provides two modes of throttle control - governor engaged
  210. // or throttle curve if governor is out of range or sensor failed
  211. float desired_throttle = calculate_desired_throttle(_collective_in);
  212. // governor is active if within user-set range from reference speed
  213. if ((_rotor_rpm >= ((float)_governor_reference - _governor_range)) && (_rotor_rpm <= ((float)_governor_reference + _governor_range))) {
  214. float governor_droop = constrain_float((float)_governor_reference - _rotor_rpm,0.0f,_governor_range);
  215. // if rpm has not reached 40% of the operational range from reference speed, governor
  216. // remains in pre-engage status, no reference speed compensation due to droop
  217. // this provides a soft-start function that engages the governor less aggressively
  218. if (_governor_engage && _rotor_rpm < ((float)_governor_reference - (_governor_range * 0.4f))) {
  219. _governor_output = ((_rotor_rpm - (float)_governor_reference) * desired_throttle) * get_governor_droop_response() * -0.01f;
  220. } else {
  221. // normal flight status, governor fully engaged with reference speed compensation for droop
  222. _governor_engage = true;
  223. _governor_output = ((_rotor_rpm - ((float)_governor_reference + governor_droop)) * desired_throttle) * get_governor_droop_response() * -0.01f;
  224. }
  225. // check for governor disengage for return to flight idle power
  226. if (desired_throttle <= get_governor_disengage()) {
  227. _governor_output = 0.0f;
  228. _governor_engage = false;
  229. }
  230. // throttle output with governor on is constrained from minimum called for from throttle curve
  231. // to maximum WOT. This prevents outliers on rpm signal from closing the throttle in flight due
  232. // to rpm sensor failure or bad signal quality
  233. _control_output = constrain_float(get_idle_output() + (_rotor_ramp_output * (((desired_throttle * get_governor_tcgain()) + _governor_output) - get_idle_output())), get_idle_output() + (_rotor_ramp_output * ((desired_throttle * get_governor_tcgain())) - get_idle_output()), 1.0f);
  234. } else {
  235. // hold governor output at zero, engage status is false and use the throttle curve
  236. // this is failover for in-flight failure of the speed sensor
  237. _governor_output = 0.0f;
  238. _governor_engage = false;
  239. _control_output = get_idle_output() + (_rotor_ramp_output * (desired_throttle - get_idle_output()));
  240. }
  241. }
  242. break;
  243. }
  244. // update rotor speed run-up estimate
  245. update_rotor_runup(dt);
  246. if (_power_slewrate > 0) {
  247. // implement slew rate for throttle
  248. float max_delta = dt * _power_slewrate * 0.01f;
  249. _control_output = constrain_float(_control_output, last_control_output-max_delta, last_control_output+max_delta);
  250. }
  251. // output to rsc servo
  252. write_rsc(_control_output);
  253. }
  254. // update_rotor_ramp - slews rotor output scalar between 0 and 1, outputs float scalar to _rotor_ramp_output
  255. void AP_MotorsHeli_RSC::update_rotor_ramp(float rotor_ramp_input, float dt)
  256. {
  257. // sanity check ramp time
  258. if (_ramp_time <= 0) {
  259. _ramp_time = 1;
  260. }
  261. // ramp output upwards towards target
  262. if (_rotor_ramp_output < rotor_ramp_input) {
  263. // allow control output to jump to estimated speed
  264. if (_rotor_ramp_output < _rotor_runup_output) {
  265. _rotor_ramp_output = _rotor_runup_output;
  266. }
  267. // ramp up slowly to target
  268. _rotor_ramp_output += (dt / _ramp_time);
  269. if (_rotor_ramp_output > rotor_ramp_input) {
  270. _rotor_ramp_output = rotor_ramp_input;
  271. }
  272. }else{
  273. // ramping down happens instantly
  274. _rotor_ramp_output = rotor_ramp_input;
  275. }
  276. }
  277. // update_rotor_runup - function to slew rotor runup scalar, outputs float scalar to _rotor_runup_ouptut
  278. void AP_MotorsHeli_RSC::update_rotor_runup(float dt)
  279. {
  280. // sanity check runup time
  281. if (_runup_time < _ramp_time) {
  282. _runup_time = _ramp_time;
  283. }
  284. if (_runup_time <= 0 ) {
  285. _runup_time = 1;
  286. }
  287. // ramp speed estimate towards control out
  288. float runup_increment = dt / _runup_time;
  289. if (_rotor_runup_output < _rotor_ramp_output) {
  290. _rotor_runup_output += runup_increment;
  291. if (_rotor_runup_output > _rotor_ramp_output) {
  292. _rotor_runup_output = _rotor_ramp_output;
  293. }
  294. }else{
  295. _rotor_runup_output -= runup_increment;
  296. if (_rotor_runup_output < _rotor_ramp_output) {
  297. _rotor_runup_output = _rotor_ramp_output;
  298. }
  299. }
  300. // update run-up complete flag
  301. // if control mode is disabled, then run-up complete always returns true
  302. if ( _control_mode == ROTOR_CONTROL_MODE_DISABLED ){
  303. _runup_complete = true;
  304. return;
  305. }
  306. // if rotor ramp and runup are both at full speed, then run-up has been completed
  307. if (!_runup_complete && (_rotor_ramp_output >= 1.0f) && (_rotor_runup_output >= 1.0f)) {
  308. _runup_complete = true;
  309. }
  310. // if rotor speed is less than critical speed, then run-up is not complete
  311. // this will prevent the case where the target rotor speed is less than critical speed
  312. if (_runup_complete && (get_rotor_speed() <= get_critical_speed())) {
  313. _runup_complete = false;
  314. }
  315. }
  316. // get_rotor_speed - gets rotor speed either as an estimate, or (ToDO) a measured value
  317. float AP_MotorsHeli_RSC::get_rotor_speed() const
  318. {
  319. // if no actual measured rotor speed is available, estimate speed based on rotor runup scalar.
  320. return _rotor_runup_output;
  321. }
  322. // write_rsc - outputs pwm onto output rsc channel
  323. // servo_out parameter is of the range 0 ~ 1
  324. void AP_MotorsHeli_RSC::write_rsc(float servo_out)
  325. {
  326. if (_control_mode == ROTOR_CONTROL_MODE_DISABLED){
  327. // do not do servo output to avoid conflicting with other output on the channel
  328. // ToDo: We should probably use RC_Channel_Aux to avoid this problem
  329. return;
  330. } else {
  331. SRV_Channels::set_output_scaled(_aux_fn, (uint16_t) (servo_out * 1000));
  332. }
  333. }
  334. // calculate_desired_throttle - uses throttle curve and collective input to determine throttle setting
  335. float AP_MotorsHeli_RSC::calculate_desired_throttle(float collective_in)
  336. {
  337. const float inpt = collective_in * 4.0f + 1.0f;
  338. uint8_t idx = constrain_int16(int8_t(collective_in * 4), 0, 3);
  339. const float a = inpt - (idx + 1.0f);
  340. const float b = (idx + 1.0f) - inpt + 1.0f;
  341. float throttle = _thrcrv_poly[idx][0] * a + _thrcrv_poly[idx][1] * b + _thrcrv_poly[idx][2] * (powf(a,3.0f) - a) / 6.0f + _thrcrv_poly[idx][3] * (powf(b,3.0f) - b) / 6.0f;
  342. throttle = constrain_float(throttle, 0.0f, 1.0f);
  343. return throttle;
  344. }