mixer.cpp 7.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221
  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. mixer for failsafe operation when FMU is dead
  15. */
  16. #include <AP_HAL/AP_HAL.h>
  17. #include <AP_Math/AP_Math.h>
  18. #include <SRV_Channel/SRV_Channel.h>
  19. #include "iofirmware.h"
  20. #define ANGLE_SCALE ((int32_t)4500)
  21. #define RANGE_SCALE ((int32_t)1000)
  22. /*
  23. return a RC input value scaled from -4500 to 4500
  24. */
  25. int16_t AP_IOMCU_FW::mix_input_angle(uint8_t channel, uint16_t radio_in) const
  26. {
  27. const uint16_t &rc_min = mixing.rc_min[channel];
  28. const uint16_t &rc_max = mixing.rc_max[channel];
  29. const uint16_t &rc_trim = mixing.rc_trim[channel];
  30. const uint16_t &reversed = mixing.rc_reversed[channel];
  31. int16_t ret = 0;
  32. if (radio_in > rc_trim && rc_max != rc_trim) {
  33. ret = (ANGLE_SCALE * (int32_t)(radio_in - rc_trim)) / (int32_t)(rc_max - rc_trim);
  34. } else if (radio_in < rc_trim && rc_trim != rc_min) {
  35. ret = (ANGLE_SCALE * (int32_t)(radio_in - rc_trim)) / (int32_t)(rc_trim - rc_min);
  36. }
  37. if (reversed) {
  38. ret = -ret;
  39. }
  40. return ret;
  41. }
  42. /*
  43. return a RC input value scaled from 0 to 1000
  44. */
  45. int16_t AP_IOMCU_FW::mix_input_range(uint8_t channel, uint16_t radio_in) const
  46. {
  47. const uint16_t &rc_min = mixing.rc_min[channel];
  48. const uint16_t &rc_max = mixing.rc_max[channel];
  49. const uint16_t &reversed = mixing.rc_reversed[channel];
  50. int16_t ret = 0;
  51. if (radio_in > rc_max) {
  52. ret = RANGE_SCALE;
  53. } else if (radio_in < rc_min) {
  54. ret = -RANGE_SCALE;
  55. } else {
  56. ret = (RANGE_SCALE * (int32_t)(radio_in - rc_min)) / (int32_t)(rc_max - rc_min);
  57. }
  58. if (reversed) {
  59. ret = -ret;
  60. }
  61. return ret;
  62. }
  63. /*
  64. return an output pwm giving an angle for a servo channel
  65. */
  66. uint16_t AP_IOMCU_FW::mix_output_angle(uint8_t channel, int16_t angle) const
  67. {
  68. const uint16_t &srv_min = mixing.servo_min[channel];
  69. const uint16_t &srv_max = mixing.servo_max[channel];
  70. const uint16_t &srv_trim = mixing.servo_trim[channel];
  71. const uint16_t &reversed = mixing.servo_reversed[channel];
  72. if (reversed) {
  73. angle = -angle;
  74. }
  75. angle = constrain_int16(angle, -ANGLE_SCALE, ANGLE_SCALE);
  76. if (angle > 0) {
  77. return srv_trim + ((int32_t)angle * (int32_t)(srv_max - srv_trim)) / ANGLE_SCALE;
  78. }
  79. return srv_trim - (-(int32_t)angle * (int32_t)(srv_trim - srv_min)) / ANGLE_SCALE;
  80. }
  81. /*
  82. return an output pwm giving an range for a servo channel
  83. */
  84. uint16_t AP_IOMCU_FW::mix_output_range(uint8_t channel, int16_t value) const
  85. {
  86. const uint16_t &srv_min = mixing.servo_min[channel];
  87. const uint16_t &srv_max = mixing.servo_max[channel];
  88. const uint16_t &reversed = mixing.servo_reversed[channel];
  89. value = constrain_int16(value, 0, RANGE_SCALE);
  90. if (reversed) {
  91. value = RANGE_SCALE - value;
  92. }
  93. return srv_min + ((int32_t)value * (int32_t)(srv_max - srv_min)) / RANGE_SCALE;
  94. }
  95. /*
  96. elevon and vtail mixer
  97. */
  98. int16_t AP_IOMCU_FW::mix_elevon_vtail(int16_t angle1, int16_t angle2, bool first_output) const
  99. {
  100. if (first_output) {
  101. return (angle2 - angle1) * mixing.mixing_gain / 1000;
  102. }
  103. return (angle1 + angle2) * mixing.mixing_gain / 1000;
  104. }
  105. /*
  106. run mixer. This is used when FMU is not providing inputs, or when
  107. the OVERRIDE_CHAN is high. It allows for manual fixed wing flight
  108. */
  109. void AP_IOMCU_FW::run_mixer(void)
  110. {
  111. int16_t rcin[4] = {0, 0, 0, 0};
  112. int16_t &roll = rcin[0];
  113. int16_t &pitch = rcin[1];
  114. int16_t &throttle = rcin[2];
  115. int16_t &rudder = rcin[3];
  116. // get RC input angles
  117. if (rc_input.flags_rc_ok) {
  118. for (uint8_t i=0;i<4; i++) {
  119. if (mixing.rc_channel[i] > 0 && mixing.rc_channel[i] <= IOMCU_MAX_CHANNELS) {
  120. uint8_t chan = mixing.rc_channel[i]-1;
  121. if (i == 2 && !mixing.throttle_is_angle) {
  122. rcin[i] = mix_input_range(i, rc_input.pwm[chan]);
  123. } else {
  124. rcin[i] = mix_input_angle(i, rc_input.pwm[chan]);
  125. }
  126. }
  127. }
  128. }
  129. for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
  130. SRV_Channel::Aux_servo_function_t function = (SRV_Channel::Aux_servo_function_t)mixing.servo_function[i];
  131. uint16_t &pwm = reg_direct_pwm.pwm[i];
  132. if (mixing.manual_rc_mask & (1U<<i)) {
  133. // treat as pass-thru if this channel is set in MANUAL_RC_MASK
  134. function = SRV_Channel::k_manual;
  135. }
  136. switch (function) {
  137. case SRV_Channel::k_manual:
  138. pwm = rc_input.pwm[i];
  139. break;
  140. case SRV_Channel::k_rcin1 ... SRV_Channel::k_rcin16:
  141. pwm = rc_input.pwm[(uint8_t)(function - SRV_Channel::k_rcin1)];
  142. break;
  143. case SRV_Channel::k_aileron:
  144. case SRV_Channel::k_aileron_with_input:
  145. case SRV_Channel::k_flaperon_left:
  146. case SRV_Channel::k_flaperon_right:
  147. pwm = mix_output_angle(i, roll);
  148. break;
  149. case SRV_Channel::k_elevator:
  150. case SRV_Channel::k_elevator_with_input:
  151. pwm = mix_output_angle(i, pitch);
  152. break;
  153. case SRV_Channel::k_rudder:
  154. case SRV_Channel::k_steering:
  155. pwm = mix_output_angle(i, rudder);
  156. break;
  157. case SRV_Channel::k_throttle:
  158. case SRV_Channel::k_throttleLeft:
  159. case SRV_Channel::k_throttleRight:
  160. if (mixing.throttle_is_angle) {
  161. pwm = mix_output_angle(i, throttle);
  162. } else {
  163. pwm = mix_output_range(i, throttle);
  164. }
  165. break;
  166. case SRV_Channel::k_flap:
  167. case SRV_Channel::k_flap_auto:
  168. // zero flaps
  169. pwm = mix_output_range(i, 0);
  170. break;
  171. case SRV_Channel::k_elevon_left:
  172. case SRV_Channel::k_dspoilerLeft1:
  173. case SRV_Channel::k_dspoilerLeft2:
  174. // treat differential spoilers as elevons
  175. pwm = mix_output_angle(i, mix_elevon_vtail(roll, pitch, true));
  176. break;
  177. case SRV_Channel::k_elevon_right:
  178. case SRV_Channel::k_dspoilerRight1:
  179. case SRV_Channel::k_dspoilerRight2:
  180. // treat differential spoilers as elevons
  181. pwm = mix_output_angle(i, mix_elevon_vtail(roll, pitch, false));
  182. break;
  183. case SRV_Channel::k_vtail_left:
  184. pwm = mix_output_angle(i, mix_elevon_vtail(rudder, pitch, false));
  185. break;
  186. case SRV_Channel::k_vtail_right:
  187. pwm = mix_output_angle(i, mix_elevon_vtail(rudder, pitch, true));
  188. break;
  189. default:
  190. break;
  191. }
  192. }
  193. }