APM:Libraries
AC_Sprayer.h
Go to the documentation of this file.
1 
15 #pragma once
16 
17 #include <inttypes.h>
18 #include <AP_Common/AP_Common.h>
19 #include <AP_Param/AP_Param.h>
20 #include <AP_Math/AP_Math.h>
22 #include <AP_AHRS/AP_AHRS.h>
23 
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
30 
31 class AC_Sprayer {
34 public:
35  AC_Sprayer();
36 
37  /* Do not allow copies */
38  AC_Sprayer(const AC_Sprayer &other) = delete;
39  AC_Sprayer &operator=(const AC_Sprayer&) = delete;
40 
42  void run(bool true_false);
43 
45  bool running() const { return _flags.running; }
46 
48  bool spraying() const { return _flags.spraying; }
49 
51  void test_pump(bool true_false) { _flags.testing = true_false; }
52 
54 
56  void set_pump_rate(float pct_at_1ms) { _pump_pct_1ms.set(pct_at_1ms); }
57 
59  void update();
60 
61  static const struct AP_Param::GroupInfo var_info[];
62 
63 private:
64 
65  // parameters
66  AP_Int8 _enabled;
67  AP_Float _pump_pct_1ms;
68  AP_Int8 _pump_min_pct;
69  AP_Int16 _spinner_pwm;
70  AP_Float _speed_min;
71 
74  uint8_t spraying : 1;
75  uint8_t testing : 1;
76  uint8_t running : 1;
77  } _flags;
78 
79  // internal variables
82 
83  void stop_spraying();
84 };
void test_pump(bool true_false)
test_pump - set to true to turn on pump as if travelling at 1m/s as a test
Definition: AC_Sprayer.h:51
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 ...
Definition: AC_Sprayer.h:67
AP_Float _speed_min
minimum speed in cm/s above which the sprayer will be started
Definition: AC_Sprayer.h:70
void set_pump_rate(float pct_at_1ms)
To-Do: add function to decode pilot input from channel 6 tuning knob.
Definition: AC_Sprayer.h:56
void run(bool true_false)
run - allow or disallow spraying to occur
Definition: AC_Sprayer.cpp:66
bool spraying() const
spraying - returns true if spraying is actually happening
Definition: AC_Sprayer.h:48
AP_Int8 _enabled
top level enable/disable control
Definition: AC_Sprayer.h:66
struct AC_Sprayer::sprayer_flags_type _flags
uint32_t _speed_over_min_time
time at which we reached speed minimum
Definition: AC_Sprayer.h:80
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
Definition: AC_Sprayer.h:75
uint8_t running
1 if we are permitted to run sprayer
Definition: AC_Sprayer.h:76
void update()
update - adjusts servo positions based on speed and requested quantity
Definition: AC_Sprayer.cpp:92
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_Sprayer.h:61
AP_Int16 _spinner_pwm
pwm rate of spinner
Definition: AC_Sprayer.h:69
void stop_spraying()
Definition: AC_Sprayer.cpp:83
AP_Int8 _pump_min_pct
minimum pump rate (expressed as a percentage from 0 to 100)
Definition: AC_Sprayer.h:68
Common definitions and utility routines for the ArduPilot libraries.
bool running() const
running - returns true if spraying is currently permitted
Definition: AC_Sprayer.h:45
Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm...
Definition: AC_Sprayer.h:33
uint32_t _speed_under_min_time
time at which we fell below speed minimum
Definition: AC_Sprayer.h:81
uint8_t spraying
1 if we are currently spraying
Definition: AC_Sprayer.h:74