HAL_PX4: fixed enabling oneshot on a subset of motors

This commit is contained in:
Andrew Tridgell 2016-04-22 13:24:24 +10:00
parent fd7c87e629
commit 5ce7ae71a7
1 changed files with 8 additions and 8 deletions

View File

@ -100,7 +100,7 @@ void PX4RCOutput::_init_alt_channels(void)
void PX4RCOutput::set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz)
{
// we can't set this per channel
if (freq_hz > 50) {
if (freq_hz > 50 || freq_hz == 1) {
// we're being asked to set the alt rate
if (_output_mode == MODE_PWM_ONESHOT) {
/*
@ -110,6 +110,7 @@ void PX4RCOutput::set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz)
*/
freq_hz = 1;
}
//::printf("SET_UPDATE_RATE %u\n", (unsigned)freq_hz);
if (ioctl(fd, PWM_SERVO_SET_UPDATE_RATE, (unsigned long)freq_hz) != 0) {
hal.console->printf("RCOutput: Unable to set alt rate to %uHz\n", (unsigned)freq_hz);
return;
@ -128,7 +129,7 @@ void PX4RCOutput::set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz)
For the moment we never set the channels above 8 to more than
50Hz
*/
if (freq_hz > 50) {
if (freq_hz > 50 || freq_hz == 1) {
// we are setting high rates on the given channels
_rate_mask |= chmask & 0xFF;
if (_rate_mask & 0x3) {
@ -153,6 +154,7 @@ void PX4RCOutput::set_freq_fd(int fd, uint32_t chmask, uint16_t freq_hz)
}
}
//::printf("SELECT_UPDATE_RATE 0x%02x\n", (unsigned)_rate_mask);
if (ioctl(fd, PWM_SERVO_SET_SELECT_UPDATE_RATE, _rate_mask) != 0) {
hal.console->printf("RCOutput: Unable to set alt rate mask to 0x%x\n", (unsigned)_rate_mask);
}
@ -163,11 +165,6 @@ 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 (_output_mode == MODE_PWM_ONESHOT) {
// changing the output frequency makes no sense in oneshot
// mode, and can disturb the timers causing spurious glitches
return;
}
// greater than 400 doesn't give enough room at higher periods for
// the down pulse
if (freq_hz > 400) {
@ -539,13 +536,16 @@ void PX4RCOutput::set_output_mode(enum output_mode mode)
// no change
return;
}
if (mode == MODE_PWM_ONESHOT) {
set_freq(_rate_mask, 1);
}
_output_mode = mode;
if (_output_mode == MODE_PWM_ONESHOT) {
//::printf("enable oneshot\n");
ioctl(_pwm_fd, PWM_SERVO_SET_ONESHOT, 1);
if (_alt_fd != -1) {
ioctl(_alt_fd, PWM_SERVO_SET_ONESHOT, 1);
}
set_freq(0xFFFF, 51);
} else {
ioctl(_pwm_fd, PWM_SERVO_SET_ONESHOT, 0);
if (_alt_fd != -1) {