mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Motors: added DShot to parameter docs
This commit is contained in:
parent
95a261e061
commit
bd9df6d0ec
@ -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),
|
||||
|
Loading…
Reference in New Issue
Block a user