AP_HAL_PX4: fixed hexacopter on Pixracer

the _servo_count was 4 as we didn't re-fetch the count after applying
changes in AP_BoardConfig from BRD_PWM_COUNT
This commit is contained in:
Andrew Tridgell 2016-05-11 13:01:15 +10:00
parent 8a7627474f
commit eeef28be5e

View File

@ -165,6 +165,16 @@ void PX4RCOutput::set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz)
*/
void PX4RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
{
// re-fetch servo count as it might have changed due to a change in BRD_PWM_COUNT
if (_pwm_fd != -1 && ioctl(_pwm_fd, PWM_SERVO_GET_COUNT, (unsigned long)&_servo_count) != 0) {
hal.console->printf("RCOutput: Unable to get servo count\n");
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
// the down pulse
if (freq_hz > 400) {