|
|
|
@ -83,8 +83,8 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = {
@@ -83,8 +83,8 @@ 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 or brushed motor output
|
|
|
|
|
// @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed
|
|
|
|
|
// @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
|
|
|
|
|
// @User: Advanced
|
|
|
|
|
// @RebootRequired: True
|
|
|
|
|
AP_GROUPINFO("PWM_TYPE", 15, AP_MotorsMulticopter, _pwm_type, PWM_TYPE_NORMAL), |
|
|
|
|