AP_MotorsSingle.cpp 11 KB

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