mirror of https://github.com/ArduPilot/ardupilot
AC_Sprayer: Change the comment of the variables in the form of doxygen.
This commit is contained in:
parent
fce798bc7a
commit
c78dfd4aa4
|
@ -25,12 +25,12 @@
|
|||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library
|
||||
|
||||
#define AC_SPRAYER_DEFAULT_PUMP_RATE 10.0f // default quantity of spray per meter travelled
|
||||
#define AC_SPRAYER_DEFAULT_PUMP_MIN 0 // default minimum pump speed expressed as a percentage from 0 to 100
|
||||
#define AC_SPRAYER_DEFAULT_SPINNER_PWM 1300 // default speed of spinner (higher means spray is throw further horizontally
|
||||
#define AC_SPRAYER_DEFAULT_SPEED_MIN 100 // we must be travelling at least 1m/s to begin spraying
|
||||
#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
|
||||
#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
|
||||
#define AC_SPRAYER_DEFAULT_PUMP_RATE 10.0f ///< default quantity of spray per meter travelled
|
||||
#define AC_SPRAYER_DEFAULT_PUMP_MIN 0 ///< default minimum pump speed expressed as a percentage from 0 to 100
|
||||
#define AC_SPRAYER_DEFAULT_SPINNER_PWM 1300 ///< default speed of spinner (higher means spray is throw further horizontally
|
||||
#define AC_SPRAYER_DEFAULT_SPEED_MIN 100 ///< we must be travelling at least 1m/s to begin spraying
|
||||
#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
|
||||
#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
|
||||
|
||||
/// @class AC_Sprayer
|
||||
/// @brief Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm
|
||||
|
@ -61,23 +61,22 @@ public:
|
|||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
// pointers to other objects we depend upon
|
||||
const AP_InertialNav* const _inav;
|
||||
const AP_InertialNav* const _inav; ///< pointers to other objects we depend upon
|
||||
|
||||
// parameters
|
||||
AP_Int8 _enabled; // top level enable/disable control
|
||||
AP_Float _pump_pct_1ms; // desired pump rate (expressed as a percentage of top rate) when travelling at 1m/s
|
||||
AP_Int8 _pump_min_pct; // minimum pump rate (expressed as a percentage from 0 to 100)
|
||||
AP_Int16 _spinner_pwm; // pwm rate of spinner
|
||||
AP_Float _speed_min; // minimum speed in cm/s above which the sprayer will be started
|
||||
AP_Int8 _enabled; ///< top level enable/disable control
|
||||
AP_Float _pump_pct_1ms; ///< desired pump rate (expressed as a percentage of top rate) when travelling at 1m/s
|
||||
AP_Int8 _pump_min_pct; ///< minimum pump rate (expressed as a percentage from 0 to 100)
|
||||
AP_Int16 _spinner_pwm; ///< pwm rate of spinner
|
||||
AP_Float _speed_min; ///< minimum speed in cm/s above which the sprayer will be started
|
||||
|
||||
// flag bitmask
|
||||
/// flag bitmask
|
||||
struct sprayer_flags_type {
|
||||
uint8_t spraying : 1; // 1 if we are currently spraying
|
||||
uint8_t testing : 1; // 1 if we are testing the sprayer and should output a minimum value
|
||||
uint8_t spraying : 1; ///< 1 if we are currently spraying
|
||||
uint8_t testing : 1; ///< 1 if we are testing the sprayer and should output a minimum value
|
||||
} _flags;
|
||||
|
||||
// internal variables
|
||||
uint32_t _speed_over_min_time; // time at which we reached speed minimum
|
||||
uint32_t _speed_under_min_time; // time at which we fell below speed minimum
|
||||
uint32_t _speed_over_min_time; ///< time at which we reached speed minimum
|
||||
uint32_t _speed_under_min_time; ///< time at which we fell below speed minimum
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue