mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: parameter @Units to Percent*10
This commit is contained in:
parent
f8e2947823
commit
7ae3014c14
@ -164,8 +164,8 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(optflow_enabled, "FLOW_ENABLE", DISABLED),
|
||||
|
||||
// @Param: SUPER_SIMPLE
|
||||
// @DisplayName: Enable Super Simple Mode
|
||||
// @Description: Enabling this turn on one of the Super Simple Mode variants. Setting this to Disabled(0) will disable Super Simple Mode
|
||||
// @DisplayName: Super Simple Mode
|
||||
// @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode
|
||||
// @Values: 0:Disabled,1:Mode1,2:Mode2,3:Mode1+2,4:Mode3,5:Mode1+3,6:Mode2+3,7:Mode1+2+3,8:Mode4,9:Mode1+4,10:Mode2+4,11:Mode1+2+4,12:Mode3+4,13:Mode1+3+4,14:Mode2+3+4,15:Mode1+2+3+4,16:Mode5,17:Mode1+5,18:Mode2+5,19:Mode1+2+5,20:Mode3+5,21:Mode1+3+5,22:Mode2+3+5,23:Mode1+2+3+5,24:Mode4+5,25:Mode1+4+5,26:Mode2+4+5,27:Mode1+2+4+5,28:Mode3+4+5,29:Mode1+3+4+5,30:Mode2+3+4+5,31:Mode1+2+3+4+5,32:Mode6,33:Mode1+6,34:Mode2+6,35:Mode1+2+6,36:Mode3+6,37:Mode1+3+6,38:Mode2+3+6,39:Mode1+2+3+6,40:Mode4+6,41:Mode1+4+6,42:Mode2+4+6,43:Mode1+2+4+6,44:Mode3+4+6,45:Mode1+3+4+6,46:Mode2+3+4+6,47:Mode1+2+3+4+6,48:Mode5+6,49:Mode1+5+6,50:Mode2+5+6,51:Mode1+2+5+6,52:Mode3+5+6,53:Mode1+3+5+6,54:Mode2+3+5+6,55:Mode1+2+3+5+6,56:Mode4+5+6,57:Mode1+4+5+6,58:Mode2+4+5+6,59:Mode1+2+4+5+6,60:Mode3+4+5+6,61:Mode1+3+4+5+6,62:Mode2+3+4+5+6,63:Mode1+2+3+4+5+6
|
||||
// @User: Standard
|
||||
GSCALAR(super_simple, "SUPER_SIMPLE", SUPER_SIMPLE),
|
||||
@ -190,7 +190,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @DisplayName: Yaw behaviour during missions
|
||||
// @Description: Determines how the autopilot controls the yaw during missions and RTL
|
||||
// @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course
|
||||
// @User: Advanced
|
||||
// @User: Standard
|
||||
GSCALAR(wp_yaw_behavior, "WP_YAW_BEHAVIOR", WP_YAW_BEHAVIOR_DEFAULT),
|
||||
|
||||
// @Param: WP_TOTAL
|
||||
@ -251,18 +251,18 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(pilot_velocity_z_max, "PILOT_VELZ_MAX", PILOT_VELZ_MAX),
|
||||
|
||||
// @Param: THR_MIN
|
||||
// @DisplayName: Minimum Throttle
|
||||
// @DisplayName: Throttle Minimum
|
||||
// @Description: The minimum throttle that will be sent to the motors to keep them spinning
|
||||
// @Units: pwm
|
||||
// @Units: Percent*10
|
||||
// @Range: 0 300
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_min, "THR_MIN", THR_MIN_DEFAULT),
|
||||
|
||||
// @Param: THR_MAX
|
||||
// @DisplayName: Maximum Throttle
|
||||
// @DisplayName: Throttle Maximum
|
||||
// @Description: The maximum throttle that will be sent to the motors
|
||||
// @Units: pwm
|
||||
// @Units: Percent*10
|
||||
// @Range: 0 1000
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
@ -288,8 +288,8 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @DisplayName: Throttle Trim
|
||||
// @Description: The autopilot's estimate of the throttle required to maintain a level hover. Calculated automatically from the pilot's throttle input while in stabilize mode
|
||||
// @Range: 0 1000
|
||||
// @Units: pwm
|
||||
// @User: Standard
|
||||
// @Units: Percent*10
|
||||
// @User: Advanced
|
||||
GSCALAR(throttle_cruise, "TRIM_THROTTLE", THROTTLE_CRUISE),
|
||||
|
||||
// @Param: THR_MID
|
||||
@ -297,7 +297,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Description: The throttle output (0 ~ 1000) when throttle stick is in mid position. Used to scale the manual throttle so that the mid throttle stick position is close to the throttle required to hover
|
||||
// @User: Standard
|
||||
// @Range: 300 700
|
||||
// @Units: pwm
|
||||
// @Units: Percent*10
|
||||
// @Increment: 1
|
||||
GSCALAR(throttle_mid, "THR_MID", THR_MID_DEFAULT),
|
||||
|
||||
@ -353,7 +353,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @DisplayName: Log bitmask
|
||||
// @Description: 2 byte bitmap of log types to enable
|
||||
// @Values: 0:Disabled,830:Default,958:Default+IMU,1854:Default+Motors,17214:Default+INav
|
||||
// @User: Advanced
|
||||
// @User: Standard
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
|
||||
// @Param: ESC
|
||||
@ -468,7 +468,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @DisplayName: Heli Stabilize Throttle Collective Minimum
|
||||
// @Description: Helicopter's minimum collective position while pilot directly controls collective in stabilize mode
|
||||
// @Range: 0 500
|
||||
// @Units: pwm
|
||||
// @Units: Percent*10
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(heli_stab_col_min, "STAB_COL_MIN", HELI_STAB_COLLECTIVE_MIN_DEFAULT),
|
||||
@ -477,7 +477,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @DisplayName: Stabilize Throttle Maximum
|
||||
// @Description: Helicopter's maximum collective position while pilot directly controls collective in stabilize mode
|
||||
// @Range: 500 1000
|
||||
// @Units: pwm
|
||||
// @Units: Percent*10
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(heli_stab_col_max, "STAB_COL_MAX", HELI_STAB_COLLECTIVE_MAX_DEFAULT),
|
||||
@ -619,7 +619,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
||||
// @Range: 0 500
|
||||
// @Increment: 10
|
||||
// @Units: pwm
|
||||
// @Units: Percent*10
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RATE_RLL_D
|
||||
@ -649,7 +649,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
||||
// @Range: 0 500
|
||||
// @Increment: 10
|
||||
// @Units: pwm
|
||||
// @Units: Percent*10
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RATE_PIT_D
|
||||
@ -679,7 +679,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
||||
// @Range: 0 800
|
||||
// @Increment: 10
|
||||
// @Units: pwm
|
||||
// @Units: Percent*10
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RATE_YAW_D
|
||||
@ -792,7 +792,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @DisplayName: Throttle acceleration controller I gain maximum
|
||||
// @Description: Throttle acceleration controller I gain maximum. Constrains the maximum pwm that the I term will generate
|
||||
// @Range: 0 500
|
||||
// @Units: pwm
|
||||
// @Units: Percent*10
|
||||
// @User: Standard
|
||||
|
||||
// @Param: THR_ACCEL_D
|
||||
|
Loading…
Reference in New Issue
Block a user