|
|
|
@ -78,7 +78,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
@@ -78,7 +78,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
|
|
|
|
|
// @Param: PWM_TYPE
|
|
|
|
|
// @DisplayName: Output PWM type
|
|
|
|
|
// @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output
|
|
|
|
|
// @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200
|
|
|
|
|
// @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200,8:PWMRange
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
// @RebootRequired: True
|
|
|
|
|
AP_GROUPINFO("PWM_TYPE", 15, AP_MotorsMulticopter, _pwm_type, PWM_TYPE_NORMAL), |
|
|
|
@ -512,8 +512,9 @@ void AP_MotorsMulticopter::set_throttle_range(int16_t radio_min, int16_t radio_m
@@ -512,8 +512,9 @@ void AP_MotorsMulticopter::set_throttle_range(int16_t radio_min, int16_t radio_m
|
|
|
|
|
_throttle_radio_min = radio_min; |
|
|
|
|
_throttle_radio_max = radio_max; |
|
|
|
|
|
|
|
|
|
// if all outputs are digital adjust the range
|
|
|
|
|
if (SRV_Channels::have_digital_outputs(get_motor_mask())) { |
|
|
|
|
// if all outputs are digital adjust the range. We also do this for type PWM_RANGE, as those use the
|
|
|
|
|
// scaled output, which is then mapped to PWM via the SRV_Channel library
|
|
|
|
|
if (SRV_Channels::have_digital_outputs(get_motor_mask()) || (_pwm_type == PWM_TYPE_PWM_RANGE)) { |
|
|
|
|
_pwm_min = 1000; |
|
|
|
|
_pwm_max = 2000; |
|
|
|
|
} |
|
|
|
|