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:
Jacob Walser 2017-03-31 21:31:56 -04:00 committed by Andrew Tridgell
parent 6ec32472c5
commit 98b7dac870

View File

@ -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) {