AP_ServoRelayEvents: fix do_set_servo

this was broken by the recent SRV_Channels changes

thanks to Jacob for noticing this!
This commit is contained in:
Andrew Tridgell 2017-03-10 17:47:28 +11:00 committed by Randy Mackay
parent 15d96b4b5d
commit 2ef6473816
1 changed files with 14 additions and 8 deletions

View File

@ -36,8 +36,11 @@ bool AP_ServoRelayEvents::do_set_servo(uint8_t _channel, uint16_t pwm)
// cancel previous repeat
repeat = 0;
}
hal.rcout->enable_ch(_channel-1);
hal.rcout->write(_channel-1, pwm);
SRV_Channel *c = SRV_Channels::srv_channel(_channel-1);
if (c == nullptr) {
return false;
}
c->set_output_pwm(pwm);
return true;
}
@ -110,14 +113,17 @@ void AP_ServoRelayEvents::update_events(void)
start_time_ms = AP_HAL::millis();
switch (type) {
case EVENT_TYPE_SERVO:
hal.rcout->enable_ch(channel-1);
if (repeat & 1) {
hal.rcout->write(channel-1, SRV_Channels::srv_channel(channel-1)->get_trim());
} else {
hal.rcout->write(channel-1, servo_value);
case EVENT_TYPE_SERVO: {
SRV_Channel *c = SRV_Channels::srv_channel(channel-1);
if (c != nullptr) {
if (repeat & 1) {
c->set_output_pwm(c->get_trim());
} else {
c->set_output_pwm(servo_value);
}
}
break;
}
case EVENT_TYPE_RELAY:
relay.toggle(channel);