APM:Libraries
Classes | Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
AC_Sprayer Class Reference

Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm. More...

#include <AC_Sprayer.h>

Collaboration diagram for AC_Sprayer:
[legend]

Classes

struct  sprayer_flags_type
 flag bitmask More...
 

Public Member Functions

 AC_Sprayer ()
 
 AC_Sprayer (const AC_Sprayer &other)=delete
 
AC_Sprayeroperator= (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...
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ AC_Sprayer() [1/2]

AC_Sprayer::AC_Sprayer ( )

Definition at line 51 of file AC_Sprayer.cpp.

Here is the call graph for this function:

◆ AC_Sprayer() [2/2]

AC_Sprayer::AC_Sprayer ( const AC_Sprayer other)
delete

Member Function Documentation

◆ operator=()

AC_Sprayer& AC_Sprayer::operator= ( const AC_Sprayer )
delete

◆ run()

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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ running()

bool AC_Sprayer::running ( ) const
inline

running - returns true if spraying is currently permitted

Definition at line 45 of file AC_Sprayer.h.

Referenced by update().

Here is the caller graph for this function:

◆ set_pump_rate()

void AC_Sprayer::set_pump_rate ( float  pct_at_1ms)
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.

Here is the call graph for this function:

◆ spraying()

bool AC_Sprayer::spraying ( ) const
inline

spraying - returns true if spraying is actually happening

Definition at line 48 of file AC_Sprayer.h.

◆ stop_spraying()

void AC_Sprayer::stop_spraying ( )
private

Definition at line 83 of file AC_Sprayer.cpp.

Referenced by run(), and update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ test_pump()

void AC_Sprayer::test_pump ( bool  true_false)
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.

◆ update()

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().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _enabled

AP_Int8 AC_Sprayer::_enabled
private

top level enable/disable control

Definition at line 66 of file AC_Sprayer.h.

Referenced by run(), and update().

◆ _flags

struct AC_Sprayer::sprayer_flags_type AC_Sprayer::_flags
private

◆ _pump_min_pct

AP_Int8 AC_Sprayer::_pump_min_pct
private

minimum pump rate (expressed as a percentage from 0 to 100)

Definition at line 68 of file AC_Sprayer.h.

Referenced by update().

◆ _pump_pct_1ms

AP_Float AC_Sprayer::_pump_pct_1ms
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().

◆ _speed_min

AP_Float AC_Sprayer::_speed_min
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().

◆ _speed_over_min_time

uint32_t AC_Sprayer::_speed_over_min_time
private

time at which we reached speed minimum

Definition at line 80 of file AC_Sprayer.h.

Referenced by update().

◆ _speed_under_min_time

uint32_t AC_Sprayer::_speed_under_min_time
private

time at which we fell below speed minimum

Definition at line 81 of file AC_Sprayer.h.

Referenced by update().

◆ _spinner_pwm

AP_Int16 AC_Sprayer::_spinner_pwm
private

pwm rate of spinner

Definition at line 69 of file AC_Sprayer.h.

Referenced by AC_Sprayer(), and update().

◆ var_info

const AP_Param::GroupInfo AC_Sprayer::var_info
static

Definition at line 61 of file AC_Sprayer.h.

Referenced by AC_Sprayer().


The documentation for this class was generated from the following files: