AC_Sprayer.cpp 6.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200
  1. #include "AC_Sprayer.h"
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #include <AP_HAL/AP_HAL.h>
  4. #include <AP_Math/AP_Math.h>
  5. #include <SRV_Channel/SRV_Channel.h>
  6. extern const AP_HAL::HAL& hal;
  7. // ------------------------------
  8. const AP_Param::GroupInfo AC_Sprayer::var_info[] = {
  9. // @Param: ENABLE
  10. // @DisplayName: Sprayer enable/disable
  11. // @Description: Allows you to enable (1) or disable (0) the sprayer
  12. // @Values: 0:Disabled,1:Enabled
  13. // @User: Standard
  14. AP_GROUPINFO_FLAGS("ENABLE", 0, AC_Sprayer, _enabled, 0, AP_PARAM_FLAG_ENABLE),
  15. // @Param: PUMP_RATE
  16. // @DisplayName: Pump speed
  17. // @Description: Desired pump speed when traveling 1m/s expressed as a percentage
  18. // @Units: %
  19. // @Range: 0 100
  20. // @User: Standard
  21. AP_GROUPINFO("PUMP_RATE", 1, AC_Sprayer, _pump_pct_1ms, AC_SPRAYER_DEFAULT_PUMP_RATE),
  22. // @Param: SPINNER
  23. // @DisplayName: Spinner rotation speed
  24. // @Description: Spinner's rotation speed in PWM (a higher rate will disperse the spray over a wider area horizontally)
  25. // @Units: ms
  26. // @Range: 1000 2000
  27. // @User: Standard
  28. AP_GROUPINFO("SPINNER", 2, AC_Sprayer, _spinner_pwm, AC_SPRAYER_DEFAULT_SPINNER_PWM),
  29. // @Param: SPEED_MIN
  30. // @DisplayName: Speed minimum
  31. // @Description: Speed minimum at which we will begin spraying
  32. // @Units: cm/s
  33. // @Range: 0 1000
  34. // @User: Standard
  35. AP_GROUPINFO("SPEED_MIN", 3, AC_Sprayer, _speed_min, AC_SPRAYER_DEFAULT_SPEED_MIN),
  36. // @Param: PUMP_MIN
  37. // @DisplayName: Pump speed minimum
  38. // @Description: Minimum pump speed expressed as a percentage
  39. // @Units: %
  40. // @Range: 0 100
  41. // @User: Standard
  42. AP_GROUPINFO("PUMP_MIN", 4, AC_Sprayer, _pump_min_pct, AC_SPRAYER_DEFAULT_PUMP_MIN),
  43. AP_GROUPEND
  44. };
  45. AC_Sprayer::AC_Sprayer()
  46. {
  47. if (_singleton) {
  48. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  49. AP_HAL::panic("Too many sprayers");
  50. #endif
  51. return;
  52. }
  53. _singleton = this;
  54. AP_Param::setup_object_defaults(this, var_info);
  55. // check for silly parameter values
  56. if (_pump_pct_1ms < 0.0f || _pump_pct_1ms > 100.0f) {
  57. _pump_pct_1ms.set_and_save(AC_SPRAYER_DEFAULT_PUMP_RATE);
  58. }
  59. if (_spinner_pwm < 0) {
  60. _spinner_pwm.set_and_save(AC_SPRAYER_DEFAULT_SPINNER_PWM);
  61. }
  62. // To-Do: ensure that the pump and spinner servo channels are enabled
  63. }
  64. /*
  65. * Get the AP_Sprayer singleton
  66. */
  67. AC_Sprayer *AC_Sprayer::_singleton;
  68. AC_Sprayer *AC_Sprayer::get_singleton()
  69. {
  70. return _singleton;
  71. }
  72. void AC_Sprayer::run(const bool true_false)
  73. {
  74. // return immediately if no change
  75. if (true_false == _flags.running) {
  76. return;
  77. }
  78. // set flag indicate whether spraying is permitted:
  79. // do not allow running to be set to true if we are currently not enabled
  80. _flags.running = true_false && _enabled;
  81. // turn off the pump and spinner servos if necessary
  82. if (!_flags.running) {
  83. stop_spraying();
  84. }
  85. }
  86. void AC_Sprayer::stop_spraying()
  87. {
  88. SRV_Channels::set_output_limit(SRV_Channel::k_sprayer_pump, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
  89. SRV_Channels::set_output_limit(SRV_Channel::k_sprayer_spinner, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
  90. _flags.spraying = false;
  91. }
  92. /// update - adjust pwm of servo controlling pump speed according to the desired quantity and our horizontal speed
  93. void AC_Sprayer::update()
  94. {
  95. // exit immediately if we are disabled or shouldn't be running
  96. if (!_enabled || !running()) {
  97. run(false);
  98. return;
  99. }
  100. // exit immediately if the pump function has not been set-up for any servo
  101. if (!SRV_Channels::function_assigned(SRV_Channel::k_sprayer_pump)) {
  102. return;
  103. }
  104. // get horizontal velocity
  105. Vector3f velocity;
  106. if (!AP::ahrs().get_velocity_NED(velocity)) {
  107. // treat unknown velocity as zero which should lead to pump stopping
  108. // velocity will already be zero but this avoids a coverity warning
  109. velocity.zero();
  110. }
  111. float ground_speed = norm(velocity.x * 100.0f, velocity.y * 100.0f);
  112. // get the current time
  113. const uint32_t now = AP_HAL::millis();
  114. bool should_be_spraying = _flags.spraying;
  115. // check our speed vs the minimum
  116. if (ground_speed >= _speed_min) {
  117. // if we are not already spraying
  118. if (!_flags.spraying) {
  119. // set the timer if this is the first time we've surpassed the min speed
  120. if (_speed_over_min_time == 0) {
  121. _speed_over_min_time = now;
  122. }else{
  123. // check if we've been over the speed long enough to engage the sprayer
  124. if((now - _speed_over_min_time) > AC_SPRAYER_DEFAULT_TURN_ON_DELAY) {
  125. should_be_spraying = true;
  126. _speed_over_min_time = 0;
  127. }
  128. }
  129. }
  130. // reset the speed under timer
  131. _speed_under_min_time = 0;
  132. } else {
  133. // we are under the min speed.
  134. if (_flags.spraying) {
  135. // set the timer if this is the first time we've dropped below the min speed
  136. if (_speed_under_min_time == 0) {
  137. _speed_under_min_time = now;
  138. }else{
  139. // check if we've been over the speed long enough to engage the sprayer
  140. if((now - _speed_under_min_time) > AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY) {
  141. should_be_spraying = false;
  142. _speed_under_min_time = 0;
  143. }
  144. }
  145. }
  146. // reset the speed over timer
  147. _speed_over_min_time = 0;
  148. }
  149. // if testing pump output speed as if traveling at 1m/s
  150. if (_flags.testing) {
  151. ground_speed = 100.0f;
  152. should_be_spraying = true;
  153. }
  154. // if spraying or testing update the pump servo position
  155. if (should_be_spraying) {
  156. float pos = ground_speed * _pump_pct_1ms;
  157. pos = MAX(pos, 100 *_pump_min_pct); // ensure min pump speed
  158. pos = MIN(pos,10000); // clamp to range
  159. SRV_Channels::move_servo(SRV_Channel::k_sprayer_pump, pos, 0, 10000);
  160. SRV_Channels::set_output_pwm(SRV_Channel::k_sprayer_spinner, _spinner_pwm);
  161. _flags.spraying = true;
  162. } else {
  163. stop_spraying();
  164. }
  165. }
  166. namespace AP {
  167. AC_Sprayer *sprayer()
  168. {
  169. return AC_Sprayer::get_singleton();
  170. }
  171. };