HAL_PX4: prevent rate changes once oneshot is setup

this fixes a problem with small motor outputs at the start of a motor
test.

Thanks to Luis for reporting this.
This commit is contained in:
Andrew Tridgell 2016-05-26 12:18:40 +10:00
parent a44b0e0011
commit dda35a366c

View File

@ -165,6 +165,11 @@ 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)
{
if (freq_hz > 50 && _output_mode == MODE_PWM_ONESHOT) {
// rate is irrelevent in oneshot
return;
}
// 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");