|
APM:Libraries
|
Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm. More...
#include <AC_Sprayer.h>
Classes | |
| struct | sprayer_flags_type |
| flag bitmask More... | |
Public Member Functions | |
| AC_Sprayer () | |
| AC_Sprayer (const AC_Sprayer &other)=delete | |
| AC_Sprayer & | operator= (const AC_Sprayer &)=delete |
| void | run (bool true_false) |
| run - allow or disallow spraying to occur More... | |
| bool | running () const |
| running - returns true if spraying is currently permitted More... | |
| bool | spraying () const |
| spraying - returns true if spraying is actually happening More... | |
| void | test_pump (bool true_false) |
| test_pump - set to true to turn on pump as if travelling at 1m/s as a test More... | |
| void | set_pump_rate (float pct_at_1ms) |
| To-Do: add function to decode pilot input from channel 6 tuning knob. More... | |
| void | update () |
| update - adjusts servo positions based on speed and requested quantity More... | |
Static Public Attributes | |
| static const struct AP_Param::GroupInfo | var_info [] |
Private Member Functions | |
| void | stop_spraying () |
Private Attributes | |
| AP_Int8 | _enabled |
| top level enable/disable control More... | |
| AP_Float | _pump_pct_1ms |
| desired pump rate (expressed as a percentage of top rate) when travelling at 1m/s More... | |
| AP_Int8 | _pump_min_pct |
| minimum pump rate (expressed as a percentage from 0 to 100) More... | |
| AP_Int16 | _spinner_pwm |
| pwm rate of spinner More... | |
| AP_Float | _speed_min |
| minimum speed in cm/s above which the sprayer will be started More... | |
| struct AC_Sprayer::sprayer_flags_type | _flags |
| uint32_t | _speed_over_min_time |
| time at which we reached speed minimum More... | |
| uint32_t | _speed_under_min_time |
| time at which we fell below speed minimum More... | |
Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm.
Definition at line 33 of file AC_Sprayer.h.
| AC_Sprayer::AC_Sprayer | ( | ) |
|
delete |
|
delete |
| void AC_Sprayer::run | ( | bool | true_false | ) |
run - allow or disallow spraying to occur
Definition at line 66 of file AC_Sprayer.cpp.
Referenced by update().
|
inline |
running - returns true if spraying is currently permitted
Definition at line 45 of file AC_Sprayer.h.
Referenced by update().
|
inline |
To-Do: add function to decode pilot input from channel 6 tuning knob.
set_pump_rate - sets desired quantity of spray when travelling at 1m/s as a percentage of the pumps maximum rate
Definition at line 56 of file AC_Sprayer.h.
|
inline |
spraying - returns true if spraying is actually happening
Definition at line 48 of file AC_Sprayer.h.
|
private |
Definition at line 83 of file AC_Sprayer.cpp.
Referenced by run(), and update().
|
inline |
test_pump - set to true to turn on pump as if travelling at 1m/s as a test
Definition at line 51 of file AC_Sprayer.h.
| void AC_Sprayer::update | ( | ) |
update - adjusts servo positions based on speed and requested quantity
update - adjust pwm of servo controlling pump speed according to the desired quantity and our horizontal speed
Definition at line 92 of file AC_Sprayer.cpp.
Referenced by set_pump_rate().
|
private |
top level enable/disable control
Definition at line 66 of file AC_Sprayer.h.
|
private |
Referenced by run(), running(), spraying(), stop_spraying(), test_pump(), and update().
|
private |
minimum pump rate (expressed as a percentage from 0 to 100)
Definition at line 68 of file AC_Sprayer.h.
Referenced by update().
|
private |
desired pump rate (expressed as a percentage of top rate) when travelling at 1m/s
Definition at line 67 of file AC_Sprayer.h.
Referenced by AC_Sprayer(), set_pump_rate(), and update().
|
private |
minimum speed in cm/s above which the sprayer will be started
Definition at line 70 of file AC_Sprayer.h.
Referenced by update().
|
private |
time at which we reached speed minimum
Definition at line 80 of file AC_Sprayer.h.
Referenced by update().
|
private |
time at which we fell below speed minimum
Definition at line 81 of file AC_Sprayer.h.
Referenced by update().
|
private |
pwm rate of spinner
Definition at line 69 of file AC_Sprayer.h.
Referenced by AC_Sprayer(), and update().
|
static |
Definition at line 61 of file AC_Sprayer.h.
Referenced by AC_Sprayer().
1.8.13