AC_Sprayer: use ahrs singleton

Also remove some unneeded initialisations
This commit is contained in:
Peter Barker 2018-04-11 21:06:20 +10:00 committed by Randy Mackay
parent 0fd71f909c
commit 7c14a9dd7b
2 changed files with 3 additions and 7 deletions

View File

@ -48,10 +48,7 @@ const AP_Param::GroupInfo AC_Sprayer::var_info[] = {
AP_GROUPEND
};
AC_Sprayer::AC_Sprayer(const AP_AHRS_NavEKF &ahrs) :
_ahrs(ahrs),
_speed_over_min_time(0),
_speed_under_min_time(0)
AC_Sprayer::AC_Sprayer()
{
AP_Param::setup_object_defaults(this, var_info);
@ -107,7 +104,7 @@ void AC_Sprayer::update()
// get horizontal velocity
Vector3f velocity;
if (!_ahrs.get_velocity_NED(velocity)) {
if (!AP::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();

View File

@ -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_AHRS_NavEKF &ahrs);
AC_Sprayer();
/* Do not allow copies */
AC_Sprayer(const AC_Sprayer &other) = delete;
@ -61,7 +61,6 @@ public:
static const struct AP_Param::GroupInfo var_info[];
private:
const AP_AHRS_NavEKF &_ahrs; ///< pointers to other objects we depend upon
// parameters
AP_Int8 _enabled; ///< top level enable/disable control