AP_MotorsTailsitter.cpp 7.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210
  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_MotorsTailsitter.cpp - ArduCopter motors library for tailsitters and bicopters
  15. *
  16. */
  17. #include <AP_HAL/AP_HAL.h>
  18. #include <AP_Math/AP_Math.h>
  19. #include "AP_MotorsTailsitter.h"
  20. #include <GCS_MAVLink/GCS.h>
  21. extern const AP_HAL::HAL& hal;
  22. #define SERVO_OUTPUT_RANGE 4500
  23. // init
  24. void AP_MotorsTailsitter::init(motor_frame_class frame_class, motor_frame_type frame_type)
  25. {
  26. // setup default motor and servo mappings
  27. uint8_t chan;
  28. // right throttle defaults to servo output 1
  29. SRV_Channels::set_aux_channel_default(SRV_Channel::k_throttleRight, CH_1);
  30. if (SRV_Channels::find_channel(SRV_Channel::k_throttleRight, chan)) {
  31. motor_enabled[chan] = true;
  32. }
  33. // left throttle defaults to servo output 2
  34. SRV_Channels::set_aux_channel_default(SRV_Channel::k_throttleLeft, CH_2);
  35. if (SRV_Channels::find_channel(SRV_Channel::k_throttleLeft, chan)) {
  36. motor_enabled[chan] = true;
  37. }
  38. // right servo defaults to servo output 3
  39. SRV_Channels::set_aux_channel_default(SRV_Channel::k_tiltMotorRight, CH_3);
  40. SRV_Channels::set_angle(SRV_Channel::k_tiltMotorRight, SERVO_OUTPUT_RANGE);
  41. // left servo defaults to servo output 4
  42. SRV_Channels::set_aux_channel_default(SRV_Channel::k_tiltMotorLeft, CH_4);
  43. SRV_Channels::set_angle(SRV_Channel::k_tiltMotorLeft, SERVO_OUTPUT_RANGE);
  44. // record successful initialisation if what we setup was the desired frame_class
  45. _flags.initialised_ok = (frame_class == MOTOR_FRAME_TAILSITTER);
  46. }
  47. /// Constructor
  48. AP_MotorsTailsitter::AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz) :
  49. AP_MotorsMulticopter(loop_rate, speed_hz)
  50. {
  51. set_update_rate(speed_hz);
  52. }
  53. // set update rate to motors - a value in hertz
  54. void AP_MotorsTailsitter::set_update_rate(uint16_t speed_hz)
  55. {
  56. // record requested speed
  57. _speed_hz = speed_hz;
  58. SRV_Channels::set_rc_frequency(SRV_Channel::k_throttleLeft, speed_hz);
  59. SRV_Channels::set_rc_frequency(SRV_Channel::k_throttleRight, speed_hz);
  60. }
  61. void AP_MotorsTailsitter::output_to_motors()
  62. {
  63. if (!_flags.initialised_ok) {
  64. return;
  65. }
  66. switch (_spool_state) {
  67. case SpoolState::SHUT_DOWN:
  68. SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, get_pwm_output_min());
  69. SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, get_pwm_output_min());
  70. break;
  71. case SpoolState::GROUND_IDLE:
  72. set_actuator_with_slew(_actuator[1], actuator_spin_up_to_ground_idle());
  73. SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, output_to_pwm(actuator_spin_up_to_ground_idle()));
  74. SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, output_to_pwm(actuator_spin_up_to_ground_idle()));
  75. break;
  76. case SpoolState::SPOOLING_UP:
  77. case SpoolState::THROTTLE_UNLIMITED:
  78. case SpoolState::SPOOLING_DOWN:
  79. SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, output_to_pwm(thrust_to_actuator(_thrust_left)));
  80. SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, output_to_pwm(thrust_to_actuator(_thrust_right)));
  81. break;
  82. }
  83. // Always output to tilt servos
  84. SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, _tilt_left*SERVO_OUTPUT_RANGE);
  85. SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, _tilt_right*SERVO_OUTPUT_RANGE);
  86. }
  87. // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
  88. // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
  89. uint16_t AP_MotorsTailsitter::get_motor_mask()
  90. {
  91. uint32_t motor_mask = 0;
  92. uint8_t chan;
  93. if (SRV_Channels::find_channel(SRV_Channel::k_throttleLeft, chan)) {
  94. motor_mask |= 1U << chan;
  95. }
  96. if (SRV_Channels::find_channel(SRV_Channel::k_throttleRight, chan)) {
  97. motor_mask |= 1U << chan;
  98. }
  99. // add parent's mask
  100. motor_mask |= AP_MotorsMulticopter::get_motor_mask();
  101. return motor_mask;
  102. }
  103. // calculate outputs to the motors
  104. void AP_MotorsTailsitter::output_armed_stabilizing()
  105. {
  106. float roll_thrust; // roll thrust input value, +/- 1.0
  107. float pitch_thrust; // pitch thrust input value, +/- 1.0
  108. float yaw_thrust; // yaw thrust input value, +/- 1.0
  109. float throttle_thrust; // throttle thrust input value, 0.0 - 1.0
  110. float thrust_max; // highest motor value
  111. float thr_adj = 0.0f; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy
  112. // apply voltage and air pressure compensation
  113. const float compensation_gain = get_compensation_gain();
  114. roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain;
  115. pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain;
  116. yaw_thrust = (_yaw_in + _yaw_in_ff) * compensation_gain;
  117. throttle_thrust = get_throttle() * compensation_gain;
  118. // sanity check throttle is above zero and below current limited throttle
  119. if (throttle_thrust <= 0.0f) {
  120. throttle_thrust = 0.0f;
  121. limit.throttle_lower = true;
  122. }
  123. if (throttle_thrust >= _throttle_thrust_max) {
  124. throttle_thrust = _throttle_thrust_max;
  125. limit.throttle_upper = true;
  126. }
  127. // calculate left and right throttle outputs
  128. _thrust_left = throttle_thrust + roll_thrust * 0.5f;
  129. _thrust_right = throttle_thrust - roll_thrust * 0.5f;
  130. // if max thrust is more than one reduce average throttle
  131. thrust_max = MAX(_thrust_right,_thrust_left);
  132. if (thrust_max > 1.0f) {
  133. thr_adj = 1.0f - thrust_max;
  134. limit.throttle_upper = true;
  135. limit.roll = true;
  136. limit.pitch = true;
  137. }
  138. // Add adjustment to reduce average throttle
  139. _thrust_left = constrain_float(_thrust_left + thr_adj, 0.0f, 1.0f);
  140. _thrust_right = constrain_float(_thrust_right + thr_adj, 0.0f, 1.0f);
  141. _throttle = throttle_thrust + thr_adj;
  142. // thrust vectoring
  143. _tilt_left = pitch_thrust - yaw_thrust;
  144. _tilt_right = pitch_thrust + yaw_thrust;
  145. }
  146. // output_test_seq - spin a motor at the pwm value specified
  147. // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
  148. // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
  149. void AP_MotorsTailsitter::output_test_seq(uint8_t motor_seq, int16_t pwm)
  150. {
  151. // exit immediately if not armed
  152. if (!armed()) {
  153. return;
  154. }
  155. // output to motors and servos
  156. switch (motor_seq) {
  157. case 1:
  158. // right throttle
  159. SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, pwm);
  160. break;
  161. case 2:
  162. // right tilt servo
  163. SRV_Channels::set_output_pwm(SRV_Channel::k_tiltMotorRight, pwm);
  164. break;
  165. case 3:
  166. // left throttle
  167. SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, pwm);
  168. break;
  169. case 4:
  170. // left tilt servo
  171. SRV_Channels::set_output_pwm(SRV_Channel::k_tiltMotorLeft, pwm);
  172. break;
  173. default:
  174. // do nothing
  175. break;
  176. }
  177. }