AP_Motors_Class.cpp 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178
  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_Motors.cpp - ArduCopter motors library
  15. * Code by RandyMackay. DIYDrones.com
  16. *
  17. */
  18. #include "AP_Motors_Class.h"
  19. #include <AP_HAL/AP_HAL.h>
  20. #include <SRV_Channel/SRV_Channel.h>
  21. #include <GCS_MAVLink/GCS.h>
  22. extern const AP_HAL::HAL& hal;
  23. // singleton instance
  24. AP_Motors *AP_Motors::_singleton;
  25. // Constructor
  26. AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
  27. _loop_rate(loop_rate),
  28. _speed_hz(speed_hz),
  29. _throttle_filter(),
  30. _spool_desired(DesiredSpoolState::SHUT_DOWN),
  31. _spool_state(SpoolState::SHUT_DOWN),
  32. _air_density_ratio(1.0f)
  33. {
  34. _singleton = this;
  35. // setup throttle filtering
  36. _throttle_filter.set_cutoff_frequency(0.0f);
  37. _throttle_filter.reset(0.0f);
  38. // init limit flags
  39. limit.roll = true;
  40. limit.pitch = true;
  41. limit.yaw = true;
  42. limit.throttle_lower = true;
  43. limit.throttle_upper = true;
  44. _thrust_boost = false;
  45. _thrust_balanced = true;
  46. };
  47. void AP_Motors::armed(bool arm)
  48. {
  49. if (_flags.armed != arm) {
  50. _flags.armed = arm;
  51. AP_Notify::flags.armed = arm;
  52. if (!arm) {
  53. save_params_on_disarm();
  54. }
  55. }
  56. };
  57. void AP_Motors::set_desired_spool_state(DesiredSpoolState spool)
  58. {
  59. if (_flags.armed || (spool == DesiredSpoolState::SHUT_DOWN)) {
  60. _spool_desired = spool;
  61. }
  62. };
  63. // pilot input in the -1 ~ +1 range for roll, pitch and yaw. 0~1 range for throttle
  64. void AP_Motors::set_radio_passthrough(float roll_input, float pitch_input, float throttle_input, float yaw_input)
  65. {
  66. _roll_radio_passthrough = roll_input;
  67. _pitch_radio_passthrough = pitch_input;
  68. _throttle_radio_passthrough = throttle_input;
  69. _yaw_radio_passthrough = yaw_input;
  70. }
  71. /*
  72. write to an output channel
  73. */
  74. void AP_Motors::rc_write(uint8_t chan, uint16_t pwm)
  75. {
  76. SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(chan);
  77. SRV_Channels::set_output_pwm(function, pwm);
  78. }
  79. /*
  80. write to an output channel for an angle actuator
  81. */
  82. void AP_Motors::rc_write_angle(uint8_t chan, int16_t angle_cd)
  83. {
  84. SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(chan);
  85. SRV_Channels::set_output_scaled(function, angle_cd);
  86. }
  87. /*
  88. set frequency of a set of channels
  89. */
  90. void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
  91. {
  92. if (freq_hz > 50) {
  93. _motor_fast_mask |= mask;
  94. }
  95. mask = rc_map_mask(mask);
  96. hal.rcout->set_freq(mask, freq_hz);
  97. switch (pwm_type(_pwm_type.get())) {
  98. case PWM_TYPE_ONESHOT:
  99. if (freq_hz > 50 && mask != 0) {
  100. hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT);
  101. }
  102. break;
  103. case PWM_TYPE_ONESHOT125:
  104. if (freq_hz > 50 && mask != 0) {
  105. hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_ONESHOT125);
  106. }
  107. break;
  108. case PWM_TYPE_BRUSHED:
  109. hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED);
  110. break;
  111. case PWM_TYPE_DSHOT150:
  112. hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT150);
  113. break;
  114. case PWM_TYPE_DSHOT300:
  115. hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT300);
  116. break;
  117. case PWM_TYPE_DSHOT600:
  118. hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT600);
  119. break;
  120. case PWM_TYPE_DSHOT1200:
  121. hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_DSHOT1200);
  122. break;
  123. default:
  124. hal.rcout->set_output_mode(mask, AP_HAL::RCOutput::MODE_PWM_NORMAL);
  125. break;
  126. }
  127. }
  128. /*
  129. map an internal motor mask to real motor mask, accounting for
  130. SERVOn_FUNCTION mappings, and allowing for multiple outputs per
  131. motor number
  132. */
  133. uint32_t AP_Motors::rc_map_mask(uint32_t mask) const
  134. {
  135. uint32_t mask2 = 0;
  136. for (uint8_t i = 0; i < 32; i++) {
  137. uint32_t bit = 1UL << i;
  138. if (mask & bit) {
  139. SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(i);
  140. mask2 |= SRV_Channels::get_output_channel_mask(function);
  141. }
  142. }
  143. return mask2;
  144. }
  145. /*
  146. add a motor, setting up default output function as needed
  147. */
  148. void AP_Motors::add_motor_num(int8_t motor_num)
  149. {
  150. // ensure valid motor number is provided
  151. if (motor_num >= 0 && motor_num < AP_MOTORS_MAX_NUM_MOTORS) {
  152. uint8_t chan;
  153. SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(motor_num);
  154. SRV_Channels::set_aux_channel_default(function, motor_num);
  155. if (!SRV_Channels::find_channel(function, chan)) {
  156. gcs().send_text(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num);
  157. }
  158. }
  159. }