CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_Sprayer/AC_Sprayer.h
Views: 1798
1
/// @file AC_Sprayer.h
2
/// @brief Crop sprayer library
3
4
/**
5
The crop spraying functionality can be enabled in ArduCopter by doing the following:
6
- set RC7_OPTION or RC8_OPTION parameter to 15 to allow turning the sprayer on/off from one of these channels
7
- set SERVO10_FUNCTION to 22 to enable the servo output controlling the pump speed on servo-out 10
8
- set SERVO11_FUNCTION to 23 to enable the servo output controlling the spinner on servo-out 11
9
- 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
10
- set the SPRAY_SPINNER to the pwm value the spinner should spin at when on
11
- set the SPRAY_PUMP_RATE to the value the pump servo should move to when the vehicle is travelling at 1m/s. This is 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
12
- 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
13
- 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
14
**/
15
#pragma once
16
17
#include "AC_Sprayer_config.h"
18
19
#if HAL_SPRAYER_ENABLED
20
21
#include <inttypes.h>
22
#include <AP_Common/AP_Common.h>
23
#include <AP_Param/AP_Param.h>
24
25
#define AC_SPRAYER_DEFAULT_PUMP_RATE 10.0f ///< default quantity of spray per meter travelled
26
#define AC_SPRAYER_DEFAULT_PUMP_MIN 0 ///< default minimum pump speed expressed as a percentage from 0 to 100
27
#define AC_SPRAYER_DEFAULT_SPINNER_PWM 1300 ///< default speed of spinner (higher means spray is throw further horizontally
28
#define AC_SPRAYER_DEFAULT_SPEED_MIN 100 ///< we must be travelling at least 1m/s to begin spraying
29
#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
30
#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
31
32
/// @class AC_Sprayer
33
/// @brief Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm
34
class AC_Sprayer {
35
public:
36
AC_Sprayer();
37
38
/* Do not allow copies */
39
CLASS_NO_COPY(AC_Sprayer);
40
41
static AC_Sprayer *get_singleton();
42
static AC_Sprayer *_singleton;
43
44
/// run - allow or disallow spraying to occur
45
void run(bool true_false);
46
47
/// running - returns true if spraying is currently permitted
48
bool running() const { return _flags.running; }
49
50
/// spraying - returns true if spraying is actually happening
51
bool spraying() const { return _flags.spraying; }
52
53
/// test_pump - set to true to turn on pump as if travelling at 1m/s as a test
54
void test_pump(bool true_false) { _flags.testing = true_false; }
55
56
/// To-Do: add function to decode pilot input from channel 6 tuning knob
57
58
/// set_pump_rate - sets desired quantity of spray when travelling at 1m/s as a percentage of the pumps maximum rate
59
void set_pump_rate(float pct_at_1ms) { _pump_pct_1ms.set(pct_at_1ms); }
60
61
/// update - adjusts servo positions based on speed and requested quantity
62
void update();
63
64
static const struct AP_Param::GroupInfo var_info[];
65
66
private:
67
68
// parameters
69
AP_Int8 _enabled; ///< top level enable/disable control
70
AP_Float _pump_pct_1ms; ///< desired pump rate (expressed as a percentage of top rate) when travelling at 1m/s
71
AP_Int8 _pump_min_pct; ///< minimum pump rate (expressed as a percentage from 0 to 100)
72
AP_Int16 _spinner_pwm; ///< pwm rate of spinner
73
AP_Float _speed_min; ///< minimum speed in cm/s above which the sprayer will be started
74
75
/// flag bitmask
76
struct sprayer_flags_type {
77
uint8_t spraying : 1; ///< 1 if we are currently spraying
78
uint8_t testing : 1; ///< 1 if we are testing the sprayer and should output a minimum value
79
uint8_t running : 1; ///< 1 if we are permitted to run sprayer
80
} _flags;
81
82
// internal variables
83
uint32_t _speed_over_min_time; ///< time at which we reached speed minimum
84
uint32_t _speed_under_min_time; ///< time at which we fell below speed minimum
85
86
void stop_spraying();
87
};
88
89
namespace AP {
90
AC_Sprayer *sprayer();
91
};
92
#endif // HAL_SPRAYER_ENABLED
93
94