AP_MotorsMatrixTS.cpp 6.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172
  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_MotorsMatrixTS.cpp - tailsitters with multicopter motor configuration
  15. */
  16. #include <AP_BattMonitor/AP_BattMonitor.h>
  17. #include <AP_HAL/AP_HAL.h>
  18. #include "AP_MotorsMatrixTS.h"
  19. extern const AP_HAL::HAL& hal;
  20. #define SERVO_OUTPUT_RANGE 4500
  21. // output a thrust to all motors that match a given motor mask. This
  22. // is used to control motors enabled for forward flight. Thrust is in
  23. // the range 0 to 1
  24. void AP_MotorsMatrixTS::output_motor_mask(float thrust, uint8_t mask, float rudder_dt)
  25. {
  26. const int16_t pwm_min = get_pwm_output_min();
  27. const int16_t pwm_range = get_pwm_output_max() - pwm_min;
  28. for (uint8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  29. if (motor_enabled[i]) {
  30. int16_t motor_out;
  31. if (mask & (1U<<i)) {
  32. /*
  33. apply rudder mixing differential thrust
  34. copter frame roll is plane frame yaw (this is only
  35. used by tiltrotors and tailsitters)
  36. */
  37. float diff_thrust = get_roll_factor(i) * rudder_dt * 0.5f;
  38. motor_out = pwm_min + pwm_range * constrain_float(thrust + diff_thrust, 0.0f, 1.0f);
  39. } else {
  40. motor_out = pwm_min;
  41. }
  42. rc_write(i, motor_out);
  43. }
  44. }
  45. }
  46. void AP_MotorsMatrixTS::output_to_motors()
  47. {
  48. // calls calc_thrust_to_pwm(_thrust_rpyt_out[i]) for each enabled motor
  49. AP_MotorsMatrix::output_to_motors();
  50. // also actuate control surfaces
  51. SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, -_yaw_in * SERVO_OUTPUT_RANGE);
  52. SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, _pitch_in * SERVO_OUTPUT_RANGE);
  53. SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, _roll_in * SERVO_OUTPUT_RANGE);
  54. }
  55. // output_armed - sends commands to the motors
  56. // includes new scaling stability patch
  57. void AP_MotorsMatrixTS::output_armed_stabilizing()
  58. {
  59. float roll_thrust; // roll thrust input value, +/- 1.0
  60. float pitch_thrust; // pitch thrust input value, +/- 1.0
  61. float throttle_thrust; // throttle thrust input value, 0.0 - 1.0
  62. float thrust_max = 0.0f; // highest motor value
  63. float thr_adj = 0.0f; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy
  64. // apply voltage and air pressure compensation
  65. const float compensation_gain = get_compensation_gain(); // compensation for battery voltage and altitude
  66. roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain;
  67. pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain;
  68. throttle_thrust = get_throttle() * compensation_gain;
  69. // sanity check throttle is above zero and below current limited throttle
  70. if (throttle_thrust <= 0.0f) {
  71. throttle_thrust = 0.0f;
  72. limit.throttle_lower = true;
  73. }
  74. if (throttle_thrust >= _throttle_thrust_max) {
  75. throttle_thrust = _throttle_thrust_max;
  76. limit.throttle_upper = true;
  77. }
  78. thrust_max = 0.0f;
  79. for (int i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  80. if (motor_enabled[i]) {
  81. // calculate the thrust outputs for roll and pitch
  82. _thrust_rpyt_out[i] = throttle_thrust + roll_thrust * _roll_factor[i] + pitch_thrust * _pitch_factor[i];
  83. if (thrust_max < _thrust_rpyt_out[i]) {
  84. thrust_max = _thrust_rpyt_out[i];
  85. }
  86. }
  87. }
  88. // if max thrust is more than one reduce average throttle
  89. if (thrust_max > 1.0f) {
  90. thr_adj = 1.0f - thrust_max;
  91. limit.throttle_upper = true;
  92. limit.roll = true;
  93. limit.pitch = true;
  94. for (int i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  95. if (motor_enabled[i]) {
  96. // calculate the thrust outputs for roll and pitch
  97. _thrust_rpyt_out[i] += thr_adj;
  98. }
  99. }
  100. }
  101. }
  102. void AP_MotorsMatrixTS::setup_motors(motor_frame_class frame_class, motor_frame_type frame_type)
  103. {
  104. // remove existing motors
  105. for (int8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++) {
  106. remove_motor(i);
  107. }
  108. bool success = false;
  109. switch (frame_class) {
  110. case MOTOR_FRAME_TRI:
  111. // frame_type ignored since only one frame type is currently supported
  112. add_motor(AP_MOTORS_MOT_1, 90, 0, 2);
  113. add_motor(AP_MOTORS_MOT_2, -90, 0, 4);
  114. add_motor(AP_MOTORS_MOT_4, 180, 0, 3);
  115. success = true;
  116. break;
  117. case MOTOR_FRAME_QUAD:
  118. switch (frame_type) {
  119. case MOTOR_FRAME_TYPE_PLUS:
  120. // motors 1,2 on wings, motors 3,4 on vertical tail/subfin
  121. // motors 1,2 are counter-rotating, as are motors 3,4
  122. // left wing motor is CW (looking from front)
  123. // don't think it matters which of 3,4 is CW
  124. add_motor(AP_MOTORS_MOT_1, 90, 0, 2);
  125. add_motor(AP_MOTORS_MOT_2, -90, 0, 4);
  126. add_motor(AP_MOTORS_MOT_3, 0, 0, 1);
  127. add_motor(AP_MOTORS_MOT_4, 180, 0, 3);
  128. success = true;
  129. break;
  130. case MOTOR_FRAME_TYPE_X:
  131. // PLUS_TS layout rotated 45 degrees about X axis
  132. add_motor(AP_MOTORS_MOT_1, 45, 0, 1);
  133. add_motor(AP_MOTORS_MOT_2, -135, 0, 3);
  134. add_motor(AP_MOTORS_MOT_3, -45, 0, 4);
  135. add_motor(AP_MOTORS_MOT_4, 135, 0, 2);
  136. success = true;
  137. break;
  138. default:
  139. // matrixTS doesn't support the configured frame_type
  140. break;
  141. }
  142. break;
  143. default:
  144. // matrixTS doesn't support the configured frame_class
  145. break;
  146. } // switch frame_class
  147. // normalise factors to magnitude 0.5
  148. normalise_rpy_factors();
  149. _flags.initialised_ok = success;
  150. }