APM:Libraries
AC_Sprayer.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include "AC_Sprayer.h"
3 
4 extern const AP_HAL::HAL& hal;
5 
6 // ------------------------------
7 
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 
16  // @Param: PUMP_RATE
17  // @DisplayName: Pump speed
18  // @Description: Desired pump speed when traveling 1m/s expressed as a percentage
19  // @Units: %
20  // @Range: 0 100
21  // @User: Standard
22  AP_GROUPINFO("PUMP_RATE", 1, AC_Sprayer, _pump_pct_1ms, AC_SPRAYER_DEFAULT_PUMP_RATE),
23 
24  // @Param: SPINNER
25  // @DisplayName: Spinner rotation speed
26  // @Description: Spinner's rotation speed in PWM (a higher rate will disperse the spray over a wider area horizontally)
27  // @Units: ms
28  // @Range: 1000 2000
29  // @User: Standard
30  AP_GROUPINFO("SPINNER", 2, AC_Sprayer, _spinner_pwm, AC_SPRAYER_DEFAULT_SPINNER_PWM),
31 
32  // @Param: SPEED_MIN
33  // @DisplayName: Speed minimum
34  // @Description: Speed minimum at which we will begin spraying
35  // @Units: cm/s
36  // @Range: 0 1000
37  // @User: Standard
38  AP_GROUPINFO("SPEED_MIN", 3, AC_Sprayer, _speed_min, AC_SPRAYER_DEFAULT_SPEED_MIN),
39 
40  // @Param: PUMP_MIN
41  // @DisplayName: Pump speed minimum
42  // @Description: Minimum pump speed expressed as a percentage
43  // @Units: %
44  // @Range: 0 100
45  // @User: Standard
46  AP_GROUPINFO("PUMP_MIN", 4, AC_Sprayer, _pump_min_pct, AC_SPRAYER_DEFAULT_PUMP_MIN),
47 
49 };
50 
52 {
54 
55  // check for silly parameter values
56  if (_pump_pct_1ms < 0.0f || _pump_pct_1ms > 100.0f) {
58  }
59  if (_spinner_pwm < 0) {
61  }
62 
63  // To-Do: ensure that the pump and spinner servo channels are enabled
64 }
65 
66 void AC_Sprayer::run(const bool true_false)
67 {
68  // return immediately if no change
69  if (true_false == _flags.running) {
70  return;
71  }
72 
73  // set flag indicate whether spraying is permitted:
74  // do not allow running to be set to true if we are currently not enabled
75  _flags.running = true_false && _enabled;
76 
77  // turn off the pump and spinner servos if necessary
78  if (!_flags.running) {
79  stop_spraying();
80  }
81 }
82 
84 {
87 
88  _flags.spraying = false;
89 }
90 
93 {
94  // exit immediately if we are disabled or shouldn't be running
95  if (!_enabled || !running()) {
96  run(false);
97  return;
98  }
99 
100  // exit immediately if the pump function has not been set-up for any servo
102  return;
103  }
104 
105  // get horizontal velocity
106  Vector3f velocity;
107  if (!AP::ahrs().get_velocity_NED(velocity)) {
108  // treat unknown velocity as zero which should lead to pump stopping
109  // velocity will already be zero but this avoids a coverity warning
110  velocity.zero();
111  }
112  float ground_speed = norm(velocity.x * 100.0f, velocity.y * 100.0f);
113 
114  // get the current time
115  const uint32_t now = AP_HAL::millis();
116 
117  bool should_be_spraying = _flags.spraying;
118  // check our speed vs the minimum
119  if (ground_speed >= _speed_min) {
120  // if we are not already spraying
121  if (!_flags.spraying) {
122  // set the timer if this is the first time we've surpassed the min speed
123  if (_speed_over_min_time == 0) {
124  _speed_over_min_time = now;
125  }else{
126  // check if we've been over the speed long enough to engage the sprayer
128  should_be_spraying = true;
130  }
131  }
132  }
133  // reset the speed under timer
135  } else {
136  // we are under the min speed.
137  if (_flags.spraying) {
138  // set the timer if this is the first time we've dropped below the min speed
139  if (_speed_under_min_time == 0) {
140  _speed_under_min_time = now;
141  }else{
142  // check if we've been over the speed long enough to engage the sprayer
144  should_be_spraying = false;
146  }
147  }
148  }
149  // reset the speed over timer
151  }
152 
153  // if testing pump output speed as if traveling at 1m/s
154  if (_flags.testing) {
155  ground_speed = 100.0f;
156  should_be_spraying = true;
157  }
158 
159  // if spraying or testing update the pump servo position
160  if (should_be_spraying) {
161  float pos = ground_speed * _pump_pct_1ms;
162  pos = MAX(pos, 100 *_pump_min_pct); // ensure min pump speed
163  pos = MIN(pos,10000); // clamp to range
166  _flags.spraying = true;
167  } else {
168  stop_spraying();
169  }
170 }
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
static void move_servo(SRV_Channel::Aux_servo_function_t function, int16_t value, int16_t angle_min, int16_t angle_max)
Crop sprayer library.
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
#define AC_SPRAYER_DEFAULT_PUMP_MIN
default minimum pump speed expressed as a percentage from 0 to 100
Definition: AC_Sprayer.h:25
crop sprayer pump channel
Definition: SRV_Channel.h:66
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
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void run(bool true_false)
run - allow or disallow spraying to occur
Definition: AC_Sprayer.cpp:66
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
crop sprayer spinner channel
Definition: SRV_Channel.h:67
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
#define MIN(a, b)
Definition: usb_conf.h:215
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
#define AC_SPRAYER_DEFAULT_PUMP_RATE
default quantity of spray per meter travelled
Definition: AC_Sprayer.h:24
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
#define AC_SPRAYER_DEFAULT_SPINNER_PWM
default speed of spinner (higher means spray is throw further horizontally
Definition: AC_Sprayer.h:26
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
#define f(i)
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
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
bool running() const
running - returns true if spraying is currently permitted
Definition: AC_Sprayer.h:45
AP_AHRS & ahrs()
Definition: AP_AHRS.cpp:488
Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm...
Definition: AC_Sprayer.h:33
#define AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY
shut-off delay in milli seconds. This reduces the likelihood of constantly turning on/off the pump ...
Definition: AC_Sprayer.h:29
#define AC_SPRAYER_DEFAULT_TURN_ON_DELAY
delay between when we reach the minimum speed and we begin spraying. This reduces the likelihood of c...
Definition: AC_Sprayer.h:28
#define AC_SPRAYER_DEFAULT_SPEED_MIN
we must be travelling at least 1m/s to begin spraying
Definition: AC_Sprayer.h:27
uint32_t _speed_under_min_time
time at which we fell below speed minimum
Definition: AC_Sprayer.h:81
static bool function_assigned(SRV_Channel::Aux_servo_function_t function)
#define AP_GROUPEND
Definition: AP_Param.h:121
uint8_t spraying
1 if we are currently spraying
Definition: AC_Sprayer.h:74
void zero()
Definition: vector3.h:182
T x
Definition: vector3.h:67
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214