56 if (_pump_pct_1ms < 0.0f || _pump_pct_1ms > 100.0
f) {
107 if (!
AP::ahrs().get_velocity_NED(velocity)) {
112 float ground_speed =
norm(velocity.
x * 100.0f, velocity.
y * 100.0f);
128 should_be_spraying =
true;
144 should_be_spraying =
false;
155 ground_speed = 100.0f;
156 should_be_spraying =
true;
160 if (should_be_spraying) {
163 pos =
MIN(pos,10000);
float norm(const T first, const U second, const Params... parameters)
static void move_servo(SRV_Channel::Aux_servo_function_t function, int16_t value, int16_t angle_min, int16_t angle_max)
#define AP_PARAM_FLAG_ENABLE
#define AC_SPRAYER_DEFAULT_PUMP_MIN
default minimum pump speed expressed as a percentage from 0 to 100
crop sprayer pump channel
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
#define AP_GROUPINFO(name, idx, clazz, element, def)
void run(bool true_false)
run - allow or disallow spraying to occur
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
crop sprayer spinner channel
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
#define AC_SPRAYER_DEFAULT_PUMP_RATE
default quantity of spray per meter travelled
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
#define AC_SPRAYER_DEFAULT_SPINNER_PWM
default speed of spinner (higher means spray is throw further horizontally
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[]
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
AP_Int16 _spinner_pwm
pwm rate of spinner
AP_Int8 _pump_min_pct
minimum pump rate (expressed as a percentage from 0 to 100)
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...
#define AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY
shut-off delay in milli seconds. This reduces the likelihood of constantly turning on/off the pump ...
#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...
#define AC_SPRAYER_DEFAULT_SPEED_MIN
we must be travelling at least 1m/s to begin spraying
uint32_t _speed_under_min_time
time at which we fell below speed minimum
static bool function_assigned(SRV_Channel::Aux_servo_function_t function)
uint8_t spraying
1 if we are currently spraying
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)