mirror of https://github.com/ArduPilot/ardupilot
AC_Sprayer: use enum-class for SRV_CHANNEL_LIMIT_TRIM and friends
This commit is contained in:
parent
f1c2e55f68
commit
48def9b8a4
|
@ -103,8 +103,8 @@ void AC_Sprayer::run(const bool true_false)
|
||||||
|
|
||||||
void AC_Sprayer::stop_spraying()
|
void AC_Sprayer::stop_spraying()
|
||||||
{
|
{
|
||||||
SRV_Channels::set_output_limit(SRV_Channel::k_sprayer_pump, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
SRV_Channels::set_output_limit(SRV_Channel::k_sprayer_pump, SRV_Channel::Limit::MIN);
|
||||||
SRV_Channels::set_output_limit(SRV_Channel::k_sprayer_spinner, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
SRV_Channels::set_output_limit(SRV_Channel::k_sprayer_spinner, SRV_Channel::Limit::MIN);
|
||||||
|
|
||||||
_flags.spraying = false;
|
_flags.spraying = false;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue