mirror of https://github.com/ArduPilot/ardupilot
AC_Sprayer: move the check for srv_channel assignment from update to run method
It should be enough to do this check only once in run method instead of doing it in update method
This commit is contained in:
parent
18dc37eef8
commit
7630aeb0e4
|
@ -93,6 +93,11 @@ void AC_Sprayer::run(const bool activate)
|
|||
return;
|
||||
}
|
||||
|
||||
// exit immediately if the pump function has not been set-up for any servos
|
||||
if (!SRV_Channels::function_assigned(SRV_Channel::k_sprayer_pump)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// set flag indicate whether spraying is permitted:
|
||||
// do not allow running to be set to true if we are currently not enabled
|
||||
_flags.running = _enabled && activate;
|
||||
|
@ -120,11 +125,6 @@ void AC_Sprayer::update()
|
|||
return;
|
||||
}
|
||||
|
||||
// exit immediately if the pump function has not been set-up for any servo
|
||||
if (!SRV_Channels::function_assigned(SRV_Channel::k_sprayer_pump)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// get horizontal velocity
|
||||
Vector3f velocity;
|
||||
if (!AP::ahrs().get_velocity_NED(velocity)) {
|
||||
|
|
Loading…
Reference in New Issue