AP_MotorsCoax.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263
  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_MotorsSingle.cpp - ArduCopter motors library
  15. * Code by RandyMackay. DIYDrones.com
  16. *
  17. */
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AP_Math/AP_Math.h>
  20. #include "AP_MotorsCoax.h"
  21. #include <GCS_MAVLink/GCS.h>
  22. extern const AP_HAL::HAL& hal;
  23. // init
  24. void AP_MotorsCoax::init(motor_frame_class frame_class, motor_frame_type frame_type)
  25. {
  26. // make sure 6 output channels are mapped
  27. for (uint8_t i = 0; i < 6; i++) {
  28. add_motor_num(CH_1 + i);
  29. }
  30. // set the motor_enabled flag so that the main ESC can be calibrated like other frame types
  31. motor_enabled[AP_MOTORS_MOT_5] = true;
  32. motor_enabled[AP_MOTORS_MOT_6] = true;
  33. // setup actuator scaling
  34. for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
  35. SRV_Channels::set_angle(SRV_Channels::get_motor_function(i), AP_MOTORS_COAX_SERVO_INPUT_RANGE);
  36. }
  37. // record successful initialisation if what we setup was the desired frame_class
  38. _flags.initialised_ok = (frame_class == MOTOR_FRAME_COAX);
  39. }
  40. // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
  41. void AP_MotorsCoax::set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
  42. {
  43. _flags.initialised_ok = (frame_class == MOTOR_FRAME_COAX);
  44. }
  45. // set update rate to motors - a value in hertz
  46. void AP_MotorsCoax::set_update_rate(uint16_t speed_hz)
  47. {
  48. // record requested speed
  49. _speed_hz = speed_hz;
  50. uint32_t mask =
  51. 1U << AP_MOTORS_MOT_5 |
  52. 1U << AP_MOTORS_MOT_6 ;
  53. rc_set_freq(mask, _speed_hz);
  54. }
  55. void AP_MotorsCoax::output_to_motors()
  56. {
  57. switch (_spool_state) {
  58. case SpoolState::SHUT_DOWN:
  59. // sends minimum values out to the motors
  60. rc_write_angle(AP_MOTORS_MOT_1, _roll_radio_passthrough * AP_MOTORS_COAX_SERVO_INPUT_RANGE);
  61. rc_write_angle(AP_MOTORS_MOT_2, _pitch_radio_passthrough * AP_MOTORS_COAX_SERVO_INPUT_RANGE);
  62. rc_write_angle(AP_MOTORS_MOT_3, -_roll_radio_passthrough * AP_MOTORS_COAX_SERVO_INPUT_RANGE);
  63. rc_write_angle(AP_MOTORS_MOT_4, -_pitch_radio_passthrough * AP_MOTORS_COAX_SERVO_INPUT_RANGE);
  64. rc_write(AP_MOTORS_MOT_5, output_to_pwm(0));
  65. rc_write(AP_MOTORS_MOT_6, output_to_pwm(0));
  66. break;
  67. case SpoolState::GROUND_IDLE:
  68. // sends output to motors when armed but not flying
  69. for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
  70. rc_write_angle(AP_MOTORS_MOT_1 + i, _spin_up_ratio * _actuator_out[i] * AP_MOTORS_COAX_SERVO_INPUT_RANGE);
  71. }
  72. set_actuator_with_slew(_actuator[5], actuator_spin_up_to_ground_idle());
  73. set_actuator_with_slew(_actuator[6], actuator_spin_up_to_ground_idle());
  74. rc_write(AP_MOTORS_MOT_5, output_to_pwm(_actuator[5]));
  75. rc_write(AP_MOTORS_MOT_6, output_to_pwm(_actuator[6]));
  76. break;
  77. case SpoolState::SPOOLING_UP:
  78. case SpoolState::THROTTLE_UNLIMITED:
  79. case SpoolState::SPOOLING_DOWN:
  80. // set motor output based on thrust requests
  81. for (uint8_t i = 0; i < NUM_ACTUATORS; i++) {
  82. rc_write_angle(AP_MOTORS_MOT_1 + i, _actuator_out[i] * AP_MOTORS_COAX_SERVO_INPUT_RANGE);
  83. }
  84. set_actuator_with_slew(_actuator[5], thrust_to_actuator(_thrust_yt_ccw));
  85. set_actuator_with_slew(_actuator[6], thrust_to_actuator(_thrust_yt_cw));
  86. rc_write(AP_MOTORS_MOT_5, output_to_pwm(_actuator[5]));
  87. rc_write(AP_MOTORS_MOT_6, output_to_pwm(_actuator[6]));
  88. break;
  89. }
  90. }
  91. // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
  92. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  93. uint16_t AP_MotorsCoax::get_motor_mask()
  94. {
  95. uint32_t motor_mask =
  96. 1U << AP_MOTORS_MOT_1 |
  97. 1U << AP_MOTORS_MOT_2 |
  98. 1U << AP_MOTORS_MOT_3 |
  99. 1U << AP_MOTORS_MOT_4 |
  100. 1U << AP_MOTORS_MOT_5 |
  101. 1U << AP_MOTORS_MOT_6;
  102. uint16_t mask = rc_map_mask(motor_mask);
  103. // add parent's mask
  104. mask |= AP_MotorsMulticopter::get_motor_mask();
  105. return mask;
  106. }
  107. // sends commands to the motors
  108. void AP_MotorsCoax::output_armed_stabilizing()
  109. {
  110. float roll_thrust; // roll thrust input value, +/- 1.0
  111. float pitch_thrust; // pitch thrust input value, +/- 1.0
  112. float yaw_thrust; // yaw thrust input value, +/- 1.0
  113. float throttle_thrust; // throttle thrust input value, 0.0 - 1.0
  114. float throttle_avg_max; // throttle thrust average maximum value, 0.0 - 1.0
  115. float thrust_min_rpy; // the minimum throttle setting that will not limit the roll and pitch output
  116. float thr_adj; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy
  117. float thrust_out; //
  118. float rp_scale = 1.0f; // this is used to scale the roll, pitch and yaw to fit within the motor limits
  119. float actuator_allowed = 0.0f; // amount of yaw we can fit in
  120. // apply voltage and air pressure compensation
  121. const float compensation_gain = get_compensation_gain();
  122. roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain;
  123. pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain;
  124. yaw_thrust = (_yaw_in + _yaw_in_ff) * compensation_gain;
  125. throttle_thrust = get_throttle() * compensation_gain;
  126. throttle_avg_max = _throttle_avg_max * compensation_gain;
  127. // sanity check throttle is above zero and below current limited throttle
  128. if (throttle_thrust <= 0.0f) {
  129. throttle_thrust = 0.0f;
  130. limit.throttle_lower = true;
  131. }
  132. if (throttle_thrust >= _throttle_thrust_max) {
  133. throttle_thrust = _throttle_thrust_max;
  134. limit.throttle_upper = true;
  135. }
  136. throttle_avg_max = constrain_float(throttle_avg_max, throttle_thrust, _throttle_thrust_max);
  137. float rp_thrust_max = MAX(fabsf(roll_thrust), fabsf(pitch_thrust));
  138. // calculate how much roll and pitch must be scaled to leave enough range for the minimum yaw
  139. if (is_zero(rp_thrust_max)) {
  140. rp_scale = 1.0f;
  141. } else {
  142. rp_scale = constrain_float((1.0f - MIN(fabsf(yaw_thrust), 0.5f * (float)_yaw_headroom / 1000.0f)) / rp_thrust_max, 0.0f, 1.0f);
  143. if (rp_scale < 1.0f) {
  144. limit.roll = true;
  145. limit.pitch = true;
  146. }
  147. }
  148. actuator_allowed = 2.0f * (1.0f - rp_scale * rp_thrust_max);
  149. if (fabsf(yaw_thrust) > actuator_allowed) {
  150. yaw_thrust = constrain_float(yaw_thrust, -actuator_allowed, actuator_allowed);
  151. limit.yaw = true;
  152. }
  153. // calculate the minimum thrust that doesn't limit the roll, pitch and yaw forces
  154. thrust_min_rpy = MAX(fabsf(rp_scale * rp_thrust_max), fabsf(yaw_thrust));
  155. thr_adj = throttle_thrust - throttle_avg_max;
  156. if (thr_adj < (thrust_min_rpy - throttle_avg_max)) {
  157. // Throttle can't be reduced to the desired level because this would reduce airflow over
  158. // the control surfaces preventing roll and pitch reaching the desired level.
  159. thr_adj = MIN(thrust_min_rpy, throttle_avg_max) - throttle_avg_max;
  160. }
  161. // calculate the throttle setting for the lift fan
  162. thrust_out = throttle_avg_max + thr_adj;
  163. if (fabsf(yaw_thrust) > thrust_out) {
  164. yaw_thrust = constrain_float(yaw_thrust, -thrust_out, thrust_out);
  165. limit.yaw = true;
  166. }
  167. _thrust_yt_ccw = thrust_out + 0.5f * yaw_thrust;
  168. _thrust_yt_cw = thrust_out - 0.5f * yaw_thrust;
  169. // limit thrust out for calculation of actuator gains
  170. float thrust_out_actuator = constrain_float(MAX(_throttle_hover * 0.5f, thrust_out), 0.5f, 1.0f);
  171. if (is_zero(thrust_out)) {
  172. limit.roll = true;
  173. limit.pitch = true;
  174. }
  175. // force of a lifting surface is approximately equal to the angle of attack times the airflow velocity squared
  176. // static thrust is proportional to the airflow velocity squared
  177. // therefore the torque of the roll and pitch actuators should be approximately proportional to
  178. // the angle of attack multiplied by the static thrust.
  179. _actuator_out[0] = roll_thrust / thrust_out_actuator;
  180. _actuator_out[1] = pitch_thrust / thrust_out_actuator;
  181. if (fabsf(_actuator_out[0]) > 1.0f) {
  182. limit.roll = true;
  183. _actuator_out[0] = constrain_float(_actuator_out[0], -1.0f, 1.0f);
  184. }
  185. if (fabsf(_actuator_out[1]) > 1.0f) {
  186. limit.pitch = true;
  187. _actuator_out[1] = constrain_float(_actuator_out[1], -1.0f, 1.0f);
  188. }
  189. _actuator_out[2] = -_actuator_out[0];
  190. _actuator_out[3] = -_actuator_out[1];
  191. }
  192. // output_test_seq - spin a motor at the pwm value specified
  193. // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
  194. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  195. void AP_MotorsCoax::output_test_seq(uint8_t motor_seq, int16_t pwm)
  196. {
  197. // exit immediately if not armed
  198. if (!armed()) {
  199. return;
  200. }
  201. // output to motors and servos
  202. switch (motor_seq) {
  203. case 1:
  204. // flap servo 1
  205. rc_write(AP_MOTORS_MOT_1, pwm);
  206. break;
  207. case 2:
  208. // flap servo 2
  209. rc_write(AP_MOTORS_MOT_2, pwm);
  210. break;
  211. case 3:
  212. // flap servo 3
  213. rc_write(AP_MOTORS_MOT_3, pwm);
  214. break;
  215. case 4:
  216. // flap servo 4
  217. rc_write(AP_MOTORS_MOT_4, pwm);
  218. break;
  219. case 5:
  220. // motor 1
  221. rc_write(AP_MOTORS_MOT_5, pwm);
  222. break;
  223. case 6:
  224. // motor 2
  225. rc_write(AP_MOTORS_MOT_6, pwm);
  226. break;
  227. default:
  228. // do nothing
  229. break;
  230. }
  231. }