mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_ServoRelayEvents: Remove constraint on 'channel' value
This was preventing proper function of Relay #0, and the intention of this check was redundant
This commit is contained in:
parent
6ec32472c5
commit
98b7dac870
@ -106,10 +106,6 @@ void AP_ServoRelayEvents::update_events(void)
|
||||
return;
|
||||
}
|
||||
|
||||
if (channel > NUM_SERVO_CHANNELS || channel == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
start_time_ms = AP_HAL::millis();
|
||||
|
||||
switch (type) {
|
||||
|
Loading…
Reference in New Issue
Block a user