mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Motors: tradheli - TAIL_SPEED metadata correction
This commit is contained in:
parent
096a624301
commit
0afd4d75f4
@ -62,10 +62,10 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = {
|
|||||||
AP_GROUPINFO("FLYBAR_MODE", 9, AP_MotorsHeli_Single, _flybar_mode, AP_MOTORS_HELI_NOFLYBAR),
|
AP_GROUPINFO("FLYBAR_MODE", 9, AP_MotorsHeli_Single, _flybar_mode, AP_MOTORS_HELI_NOFLYBAR),
|
||||||
|
|
||||||
// @Param: TAIL_SPEED
|
// @Param: TAIL_SPEED
|
||||||
// @DisplayName: Direct Drive VarPitch Tail ESC speed
|
// @DisplayName: DDVP Tail ESC speed
|
||||||
// @Description: Direct Drive VarPitch Tail ESC speed in PWM microseconds. Only used when TailType is DirectDrive VarPitch
|
// @Description: Direct drive, variable pitch tail ESC speed in percent output to the tail motor esc (HeliTailRSC Servo) when motor interlock enabled (throttle hold off).
|
||||||
// @Range: 0 1000
|
// @Range: 0 100
|
||||||
// @Units: PWM
|
// @Units: %
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("TAIL_SPEED", 10, AP_MotorsHeli_Single, _direct_drive_tailspeed, AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT),
|
AP_GROUPINFO("TAIL_SPEED", 10, AP_MotorsHeli_Single, _direct_drive_tailspeed, AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT),
|
||||||
|
Loading…
Reference in New Issue
Block a user