mirror of https://github.com/ArduPilot/ardupilot
AC_Sprayer: adapt to new RC_Channel API
This commit is contained in:
parent
39ab1a0abc
commit
1ac5776b8b
|
@ -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();
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <SRV_Channel/SRV_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
|
||||
|
|
Loading…
Reference in New Issue