AP_MotorsHeli_Dual.cpp 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596
  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. *
  7. * This program is distributed in the hope that it will be useful,
  8. * but WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  10. * GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License
  13. * along with this program. If not, see <http://www.gnu.org/licenses/>.
  14. */
  15. #include <stdlib.h>
  16. #include <AP_HAL/AP_HAL.h>
  17. #include "AP_MotorsHeli_Dual.h"
  18. #include <GCS_MAVLink/GCS.h>
  19. extern const AP_HAL::HAL& hal;
  20. const AP_Param::GroupInfo AP_MotorsHeli_Dual::var_info[] = {
  21. AP_NESTEDGROUPINFO(AP_MotorsHeli, 0),
  22. // Indices 1-6 were used by servo position params and should not be used
  23. // Indices 7-8 were used by phase angle params and should not be used
  24. // @Param: DUAL_MODE
  25. // @DisplayName: Dual Mode
  26. // @Description: Sets the dual mode of the heli, either as tandem or as transverse.
  27. // @Values: 0:Longitudinal, 1:Transverse
  28. // @User: Standard
  29. AP_GROUPINFO("DUAL_MODE", 9, AP_MotorsHeli_Dual, _dual_mode, AP_MOTORS_HELI_DUAL_MODE_TANDEM),
  30. // @Param: DCP_SCALER
  31. // @DisplayName: Differential-Collective-Pitch Scaler
  32. // @Description: Scaling factor applied to the differential-collective-pitch
  33. // @Range: 0 1
  34. // @User: Standard
  35. AP_GROUPINFO("DCP_SCALER", 10, AP_MotorsHeli_Dual, _dcp_scaler, AP_MOTORS_HELI_DUAL_DCP_SCALER),
  36. // @Param: DCP_YAW
  37. // @DisplayName: Differential-Collective-Pitch Yaw Mixing
  38. // @Description: Feed-forward compensation to automatically add yaw input when differential collective pitch is applied.
  39. // @Range: -10 10
  40. // @Increment: 0.1
  41. AP_GROUPINFO("DCP_YAW", 11, AP_MotorsHeli_Dual, _dcp_yaw_effect, 0),
  42. // @Param: YAW_SCALER
  43. // @DisplayName: Scaler for yaw mixing
  44. // @Description: Scaler for mixing yaw into roll or pitch.
  45. // @Range: -10 10
  46. // @Increment: 0.1
  47. AP_GROUPINFO("YAW_SCALER", 12, AP_MotorsHeli_Dual, _yaw_scaler, 1.0f),
  48. // Indices 13-15 were used by RSC_PWM_MIN, RSC_PWM_MAX and RSC_PWM_REV and should not be used
  49. // @Param: COL2_MIN
  50. // @DisplayName: Collective Pitch Minimum for rear swashplate
  51. // @Description: Lowest possible servo position in PWM microseconds for the rear swashplate
  52. // @Range: 1000 2000
  53. // @Units: PWM
  54. // @Increment: 1
  55. // @User: Standard
  56. AP_GROUPINFO("COL2_MIN", 16, AP_MotorsHeli_Dual, _collective2_min, AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN),
  57. // @Param: COL2_MAX
  58. // @DisplayName: Collective Pitch Maximum for rear swashplate
  59. // @Description: Highest possible servo position in PWM microseconds for the rear swashplate
  60. // @Range: 1000 2000
  61. // @Units: PWM
  62. // @Increment: 1
  63. // @User: Standard
  64. AP_GROUPINFO("COL2_MAX", 17, AP_MotorsHeli_Dual, _collective2_max, AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX),
  65. // @Param: COL2_MID
  66. // @DisplayName: Collective Pitch Mid-Point for rear swashplate
  67. // @Description: Swash servo position in PWM microseconds corresponding to zero collective pitch for the rear swashplate (or zero lift for Asymmetrical blades)
  68. // @Range: 1000 2000
  69. // @Units: PWM
  70. // @Increment: 1
  71. // @User: Standard
  72. AP_GROUPINFO("COL2_MID", 18, AP_MotorsHeli_Dual, _collective2_mid, AP_MOTORS_HELI_DUAL_COLLECTIVE2_MID),
  73. // Indice 19 was used by COL_CTRL_DIR and should not be used
  74. // @Group: SW1_H3_
  75. // @Path: AP_MotorsHeli_Swash.cpp
  76. AP_SUBGROUPINFO(_swashplate1, "SW1_", 20, AP_MotorsHeli_Dual, AP_MotorsHeli_Swash),
  77. // @Group: SW2_H3_
  78. // @Path: AP_MotorsHeli_Swash.cpp
  79. AP_SUBGROUPINFO(_swashplate2, "SW2_", 21, AP_MotorsHeli_Dual, AP_MotorsHeli_Swash),
  80. AP_GROUPEND
  81. };
  82. // set update rate to motors - a value in hertz
  83. void AP_MotorsHeli_Dual::set_update_rate( uint16_t speed_hz )
  84. {
  85. // record requested speed
  86. _speed_hz = speed_hz;
  87. // setup fast channels
  88. uint16_t mask = 0;
  89. for (uint8_t i=0; i<AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS; i++) {
  90. mask |= 1U << (AP_MOTORS_MOT_1+i);
  91. }
  92. if (_swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  93. mask |= 1U << (AP_MOTORS_MOT_7);
  94. }
  95. if (_swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  96. mask |= 1U << (AP_MOTORS_MOT_8);
  97. }
  98. rc_set_freq(mask, _speed_hz);
  99. }
  100. // init_outputs
  101. bool AP_MotorsHeli_Dual::init_outputs()
  102. {
  103. if (!_flags.initialised_ok) {
  104. // make sure 6 output channels are mapped
  105. for (uint8_t i=0; i<AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS; i++) {
  106. add_motor_num(CH_1+i);
  107. }
  108. if (_swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  109. add_motor_num(CH_7);
  110. }
  111. if (_swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  112. add_motor_num(CH_8);
  113. }
  114. // set rotor servo range
  115. _main_rotor.init_servo();
  116. }
  117. // reset swash servo range and endpoints
  118. for (uint8_t i=0; i<AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS; i++) {
  119. reset_swash_servo(SRV_Channels::get_motor_function(i));
  120. }
  121. if (_swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  122. reset_swash_servo(SRV_Channels::get_motor_function(6));
  123. }
  124. if (_swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  125. reset_swash_servo(SRV_Channels::get_motor_function(7));
  126. }
  127. _flags.initialised_ok = true;
  128. return true;
  129. }
  130. // output_test_seq - spin a motor at the pwm value specified
  131. // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
  132. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  133. void AP_MotorsHeli_Dual::output_test_seq(uint8_t motor_seq, int16_t pwm)
  134. {
  135. // exit immediately if not armed
  136. if (!armed()) {
  137. return;
  138. }
  139. // output to motors and servos
  140. switch (motor_seq) {
  141. case 1:
  142. // swash servo 1
  143. rc_write(AP_MOTORS_MOT_1, pwm);
  144. break;
  145. case 2:
  146. // swash servo 2
  147. rc_write(AP_MOTORS_MOT_2, pwm);
  148. break;
  149. case 3:
  150. // swash servo 3
  151. rc_write(AP_MOTORS_MOT_3, pwm);
  152. break;
  153. case 4:
  154. // swash servo 4
  155. rc_write(AP_MOTORS_MOT_4, pwm);
  156. break;
  157. case 5:
  158. // swash servo 5
  159. rc_write(AP_MOTORS_MOT_5, pwm);
  160. break;
  161. case 6:
  162. // swash servo 6
  163. rc_write(AP_MOTORS_MOT_6, pwm);
  164. break;
  165. case 7:
  166. // main rotor
  167. rc_write(AP_MOTORS_HELI_RSC, pwm);
  168. break;
  169. default:
  170. // do nothing
  171. break;
  172. }
  173. }
  174. // set_desired_rotor_speed
  175. void AP_MotorsHeli_Dual::set_desired_rotor_speed(float desired_speed)
  176. {
  177. _main_rotor.set_desired_speed(desired_speed);
  178. }
  179. // set_rotor_rpm - used for governor with speed sensor
  180. void AP_MotorsHeli_Dual::set_rpm(float rotor_rpm)
  181. {
  182. _main_rotor.set_rotor_rpm(rotor_rpm);
  183. }
  184. // calculate_armed_scalars
  185. void AP_MotorsHeli_Dual::calculate_armed_scalars()
  186. {
  187. // Set rsc mode specific parameters
  188. if (_main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_OPEN_LOOP_POWER_OUTPUT || _main_rotor._rsc_mode.get() == ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT) {
  189. _main_rotor.set_throttle_curve();
  190. }
  191. // keeps user from changing RSC mode while armed
  192. if (_main_rotor._rsc_mode.get() != _main_rotor.get_control_mode()) {
  193. _main_rotor.reset_rsc_mode_param();
  194. _heliflags.save_rsc_mode = true;
  195. gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed");
  196. }
  197. // saves rsc mode parameter when disarmed if it had been reset while armed
  198. if (_heliflags.save_rsc_mode && !_flags.armed) {
  199. _main_rotor._rsc_mode.save();
  200. _heliflags.save_rsc_mode = false;
  201. }
  202. }
  203. // calculate_scalars
  204. void AP_MotorsHeli_Dual::calculate_scalars()
  205. {
  206. // range check collective min, max and mid
  207. if( _collective_min >= _collective_max ) {
  208. _collective_min = AP_MOTORS_HELI_COLLECTIVE_MIN;
  209. _collective_max = AP_MOTORS_HELI_COLLECTIVE_MAX;
  210. }
  211. // range check collective min, max and mid for rear swashplate
  212. if( _collective2_min >= _collective2_max ) {
  213. _collective2_min = AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN;
  214. _collective2_max = AP_MOTORS_HELI_DUAL_COLLECTIVE2_MAX;
  215. }
  216. _collective_mid = constrain_int16(_collective_mid, _collective_min, _collective_max);
  217. _collective2_mid = constrain_int16(_collective2_mid, _collective2_min, _collective2_max);
  218. // calculate collective mid point as a number from 0 to 1000
  219. _collective_mid_pct = ((float)(_collective_mid-_collective_min))/((float)(_collective_max-_collective_min));
  220. _collective2_mid_pct = ((float)(_collective2_mid-_collective2_min))/((float)(_collective2_max-_collective2_min));
  221. // configure swashplate 1 and update scalars
  222. _swashplate1.configure();
  223. _swashplate1.calculate_roll_pitch_collective_factors();
  224. // configure swashplate 2 and update scalars
  225. _swashplate2.configure();
  226. _swashplate2.calculate_roll_pitch_collective_factors();
  227. // set mode of main rotor controller and trigger recalculation of scalars
  228. _main_rotor.set_control_mode(static_cast<RotorControlMode>(_main_rotor._rsc_mode.get()));
  229. calculate_armed_scalars();
  230. }
  231. // get_swashplate - calculate movement of each swashplate based on configuration
  232. float AP_MotorsHeli_Dual::get_swashplate (int8_t swash_num, int8_t swash_axis, float pitch_input, float roll_input, float yaw_input, float coll_input)
  233. {
  234. float swash_tilt = 0.0f;
  235. if (_dual_mode == AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE) {
  236. // roll tilt
  237. if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL) {
  238. if (swash_num == 1) {
  239. swash_tilt = 0.0f;
  240. } else if (swash_num == 2) {
  241. swash_tilt = 0.0f;
  242. }
  243. } else if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH) {
  244. // pitch tilt
  245. if (swash_num == 1) {
  246. swash_tilt = pitch_input - _yaw_scaler * yaw_input;
  247. } else if (swash_num == 2) {
  248. swash_tilt = pitch_input + _yaw_scaler * yaw_input;
  249. }
  250. } else if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL) {
  251. // collective
  252. if (swash_num == 1) {
  253. swash_tilt = 0.45f * _dcp_scaler * roll_input + coll_input;
  254. } else if (swash_num == 2) {
  255. swash_tilt = -0.45f * _dcp_scaler * roll_input + coll_input;
  256. }
  257. }
  258. } else { // AP_MOTORS_HELI_DUAL_MODE_TANDEM
  259. // roll tilt
  260. if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL) {
  261. if (swash_num == 1) {
  262. swash_tilt = roll_input + _yaw_scaler * yaw_input;
  263. } else if (swash_num == 2) {
  264. swash_tilt = roll_input - _yaw_scaler * yaw_input;
  265. }
  266. } else if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH) {
  267. // pitch tilt
  268. if (swash_num == 1) {
  269. swash_tilt = 0.0f;
  270. } else if (swash_num == 2) {
  271. swash_tilt = 0.0f;
  272. }
  273. } else if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL) {
  274. // collective
  275. if (swash_num == 1) {
  276. swash_tilt = 0.45f * _dcp_scaler * pitch_input + coll_input;
  277. } else if (swash_num == 2) {
  278. swash_tilt = -0.45f * _dcp_scaler * pitch_input + coll_input;
  279. }
  280. }
  281. }
  282. return swash_tilt;
  283. }
  284. // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
  285. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  286. uint16_t AP_MotorsHeli_Dual::get_motor_mask()
  287. {
  288. // dual heli uses channels 1,2,3,4,5,6 and 8
  289. uint16_t mask = 0;
  290. for (uint8_t i=0; i<AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS; i++) {
  291. mask |= 1U << (AP_MOTORS_MOT_1+i);
  292. }
  293. if (_swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  294. mask |= 1U << AP_MOTORS_MOT_7;
  295. }
  296. if (_swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  297. mask |= 1U << AP_MOTORS_MOT_8;
  298. }
  299. mask |= 1U << AP_MOTORS_HELI_RSC;
  300. return mask;
  301. }
  302. // update_motor_controls - sends commands to motor controllers
  303. void AP_MotorsHeli_Dual::update_motor_control(RotorControlState state)
  304. {
  305. // Send state update to motors
  306. _main_rotor.output(state);
  307. if (state == ROTOR_CONTROL_STOP) {
  308. // set engine run enable aux output to not run position to kill engine when disarmed
  309. SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
  310. } else {
  311. // else if armed, set engine run enable output to run position
  312. SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MAX);
  313. }
  314. // Check if rotors are run-up
  315. _heliflags.rotor_runup_complete = _main_rotor.is_runup_complete();
  316. }
  317. //
  318. // move_actuators - moves swash plate to attitude of parameters passed in
  319. // - expected ranges:
  320. // roll : -1 ~ +1
  321. // pitch: -1 ~ +1
  322. // collective: 0 ~ 1
  323. // yaw: -1 ~ +1
  324. //
  325. void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float collective_in, float yaw_out)
  326. {
  327. // initialize limits flag
  328. limit.roll = false;
  329. limit.pitch = false;
  330. limit.yaw = false;
  331. limit.throttle_lower = false;
  332. limit.throttle_upper = false;
  333. if (_dual_mode == AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE) {
  334. if (pitch_out < -_cyclic_max/4500.0f) {
  335. pitch_out = -_cyclic_max/4500.0f;
  336. limit.pitch = true;
  337. }
  338. if (pitch_out > _cyclic_max/4500.0f) {
  339. pitch_out = _cyclic_max/4500.0f;
  340. limit.pitch = true;
  341. }
  342. } else {
  343. if (roll_out < -_cyclic_max/4500.0f) {
  344. roll_out = -_cyclic_max/4500.0f;
  345. limit.roll = true;
  346. }
  347. if (roll_out > _cyclic_max/4500.0f) {
  348. roll_out = _cyclic_max/4500.0f;
  349. limit.roll = true;
  350. }
  351. }
  352. if (_heliflags.inverted_flight) {
  353. collective_in = 1 - collective_in;
  354. }
  355. float yaw_compensation = 0.0f;
  356. // if servo output not in manual mode, process pre-compensation factors
  357. if (_servo_mode == SERVO_CONTROL_MODE_AUTOMATED) {
  358. // add differential collective pitch yaw compensation
  359. if (_dual_mode == AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE) {
  360. yaw_compensation = _dcp_yaw_effect * roll_out;
  361. } else { // AP_MOTORS_HELI_DUAL_MODE_TANDEM
  362. yaw_compensation = _dcp_yaw_effect * pitch_out;
  363. }
  364. yaw_out = yaw_out + yaw_compensation;
  365. }
  366. // scale yaw and update limits
  367. if (yaw_out < -_cyclic_max/4500.0f) {
  368. yaw_out = -_cyclic_max/4500.0f;
  369. limit.yaw = true;
  370. }
  371. if (yaw_out > _cyclic_max/4500.0f) {
  372. yaw_out = _cyclic_max/4500.0f;
  373. limit.yaw = true;
  374. }
  375. // constrain collective input
  376. float collective_out = collective_in;
  377. if (collective_out <= 0.0f) {
  378. collective_out = 0.0f;
  379. limit.throttle_lower = true;
  380. }
  381. if (collective_out >= 1.0f) {
  382. collective_out = 1.0f;
  383. limit.throttle_upper = true;
  384. }
  385. // ensure not below landed/landing collective
  386. if (_heliflags.landing_collective && collective_out < _collective_mid_pct) {
  387. collective_out = _collective_mid_pct;
  388. limit.throttle_lower = true;
  389. }
  390. // Set rear collective to midpoint if required
  391. float collective2_out = collective_out;
  392. if (_servo_mode == SERVO_CONTROL_MODE_MANUAL_CENTER) {
  393. collective2_out = _collective2_mid_pct;
  394. }
  395. // scale collective pitch for front swashplate (servos 1,2,3)
  396. float collective_scaler = ((float)(_collective_max-_collective_min))*0.001f;
  397. float collective_out_scaled = collective_out * collective_scaler + (_collective_min - 1000)*0.001f;
  398. // scale collective pitch for rear swashplate (servos 4,5,6)
  399. float collective2_scaler = ((float)(_collective2_max-_collective2_min))*0.001f;
  400. float collective2_out_scaled = collective2_out * collective2_scaler + (_collective2_min - 1000)*0.001f;
  401. // feed power estimate into main rotor controller
  402. // ToDo: add main rotor cyclic power?
  403. _main_rotor.set_collective(fabsf(collective_out));
  404. // compute swashplate tilt
  405. float swash1_pitch = get_swashplate(1, AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH, pitch_out, roll_out, yaw_out, collective_out_scaled);
  406. float swash1_roll = get_swashplate(1, AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL, pitch_out, roll_out, yaw_out, collective_out_scaled);
  407. float swash1_coll = get_swashplate(1, AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL, pitch_out, roll_out, yaw_out, collective_out_scaled);
  408. float swash2_pitch = get_swashplate(2, AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH, pitch_out, roll_out, yaw_out, collective2_out_scaled);
  409. float swash2_roll = get_swashplate(2, AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL, pitch_out, roll_out, yaw_out, collective2_out_scaled);
  410. float swash2_coll = get_swashplate(2, AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL, pitch_out, roll_out, yaw_out, collective2_out_scaled);
  411. // get servo positions from swashplate library
  412. _servo_out[CH_1] = _swashplate1.get_servo_out(CH_1,swash1_pitch,swash1_roll,swash1_coll);
  413. _servo_out[CH_2] = _swashplate1.get_servo_out(CH_2,swash1_pitch,swash1_roll,swash1_coll);
  414. _servo_out[CH_3] = _swashplate1.get_servo_out(CH_3,swash1_pitch,swash1_roll,swash1_coll);
  415. if (_swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  416. _servo_out[CH_7] = _swashplate1.get_servo_out(CH_4,swash1_pitch,swash1_roll,swash1_coll);
  417. }
  418. // get servo positions from swashplate library
  419. _servo_out[CH_4] = _swashplate2.get_servo_out(CH_1,swash2_pitch,swash2_roll,swash2_coll);
  420. _servo_out[CH_5] = _swashplate2.get_servo_out(CH_2,swash2_pitch,swash2_roll,swash2_coll);
  421. _servo_out[CH_6] = _swashplate2.get_servo_out(CH_3,swash2_pitch,swash2_roll,swash2_coll);
  422. if (_swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  423. _servo_out[CH_8] = _swashplate2.get_servo_out(CH_4,swash2_pitch,swash2_roll,swash2_coll);
  424. }
  425. }
  426. void AP_MotorsHeli_Dual::output_to_motors()
  427. {
  428. if (!_flags.initialised_ok) {
  429. return;
  430. }
  431. // actually move the servos. PWM is sent based on nominal 1500 center. servo output shifts center based on trim value.
  432. for (uint8_t i=0; i<AP_MOTORS_HELI_DUAL_NUM_SWASHPLATE_SERVOS; i++) {
  433. rc_write_swash(i, _servo_out[CH_1+i]);
  434. }
  435. // write to servo for 4 servo of 4 servo swashplate
  436. if (_swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate1.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  437. rc_write_swash(AP_MOTORS_MOT_7, _servo_out[CH_7]);
  438. }
  439. // write to servo for 4 servo of 4 servo swashplate
  440. if (_swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate2.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  441. rc_write_swash(AP_MOTORS_MOT_8, _servo_out[CH_8]);
  442. }
  443. switch (_spool_state) {
  444. case SpoolState::SHUT_DOWN:
  445. // sends minimum values out to the motors
  446. update_motor_control(ROTOR_CONTROL_STOP);
  447. break;
  448. case SpoolState::GROUND_IDLE:
  449. // sends idle output to motors when armed. rotor could be static or turning (autorotation)
  450. update_motor_control(ROTOR_CONTROL_IDLE);
  451. break;
  452. case SpoolState::SPOOLING_UP:
  453. case SpoolState::THROTTLE_UNLIMITED:
  454. // set motor output based on thrust requests
  455. update_motor_control(ROTOR_CONTROL_ACTIVE);
  456. break;
  457. case SpoolState::SPOOLING_DOWN:
  458. // sends idle output to motors and wait for rotor to stop
  459. update_motor_control(ROTOR_CONTROL_IDLE);
  460. break;
  461. }
  462. }
  463. // servo_test - move servos through full range of movement
  464. void AP_MotorsHeli_Dual::servo_test()
  465. {
  466. // this test cycle is equivalent to that of AP_MotorsHeli_Single, but excluding
  467. // mixing of yaw, as that physical movement is represented by pitch and roll
  468. _servo_test_cycle_time += 1.0f / _loop_rate;
  469. if ((_servo_test_cycle_time >= 0.0f && _servo_test_cycle_time < 0.5f)|| // Tilt swash back
  470. (_servo_test_cycle_time >= 6.0f && _servo_test_cycle_time < 6.5f)){
  471. _pitch_test += (1.0f / (_loop_rate/2));
  472. _oscillate_angle += 8 * M_PI / _loop_rate;
  473. } else if ((_servo_test_cycle_time >= 0.5f && _servo_test_cycle_time < 4.5f)|| // Roll swash around
  474. (_servo_test_cycle_time >= 6.5f && _servo_test_cycle_time < 10.5f)){
  475. _oscillate_angle += M_PI / (2 * _loop_rate);
  476. _roll_test = sinf(_oscillate_angle);
  477. _pitch_test = cosf(_oscillate_angle);
  478. } else if ((_servo_test_cycle_time >= 4.5f && _servo_test_cycle_time < 5.0f)|| // Return swash to level
  479. (_servo_test_cycle_time >= 10.5f && _servo_test_cycle_time < 11.0f)){
  480. _pitch_test -= (1.0f / (_loop_rate/2));
  481. _oscillate_angle += 8 * M_PI / _loop_rate;
  482. } else if (_servo_test_cycle_time >= 5.0f && _servo_test_cycle_time < 6.0f){ // Raise swash to top
  483. _collective_test += (1.0f / _loop_rate);
  484. _oscillate_angle += 2 * M_PI / _loop_rate;
  485. } else if (_servo_test_cycle_time >= 11.0f && _servo_test_cycle_time < 12.0f){ // Lower swash to bottom
  486. _collective_test -= (1.0f / _loop_rate);
  487. _oscillate_angle += 2 * M_PI / _loop_rate;
  488. } else { // reset cycle
  489. _servo_test_cycle_time = 0.0f;
  490. _oscillate_angle = 0.0f;
  491. _collective_test = 0.0f;
  492. _roll_test = 0.0f;
  493. _pitch_test = 0.0f;
  494. // decrement servo test cycle counter at the end of the cycle
  495. if (_servo_test_cycle_counter > 0){
  496. _servo_test_cycle_counter--;
  497. }
  498. }
  499. // over-ride servo commands to move servos through defined ranges
  500. _throttle_filter.reset(constrain_float(_collective_test, 0.0f, 1.0f));
  501. _roll_in = constrain_float(_roll_test, -1.0f, 1.0f);
  502. _pitch_in = constrain_float(_pitch_test, -1.0f, 1.0f);
  503. }
  504. // parameter_check - check if helicopter specific parameters are sensible
  505. bool AP_MotorsHeli_Dual::parameter_check(bool display_msg) const
  506. {
  507. // returns false if Phase Angle is outside of range for H3 swashplate 1
  508. if (_swashplate1.get_swash_type() == SWASHPLATE_TYPE_H3 && (_swashplate1.get_phase_angle() > 30 || _swashplate1.get_phase_angle() < -30)){
  509. if (display_msg) {
  510. gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_SW1_H3_PHANG out of range");
  511. }
  512. return false;
  513. }
  514. // returns false if Phase Angle is outside of range for H3 swashplate 2
  515. if (_swashplate2.get_swash_type() == SWASHPLATE_TYPE_H3 && (_swashplate2.get_phase_angle() > 30 || _swashplate2.get_phase_angle() < -30)){
  516. if (display_msg) {
  517. gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_SW2_H3_PHANG out of range");
  518. }
  519. return false;
  520. }
  521. // check parent class parameters
  522. return AP_MotorsHeli::parameter_check(display_msg);
  523. }