AP_MotorsHeli_Quad.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320
  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 <GCS_MAVLink/GCS.h>
  18. #include "AP_MotorsHeli_Quad.h"
  19. extern const AP_HAL::HAL& hal;
  20. const AP_Param::GroupInfo AP_MotorsHeli_Quad::var_info[] = {
  21. AP_NESTEDGROUPINFO(AP_MotorsHeli, 0),
  22. // Indices 1-3 were used by RSC_PWM_MIN, RSC_PWM_MAX and RSC_PWM_REV and should not be used
  23. AP_GROUPEND
  24. };
  25. #define QUAD_SERVO_MAX_ANGLE 4500
  26. // set update rate to motors - a value in hertz
  27. void AP_MotorsHeli_Quad::set_update_rate( uint16_t speed_hz )
  28. {
  29. // record requested speed
  30. _speed_hz = speed_hz;
  31. // setup fast channels
  32. uint32_t mask = 0;
  33. for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
  34. mask |= 1U << (AP_MOTORS_MOT_1+i);
  35. }
  36. rc_set_freq(mask, _speed_hz);
  37. }
  38. // init_outputs
  39. bool AP_MotorsHeli_Quad::init_outputs()
  40. {
  41. if (_flags.initialised_ok) {
  42. return true;
  43. }
  44. for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
  45. add_motor_num(CH_1+i);
  46. SRV_Channels::set_angle(SRV_Channels::get_motor_function(i), QUAD_SERVO_MAX_ANGLE);
  47. }
  48. // set rotor servo range
  49. _main_rotor.init_servo();
  50. _flags.initialised_ok = true;
  51. return true;
  52. }
  53. // output_test_seq - spin a motor at the pwm value specified
  54. // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
  55. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  56. void AP_MotorsHeli_Quad::output_test_seq(uint8_t motor_seq, int16_t pwm)
  57. {
  58. // exit immediately if not armed
  59. if (!armed()) {
  60. return;
  61. }
  62. // output to motors and servos
  63. switch (motor_seq) {
  64. case 1 ... AP_MOTORS_HELI_QUAD_NUM_MOTORS:
  65. rc_write(AP_MOTORS_MOT_1 + (motor_seq-1), pwm);
  66. break;
  67. case AP_MOTORS_HELI_QUAD_NUM_MOTORS+1:
  68. // main rotor
  69. rc_write(AP_MOTORS_HELI_RSC, pwm);
  70. break;
  71. default:
  72. // do nothing
  73. break;
  74. }
  75. }
  76. // set_desired_rotor_speed
  77. void AP_MotorsHeli_Quad::set_desired_rotor_speed(float desired_speed)
  78. {
  79. _main_rotor.set_desired_speed(desired_speed);
  80. }
  81. // set_rotor_rpm - used for governor with speed sensor
  82. void AP_MotorsHeli_Quad::set_rpm(float rotor_rpm)
  83. {
  84. _main_rotor.set_rotor_rpm(rotor_rpm);
  85. }
  86. // calculate_armed_scalars
  87. void AP_MotorsHeli_Quad::calculate_armed_scalars()
  88. {
  89. // Set rsc mode specific parameters
  90. 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) {
  91. _main_rotor.set_throttle_curve();
  92. }
  93. // keeps user from changing RSC mode while armed
  94. if (_main_rotor._rsc_mode.get() != _main_rotor.get_control_mode()) {
  95. _main_rotor.reset_rsc_mode_param();
  96. gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed");
  97. _heliflags.save_rsc_mode = true;
  98. }
  99. // saves rsc mode parameter when disarmed if it had been reset while armed
  100. if (_heliflags.save_rsc_mode && !_flags.armed) {
  101. _main_rotor._rsc_mode.save();
  102. _heliflags.save_rsc_mode = false;
  103. }
  104. }
  105. // calculate_scalars
  106. void AP_MotorsHeli_Quad::calculate_scalars()
  107. {
  108. // range check collective min, max and mid
  109. if( _collective_min >= _collective_max ) {
  110. _collective_min = AP_MOTORS_HELI_COLLECTIVE_MIN;
  111. _collective_max = AP_MOTORS_HELI_COLLECTIVE_MAX;
  112. }
  113. _collective_mid = constrain_int16(_collective_mid, _collective_min, _collective_max);
  114. // calculate collective mid point as a number from 0 to 1000
  115. _collective_mid_pct = ((float)(_collective_mid-_collective_min))/((float)(_collective_max-_collective_min));
  116. // calculate factors based on swash type and servo position
  117. calculate_roll_pitch_collective_factors();
  118. // set mode of main rotor controller and trigger recalculation of scalars
  119. _main_rotor.set_control_mode(static_cast<RotorControlMode>(_main_rotor._rsc_mode.get()));
  120. calculate_armed_scalars();
  121. }
  122. // calculate_swash_factors - calculate factors based on swash type and servo position
  123. void AP_MotorsHeli_Quad::calculate_roll_pitch_collective_factors()
  124. {
  125. // assume X quad layout, with motors at 45, 135, 225 and 315 degrees
  126. // order FrontRight, RearLeft, FrontLeft, RearLeft
  127. const float angles[AP_MOTORS_HELI_QUAD_NUM_MOTORS] = { 45, 225, 315, 135 };
  128. const bool x_clockwise[AP_MOTORS_HELI_QUAD_NUM_MOTORS] = { false, false, true, true };
  129. const float cos45 = cosf(radians(45));
  130. for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
  131. bool clockwise = x_clockwise[i];
  132. if (_frame_type == MOTOR_FRAME_TYPE_H) {
  133. // reverse yaw for H frame
  134. clockwise = !clockwise;
  135. }
  136. _rollFactor[CH_1+i] = -0.5*sinf(radians(angles[i]))/cos45;
  137. _pitchFactor[CH_1+i] = 0.5*cosf(radians(angles[i]))/cos45;
  138. _yawFactor[CH_1+i] = clockwise?-0.5:0.5;
  139. _collectiveFactor[CH_1+i] = 1;
  140. }
  141. }
  142. // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
  143. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  144. uint16_t AP_MotorsHeli_Quad::get_motor_mask()
  145. {
  146. uint16_t mask = 0;
  147. for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
  148. mask |= 1U << (AP_MOTORS_MOT_1+i);
  149. }
  150. mask |= 1U << AP_MOTORS_HELI_RSC;
  151. return mask;
  152. }
  153. // update_motor_controls - sends commands to motor controllers
  154. void AP_MotorsHeli_Quad::update_motor_control(RotorControlState state)
  155. {
  156. // Send state update to motors
  157. _main_rotor.output(state);
  158. if (state == ROTOR_CONTROL_STOP) {
  159. // set engine run enable aux output to not run position to kill engine when disarmed
  160. SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
  161. } else {
  162. // else if armed, set engine run enable output to run position
  163. SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::SRV_CHANNEL_LIMIT_MAX);
  164. }
  165. // Check if rotors are run-up
  166. _heliflags.rotor_runup_complete = _main_rotor.is_runup_complete();
  167. }
  168. //
  169. // move_actuators - moves swash plate to attitude of parameters passed in
  170. // - expected ranges:
  171. // roll : -1 ~ +1
  172. // pitch: -1 ~ +1
  173. // collective: 0 ~ 1
  174. // yaw: -1 ~ +1
  175. //
  176. void AP_MotorsHeli_Quad::move_actuators(float roll_out, float pitch_out, float collective_in, float yaw_out)
  177. {
  178. // initialize limits flag
  179. limit.roll = false;
  180. limit.pitch = false;
  181. limit.yaw = false;
  182. limit.throttle_lower = false;
  183. limit.throttle_upper = false;
  184. // constrain collective input
  185. float collective_out = collective_in;
  186. if (collective_out <= 0.0f) {
  187. collective_out = 0.0f;
  188. limit.throttle_lower = true;
  189. }
  190. if (collective_out >= 1.0f) {
  191. collective_out = 1.0f;
  192. limit.throttle_upper = true;
  193. }
  194. // ensure not below landed/landing collective
  195. if (_heliflags.landing_collective && collective_out < _collective_mid_pct) {
  196. collective_out = _collective_mid_pct;
  197. limit.throttle_lower = true;
  198. }
  199. float collective_range = (_collective_max - _collective_min)*0.001f;
  200. if (_heliflags.inverted_flight) {
  201. collective_out = 1 - collective_out;
  202. }
  203. // feed power estimate into main rotor controller
  204. _main_rotor.set_collective(fabsf(collective_out));
  205. // scale collective to -1 to 1
  206. collective_out = collective_out*2-1;
  207. // reserve some collective for attitude control
  208. collective_out *= collective_range;
  209. for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
  210. _out[i] =
  211. _rollFactor[CH_1+i] * roll_out +
  212. _pitchFactor[CH_1+i] * pitch_out +
  213. _collectiveFactor[CH_1+i] * collective_out;
  214. }
  215. // see if we need to scale down yaw_out
  216. for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
  217. float y = _yawFactor[CH_1+i] * yaw_out;
  218. if (_out[i] < 0) {
  219. // the slope of the yaw effect changes at zero collective
  220. y = -y;
  221. }
  222. if (_out[i] * (_out[i] + y) < 0) {
  223. // applying this yaw demand would change the sign of the
  224. // collective, which means the yaw would not be applied
  225. // evenly. We scale down the overall yaw demand to prevent
  226. // it crossing over zero
  227. float s = -(_out[i] / y);
  228. yaw_out *= s;
  229. }
  230. }
  231. // now apply the yaw correction
  232. for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
  233. float y = _yawFactor[CH_1+i] * yaw_out;
  234. if (_out[i] < 0) {
  235. // the slope of the yaw effect changes at zero collective
  236. y = -y;
  237. }
  238. _out[i] += y;
  239. }
  240. }
  241. void AP_MotorsHeli_Quad::output_to_motors()
  242. {
  243. if (!_flags.initialised_ok) {
  244. return;
  245. }
  246. // move the servos
  247. for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
  248. rc_write_angle(AP_MOTORS_MOT_1+i, _out[i] * QUAD_SERVO_MAX_ANGLE);
  249. }
  250. switch (_spool_state) {
  251. case SpoolState::SHUT_DOWN:
  252. // sends minimum values out to the motors
  253. update_motor_control(ROTOR_CONTROL_STOP);
  254. break;
  255. case SpoolState::GROUND_IDLE:
  256. // sends idle output to motors when armed. rotor could be static or turning (autorotation)
  257. update_motor_control(ROTOR_CONTROL_IDLE);
  258. break;
  259. case SpoolState::SPOOLING_UP:
  260. case SpoolState::THROTTLE_UNLIMITED:
  261. // set motor output based on thrust requests
  262. update_motor_control(ROTOR_CONTROL_ACTIVE);
  263. break;
  264. case SpoolState::SPOOLING_DOWN:
  265. // sends idle output to motors and wait for rotor to stop
  266. update_motor_control(ROTOR_CONTROL_IDLE);
  267. break;
  268. }
  269. }
  270. // servo_test - move servos through full range of movement
  271. void AP_MotorsHeli_Quad::servo_test()
  272. {
  273. // not implemented
  274. }