mirror of https://github.com/ArduPilot/ardupilot
Rover: handle oneshot125 separately
This commit is contained in:
parent
0bb2c4564d
commit
4f6240ee8a
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue