AC_Sprayer.h 4.7 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788
  1. /// @file AC_Sprayer.h
  2. /// @brief Crop sprayer library
  3. /**
  4. The crop spraying functionality can be enabled in ArduCopter by doing the following:
  5. - set RC7_OPTION or RC8_OPTION parameter to 15 to allow turning the sprayer on/off from one of these channels
  6. - set SERVO10_FUNCTION to 22 to enable the servo output controlling the pump speed on servo-out 10
  7. - set SERVO11_FUNCTION to 23 to enable the servo output controlling the spinner on servo-out 11
  8. - ensure the RC10_MIN, RC10_MAX, RC11_MIN, RC11_MAX accurately hold the min and maximum servo values you could possibly output to the pump and spinner
  9. - set the SPRAY_SPINNER to the pwm value the spinner should spin at when on
  10. - set the SPRAY_PUMP_RATE to the value the pump servo should move to when the vehicle is travelling 1m/s expressed as a percentage (i.e. 0 ~ 100) of the full servo range. I.e. 0 = the pump will not operate, 100 = maximum speed at 1m/s. 50 = 1/2 speed at 1m/s, full speed at 2m/s
  11. - set the SPRAY_PUMP_MIN to the minimum value that the pump servo should move to while engaged expressed as a percentage (i.e. 0 ~ 100) of the full servo range
  12. - set the SPRAY_SPEED_MIN to the minimum speed (in cm/s) the vehicle should be moving at before the pump and sprayer are turned on. 0 will mean the pump and spinner will always be on when the system is enabled with ch7/ch8 switch
  13. **/
  14. #pragma once
  15. #include <inttypes.h>
  16. #include <AP_Common/AP_Common.h>
  17. #include <AP_Param/AP_Param.h>
  18. #define AC_SPRAYER_DEFAULT_PUMP_RATE 10.0f ///< default quantity of spray per meter travelled
  19. #define AC_SPRAYER_DEFAULT_PUMP_MIN 0 ///< default minimum pump speed expressed as a percentage from 0 to 100
  20. #define AC_SPRAYER_DEFAULT_SPINNER_PWM 1300 ///< default speed of spinner (higher means spray is throw further horizontally
  21. #define AC_SPRAYER_DEFAULT_SPEED_MIN 100 ///< we must be travelling at least 1m/s to begin spraying
  22. #define AC_SPRAYER_DEFAULT_TURN_ON_DELAY 100 ///< delay between when we reach the minimum speed and we begin spraying. This reduces the likelihood of constantly turning on/off the pump
  23. #define AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY 1000 ///< shut-off delay in milli seconds. This reduces the likelihood of constantly turning on/off the pump
  24. /// @class AC_Sprayer
  25. /// @brief Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm
  26. class AC_Sprayer {
  27. public:
  28. AC_Sprayer();
  29. /* Do not allow copies */
  30. AC_Sprayer(const AC_Sprayer &other) = delete;
  31. AC_Sprayer &operator=(const AC_Sprayer&) = delete;
  32. static AC_Sprayer *get_singleton();
  33. static AC_Sprayer *_singleton;
  34. /// run - allow or disallow spraying to occur
  35. void run(bool true_false);
  36. /// running - returns true if spraying is currently permitted
  37. bool running() const { return _flags.running; }
  38. /// spraying - returns true if spraying is actually happening
  39. bool spraying() const { return _flags.spraying; }
  40. /// test_pump - set to true to turn on pump as if travelling at 1m/s as a test
  41. void test_pump(bool true_false) { _flags.testing = true_false; }
  42. /// To-Do: add function to decode pilot input from channel 6 tuning knob
  43. /// set_pump_rate - sets desired quantity of spray when travelling at 1m/s as a percentage of the pumps maximum rate
  44. void set_pump_rate(float pct_at_1ms) { _pump_pct_1ms.set(pct_at_1ms); }
  45. /// update - adjusts servo positions based on speed and requested quantity
  46. void update();
  47. static const struct AP_Param::GroupInfo var_info[];
  48. private:
  49. // parameters
  50. AP_Int8 _enabled; ///< top level enable/disable control
  51. AP_Float _pump_pct_1ms; ///< desired pump rate (expressed as a percentage of top rate) when travelling at 1m/s
  52. AP_Int8 _pump_min_pct; ///< minimum pump rate (expressed as a percentage from 0 to 100)
  53. AP_Int16 _spinner_pwm; ///< pwm rate of spinner
  54. AP_Float _speed_min; ///< minimum speed in cm/s above which the sprayer will be started
  55. /// flag bitmask
  56. struct sprayer_flags_type {
  57. uint8_t spraying : 1; ///< 1 if we are currently spraying
  58. uint8_t testing : 1; ///< 1 if we are testing the sprayer and should output a minimum value
  59. uint8_t running : 1; ///< 1 if we are permitted to run sprayer
  60. } _flags;
  61. // internal variables
  62. uint32_t _speed_over_min_time; ///< time at which we reached speed minimum
  63. uint32_t _speed_under_min_time; ///< time at which we fell below speed minimum
  64. void stop_spraying();
  65. };
  66. namespace AP {
  67. AC_Sprayer *sprayer();
  68. };