mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: fixed RC rate when BRD_PWM_COUNT=0
if BRD_PWM_COUNT is zero then alt_fd is -1, and we were not setting servo output rate
This commit is contained in:
parent
c952e58edb
commit
02976168cc
|
@ -184,10 +184,6 @@ void PX4RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
|
||||||
hal.console->printf("RCOutput: Unable to get servo count\n");
|
hal.console->printf("RCOutput: Unable to get servo count\n");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (_alt_fd != -1 && ioctl(_alt_fd, PWM_SERVO_GET_COUNT, (unsigned long)&_alt_servo_count) != 0) {
|
|
||||||
hal.console->printf("RCOutput: Unable to get alt servo count\n");
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// greater than 400 doesn't give enough room at higher periods for
|
// greater than 400 doesn't give enough room at higher periods for
|
||||||
// the down pulse
|
// the down pulse
|
||||||
|
|
Loading…
Reference in New Issue