Browse Source

Plane: Use SI units conventions in parameter units

Follow the rules from:
http://physics.nist.gov/cuu/Units/units.html
http://physics.nist.gov/cuu/Units/outside.html
and
http://physics.nist.gov/cuu/Units/checklist.html
one further constrain is that only printable (7bit) ASCII characters are allowed
mission-4.1.18
Dr.-Ing. Amilcar Do Carmo Lucas 8 years ago committed by Andrew Tridgell
parent
commit
2f5f8eb323
  1. 92
      ArduPlane/Parameters.cpp
  2. 20
      ArduPlane/quadplane.cpp

92
ArduPlane/Parameters.cpp

@ -64,7 +64,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -64,7 +64,7 @@ const AP_Param::Info Plane::var_info[] = {
// @DisplayName: Telemetry startup delay
// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
// @User: Standard
// @Units: seconds
// @Units: s
// @Range: 0 30
// @Increment: 1
GSCALAR(telem_delay, "TELEM_DELAY", 0),
@ -97,7 +97,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -97,7 +97,7 @@ const AP_Param::Info Plane::var_info[] = {
// @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.
// @Range: 0 15
// @Increment: 0.1
// @Units: Degrees
// @Units: deg
// @User: Advanced
GSCALAR(stab_pitch_down, "STAB_PITCH_DOWN", 2.0f),
@ -106,7 +106,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -106,7 +106,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Description: This controls the minimum altitude change for a waypoint before a glide slope will be used instead of an immediate altitude change. The default value is 15 meters, which helps to smooth out waypoint missions where small altitude changes happen near waypoints. If you don't want glide slopes to be used in missions then you can set this to zero, which will disable glide slope calculations. Otherwise you can set it to a minimum number of meters of altitude error to the destination waypoint before a glide slope will be used to change altitude.
// @Range: 0 1000
// @Increment: 1
// @Units: meters
// @Units: m
// @User: Advanced
GSCALAR(glide_slope_min, "GLIDE_SLOPE_MIN", 15),
@ -115,7 +115,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -115,7 +115,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Description: This controls the height above the glide slope the plane may be before rebuilding a glide slope. This is useful for smoothing out an autotakeoff
// @Range: 0 100
// @Increment: 1
// @Units: meters
// @Units: m
// @User: Advanced
GSCALAR(glide_slope_threshold, "GLIDE_SLOPE_THR", 5.0),
@ -154,7 +154,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -154,7 +154,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: TKOFF_THR_DELAY
// @DisplayName: Takeoff throttle delay
// @Description: This parameter sets the time delay (in 1/10ths of a second) that the ground speed check is delayed after the forward acceleration check controlled by TKOFF_THR_MINACC has passed. For hand launches with pusher propellers it is essential that this is set to a value of no less than 2 (0.2 seconds) to ensure that the aircraft is safely clear of the throwers arm before the motor can start. For bungee launches a larger value can be used (such as 30) to give time for the bungee to release from the aircraft before the motor is started.
// @Units: 0.1 seconds
// @Units: ds
// @Range: 0 127
// @Increment: 1
// @User: User
@ -163,7 +163,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -163,7 +163,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: TKOFF_TDRAG_ELEV
// @DisplayName: Takeoff tail dragger elevator
// @Description: This parameter sets the amount of elevator to apply during the initial stage of a takeoff. It is used to hold the tail wheel of a taildragger on the ground during the initial takeoff stage to give maximum steering. This option should be combined with the TKOFF_TDRAG_SPD1 option and the GROUND_STEER_ALT option along with tuning of the ground steering controller. A value of zero means to bypass the initial "tail hold" stage of takeoff. Set to zero for hand and catapult launch. For tail-draggers you should normally set this to 100, meaning full up elevator during the initial stage of takeoff. For most tricycle undercarriage aircraft a value of zero will work well, but for some tricycle aircraft a small negative value (say around -20 to -30) will apply down elevator which will hold the nose wheel firmly on the ground during initial acceleration. Only use a negative value if you find that the nosewheel doesn't grip well during takeoff. Too much down elevator on a tricycle undercarriage may cause instability in steering as the plane pivots around the nosewheel. Add down elevator 10 percent at a time.
// @Units: Percent
// @Units: %
// @Range: -100 100
// @Increment: 1
// @User: User
@ -190,7 +190,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -190,7 +190,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: TKOFF_THR_SLEW
// @DisplayName: Takeoff throttle slew rate
// @Description: This parameter sets the slew rate for the throttle during auto takeoff. When this is zero the THR_SLEWRATE parameter is used during takeoff. For rolling takeoffs it can be a good idea to set a lower slewrate for takeoff to give a slower acceleration which can improve ground steering control. The value is a percentage throttle change per second, so a value of 20 means to advance the throttle over 5 seconds on takeoff. Values below 20 are not recommended as they may cause the plane to try to climb out with too little throttle.
// @Units: percent
// @Units: %/s
// @Range: 0 127
// @Increment: 1
// @User: User
@ -199,7 +199,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -199,7 +199,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: TKOFF_PLIM_SEC
// @DisplayName: Takeoff pitch limit reduction
// @Description: This parameter reduces the pitch minimum limit of an auto-takeoff just a few seconds before it reaches the target altitude. This reduces overshoot by allowing the flight controller to start leveling off a few seconds before reaching the target height. When set to zero, the mission pitch min is enforced all the way to and through the target altitude, otherwise the pitch min slowly reduces to zero in the final segment. This is the pitch_min, not the demand. The flight controller should still be commanding to gain altitude to finish the takeoff but with this param it is not forcing it higher than it wants to be.
// @Units: seconds
// @Units: s
// @Range: 0 10
// @Increment: 0.5
// @User: Advanced
@ -209,7 +209,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -209,7 +209,7 @@ const AP_Param::Info Plane::var_info[] = {
// @DisplayName: Takeoff flap percentage
// @Description: The amount of flaps (as a percentage) to apply in automatic takeoff
// @Range: 0 100
// @Units: Percent
// @Units: %
// @User: Advanced
GSCALAR(takeoff_flap_percent, "TKOFF_FLAP_PCNT", 0),
@ -222,7 +222,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -222,7 +222,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: LEVEL_ROLL_LIMIT
// @DisplayName: Level flight roll limit
// @Description: This controls the maximum bank angle in degrees during flight modes where level flight is desired, such as in the final stages of landing, and during auto takeoff. This should be a small angle (such as 5 degrees) to prevent a wing hitting the runway during takeoff or landing. Setting this to zero will completely disable heading hold on auto takeoff and final landing approach.
// @Units: degrees
// @Units: deg
// @Range: 0 45
// @Increment: 1
// @User: User
@ -252,7 +252,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -252,7 +252,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: ALT_OFFSET
// @DisplayName: Altitude offset
// @Description: This is added to the target altitude in automatic flight. It can be used to add a global altitude offset to a mission
// @Units: Meters
// @Units: m
// @Range: -32767 32767
// @Increment: 1
// @User: Advanced
@ -261,7 +261,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -261,7 +261,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: WP_RADIUS
// @DisplayName: Waypoint Radius
// @Description: Defines the maximum distance from a waypoint that when crossed indicates the waypoint may be complete. To avoid the aircraft looping around the waypoint in case it misses by more than the WP_RADIUS an additional check is made to see if the aircraft has crossed a "finish line" passing through the waypoint and perpendicular to the flight path from the previous waypoint. If that finish line is crossed then the waypoint is considered complete. Note that the navigation controller may decide to turn later than WP_RADIUS before a waypoint, based on how sharp the turn is and the speed of the aircraft. It is safe to set WP_RADIUS much larger than the usual turn radius of your aircraft and the navigation controller will work out when to turn. If you set WP_RADIUS too small then you will tend to overshoot the turns.
// @Units: Meters
// @Units: m
// @Range: 1 32767
// @Increment: 1
// @User: Standard
@ -270,7 +270,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -270,7 +270,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: WP_MAX_RADIUS
// @DisplayName: Waypoint Maximum Radius
// @Description: Sets the maximum distance to a waypoint for the waypoint to be considered complete. This overrides the "cross the finish line" logic that is normally used to consider a waypoint complete. For normal AUTO behaviour this parameter should be set to zero. Using a non-zero value is only recommended when it is critical that the aircraft does approach within the given radius, and should loop around until it has done so. This can cause the aircraft to loop forever if its turn radius is greater than the maximum radius set.
// @Units: Meters
// @Units: m
// @Range: 0 32767
// @Increment: 1
// @User: Standard
@ -279,7 +279,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -279,7 +279,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: WP_LOITER_RAD
// @DisplayName: Waypoint Loiter Radius
// @Description: Defines the distance from the waypoint center, the plane will maintain during a loiter. If you set this value to a negative number then the default loiter direction will be counter-clockwise instead of clockwise.
// @Units: Meters
// @Units: m
// @Range: -32767 32767
// @Increment: 1
// @User: Standard
@ -288,7 +288,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -288,7 +288,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: RTL_RADIUS
// @DisplayName: RTL loiter radius
// @Description: Defines the radius of the loiter circle when in RTL mode. If this is zero then WP_LOITER_RAD is used. If the radius is negative then a counter-clockwise is used. If positive then a clockwise loiter is used.
// @Units: Meters
// @Units: m
// @Range: -32767 32767
// @Increment: 1
// @User: Standard
@ -317,7 +317,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -317,7 +317,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: FENCE_MINALT
// @DisplayName: Fence Minimum Altitude
// @Description: Minimum altitude allowed before geofence triggers
// @Units: meters
// @Units: m
// @Range: 0 32767
// @Increment: 1
// @User: Standard
@ -326,7 +326,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -326,7 +326,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: FENCE_MAXALT
// @DisplayName: Fence Maximum Altitude
// @Description: Maximum altitude allowed before geofence triggers
// @Units: meters
// @Units: m
// @Range: 0 32767
// @Increment: 1
// @User: Standard
@ -335,7 +335,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -335,7 +335,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: FENCE_RETALT
// @DisplayName: Fence Return Altitude
// @Description: Altitude the aircraft will transit to when a fence breach occurs. If FENCE_RETALT is <= 0 then the midpoint between FENCE_MAXALT and FENCE_MINALT is used, unless FENCE_MAXALT < FENCE_MINALT. If FENCE_MAXALT < FENCE_MINALT AND FENCE_RETALT is <= 0 then ALT_HOLD_RTL is the altitude used on a fence breach.
// @Units: meters
// @Units: m
// @Range: 0 32767
// @Increment: 1
// @User: Standard
@ -400,7 +400,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -400,7 +400,7 @@ const AP_Param::Info Plane::var_info[] = {
// @DisplayName: Terrain lookahead
// @Description: This controls how far ahead the terrain following code looks to ensure it stays above upcoming terrain. A value of zero means no lookahead, so the controller will track only the terrain directly below the aircraft. The lookahead will never extend beyond the next waypoint when in AUTO mode.
// @Range: 0 10000
// @Units: meters
// @Units: m
// @User: Standard
GSCALAR(terrain_lookahead, "TERRAIN_LOOKAHD", 2000),
#endif
@ -417,7 +417,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -417,7 +417,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.
// @Units: Percent
// @Units: %
// @Range: -100 100
// @Increment: 1
// @User: Standard
@ -426,7 +426,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -426,7 +426,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.
// @Units: Percent
// @Units: %
// @Range: 0 100
// @Increment: 1
// @User: Standard
@ -435,7 +435,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -435,7 +435,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: TKOFF_THR_MAX
// @DisplayName: Maximum Throttle for takeoff
// @Description: The maximum throttle setting during automatic takeoff. If this is zero then THR_MAX is used for takeoff as well.
// @Units: Percent
// @Units: %
// @Range: 0 100
// @Increment: 1
// @User: Advanced
@ -444,7 +444,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -444,7 +444,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.
// @Units: Percent
// @Units: %/s
// @Range: 0 127
// @Increment: 1
// @User: Standard
@ -453,7 +453,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -453,7 +453,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: FLAP_SLEWRATE
// @DisplayName: Flap slew rate
// @Description: maximum percentage change in flap output per second. A setting of 25 means to not change the flap by more than 25% of the full flap range in one second. A value of 0 means no rate limiting.
// @Units: Percent
// @Units: %/s
// @Range: 0 100
// @Increment: 1
// @User: Advanced
@ -492,7 +492,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -492,7 +492,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
// @Units: Percent
// @Units: %
// @Range: 0 100
// @Increment: 1
// @User: Standard
@ -515,7 +515,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -515,7 +515,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: FS_SHORT_TIMEOUT
// @DisplayName: Short failsafe timeout
// @Description: The time in seconds that a failsafe condition has to persist before a short failsafe event will occur. This defaults to 1.5 seconds
// @Units: seconds
// @Units: s
// @Range: 1 100
// @Increment: 0.5
// @User: Standard
@ -531,7 +531,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -531,7 +531,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: FS_LONG_TIMEOUT
// @DisplayName: Long failsafe timeout
// @Description: The time in seconds that a failsafe condition has to persist before a long failsafe event will occur. This defaults to 5 seconds.
// @Units: seconds
// @Units: s
// @Range: 1 300
// @Increment: 0.5
// @User: Standard
@ -540,7 +540,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -540,7 +540,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: FS_BATT_VOLTAGE
// @DisplayName: Failsafe battery voltage
// @Description: Battery voltage to trigger failsafe. Set to 0 to disable battery voltage failsafe. If the battery voltage drops below this voltage continuously for 10 seconds then the plane will switch to RTL mode.
// @Units: Volts
// @Units: V
// @Increment: 0.1
// @User: Standard
GSCALAR(fs_batt_voltage, "FS_BATT_VOLTAGE", 0),
@ -548,7 +548,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -548,7 +548,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: FS_BATT_MAH
// @DisplayName: Failsafe battery milliAmpHours
// @Description: Battery capacity remaining to trigger failsafe. Set to 0 to disable battery remaining failsafe. If the battery remaining drops below this level then the plane will switch to RTL mode immediately.
// @Units: mAh
// @Units: mA.h
// @Increment: 50
// @User: Standard
GSCALAR(fs_batt_mah, "FS_BATT_MAH", 0),
@ -618,7 +618,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -618,7 +618,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: LIM_ROLL_CD
// @DisplayName: Maximum Bank Angle
// @Description: The maximum commanded bank angle in either direction
// @Units: centi-Degrees
// @Units: cdeg
// @Range: 0 9000
// @Increment: 1
// @User: Standard
@ -627,7 +627,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -627,7 +627,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: LIM_PITCH_MAX
// @DisplayName: Maximum Pitch Angle
// @Description: The maximum commanded pitch up angle
// @Units: centi-Degrees
// @Units: cdeg
// @Range: 0 9000
// @Increment: 1
// @User: Standard
@ -636,7 +636,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -636,7 +636,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: LIM_PITCH_MIN
// @DisplayName: Minimum Pitch Angle
// @Description: The minimum commanded pitch down angle
// @Units: centi-Degrees
// @Units: cdeg
// @Range: -9000 0
// @Increment: 1
// @User: Standard
@ -645,7 +645,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -645,7 +645,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: ACRO_ROLL_RATE
// @DisplayName: ACRO mode roll rate
// @Description: The maximum roll rate at full stick deflection in ACRO mode
// @Units: degrees/second
// @Units: deg/s
// @Range: 10 500
// @Increment: 1
// @User: Standard
@ -654,7 +654,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -654,7 +654,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: ACRO_PITCH_RATE
// @DisplayName: ACRO mode pitch rate
// @Description: The maximum pitch rate at full stick deflection in ACRO mode
// @Units: degrees/second
// @Units: deg/s
// @Range: 10 500
// @Increment: 1
// @User: Standard
@ -670,7 +670,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -670,7 +670,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: GROUND_STEER_ALT
// @DisplayName: Ground steer altitude
// @Description: Altitude at which to use the ground steering controller on the rudder. If non-zero then the STEER2SRV controller will be used to control the rudder for altitudes within this limit of the home altitude.
// @Units: Meters
// @Units: m
// @Range: -100 100
// @Increment: 0.1
// @User: Standard
@ -679,7 +679,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -679,7 +679,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: GROUND_STEER_DPS
// @DisplayName: Ground steer rate
// @Description: Ground steering rate in degrees per second for full rudder stick deflection
// @Units: degrees/second
// @Units: deg/s
// @Range: 10 360
// @Increment: 1
// @User: Advanced
@ -752,7 +752,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -752,7 +752,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: MIXING_OFFSET
// @DisplayName: Mixing Offset
// @Description: The offset for the Vtail and elevon output mixers, as a percentage. This can be used in combination with MIXING_GAIN to configure how the control surfaces respond to input. The response to aileron or elevator input can be increased by setting this parameter to a positive or negative value. A common usage is to enter a positive value to increase the aileron response of the elevons of a flying wing. The default value of zero will leave the aileron-input response equal to the elevator-input response.
// @Units: percent
// @Units: d%
// @Range: -1000 1000
// @User: User
GSCALAR(mixing_offset, "MIXING_OFFSET", 0),
@ -760,7 +760,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -760,7 +760,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: DSPOILR_RUD_RATE
// @DisplayName: Differential spoilers rudder rate
// @Description: Sets the amount of deflection that the rudder output will apply to the differential spoilers, as a percentage. The default value of 100 results in full rudder applying full deflection. A value of 0 will result in the differential spoilers exactly following the elevons (no rudder effect).
// @Units: percent
// @Units: d%
// @Range: -1000 1000
// @User: User
GSCALAR(dspoiler_rud_rate, "DSPOILR_RUD_RATE", DSPOILR_RUD_RATE_DEFAULT),
@ -815,21 +815,21 @@ const AP_Param::Info Plane::var_info[] = { @@ -815,21 +815,21 @@ 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.
// @Units: centi-Degrees
// @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.
// @Units: centimeters
// @Units: cm
// @User: User
GSCALAR(RTL_altitude_cm, "ALT_HOLD_RTL", ALT_HOLD_HOME_CM),
// @Param: ALT_HOLD_FBWCM
// @DisplayName: Minimum altitude for FBWB mode
// @Description: This is the minimum altitude in centimeters that FBWB and CRUISE modes will allow. If you attempt to descend below this altitude then the plane will level off. A value of zero means no limit.
// @Units: centimeters
// @Units: cm
// @User: User
GSCALAR(FBWB_min_altitude_cm, "ALT_HOLD_FBWCM", ALT_HOLD_FBW_CM),
@ -857,7 +857,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -857,7 +857,7 @@ const AP_Param::Info Plane::var_info[] = {
// @DisplayName: Flap 1 percentage
// @Description: The percentage change in flap position when FLAP_1_SPEED is reached. Use zero to disable flaps
// @Range: 0 100
// @Units: Percent
// @Units: %
// @User: Advanced
GSCALAR(flap_1_percent, "FLAP_1_PERCNT", FLAP_1_PERCENT),
@ -874,7 +874,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -874,7 +874,7 @@ const AP_Param::Info Plane::var_info[] = {
// @DisplayName: Flap 2 percentage
// @Description: The percentage change in flap position when FLAP_2_SPEED is reached. Use zero to disable flaps
// @Range: 0 100
// @Units: Percent
// @Units: %
// @User: Advanced
GSCALAR(flap_2_percent, "FLAP_2_PERCNT", FLAP_2_PERCENT),
@ -927,7 +927,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -927,7 +927,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: HIL_ERR_LIMIT
// @DisplayName: Limit of error in HIL attitude before reset
// @Description: This controls the maximum error in degrees on any axis before HIL will reset the DCM attitude to match the HIL_STATE attitude. This limit will prevent poor timing on HIL from causing a major attitude error. If the value is zero then no limit applies.
// @Units: degrees
// @Units: deg
// @Range: 0 90
// @Increment: 0.1
// @User: Advanced
@ -951,7 +951,7 @@ const AP_Param::Info Plane::var_info[] = { @@ -951,7 +951,7 @@ const AP_Param::Info Plane::var_info[] = {
// @DisplayName: Crash Deceleration Threshold
// @Description: X-Axis deceleration threshold to notify the crash detector that there was a possible impact which helps disarm the motor quickly after a crash. This value should be much higher than normal negative x-axis forces during normal flight, check flight log files to determine the average IMU.x values for your aircraft and motor type. Higher value means less sensative (triggers on higher impact). For electric planes that don't vibrate much during fight a value of 25 is good (that's about 2.5G). For petrol/nitro planes you'll want a higher value. Set to 0 to disable the collision detector.
// @Units: m/s/s
// @Values: 10 127
// @Range: 10 127
// @User: Advanced
GSCALAR(crash_accel_threshold, "CRASH_ACC_THRESH", 0),
@ -1221,7 +1221,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { @@ -1221,7 +1221,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @DisplayName: rudder differential thrust gain
// @Description: gain control from rudder to differential thrust
// @Range: 0 100
// @Units: Percent
// @Units: %
// @Increment: 1
// @User: Standard
AP_GROUPINFO("RUDD_DT_GAIN", 9, ParametersG2, rudd_dt_gain, 10),

20
ArduPlane/quadplane.cpp

@ -18,7 +18,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { @@ -18,7 +18,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: ANGLE_MAX
// @DisplayName: Angle Max
// @Description: Maximum lean angle in all VTOL flight modes
// @Units: Centi-degrees
// @Units: cdeg
// @Range: 1000 8000
// @User: Advanced
AP_GROUPINFO("ANGLE_MAX", 10, QuadPlane, aparm.angle_max, 3000),
@ -26,7 +26,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { @@ -26,7 +26,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: TRANSITION_MS
// @DisplayName: Transition time
// @Description: Transition time in milliseconds after minimum airspeed is reached
// @Units: milliseconds
// @Units: ms
// @Range: 0 30000
// @User: Advanced
AP_GROUPINFO("TRANSITION_MS", 11, QuadPlane, transition_time_ms, 5000),
@ -91,7 +91,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { @@ -91,7 +91,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @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 1000
// @Units: Percent*10
// @Units: d%
// @User: Standard
// @Param: AZ_D
@ -115,7 +115,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { @@ -115,7 +115,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: VELZ_MAX
// @DisplayName: Pilot maximum vertical speed
// @Description: The maximum vertical velocity the pilot may request in cm/s
// @Units: Centimeters/Second
// @Units: cm/s
// @Range: 50 500
// @Increment: 10
// @User: Standard
@ -173,7 +173,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { @@ -173,7 +173,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: YAW_RATE_MAX
// @DisplayName: Maximum yaw rate
// @Description: This is the maximum yaw rate in degrees/second
// @Units: degrees/second
// @Units: deg/s
// @Range: 50 500
// @Increment: 1
// @User: Standard
@ -204,7 +204,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { @@ -204,7 +204,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Description: Maximum pitch during transition to auto fixed wing flight
// @User: Standard
// @Range: 0 30
// @Units: Degrees
// @Units: deg
// @Increment: 1
AP_GROUPINFO("TRAN_PIT_MAX", 29, QuadPlane, transition_pitch_max, 3),
@ -273,7 +273,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { @@ -273,7 +273,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: TILT_RATE_UP
// @DisplayName: Tiltrotor upwards tilt rate
// @Description: This is the maximum speed at which the motor angle will change for a tiltrotor when moving from forward flight to hover
// @Units: degrees/second
// @Units: deg/s
// @Increment: 1
// @Range: 10 300
// @User: Standard
@ -282,7 +282,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { @@ -282,7 +282,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: TILT_MAX
// @DisplayName: Tiltrotor maximum VTOL angle
// @Description: This is the maximum angle of the tiltable motors at which multicopter control will be enabled. Beyond this angle the plane will fly solely as a fixed wing aircraft and the motors will tilt to their maximum angle at the TILT_RATE
// @Units: degrees
// @Units: deg
// @Increment: 1
// @Range: 20 80
// @User: Standard
@ -322,7 +322,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { @@ -322,7 +322,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: ASSIST_ANGLE
// @DisplayName: Quadplane assistance angle
// @Description: This is the angular error in attitude beyond which the quadplane VTOL motors will provide stability assistance. This will only be used if Q_ASSIST_SPEED is also non-zero. Assistance will be given if the attitude is outside the normal attitude limits by at least 5 degrees and the angular error in roll or pitch is greater than this angle for at least 1 second. Set to zero to disable angle assistance.
// @Units: degrees
// @Units: deg
// @Range: 0 90
// @Increment: 1
// @User: Standard
@ -343,7 +343,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { @@ -343,7 +343,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: TILT_RATE_DN
// @DisplayName: Tiltrotor downwards tilt rate
// @Description: This is the maximum speed at which the motor angle will change for a tiltrotor when moving from hover to forward flight. When this is zero the Q_TILT_RATE_UP value is used.
// @Units: degrees/second
// @Units: deg/s
// @Increment: 1
// @Range: 10 300
// @User: Standard

Loading…
Cancel
Save