|
|
@ -19,7 +19,7 @@ |
|
|
|
#include <AP_Param/AP_Param.h> |
|
|
|
#include <AP_Param/AP_Param.h> |
|
|
|
#include <AP_Math/AP_Math.h> |
|
|
|
#include <AP_Math/AP_Math.h> |
|
|
|
#include <SRV_Channel/SRV_Channel.h> |
|
|
|
#include <SRV_Channel/SRV_Channel.h> |
|
|
|
#include <AP_InertialNav/AP_InertialNav.h> // Inertial Navigation library |
|
|
|
#include <AP_AHRS/AP_AHRS.h> |
|
|
|
|
|
|
|
|
|
|
|
#define AC_SPRAYER_DEFAULT_PUMP_RATE 10.0f ///< default quantity of spray per meter travelled
|
|
|
|
#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_PUMP_MIN 0 ///< default minimum pump speed expressed as a percentage from 0 to 100
|
|
|
@ -32,7 +32,7 @@ |
|
|
|
/// @brief Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm
|
|
|
|
/// @brief Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm
|
|
|
|
class AC_Sprayer { |
|
|
|
class AC_Sprayer { |
|
|
|
public: |
|
|
|
public: |
|
|
|
AC_Sprayer(const AP_InertialNav *inav); |
|
|
|
AC_Sprayer(const AP_AHRS_NavEKF &ahrs); |
|
|
|
|
|
|
|
|
|
|
|
/* Do not allow copies */ |
|
|
|
/* Do not allow copies */ |
|
|
|
AC_Sprayer(const AC_Sprayer &other) = delete; |
|
|
|
AC_Sprayer(const AC_Sprayer &other) = delete; |
|
|
@ -61,7 +61,7 @@ public: |
|
|
|
static const struct AP_Param::GroupInfo var_info[]; |
|
|
|
static const struct AP_Param::GroupInfo var_info[]; |
|
|
|
|
|
|
|
|
|
|
|
private: |
|
|
|
private: |
|
|
|
const AP_InertialNav* const _inav; ///< pointers to other objects we depend upon
|
|
|
|
const AP_AHRS_NavEKF &_ahrs; ///< pointers to other objects we depend upon
|
|
|
|
|
|
|
|
|
|
|
|
// parameters
|
|
|
|
// parameters
|
|
|
|
AP_Int8 _enabled; ///< top level enable/disable control
|
|
|
|
AP_Int8 _enabled; ///< top level enable/disable control
|
|
|
|