HAL_PX4: fixed build with DShot

This commit is contained in:
Andrew Tridgell 2018-03-16 07:28:38 +11:00
parent 1ffe75957e
commit a9b4d37bd2
1 changed files with 7 additions and 0 deletions

View File

@ -624,6 +624,13 @@ void PX4RCOutput::set_output_mode(uint16_t mask, enum output_mode mode)
ioctl(_alt_fd, PWM_SERVO_SET_ONESHOT, 1);
}
break;
case MODE_PWM_DSHOT150:
case MODE_PWM_DSHOT300:
case MODE_PWM_DSHOT600:
case MODE_PWM_DSHOT1200:
// treat as normal PWM for now
hal.console->printf("DShot not supported\n");
FALLTHROUGH;
case MODE_PWM_NORMAL:
ioctl(_pwm_fd, PWM_SERVO_SET_ONESHOT, 0);
if (_alt_fd != -1) {