From c2e546285c7c6b7397c4cf72a6e4aa9a5b33ac78 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Wed, 11 Apr 2018 09:11:17 +0900 Subject: [PATCH] AC_Sprayer: replace AP_InertialNav with AHRS --- libraries/AC_Sprayer/AC_Sprayer.cpp | 13 +++++++++---- libraries/AC_Sprayer/AC_Sprayer.h | 6 +++--- 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/libraries/AC_Sprayer/AC_Sprayer.cpp b/libraries/AC_Sprayer/AC_Sprayer.cpp index e303f3cbac..405fed8948 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.cpp +++ b/libraries/AC_Sprayer/AC_Sprayer.cpp @@ -48,8 +48,8 @@ const AP_Param::GroupInfo AC_Sprayer::var_info[] = { AP_GROUPEND }; -AC_Sprayer::AC_Sprayer(const AP_InertialNav* inav) : - _inav(inav), +AC_Sprayer::AC_Sprayer(const AP_AHRS_NavEKF &ahrs) : + _ahrs(ahrs), _speed_over_min_time(0), _speed_under_min_time(0) { @@ -107,8 +107,13 @@ AC_Sprayer::update() } // get horizontal velocity - const Vector3f &velocity = _inav->get_velocity(); - float ground_speed = norm(velocity.x,velocity.y); + Vector3f velocity; + if (!_ahrs.get_velocity_NED(velocity)) { + // treat unknown velocity as zero which should lead to pump stopping + // velocity will already be zero but this avoids a coverity warning + velocity.zero(); + } + float ground_speed = norm(velocity.x * 100.0f, velocity.y * 100.0f); // get the current time const uint32_t now = AP_HAL::millis(); diff --git a/libraries/AC_Sprayer/AC_Sprayer.h b/libraries/AC_Sprayer/AC_Sprayer.h index 6c024654c5..2849d9d4a9 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.h +++ b/libraries/AC_Sprayer/AC_Sprayer.h @@ -19,7 +19,7 @@ #include #include #include -#include // Inertial Navigation library +#include #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 @@ -32,7 +32,7 @@ /// @brief Object managing a crop sprayer comprised of a spinner and a pump both controlled by pwm class AC_Sprayer { public: - AC_Sprayer(const AP_InertialNav *inav); + AC_Sprayer(const AP_AHRS_NavEKF &ahrs); /* Do not allow copies */ AC_Sprayer(const AC_Sprayer &other) = delete; @@ -61,7 +61,7 @@ public: static const struct AP_Param::GroupInfo var_info[]; 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 AP_Int8 _enabled; ///< top level enable/disable control