Update ArduPlane/Parameters.cpp

This commit is contained in:
Nathan E 2018-12-20 17:37:41 -06:00 committed by Tom Pittenger
parent ac773ccd79
commit 448d19ddbb

View File

@ -38,7 +38,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: AUTOTUNE_LEVEL
// @DisplayName: Autotune level
// @Description: Level of aggressiveness for autotune. When autotune is run a lower AUTOTUNE_LEVEL will result in a 'softer' tune, with less aggressive gains. For most users a level of 6 is recommended.
// @Description: Level of aggressiveness of pitch and roll PID gains. Lower values result in a 'softer' tune. Level 6 recommended for most planes.
// @Range: 1 10
// @Increment: 1
// @User: Standard
@ -62,7 +62,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: KFF_RDDRMIX
// @DisplayName: Rudder Mix
// @Description: The amount of rudder mix to apply during aileron movement 0 = 0 %, 1 = 100%
// @Description: Percentage of rudder to add during aileron movement. Increase if nose initially yaws away from roll. Coordinates turns.
// @Range: 0 1
// @Increment: 0.01
// @User: Standard
@ -70,7 +70,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: KFF_THR2PTCH
// @DisplayName: Throttle to Pitch Mix
// @Description: Throttle to pitch feed-forward gain.
// @Description: Degrees of elevator added for full throttle application. Increase to compensate for throttle causing down pitch.
// @Range: 0 5
// @Increment: 0.01
// @User: Advanced
@ -78,7 +78,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: STAB_PITCH_DOWN
// @DisplayName: Low throttle pitch down trim
// @Description: This controls the amount of down pitch to add in FBWA and AUTOTUNE modes when at low throttle. No down trim is added when throttle is above TRIM_THROTTLE. Below TRIM_THROTTLE downtrim is added in proportion to the amount the throttle is below TRIM_THROTTLE. At zero throttle the full downpitch specified in this parameter is added. This parameter is meant to help keep airspeed up when flying in FBWA mode with low throttle, such as when on a landing approach, without relying on an airspeed sensor. A value of 2 degrees is good for many planes, although a higher value may be needed for high drag aircraft.
// @Description: Degrees of down pitch added when throttle is below TRIM_THROTTLE in FBWA and AUTOTUNE modes. Scales linearly so full value is added when THR_MIN is reached. Helps to keep airspeed higher in glides or landing approaches and prevents accidental stalls. 2 degrees recommended for most planes.
// @Range: 0 15
// @Increment: 0.1
// @Units: deg
@ -343,14 +343,14 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: STALL_PREVENTION
// @DisplayName: Enable stall prevention
// @Description: This controls the use of stall prevention techniques, including roll limits at low speed and raising the minimum airspeed in turns. The limits are based on the aerodynamic load factor of a banked turn. This option relies on the correct ARSPD_FBW_MIN value being set correctly. Note that if you don't have an airspeed sensor then stall prevention will use an airspeed estimate based on the ground speed plus a wind estimate taken from the response of the autopilot banked turns. That synthetic airspeed estimate may be inaccurate, so you should not assume that stall prevention with no airspeed sensor will be effective.
// @Description: Enables roll limits at low airspeed in roll limiting flight modes. Roll limits based on aerodynamic load factor in turns and scale on ARSPD_FBW_MIN that must be set correctly. Without airspeed sensor, uses synthetic airspeed from wind speed estimate that may both be inaccurate.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
ASCALAR(stall_prevention, "STALL_PREVENTION", 1),
// @Param: ARSPD_FBW_MIN
// @DisplayName: Minimum Airspeed
// @Description: This is the minimum airspeed you want to fly at in modes where the autopilot controls the airspeed. This should be set to a value around 20% higher than the level flight stall speed for the airframe. This value is also used in the STALL_PREVENTION code.
// @Description: Minimum airspeed demanded in automatic throttle modes. Should be set to 20% higher than level flight stall speed.
// @Units: m/s
// @Range: 5 100
// @Increment: 1
@ -359,7 +359,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: ARSPD_FBW_MAX
// @DisplayName: Maximum Airspeed
// @Description: This is the maximum airspeed that you want to allow for your airframe in auto-throttle modes. You should ensure that this value is sufficiently above the ARSPD_FBW_MIN value to allow for a sufficient flight envelope to accurately control altitude using airspeed. A value at least 50% above ARSPD_FBW_MIN is recommended.
// @Description: Maximum airspeed demanded in automatic throttle modes. Should be set slightly less than level flight speed at THR_MAX and also at least 50% above ARSPD_FBW_MAX to allow for accurate TECS altitude control.
// @Units: m/s
// @Range: 5 100
// @Increment: 1
@ -401,7 +401,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: THR_MIN
// @DisplayName: Minimum Throttle
// @Description: The minimum throttle setting (as a percentage) which the autopilot will apply. For the final stage of an automatic landing this is always zero. If your ESC supports reverse, use a negative value to configure for reverse thrust.
// @Description: Minimum throttle percentage used in automatic throttle modes. Negative values allow reverse thrust if hardware supports it.
// @Units: %
// @Range: -100 100
// @Increment: 1
@ -410,7 +410,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: THR_MAX
// @DisplayName: Maximum Throttle
// @Description: The maximum throttle setting (as a percentage) which the autopilot will apply.
// @Description: Maximum throttle percentage used in automatic throttle modes.
// @Units: %
// @Range: 0 100
// @Increment: 1
@ -428,7 +428,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: THR_SLEWRATE
// @DisplayName: Throttle slew rate
// @Description: maximum percentage change in throttle per second. A setting of 10 means to not change the throttle by more than 10% of the full throttle range in one second. Note that the minimum throttle change is 1 microsecond per loop, which provides a lower limit on the throttle slew rate, especially for quadplanes that run at 300 loops per second by default.
// @Description: Maximum change in throttle percentage per second. Lower limit based on 1 microsend of servo increase per loop. Divide SCHED_LOOP_RATE by approximately 10 to determine minimum achievable value.
// @Units: %/s
// @Range: 0 127
// @Increment: 1
@ -476,7 +476,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: TRIM_THROTTLE
// @DisplayName: Throttle cruise percentage
// @Description: The target percentage of throttle to apply for normal flight
// @Description: Target percentage of throttle to apply for flight in automatic throttle modes and throttle percentage that maintains TRIM_ARSPD_CM. Caution: low battery voltages at the end of flights may require higher throttle to maintain airspeed.
// @Units: %
// @Range: 0 100
// @Increment: 1
@ -585,8 +585,8 @@ const AP_Param::Info Plane::var_info[] = {
GSCALAR(initial_mode, "INITIAL_MODE", MANUAL),
// @Param: LIM_ROLL_CD
// @DisplayName: Maximum Bank Angle
// @Description: The maximum commanded bank angle in either direction
// @DisplayName: Maximum bank angle commanded in modes with stabilized limits. Increase this value for sharper turns, but decrease to prevent accelerated stalls.
// @Description:
// @Units: cdeg
// @Range: 0 9000
// @Increment: 1
@ -595,7 +595,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: LIM_PITCH_MAX
// @DisplayName: Maximum Pitch Angle
// @Description: The maximum commanded pitch up angle
// @Description: Maximum pitch up angle commanded in modes with stabilized limits.
// @Units: cdeg
// @Range: 0 9000
// @Increment: 1
@ -604,7 +604,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: LIM_PITCH_MIN
// @DisplayName: Minimum Pitch Angle
// @Description: The minimum commanded pitch down angle
// @Description: Maximum pitch down angle commanded in modes with stabilized limits
// @Units: cdeg
// @Range: -9000 0
// @Increment: 1
@ -656,7 +656,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: TRIM_AUTO
// @DisplayName: Automatic trim adjustment
// @Description: Set RC trim PWM levels to current levels when switching away from manual mode. When this option is enabled and you change from MANUAL to any other mode then the APM will take the current position of the control sticks as the trim values for aileron, elevator and rudder. It will use those to set the SERVOn_TRIM values and the RCn_TRIM values. This option is disabled by default as if a pilot is not aware of this option and changes from MANUAL to another mode while control inputs are not centered then the trim could be changed to a dangerously bad value. You can enable this option to assist with trimming your plane, by enabling it before takeoff then switching briefly to MANUAL in flight, and seeing how the plane reacts. You can then switch back to FBWA, trim the surfaces then again test MANUAL mode. Each time you switch from MANUAL the APM will take your control inputs as the new trim. After you have good trim on your aircraft you can disable TRIM_AUTO for future flights. You should also see the newer and much safer SERVO_AUTO_TRIM parameter.
// @Description: Enables the setting SERVOn_TRIM values to current levels when switching out of MANUAL mode. Should not be left on as mode switches while the plane is rolling or pitching can cause invalid trim values and subsequent unstable behavior. See newer and safer SERVO_AUTO_TRIM parameter for automated results.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
GSCALAR(auto_trim, "TRIM_AUTO", AUTO_TRIM),
@ -714,13 +714,13 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: RST_MISSION_CH
// @DisplayName: Reset Mission Channel
// @Description: RC channel to use to reset the mission to the first waypoint. When this channel goes above 1750 the mission is reset. Set RST_MISSION_CH to 0 to disable.
// @Description: Enables a channel to reset the mission to the first waypoint. Mission restart is triggered by channel rising above 1750 PWM. 0 disables.
// @User: Advanced
GSCALAR(reset_mission_chan, "RST_MISSION_CH", 0),
// @Param: TRIM_ARSPD_CM
// @DisplayName: Target airspeed
// @Description: Airspeed in cm/s to aim for when airspeed is enabled in auto mode. This is a calibrated (apparent) airspeed.
// @Description: Target airspeed in cm/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.
// @Units: cm/s
// @User: User
ASCALAR(airspeed_cruise_cm, "TRIM_ARSPD_CM", AIRSPEED_CRUISE_CM),
@ -741,14 +741,14 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: TRIM_PITCH_CD
// @DisplayName: Pitch angle offset
// @Description: offset to add to pitch - used for in-flight pitch trimming. It is recommended that instead of using this parameter you level your plane correctly on the ground for good flight attitude.
// @Description: Offset applied to AHRS pitch used for in-flight pitch trimming. Correct ground leveling is better than changing this parameter.
// @Units: cdeg
// @User: Advanced
GSCALAR(pitch_trim_cd, "TRIM_PITCH_CD", 0),
// @Param: ALT_HOLD_RTL
// @DisplayName: RTL altitude
// @Description: Return to launch target altitude. This is the relative altitude the plane will aim for and loiter at when returning home. If this is negative (usually -1) then the plane will use the current altitude at the time of entering RTL. Note that when transiting to a Rally Point the altitude of the Rally Point is used instead of ALT_HOLD_RTL.
// @Description: Target altitude above home for RTL mode. Maintains current altitude if set to -1. Rally point altitudes are used if plane does not return to home.
// @Units: cm
// @User: User
GSCALAR(RTL_altitude_cm, "ALT_HOLD_RTL", ALT_HOLD_HOME_CM),