Rover: handle oneshot125 separately

This commit is contained in:
Andrew Tridgell 2018-04-03 18:10:28 +10:00
parent 0bb2c4564d
commit 4f6240ee8a
1 changed files with 3 additions and 2 deletions

View File

@ -327,10 +327,11 @@ void AP_MotorsUGV::setup_pwm_type()
{
switch (_pwm_type) {
case PWM_TYPE_ONESHOT:
case PWM_TYPE_ONESHOT125:
// tell HAL to do immediate output
hal.rcout->set_output_mode(0xFFFF, AP_HAL::RCOutput::MODE_PWM_ONESHOT);
break;
case PWM_TYPE_ONESHOT125:
hal.rcout->set_output_mode(0xFFFF, AP_HAL::RCOutput::MODE_PWM_ONESHOT125);
break;
case PWM_TYPE_BRUSHED_WITH_RELAY:
case PWM_TYPE_BRUSHED_BIPOLAR:
hal.rcout->set_output_mode(0xFFFF, AP_HAL::RCOutput::MODE_PWM_BRUSHED);