APM:Libraries
Classes | Macros
AC_Sprayer.h File Reference

Crop sprayer library. More...

#include <inttypes.h>
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_AHRS/AP_AHRS.h>
Include dependency graph for AC_Sprayer.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  AC_Sprayer
 Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm. More...
 
struct  AC_Sprayer::sprayer_flags_type
 flag bitmask More...
 

Macros

#define AC_SPRAYER_DEFAULT_PUMP_RATE   10.0f
 default quantity of spray per meter travelled More...
 
#define AC_SPRAYER_DEFAULT_PUMP_MIN   0
 default minimum pump speed expressed as a percentage from 0 to 100 More...
 
#define AC_SPRAYER_DEFAULT_SPINNER_PWM   1300
 default speed of spinner (higher means spray is throw further horizontally More...
 
#define AC_SPRAYER_DEFAULT_SPEED_MIN   100
 we must be travelling at least 1m/s to begin spraying More...
 
#define AC_SPRAYER_DEFAULT_TURN_ON_DELAY   100
 delay between when we reach the minimum speed and we begin spraying. This reduces the likelihood of constantly turning on/off the pump More...
 
#define AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY   1000
 shut-off delay in milli seconds. This reduces the likelihood of constantly turning on/off the pump More...
 

Detailed Description

Crop sprayer library.

Definition in file AC_Sprayer.h.

Macro Definition Documentation

◆ AC_SPRAYER_DEFAULT_PUMP_MIN

#define AC_SPRAYER_DEFAULT_PUMP_MIN   0

default minimum pump speed expressed as a percentage from 0 to 100

Definition at line 25 of file AC_Sprayer.h.

◆ AC_SPRAYER_DEFAULT_PUMP_RATE

#define AC_SPRAYER_DEFAULT_PUMP_RATE   10.0f

default quantity of spray per meter travelled

The crop spraying functionality can be enabled in ArduCopter by doing the following:

  • set CH7_OPT or CH8_OPT parameter to 15 to allow turning the sprayer on/off from one of these channels
  • set RC10_FUNCTION to 22 to enable the servo output controlling the pump speed on servo-out 10
  • set RC11_FUNCTION to 23 to enable the servo output controlling the spinner on servo-out 11
  • ensure the RC10_MIN, RC10_MAX, RC11_MIN, RC11_MAX accurately hold the min and maximum servo values you could possibly output to the pump and spinner
  • set the SPRAY_SPINNER to the pwm value the spinner should spin at when on
  • set the SPRAY_PUMP_RATE to the value the pump servo should move to when the vehicle is travelling 1m/s expressed as a percentage (i.e. 0 ~ 100) of the full servo range. I.e. 0 = the pump will not operate, 100 = maximum speed at 1m/s. 50 = 1/2 speed at 1m/s, full speed at 2m/s
  • set the SPRAY_PUMP_MIN to the minimum value that the pump servo should move to while engaged expressed as a percentage (i.e. 0 ~ 100) of the full servo range
  • set the SPRAY_SPEED_MIN to the minimum speed (in cm/s) the vehicle should be moving at before the pump and sprayer are turned on. 0 will mean the pump and spinner will always be on when the system is enabled with ch7/ch8 switch

Definition at line 24 of file AC_Sprayer.h.

Referenced by AC_Sprayer::AC_Sprayer().

◆ AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY

#define AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY   1000

shut-off delay in milli seconds. This reduces the likelihood of constantly turning on/off the pump

Definition at line 29 of file AC_Sprayer.h.

Referenced by AC_Sprayer::update().

◆ AC_SPRAYER_DEFAULT_SPEED_MIN

#define AC_SPRAYER_DEFAULT_SPEED_MIN   100

we must be travelling at least 1m/s to begin spraying

Definition at line 27 of file AC_Sprayer.h.

◆ AC_SPRAYER_DEFAULT_SPINNER_PWM

#define AC_SPRAYER_DEFAULT_SPINNER_PWM   1300

default speed of spinner (higher means spray is throw further horizontally

Definition at line 26 of file AC_Sprayer.h.

Referenced by AC_Sprayer::AC_Sprayer().

◆ AC_SPRAYER_DEFAULT_TURN_ON_DELAY

#define AC_SPRAYER_DEFAULT_TURN_ON_DELAY   100

delay between when we reach the minimum speed and we begin spraying. This reduces the likelihood of constantly turning on/off the pump

Definition at line 28 of file AC_Sprayer.h.

Referenced by AC_Sprayer::update().