24 #define AC_SPRAYER_DEFAULT_PUMP_RATE        10.0f       25 #define AC_SPRAYER_DEFAULT_PUMP_MIN         0           26 #define AC_SPRAYER_DEFAULT_SPINNER_PWM      1300        27 #define AC_SPRAYER_DEFAULT_SPEED_MIN        100         28 #define AC_SPRAYER_DEFAULT_TURN_ON_DELAY    100         29 #define AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY   1000        42     void run(
bool true_false);
 void test_pump(bool true_false)
test_pump - set to true to turn on pump as if travelling at 1m/s as a test 
AC_Sprayer & operator=(const AC_Sprayer &)=delete
AP_Float _pump_pct_1ms
desired pump rate (expressed as a percentage of top rate) when travelling at 1m/s ...
AP_Float _speed_min
minimum speed in cm/s above which the sprayer will be started 
void set_pump_rate(float pct_at_1ms)
To-Do: add function to decode pilot input from channel 6 tuning knob. 
void run(bool true_false)
run - allow or disallow spraying to occur 
bool spraying() const
spraying - returns true if spraying is actually happening 
AP_Int8 _enabled
top level enable/disable control 
struct AC_Sprayer::sprayer_flags_type _flags
uint32_t _speed_over_min_time
time at which we reached speed minimum 
A system for managing and storing variables that are of general interest to the system. 
uint8_t testing
1 if we are testing the sprayer and should output a minimum value 
uint8_t running
1 if we are permitted to run sprayer 
void update()
update - adjusts servo positions based on speed and requested quantity 
static const struct AP_Param::GroupInfo var_info[]
AP_Int16 _spinner_pwm
pwm rate of spinner 
AP_Int8 _pump_min_pct
minimum pump rate (expressed as a percentage from 0 to 100) 
Common definitions and utility routines for the ArduPilot libraries. 
bool running() const
running - returns true if spraying is currently permitted 
Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm...
uint32_t _speed_under_min_time
time at which we fell below speed minimum 
uint8_t spraying
1 if we are currently spraying