From 1ac5776b8b296d5bdcbe9209d201e3c435d77aec Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 6 Jan 2017 12:20:26 +1100 Subject: [PATCH] AC_Sprayer: adapt to new RC_Channel API --- libraries/AC_Sprayer/AC_Sprayer.cpp | 13 +++++-------- libraries/AC_Sprayer/AC_Sprayer.h | 2 +- 2 files changed, 6 insertions(+), 9 deletions(-) diff --git a/libraries/AC_Sprayer/AC_Sprayer.cpp b/libraries/AC_Sprayer/AC_Sprayer.cpp index 998dd02ab1..5ad97af0bf 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.cpp +++ b/libraries/AC_Sprayer/AC_Sprayer.cpp @@ -85,11 +85,8 @@ void AC_Sprayer::run(const bool true_false) void AC_Sprayer::stop_spraying() { - // send output to pump channel - RC_Channel_aux::set_radio_to_min(RC_Channel_aux::k_sprayer_pump); - - // send output to spinner channel - RC_Channel_aux::set_radio_to_min(RC_Channel_aux::k_sprayer_spinner); + SRV_Channels::set_servo_limit(SRV_Channel::k_sprayer_pump, SRV_CHANNEL_LIMIT_MIN); + SRV_Channels::set_servo_limit(SRV_Channel::k_sprayer_spinner, SRV_CHANNEL_LIMIT_MIN); _flags.spraying = false; } @@ -105,7 +102,7 @@ AC_Sprayer::update() } // exit immediately if the pump function has not been set-up for any servo - if (!RC_Channel_aux::function_assigned(RC_Channel_aux::k_sprayer_pump)) { + if (!SRV_Channels::function_assigned(SRV_Channel::k_sprayer_pump)) { return; } @@ -163,8 +160,8 @@ AC_Sprayer::update() float pos = ground_speed * _pump_pct_1ms; pos = MAX(pos, 100 *_pump_min_pct); // ensure min pump speed pos = MIN(pos,10000); // clamp to range - RC_Channel_aux::move_servo(RC_Channel_aux::k_sprayer_pump, pos, 0, 10000); - RC_Channel_aux::set_radio(RC_Channel_aux::k_sprayer_spinner, _spinner_pwm); + SRV_Channels::move_servo(SRV_Channel::k_sprayer_pump, pos, 0, 10000); + SRV_Channels::set_output_pwm(SRV_Channel::k_sprayer_spinner, _spinner_pwm); _flags.spraying = true; }else{ stop_spraying(); diff --git a/libraries/AC_Sprayer/AC_Sprayer.h b/libraries/AC_Sprayer/AC_Sprayer.h index b4771b7f67..8164c2c109 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.h +++ b/libraries/AC_Sprayer/AC_Sprayer.h @@ -18,7 +18,7 @@ #include #include #include -#include +#include #include // Inertial Navigation library #define AC_SPRAYER_DEFAULT_PUMP_RATE 10.0f ///< default quantity of spray per meter travelled