@ -23,7 +23,7 @@ const AP_Param::GroupInfo AP_MotorsUGV::var_info[] = {
@@ -23,7 +23,7 @@ const AP_Param::GroupInfo AP_MotorsUGV::var_info[] = {
// @Param: PWM_TYPE
// @DisplayName: Output PWM type
// @Description: This selects the output PWM type as regular PWM, OneShot, Brushed motor support using PWM (duty cycle) with separated direction signal, Brushed motor support with separate throttle and direction PWM (duty cyle)
// @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed,4:BrushedPlus
// @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed,4:BrushedBiPolar
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO ( " PWM_TYPE " , 1 , AP_MotorsUGV , _pwm_type , PWM_TYPE_NORMAL ) ,
@ -232,7 +232,7 @@ void AP_MotorsUGV::setup_pwm_type()
@@ -232,7 +232,7 @@ void AP_MotorsUGV::setup_pwm_type()
hal . rcout - > set_output_mode ( AP_HAL : : RCOutput : : MODE_PWM_ONESHOT ) ;
break ;
case PWM_TYPE_BRUSHED :
case PWM_TYPE_BRUSHEDPLUS :
case PWM_TYPE_BRUSHEDBIPOLAR :
hal . rcout - > set_output_mode ( AP_HAL : : RCOutput : : MODE_PWM_BRUSHED ) ;
/*
* Group 0 : channels 0 1
@ -258,7 +258,7 @@ void AP_MotorsUGV::setup_safety_output()
@@ -258,7 +258,7 @@ void AP_MotorsUGV::setup_safety_output()
SRV_Channels : : set_trim_to_min_for ( SRV_Channel : : k_throttleRight ) ;
SRV_Channels : : setup_failsafe_trim_all ( ) ;
}
if ( _pwm_type = = PWM_TYPE_BRUSHEDPLUS ) {
if ( _pwm_type = = PWM_TYPE_BRUSHEDBIPOLAR ) {
SRV_Channels : : setup_failsafe_trim_all ( ) ;
}