mirror of https://github.com/ArduPilot/ardupilot
AP_ServoRelayEvents: allow DO_SET_SERVO commands while rc pass-thru
This commit is contained in:
parent
f9547fa28e
commit
012fcae388
|
@ -32,7 +32,13 @@ bool AP_ServoRelayEvents::do_set_servo(uint8_t _channel, uint16_t pwm)
|
||||||
if (c == nullptr) {
|
if (c == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (c->get_function() != SRV_Channel::k_none) {
|
switch(c->get_function())
|
||||||
|
{
|
||||||
|
case SRV_Channel::k_none:
|
||||||
|
case SRV_Channel::k_manual:
|
||||||
|
case SRV_Channel::k_rcin1 ... SRV_Channel::k_rcin16: // rc pass-thru
|
||||||
|
break;
|
||||||
|
default:
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "ServoRelayEvent: Channel %d is already in use", _channel);
|
gcs().send_text(MAV_SEVERITY_INFO, "ServoRelayEvent: Channel %d is already in use", _channel);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -42,6 +48,7 @@ bool AP_ServoRelayEvents::do_set_servo(uint8_t _channel, uint16_t pwm)
|
||||||
repeat = 0;
|
repeat = 0;
|
||||||
}
|
}
|
||||||
c->set_output_pwm(pwm);
|
c->set_output_pwm(pwm);
|
||||||
|
c->ignore_small_rcin_changes();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -72,7 +79,13 @@ bool AP_ServoRelayEvents::do_repeat_servo(uint8_t _channel, uint16_t _servo_valu
|
||||||
if (c == nullptr) {
|
if (c == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (c->get_function() != SRV_Channel::k_none) {
|
switch(c->get_function())
|
||||||
|
{
|
||||||
|
case SRV_Channel::k_none:
|
||||||
|
case SRV_Channel::k_manual:
|
||||||
|
case SRV_Channel::k_rcin1 ... SRV_Channel::k_rcin16: // rc pass-thru
|
||||||
|
break;
|
||||||
|
default:
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "ServoRelayEvent: Channel %d is already in use", _channel);
|
gcs().send_text(MAV_SEVERITY_INFO, "ServoRelayEvent: Channel %d is already in use", _channel);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -121,6 +134,7 @@ void AP_ServoRelayEvents::update_events(void)
|
||||||
c->set_output_pwm(c->get_trim());
|
c->set_output_pwm(c->get_trim());
|
||||||
} else {
|
} else {
|
||||||
c->set_output_pwm(servo_value);
|
c->set_output_pwm(servo_value);
|
||||||
|
c->ignore_small_rcin_changes();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
Loading…
Reference in New Issue