AP_MotorsHeli_Single.cpp 23 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572
  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 <SRV_Channel/SRV_Channel.h>
  18. #include "AP_MotorsHeli_Single.h"
  19. #include <GCS_MAVLink/GCS.h>
  20. extern const AP_HAL::HAL& hal;
  21. const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
  22. AP_NESTEDGROUPINFO(AP_MotorsHeli, 0),
  23. // Indices 1-3 were used by servo position params and should not be used
  24. // @Param: TAIL_TYPE
  25. // @DisplayName: Tail Type
  26. // @Description: Tail type selection. Simpler yaw controller used if external gyro is selected
  27. // @Values: 0:Servo only,1:Servo with ExtGyro,2:DirectDrive VarPitch,3:DirectDrive FixedPitch
  28. // @User: Standard
  29. AP_GROUPINFO("TAIL_TYPE", 4, AP_MotorsHeli_Single, _tail_type, AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO),
  30. // Indice 5 was used by SWASH_TYPE and should not be used
  31. // @Param: GYR_GAIN
  32. // @DisplayName: External Gyro Gain
  33. // @Description: PWM in microseconds sent to external gyro on ch7 when tail type is Servo w/ ExtGyro
  34. // @Range: 0 1000
  35. // @Units: PWM
  36. // @Increment: 1
  37. // @User: Standard
  38. AP_GROUPINFO("GYR_GAIN", 6, AP_MotorsHeli_Single, _ext_gyro_gain_std, AP_MOTORS_HELI_SINGLE_EXT_GYRO_GAIN),
  39. // Index 7 was used for phase angle and should not be used
  40. // @Param: COLYAW
  41. // @DisplayName: Collective-Yaw Mixing
  42. // @Description: Feed-forward compensation to automatically add rudder input when collective pitch is increased. Can be positive or negative depending on mechanics.
  43. // @Range: -10 10
  44. // @Increment: 0.1
  45. // @User: Advanced
  46. AP_GROUPINFO("COLYAW", 8, AP_MotorsHeli_Single, _collective_yaw_effect, 0),
  47. // @Param: FLYBAR_MODE
  48. // @DisplayName: Flybar Mode Selector
  49. // @Description: Flybar present or not. Affects attitude controller used during ACRO flight mode
  50. // @Values: 0:NoFlybar,1:Flybar
  51. // @User: Standard
  52. AP_GROUPINFO("FLYBAR_MODE", 9, AP_MotorsHeli_Single, _flybar_mode, AP_MOTORS_HELI_NOFLYBAR),
  53. // @Param: TAIL_SPEED
  54. // @DisplayName: Direct Drive VarPitch Tail ESC speed
  55. // @Description: Direct Drive VarPitch Tail ESC speed in PWM microseconds. Only used when TailType is DirectDrive VarPitch
  56. // @Range: 0 1000
  57. // @Units: PWM
  58. // @Increment: 1
  59. // @User: Standard
  60. AP_GROUPINFO("TAIL_SPEED", 10, AP_MotorsHeli_Single, _direct_drive_tailspeed, AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT),
  61. // @Param: GYR_GAIN_ACRO
  62. // @DisplayName: External Gyro Gain for ACRO
  63. // @Description: PWM in microseconds sent to external gyro on ch7 when tail type is Servo w/ ExtGyro. A value of zero means to use H_GYR_GAIN
  64. // @Range: 0 1000
  65. // @Units: PWM
  66. // @Increment: 1
  67. // @User: Standard
  68. AP_GROUPINFO("GYR_GAIN_ACRO", 11, AP_MotorsHeli_Single, _ext_gyro_gain_acro, 0),
  69. // Indices 16-19 were used by RSC_PWM_MIN, RSC_PWM_MAX, RSC_PWM_REV, and COL_CTRL_DIR and should not be used
  70. // @Group: H3_SW_
  71. // @Path: AP_MotorsHeli_Swash.cpp
  72. AP_SUBGROUPINFO(_swashplate, "SW_", 20, AP_MotorsHeli_Single, AP_MotorsHeli_Swash),
  73. AP_GROUPEND
  74. };
  75. #define YAW_SERVO_MAX_ANGLE 4500
  76. // set update rate to motors - a value in hertz
  77. void AP_MotorsHeli_Single::set_update_rate( uint16_t speed_hz )
  78. {
  79. // record requested speed
  80. _speed_hz = speed_hz;
  81. // setup fast channels
  82. uint32_t mask =
  83. 1U << AP_MOTORS_MOT_1 |
  84. 1U << AP_MOTORS_MOT_2 |
  85. 1U << AP_MOTORS_MOT_3 |
  86. 1U << AP_MOTORS_MOT_4;
  87. if (_swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  88. mask |= 1U << (AP_MOTORS_MOT_5);
  89. }
  90. rc_set_freq(mask, _speed_hz);
  91. }
  92. // init_outputs - initialise Servo/PWM ranges and endpoints
  93. bool AP_MotorsHeli_Single::init_outputs()
  94. {
  95. if (!_flags.initialised_ok) {
  96. // map primary swash servos
  97. for (uint8_t i=0; i<AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS; i++) {
  98. add_motor_num(CH_1+i);
  99. }
  100. if (_swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  101. add_motor_num(CH_5);
  102. }
  103. // yaw servo
  104. add_motor_num(CH_4);
  105. // initialize main rotor servo
  106. _main_rotor.init_servo();
  107. if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH) {
  108. _tail_rotor.init_servo();
  109. } else if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
  110. // external gyro output
  111. add_motor_num(AP_MOTORS_HELI_SINGLE_EXTGYRO);
  112. }
  113. }
  114. if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
  115. // External Gyro uses PWM output thus servo endpoints are forced
  116. SRV_Channels::set_output_min_max(SRV_Channels::get_motor_function(AP_MOTORS_HELI_SINGLE_EXTGYRO), 1000, 2000);
  117. }
  118. // reset swash servo range and endpoints
  119. for (uint8_t i=0; i<AP_MOTORS_HELI_SINGLE_NUM_SWASHPLATE_SERVOS; i++) {
  120. reset_swash_servo(SRV_Channels::get_motor_function(i));
  121. }
  122. if (_swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  123. reset_swash_servo(SRV_Channels::get_motor_function(4));
  124. }
  125. // yaw servo is an angle from -4500 to 4500
  126. SRV_Channels::set_angle(SRV_Channel::k_motor4, YAW_SERVO_MAX_ANGLE);
  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_Single::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. // external gyro & tail servo
  155. if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
  156. if (_acro_tail && _ext_gyro_gain_acro > 0) {
  157. rc_write(AP_MOTORS_HELI_SINGLE_EXTGYRO, _ext_gyro_gain_acro);
  158. } else {
  159. rc_write(AP_MOTORS_HELI_SINGLE_EXTGYRO, _ext_gyro_gain_std);
  160. }
  161. }
  162. rc_write(AP_MOTORS_MOT_4, pwm);
  163. break;
  164. case 5:
  165. // main rotor
  166. rc_write(AP_MOTORS_HELI_RSC, pwm);
  167. break;
  168. default:
  169. // do nothing
  170. break;
  171. }
  172. }
  173. // set_desired_rotor_speed
  174. void AP_MotorsHeli_Single::set_desired_rotor_speed(float desired_speed)
  175. {
  176. _main_rotor.set_desired_speed(desired_speed);
  177. // always send desired speed to tail rotor control, will do nothing if not DDVP not enabled
  178. _tail_rotor.set_desired_speed(_direct_drive_tailspeed*0.01f);
  179. }
  180. // set_rotor_rpm - used for governor with speed sensor
  181. void AP_MotorsHeli_Single::set_rpm(float rotor_rpm)
  182. {
  183. _main_rotor.set_rotor_rpm(rotor_rpm);
  184. }
  185. // calculate_scalars - recalculates various scalers used.
  186. void AP_MotorsHeli_Single::calculate_armed_scalars()
  187. {
  188. // Set rsc mode specific parameters
  189. 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) {
  190. _main_rotor.set_throttle_curve();
  191. }
  192. // keeps user from changing RSC mode while armed
  193. if (_main_rotor._rsc_mode.get() != _main_rotor.get_control_mode()) {
  194. _main_rotor.reset_rsc_mode_param();
  195. gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed");
  196. _heliflags.save_rsc_mode = true;
  197. }
  198. // saves rsc mode parameter when disarmed if it had been reset while armed
  199. if (_heliflags.save_rsc_mode && !_flags.armed) {
  200. _main_rotor._rsc_mode.save();
  201. _heliflags.save_rsc_mode = false;
  202. }
  203. }
  204. // calculate_scalars - recalculates various scalers used.
  205. void AP_MotorsHeli_Single::calculate_scalars()
  206. {
  207. // range check collective min, max and mid
  208. if( _collective_min >= _collective_max ) {
  209. _collective_min = AP_MOTORS_HELI_COLLECTIVE_MIN;
  210. _collective_max = AP_MOTORS_HELI_COLLECTIVE_MAX;
  211. }
  212. _collective_mid = constrain_int16(_collective_mid, _collective_min, _collective_max);
  213. // calculate collective mid point as a number from 0 to 1
  214. _collective_mid_pct = ((float)(_collective_mid-_collective_min))/((float)(_collective_max-_collective_min));
  215. // configure swashplate and update scalars
  216. _swashplate.configure();
  217. _swashplate.calculate_roll_pitch_collective_factors();
  218. // send setpoints to main rotor controller and trigger recalculation of scalars
  219. _main_rotor.set_control_mode(static_cast<RotorControlMode>(_main_rotor._rsc_mode.get()));
  220. calculate_armed_scalars();
  221. // send setpoints to DDVP rotor controller and trigger recalculation of scalars
  222. if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH) {
  223. _tail_rotor.set_control_mode(ROTOR_CONTROL_MODE_SPEED_SETPOINT);
  224. _tail_rotor.set_ramp_time(_main_rotor._ramp_time.get());
  225. _tail_rotor.set_runup_time(_main_rotor._runup_time.get());
  226. _tail_rotor.set_critical_speed(_main_rotor._critical_speed.get());
  227. _tail_rotor.set_idle_output(_main_rotor._idle_output.get());
  228. } else {
  229. _tail_rotor.set_control_mode(ROTOR_CONTROL_MODE_DISABLED);
  230. _tail_rotor.set_ramp_time(0);
  231. _tail_rotor.set_runup_time(0);
  232. _tail_rotor.set_critical_speed(0);
  233. _tail_rotor.set_idle_output(0);
  234. }
  235. }
  236. // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
  237. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  238. uint16_t AP_MotorsHeli_Single::get_motor_mask()
  239. {
  240. // heli uses channels 1,2,3,4 and 8
  241. // setup fast channels
  242. uint32_t mask = 1U << 0 | 1U << 1 | 1U << 2 | 1U << 3 | 1U << AP_MOTORS_HELI_RSC;
  243. if (_swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  244. mask |= 1U << 4;
  245. }
  246. if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
  247. mask |= 1U << AP_MOTORS_HELI_SINGLE_EXTGYRO;
  248. }
  249. if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH) {
  250. mask |= 1U << AP_MOTORS_HELI_SINGLE_TAILRSC;
  251. }
  252. return rc_map_mask(mask);
  253. }
  254. // update_motor_controls - sends commands to motor controllers
  255. void AP_MotorsHeli_Single::update_motor_control(RotorControlState state)
  256. {
  257. // Send state update to motors
  258. _tail_rotor.output(state);
  259. _main_rotor.output(state);
  260. if (state == ROTOR_CONTROL_STOP){
  261. // set engine run enable aux output to not run position to kill engine when disarmed
  262. SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
  263. } else {
  264. // else if armed, set engine run enable output to run position
  265. SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MAX);
  266. }
  267. // Check if both rotors are run-up, tail rotor controller always returns true if not enabled
  268. _heliflags.rotor_runup_complete = ( _main_rotor.is_runup_complete() && _tail_rotor.is_runup_complete() );
  269. }
  270. //
  271. // move_actuators - moves swash plate and tail rotor
  272. // - expected ranges:
  273. // roll : -1 ~ +1
  274. // pitch: -1 ~ +1
  275. // collective: 0 ~ 1
  276. // yaw: -1 ~ +1
  277. //
  278. void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out)
  279. {
  280. float yaw_offset = 0.0f;
  281. // initialize limits flag
  282. limit.roll = false;
  283. limit.pitch = false;
  284. limit.yaw = false;
  285. limit.throttle_lower = false;
  286. limit.throttle_upper = false;
  287. if (_heliflags.inverted_flight) {
  288. coll_in = 1 - coll_in;
  289. }
  290. // rescale roll_out and pitch_out into the min and max ranges to provide linear motion
  291. // across the input range instead of stopping when the input hits the constrain value
  292. // these calculations are based on an assumption of the user specified cyclic_max
  293. // coming into this equation at 4500 or less
  294. float total_out = norm(pitch_out, roll_out);
  295. if (total_out > (_cyclic_max/4500.0f)) {
  296. float ratio = (float)(_cyclic_max/4500.0f) / total_out;
  297. roll_out *= ratio;
  298. pitch_out *= ratio;
  299. limit.roll = true;
  300. limit.pitch = true;
  301. }
  302. // constrain collective input
  303. float collective_out = coll_in;
  304. if (collective_out <= 0.0f) {
  305. collective_out = 0.0f;
  306. limit.throttle_lower = true;
  307. }
  308. if (collective_out >= 1.0f) {
  309. collective_out = 1.0f;
  310. limit.throttle_upper = true;
  311. }
  312. // ensure not below landed/landing collective
  313. if (_heliflags.landing_collective && collective_out < _collective_mid_pct) {
  314. collective_out = _collective_mid_pct;
  315. limit.throttle_lower = true;
  316. }
  317. // if servo output not in manual mode, process pre-compensation factors
  318. if (_servo_mode == SERVO_CONTROL_MODE_AUTOMATED) {
  319. // rudder feed forward based on collective
  320. // the feed-forward is not required when the motor is stopped or at idle, and thus not creating torque
  321. // also not required if we are using external gyro
  322. if ((_main_rotor.get_control_output() > _main_rotor.get_idle_output()) && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
  323. // sanity check collective_yaw_effect
  324. _collective_yaw_effect = constrain_float(_collective_yaw_effect, -AP_MOTORS_HELI_SINGLE_COLYAW_RANGE, AP_MOTORS_HELI_SINGLE_COLYAW_RANGE);
  325. // the 4.5 scaling factor is to bring the values in line with previous releases
  326. yaw_offset = _collective_yaw_effect * fabsf(collective_out - _collective_mid_pct) / 4.5f;
  327. }
  328. } else {
  329. yaw_offset = 0.0f;
  330. }
  331. // feed power estimate into main rotor controller
  332. // ToDo: include tail rotor power?
  333. // ToDo: add main rotor cyclic power?
  334. _main_rotor.set_collective(fabsf(collective_out));
  335. // scale collective pitch for swashplate servos
  336. float collective_scalar = ((float)(_collective_max-_collective_min))*0.001f;
  337. float collective_out_scaled = collective_out * collective_scalar + (_collective_min - 1000)*0.001f;
  338. // get servo positions from swashplate library
  339. _servo1_out = _swashplate.get_servo_out(CH_1,pitch_out,roll_out,collective_out_scaled);
  340. _servo2_out = _swashplate.get_servo_out(CH_2,pitch_out,roll_out,collective_out_scaled);
  341. _servo3_out = _swashplate.get_servo_out(CH_3,pitch_out,roll_out,collective_out_scaled);
  342. if (_swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  343. _servo5_out = _swashplate.get_servo_out(CH_4,pitch_out,roll_out,collective_out_scaled);
  344. }
  345. // update the yaw rate using the tail rotor/servo
  346. move_yaw(yaw_out + yaw_offset);
  347. }
  348. // move_yaw
  349. void AP_MotorsHeli_Single::move_yaw(float yaw_out)
  350. {
  351. // sanity check yaw_out
  352. if (yaw_out < -1.0f) {
  353. yaw_out = -1.0f;
  354. limit.yaw = true;
  355. }
  356. if (yaw_out > 1.0f) {
  357. yaw_out = 1.0f;
  358. limit.yaw = true;
  359. }
  360. _servo4_out = yaw_out;
  361. }
  362. void AP_MotorsHeli_Single::output_to_motors()
  363. {
  364. if (!_flags.initialised_ok) {
  365. return;
  366. }
  367. // actually move the servos. PWM is sent based on nominal 1500 center. servo output shifts center based on trim value.
  368. rc_write_swash(AP_MOTORS_MOT_1, _servo1_out);
  369. rc_write_swash(AP_MOTORS_MOT_2, _servo2_out);
  370. rc_write_swash(AP_MOTORS_MOT_3, _servo3_out);
  371. // get servo positions from swashplate library and write to servo for 4 servo of 4 servo swashplate
  372. if (_swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_90 || _swashplate.get_swash_type() == SWASHPLATE_TYPE_H4_45) {
  373. rc_write_swash(AP_MOTORS_MOT_5, _servo5_out);
  374. }
  375. if (_tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH){
  376. rc_write_angle(AP_MOTORS_MOT_4, _servo4_out * YAW_SERVO_MAX_ANGLE);
  377. }
  378. if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
  379. // output gain to exernal gyro
  380. if (_acro_tail && _ext_gyro_gain_acro > 0) {
  381. rc_write(AP_MOTORS_HELI_SINGLE_EXTGYRO, 1000 + _ext_gyro_gain_acro);
  382. } else {
  383. rc_write(AP_MOTORS_HELI_SINGLE_EXTGYRO, 1000 + _ext_gyro_gain_std);
  384. }
  385. }
  386. switch (_spool_state) {
  387. case SpoolState::SHUT_DOWN:
  388. // sends minimum values out to the motors
  389. update_motor_control(ROTOR_CONTROL_STOP);
  390. if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH){
  391. rc_write_angle(AP_MOTORS_MOT_4, -YAW_SERVO_MAX_ANGLE);
  392. }
  393. break;
  394. case SpoolState::GROUND_IDLE:
  395. // sends idle output to motors when armed. rotor could be static or turning (autorotation)
  396. update_motor_control(ROTOR_CONTROL_IDLE);
  397. if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH){
  398. rc_write_angle(AP_MOTORS_MOT_4, -YAW_SERVO_MAX_ANGLE);
  399. }
  400. break;
  401. case SpoolState::SPOOLING_UP:
  402. case SpoolState::THROTTLE_UNLIMITED:
  403. // set motor output based on thrust requests
  404. update_motor_control(ROTOR_CONTROL_ACTIVE);
  405. if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH){
  406. // constrain output so that motor never fully stops
  407. _servo4_out = constrain_float(_servo4_out, -0.9f, 1.0f);
  408. // output yaw servo to tail rsc
  409. rc_write_angle(AP_MOTORS_MOT_4, _servo4_out * YAW_SERVO_MAX_ANGLE);
  410. }
  411. break;
  412. case SpoolState::SPOOLING_DOWN:
  413. // sends idle output to motors and wait for rotor to stop
  414. update_motor_control(ROTOR_CONTROL_IDLE);
  415. if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH){
  416. rc_write_angle(AP_MOTORS_MOT_4, -YAW_SERVO_MAX_ANGLE);
  417. }
  418. break;
  419. }
  420. }
  421. // servo_test - move servos through full range of movement
  422. void AP_MotorsHeli_Single::servo_test()
  423. {
  424. _servo_test_cycle_time += 1.0f / _loop_rate;
  425. if ((_servo_test_cycle_time >= 0.0f && _servo_test_cycle_time < 0.5f)|| // Tilt swash back
  426. (_servo_test_cycle_time >= 6.0f && _servo_test_cycle_time < 6.5f)){
  427. _pitch_test += (1.0f / (_loop_rate / 2.0f));
  428. _oscillate_angle += 8 * M_PI / _loop_rate;
  429. _yaw_test = 0.5f * sinf(_oscillate_angle);
  430. } else if ((_servo_test_cycle_time >= 0.5f && _servo_test_cycle_time < 4.5f)|| // Roll swash around
  431. (_servo_test_cycle_time >= 6.5f && _servo_test_cycle_time < 10.5f)){
  432. _oscillate_angle += M_PI / (2 * _loop_rate);
  433. _roll_test = sinf(_oscillate_angle);
  434. _pitch_test = cosf(_oscillate_angle);
  435. _yaw_test = sinf(_oscillate_angle);
  436. } else if ((_servo_test_cycle_time >= 4.5f && _servo_test_cycle_time < 5.0f)|| // Return swash to level
  437. (_servo_test_cycle_time >= 10.5f && _servo_test_cycle_time < 11.0f)){
  438. _pitch_test -= (1.0f / (_loop_rate / 2.0f));
  439. _oscillate_angle += 8 * M_PI / _loop_rate;
  440. _yaw_test = 0.5f * sinf(_oscillate_angle);
  441. } else if (_servo_test_cycle_time >= 5.0f && _servo_test_cycle_time < 6.0f){ // Raise swash to top
  442. _collective_test += (1.0f / _loop_rate);
  443. _oscillate_angle += 2 * M_PI / _loop_rate;
  444. _yaw_test = sinf(_oscillate_angle);
  445. } else if (_servo_test_cycle_time >= 11.0f && _servo_test_cycle_time < 12.0f){ // Lower swash to bottom
  446. _collective_test -= (1.0f / _loop_rate);
  447. _oscillate_angle += 2 * M_PI / _loop_rate;
  448. _yaw_test = sinf(_oscillate_angle);
  449. } else { // reset cycle
  450. _servo_test_cycle_time = 0.0f;
  451. _oscillate_angle = 0.0f;
  452. _collective_test = 0.0f;
  453. _roll_test = 0.0f;
  454. _pitch_test = 0.0f;
  455. _yaw_test = 0.0f;
  456. // decrement servo test cycle counter at the end of the cycle
  457. if (_servo_test_cycle_counter > 0){
  458. _servo_test_cycle_counter--;
  459. }
  460. }
  461. // over-ride servo commands to move servos through defined ranges
  462. _throttle_filter.reset(constrain_float(_collective_test, 0.0f, 1.0f));
  463. _roll_in = constrain_float(_roll_test, -1.0f, 1.0f);
  464. _pitch_in = constrain_float(_pitch_test, -1.0f, 1.0f);
  465. _yaw_in = constrain_float(_yaw_test, -1.0f, 1.0f);
  466. }
  467. // parameter_check - check if helicopter specific parameters are sensible
  468. bool AP_MotorsHeli_Single::parameter_check(bool display_msg) const
  469. {
  470. // returns false if direct drive tailspeed is outside of range
  471. if ((_direct_drive_tailspeed < 0) || (_direct_drive_tailspeed > 100)){
  472. if (display_msg) {
  473. gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_TAIL_SPEED out of range");
  474. }
  475. return false;
  476. }
  477. // returns false if Phase Angle is outside of range for H3 swashplate
  478. if (_swashplate.get_swash_type() == SWASHPLATE_TYPE_H3 && (_swashplate.get_phase_angle() > 30 || _swashplate.get_phase_angle() < -30)){
  479. if (display_msg) {
  480. gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_H3_PHANG out of range");
  481. }
  482. return false;
  483. }
  484. // returns false if Acro External Gyro Gain is outside of range
  485. if ((_ext_gyro_gain_acro < 0) || (_ext_gyro_gain_acro > 1000)){
  486. if (display_msg) {
  487. gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_GYR_GAIN_ACRO out of range");
  488. }
  489. return false;
  490. }
  491. // returns false if Standard External Gyro Gain is outside of range
  492. if ((_ext_gyro_gain_std < 0) || (_ext_gyro_gain_std > 1000)){
  493. if (display_msg) {
  494. gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_GYR_GAIN out of range");
  495. }
  496. return false;
  497. }
  498. // check parent class parameters
  499. return AP_MotorsHeli::parameter_check(display_msg);
  500. }