Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_Sprayer/AC_Sprayer.h
Views: 1798
/// @file AC_Sprayer.h1/// @brief Crop sprayer library23/**4The crop spraying functionality can be enabled in ArduCopter by doing the following:5- set RC7_OPTION or RC8_OPTION parameter to 15 to allow turning the sprayer on/off from one of these channels6- set SERVO10_FUNCTION to 22 to enable the servo output controlling the pump speed on servo-out 107- set SERVO11_FUNCTION to 23 to enable the servo output controlling the spinner on servo-out 118- 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 spinner9- set the SPRAY_SPINNER to the pwm value the spinner should spin at when on10- 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/s11- 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 range12- 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 switch13**/14#pragma once1516#include "AC_Sprayer_config.h"1718#if HAL_SPRAYER_ENABLED1920#include <inttypes.h>21#include <AP_Common/AP_Common.h>22#include <AP_Param/AP_Param.h>2324#define AC_SPRAYER_DEFAULT_PUMP_RATE 10.0f ///< default quantity of spray per meter travelled25#define AC_SPRAYER_DEFAULT_PUMP_MIN 0 ///< default minimum pump speed expressed as a percentage from 0 to 10026#define AC_SPRAYER_DEFAULT_SPINNER_PWM 1300 ///< default speed of spinner (higher means spray is throw further horizontally27#define AC_SPRAYER_DEFAULT_SPEED_MIN 100 ///< we must be travelling at least 1m/s to begin spraying28#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 pump29#define AC_SPRAYER_DEFAULT_SHUT_OFF_DELAY 1000 ///< shut-off delay in milli seconds. This reduces the likelihood of constantly turning on/off the pump3031/// @class AC_Sprayer32/// @brief Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm33class AC_Sprayer {34public:35AC_Sprayer();3637/* Do not allow copies */38CLASS_NO_COPY(AC_Sprayer);3940static AC_Sprayer *get_singleton();41static AC_Sprayer *_singleton;4243/// run - allow or disallow spraying to occur44void run(bool true_false);4546/// running - returns true if spraying is currently permitted47bool running() const { return _flags.running; }4849/// spraying - returns true if spraying is actually happening50bool spraying() const { return _flags.spraying; }5152/// test_pump - set to true to turn on pump as if travelling at 1m/s as a test53void test_pump(bool true_false) { _flags.testing = true_false; }5455/// To-Do: add function to decode pilot input from channel 6 tuning knob5657/// set_pump_rate - sets desired quantity of spray when travelling at 1m/s as a percentage of the pumps maximum rate58void set_pump_rate(float pct_at_1ms) { _pump_pct_1ms.set(pct_at_1ms); }5960/// update - adjusts servo positions based on speed and requested quantity61void update();6263static const struct AP_Param::GroupInfo var_info[];6465private:6667// parameters68AP_Int8 _enabled; ///< top level enable/disable control69AP_Float _pump_pct_1ms; ///< desired pump rate (expressed as a percentage of top rate) when travelling at 1m/s70AP_Int8 _pump_min_pct; ///< minimum pump rate (expressed as a percentage from 0 to 100)71AP_Int16 _spinner_pwm; ///< pwm rate of spinner72AP_Float _speed_min; ///< minimum speed in cm/s above which the sprayer will be started7374/// flag bitmask75struct sprayer_flags_type {76uint8_t spraying : 1; ///< 1 if we are currently spraying77uint8_t testing : 1; ///< 1 if we are testing the sprayer and should output a minimum value78uint8_t running : 1; ///< 1 if we are permitted to run sprayer79} _flags;8081// internal variables82uint32_t _speed_over_min_time; ///< time at which we reached speed minimum83uint32_t _speed_under_min_time; ///< time at which we fell below speed minimum8485void stop_spraying();86};8788namespace AP {89AC_Sprayer *sprayer();90};91#endif // HAL_SPRAYER_ENABLED929394