AP_MotorsHeli.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458
  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. /*
  14. * AP_MotorsHeli.cpp - ArduCopter motors library
  15. * Code by RandyMackay. DIYDrones.com
  16. *
  17. */
  18. #include <stdlib.h>
  19. #include <AP_HAL/AP_HAL.h>
  20. #include "AP_MotorsHeli.h"
  21. #include <GCS_MAVLink/GCS.h>
  22. extern const AP_HAL::HAL& hal;
  23. const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = {
  24. // 1 was ROL_MAX which has been replaced by CYC_MAX
  25. // 2 was PIT_MAX which has been replaced by CYC_MAX
  26. // @Param: COL_MIN
  27. // @DisplayName: Collective Pitch Minimum
  28. // @Description: Lowest possible servo position in PWM microseconds for the swashplate
  29. // @Range: 1000 2000
  30. // @Units: PWM
  31. // @Increment: 1
  32. // @User: Standard
  33. AP_GROUPINFO("COL_MIN", 3, AP_MotorsHeli, _collective_min, AP_MOTORS_HELI_COLLECTIVE_MIN),
  34. // @Param: COL_MAX
  35. // @DisplayName: Collective Pitch Maximum
  36. // @Description: Highest possible servo position in PWM microseconds for the swashplate
  37. // @Range: 1000 2000
  38. // @Units: PWM
  39. // @Increment: 1
  40. // @User: Standard
  41. AP_GROUPINFO("COL_MAX", 4, AP_MotorsHeli, _collective_max, AP_MOTORS_HELI_COLLECTIVE_MAX),
  42. // @Param: COL_MID
  43. // @DisplayName: Collective Pitch Mid-Point
  44. // @Description: Swash servo position in PWM microseconds corresponding to zero collective pitch (or zero lift for Asymmetrical blades)
  45. // @Range: 1000 2000
  46. // @Units: PWM
  47. // @Increment: 1
  48. // @User: Standard
  49. AP_GROUPINFO("COL_MID", 5, AP_MotorsHeli, _collective_mid, AP_MOTORS_HELI_COLLECTIVE_MID),
  50. // @Param: SV_MAN
  51. // @DisplayName: Manual Servo Mode
  52. // @Description: Manual servo override for swash set-up. Do not set this manually!
  53. // @Values: 0:Disabled,1:Passthrough,2:Max collective,3:Mid collective,4:Min collective
  54. // @User: Standard
  55. AP_GROUPINFO("SV_MAN", 6, AP_MotorsHeli, _servo_mode, SERVO_CONTROL_MODE_AUTOMATED),
  56. // indices 7 and 8 were RSC parameters which were moved to RSC library. Do not use these indices in the future.
  57. // index 9 was LAND_COL_MIN. Do not use this index in the future.
  58. // indices 10-13 were RSC parameters which were moved to RSC library. Do not use these indices in the future.
  59. // index 14 was RSC_POWER_LOW. Do not use this index in the future.
  60. // index 15 was RSC_POWER_HIGH. Do not use this index in the future.
  61. // @Param: CYC_MAX
  62. // @DisplayName: Cyclic Pitch Angle Max
  63. // @Description: Maximum pitch angle of the swash plate
  64. // @Range: 0 18000
  65. // @Units: cdeg
  66. // @Increment: 100
  67. // @User: Advanced
  68. AP_GROUPINFO("CYC_MAX", 16, AP_MotorsHeli, _cyclic_max, AP_MOTORS_HELI_SWASH_CYCLIC_MAX),
  69. // @Param: SV_TEST
  70. // @DisplayName: Boot-up Servo Test Cycles
  71. // @Description: Number of cycles to run servo test on boot-up
  72. // @Range: 0 10
  73. // @Increment: 1
  74. // @User: Standard
  75. AP_GROUPINFO("SV_TEST", 17, AP_MotorsHeli, _servo_test, 0),
  76. // index 18 was RSC_POWER_NEGC. Do not use this index in the future.
  77. // index 19 was RSC_SLEWRATE and was moved to RSC library. Do not use this index in the future.
  78. // indices 20 to 24 was throttle curve. Do not use this index in the future.
  79. // @Group: RSC_
  80. // @Path: AP_MotorsHeli_RSC.cpp
  81. AP_SUBGROUPINFO(_main_rotor, "RSC_", 25, AP_MotorsHeli, AP_MotorsHeli_RSC),
  82. AP_GROUPEND
  83. };
  84. //
  85. // public methods
  86. //
  87. // init
  88. void AP_MotorsHeli::init(motor_frame_class frame_class, motor_frame_type frame_type)
  89. {
  90. // remember frame class and type
  91. _frame_type = frame_type;
  92. _frame_class = frame_class;
  93. // set update rate
  94. set_update_rate(_speed_hz);
  95. // load boot-up servo test cycles into counter to be consumed
  96. _servo_test_cycle_counter = _servo_test;
  97. // ensure inputs are not passed through to servos on start-up
  98. _servo_mode = SERVO_CONTROL_MODE_AUTOMATED;
  99. // initialise radio passthrough for collective to middle
  100. _throttle_radio_passthrough = 0.5f;
  101. // initialise Servo/PWM ranges and endpoints
  102. if (!init_outputs()) {
  103. // don't set initialised_ok
  104. return;
  105. }
  106. // calculate all scalars
  107. calculate_scalars();
  108. // record successful initialisation if what we setup was the desired frame_class
  109. _flags.initialised_ok = (frame_class == MOTOR_FRAME_HELI);
  110. // set flag to true so targets are initialized once aircraft is armed for first time
  111. _heliflags.init_targets_on_arming = true;
  112. }
  113. // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
  114. void AP_MotorsHeli::set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
  115. {
  116. _flags.initialised_ok = (frame_class == MOTOR_FRAME_HELI);
  117. }
  118. // output_min - sets servos to neutral point with motors stopped
  119. void AP_MotorsHeli::output_min()
  120. {
  121. // move swash to mid
  122. move_actuators(0.0f,0.0f,0.5f,0.0f);
  123. update_motor_control(ROTOR_CONTROL_STOP);
  124. // override limits flags
  125. limit.roll = true;
  126. limit.pitch = true;
  127. limit.yaw = true;
  128. limit.throttle_lower = true;
  129. limit.throttle_upper = false;
  130. }
  131. // output - sends commands to the servos
  132. void AP_MotorsHeli::output()
  133. {
  134. // update throttle filter
  135. update_throttle_filter();
  136. // run spool logic
  137. output_logic();
  138. if (_flags.armed) {
  139. calculate_armed_scalars();
  140. if (!_flags.interlock) {
  141. output_armed_zero_throttle();
  142. } else {
  143. output_armed_stabilizing();
  144. }
  145. } else {
  146. output_disarmed();
  147. }
  148. output_to_motors();
  149. };
  150. // sends commands to the motors
  151. void AP_MotorsHeli::output_armed_stabilizing()
  152. {
  153. // if manual override active after arming, deactivate it and reinitialize servos
  154. if (_servo_mode != SERVO_CONTROL_MODE_AUTOMATED) {
  155. reset_flight_controls();
  156. }
  157. move_actuators(_roll_in, _pitch_in, get_throttle(), _yaw_in);
  158. }
  159. // output_armed_zero_throttle - sends commands to the motors
  160. void AP_MotorsHeli::output_armed_zero_throttle()
  161. {
  162. // if manual override active after arming, deactivate it and reinitialize servos
  163. if (_servo_mode != SERVO_CONTROL_MODE_AUTOMATED) {
  164. reset_flight_controls();
  165. }
  166. move_actuators(_roll_in, _pitch_in, get_throttle(), _yaw_in);
  167. }
  168. // output_disarmed - sends commands to the motors
  169. void AP_MotorsHeli::output_disarmed()
  170. {
  171. if (_servo_test_cycle_counter > 0){
  172. // perform boot-up servo test cycle if enabled
  173. servo_test();
  174. } else {
  175. // manual override (i.e. when setting up swash)
  176. switch (_servo_mode) {
  177. case SERVO_CONTROL_MODE_MANUAL_PASSTHROUGH:
  178. // pass pilot commands straight through to swash
  179. _roll_in = _roll_radio_passthrough;
  180. _pitch_in = _pitch_radio_passthrough;
  181. _throttle_filter.reset(_throttle_radio_passthrough);
  182. _yaw_in = _yaw_radio_passthrough;
  183. break;
  184. case SERVO_CONTROL_MODE_MANUAL_CENTER:
  185. // fixate mid collective
  186. _roll_in = 0.0f;
  187. _pitch_in = 0.0f;
  188. _throttle_filter.reset(_collective_mid_pct);
  189. _yaw_in = 0.0f;
  190. break;
  191. case SERVO_CONTROL_MODE_MANUAL_MAX:
  192. // fixate max collective
  193. _roll_in = 0.0f;
  194. _pitch_in = 0.0f;
  195. _throttle_filter.reset(1.0f);
  196. if (_frame_class == MOTOR_FRAME_HELI_DUAL ||
  197. _frame_class == MOTOR_FRAME_HELI_QUAD) {
  198. _yaw_in = 0;
  199. } else {
  200. _yaw_in = 1;
  201. }
  202. break;
  203. case SERVO_CONTROL_MODE_MANUAL_MIN:
  204. // fixate min collective
  205. _roll_in = 0.0f;
  206. _pitch_in = 0.0f;
  207. _throttle_filter.reset(0.0f);
  208. if (_frame_class == MOTOR_FRAME_HELI_DUAL ||
  209. _frame_class == MOTOR_FRAME_HELI_QUAD) {
  210. _yaw_in = 0;
  211. } else {
  212. _yaw_in = -1;
  213. }
  214. break;
  215. case SERVO_CONTROL_MODE_MANUAL_OSCILLATE:
  216. // use servo_test function from child classes
  217. servo_test();
  218. break;
  219. default:
  220. // no manual override
  221. break;
  222. }
  223. }
  224. // ensure swash servo endpoints haven't been moved
  225. init_outputs();
  226. // continuously recalculate scalars to allow setup
  227. calculate_scalars();
  228. // helicopters always run stabilizing flight controls
  229. move_actuators(_roll_in, _pitch_in, get_throttle(), _yaw_in);
  230. }
  231. // run spool logic
  232. void AP_MotorsHeli::output_logic()
  233. {
  234. // force desired and current spool mode if disarmed and armed with interlock enabled
  235. if (_flags.armed) {
  236. if (!_flags.interlock) {
  237. _spool_desired = DesiredSpoolState::GROUND_IDLE;
  238. } else {
  239. _heliflags.init_targets_on_arming = false;
  240. }
  241. } else {
  242. _heliflags.init_targets_on_arming = true;
  243. _spool_desired = DesiredSpoolState::SHUT_DOWN;
  244. _spool_state = SpoolState::SHUT_DOWN;
  245. }
  246. switch (_spool_state) {
  247. case SpoolState::SHUT_DOWN:
  248. // Motors should be stationary.
  249. // Servos set to their trim values or in a test condition.
  250. // make sure the motors are spooling in the correct direction
  251. if (_spool_desired != DesiredSpoolState::SHUT_DOWN) {
  252. _spool_state = SpoolState::GROUND_IDLE;
  253. break;
  254. }
  255. break;
  256. case SpoolState::GROUND_IDLE: {
  257. // Motors should be stationary or at ground idle.
  258. // Servos should be moving to correct the current attitude.
  259. if (_spool_desired == DesiredSpoolState::SHUT_DOWN){
  260. _spool_state = SpoolState::SHUT_DOWN;
  261. } else if(_spool_desired == DesiredSpoolState::THROTTLE_UNLIMITED) {
  262. _spool_state = SpoolState::SPOOLING_UP;
  263. } else { // _spool_desired == GROUND_IDLE
  264. }
  265. break;
  266. }
  267. case SpoolState::SPOOLING_UP:
  268. // Maximum throttle should move from minimum to maximum.
  269. // Servos should exhibit normal flight behavior.
  270. // make sure the motors are spooling in the correct direction
  271. if (_spool_desired != DesiredSpoolState::THROTTLE_UNLIMITED ){
  272. _spool_state = SpoolState::SPOOLING_DOWN;
  273. break;
  274. }
  275. if (_heliflags.rotor_runup_complete){
  276. _spool_state = SpoolState::THROTTLE_UNLIMITED;
  277. }
  278. break;
  279. case SpoolState::THROTTLE_UNLIMITED:
  280. // Throttle should exhibit normal flight behavior.
  281. // Servos should exhibit normal flight behavior.
  282. // make sure the motors are spooling in the correct direction
  283. if (_spool_desired != DesiredSpoolState::THROTTLE_UNLIMITED) {
  284. _spool_state = SpoolState::SPOOLING_DOWN;
  285. break;
  286. }
  287. break;
  288. case SpoolState::SPOOLING_DOWN:
  289. // Maximum throttle should move from maximum to minimum.
  290. // Servos should exhibit normal flight behavior.
  291. // make sure the motors are spooling in the correct direction
  292. if (_spool_desired == DesiredSpoolState::THROTTLE_UNLIMITED) {
  293. _spool_state = SpoolState::SPOOLING_UP;
  294. break;
  295. }
  296. if (!rotor_speed_above_critical()){
  297. _spool_state = SpoolState::GROUND_IDLE;
  298. }
  299. break;
  300. }
  301. }
  302. // parameter_check - check if helicopter specific parameters are sensible
  303. bool AP_MotorsHeli::parameter_check(bool display_msg) const
  304. {
  305. // returns false if RSC Mode is not set to a valid control mode
  306. if (_main_rotor._rsc_mode.get() <= (int8_t)ROTOR_CONTROL_MODE_DISABLED || _main_rotor._rsc_mode.get() > (int8_t)ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT) {
  307. if (display_msg) {
  308. gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_MODE invalid");
  309. }
  310. return false;
  311. }
  312. // returns false if rsc_setpoint is out of range
  313. if ( _main_rotor._rsc_setpoint.get() > 100 || _main_rotor._rsc_setpoint.get() < 10){
  314. if (display_msg) {
  315. gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_SETPOINT out of range");
  316. }
  317. return false;
  318. }
  319. // returns false if idle output is out of range
  320. if ( _main_rotor._idle_output.get() > 100 || _main_rotor._idle_output.get() < 0){
  321. if (display_msg) {
  322. gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_IDLE out of range");
  323. }
  324. return false;
  325. }
  326. // returns false if _rsc_critical is not between 0 and 100
  327. if (_main_rotor._critical_speed.get() > 100 || _main_rotor._critical_speed.get() < 0) {
  328. if (display_msg) {
  329. gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_CRITICAL out of range");
  330. }
  331. return false;
  332. }
  333. // returns false if RSC Runup Time is less than Ramp time as this could cause undesired behaviour of rotor speed estimate
  334. if (_main_rotor._runup_time.get() <= _main_rotor._ramp_time.get()){
  335. if (display_msg) {
  336. gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RUNUP_TIME too small");
  337. }
  338. return false;
  339. }
  340. // all other cases parameters are OK
  341. return true;
  342. }
  343. // reset_swash_servo
  344. void AP_MotorsHeli::reset_swash_servo(SRV_Channel::Aux_servo_function_t function)
  345. {
  346. // outputs are defined on a -500 to 500 range for swash servos
  347. SRV_Channels::set_range(function, 1000);
  348. // swash servos always use full endpoints as restricting them would lead to scaling errors
  349. SRV_Channels::set_output_min_max(function, 1000, 2000);
  350. }
  351. // update the throttle input filter
  352. void AP_MotorsHeli::update_throttle_filter()
  353. {
  354. _throttle_filter.apply(_throttle_in, 1.0f/_loop_rate);
  355. // constrain filtered throttle
  356. if (_throttle_filter.get() < 0.0f) {
  357. _throttle_filter.reset(0.0f);
  358. }
  359. if (_throttle_filter.get() > 1.0f) {
  360. _throttle_filter.reset(1.0f);
  361. }
  362. }
  363. // reset_flight_controls - resets all controls and scalars to flight status
  364. void AP_MotorsHeli::reset_flight_controls()
  365. {
  366. _servo_mode = SERVO_CONTROL_MODE_AUTOMATED;
  367. init_outputs();
  368. calculate_scalars();
  369. }
  370. // convert input in -1 to +1 range to pwm output for swashplate servo.
  371. // The value 0 corresponds to the trim value of the servo. Swashplate
  372. // servo travel range is fixed to 1000 pwm and therefore the input is
  373. // multiplied by 500 to get PWM output.
  374. void AP_MotorsHeli::rc_write_swash(uint8_t chan, float swash_in)
  375. {
  376. uint16_t pwm = (uint16_t)(1500 + 500 * swash_in);
  377. SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(chan);
  378. SRV_Channels::set_output_pwm_trimmed(function, pwm);
  379. }