mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Landing: 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
This commit is contained in:
parent
5a9baaa8b3
commit
2a16c20ce1
@ -27,7 +27,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
||||
// @DisplayName: Landing slope re-calc threshold
|
||||
// @Description: This parameter is used when using a rangefinder during landing for altitude correction from baro drift (RNGFND_LANDING=1) and the altitude correction indicates your altitude is lower than the intended slope path. This value is the threshold of the correction to re-calculate the landing approach slope. Set to zero to keep the original slope all the way down and any detected baro drift will be corrected by pitching/throttling up to snap back to resume the original slope path. Otherwise, when a rangefinder altitude correction exceeds this threshold it will trigger a slope re-calculate to give a shallower slope. This also smoothes out the approach when flying over objects such as trees. Recommend a value of 2m.
|
||||
// @Range: 0 5
|
||||
// @Units: meters
|
||||
// @Units: m
|
||||
// @Increment: 0.5
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SLOPE_RCALC", 1, AP_Landing, slope_recalc_shallow_threshold, 2.0f),
|
||||
@ -36,7 +36,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
||||
// @DisplayName: Landing auto-abort slope threshold
|
||||
// @Description: This parameter is used when using a rangefinder during landing for altitude correction from baro drift (RNGFND_LANDING=1) and the altitude correction indicates your actual altitude is higher than the intended slope path. Normally it would pitch down steeply but that can result in a crash with high airspeed so this allows remembering the baro offset and self-abort the landing and come around for another landing with the correct baro offset applied for a perfect slope. An auto-abort go-around will only happen once, next attempt will not auto-abort again. This operation happens entirely automatically in AUTO mode. This value is the delta degrees threshold to trigger the go-around compared to the original slope. Example: if set to 5 deg and the mission planned slope is 15 deg then if the new slope is 21 then it will go-around. Set to 0 to disable. Requires LAND_SLOPE_RCALC > 0.
|
||||
// @Range: 0 90
|
||||
// @Units: degrees
|
||||
// @Units: deg
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("ABORT_DEG", 2, AP_Landing, slope_recalc_steep_threshold_to_abort, 0),
|
||||
@ -44,14 +44,14 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
||||
// @Param: PITCH_CD
|
||||
// @DisplayName: Landing Pitch
|
||||
// @Description: Used in autoland to give the minimum pitch in the final stage of landing (after the flare). This parameter can be used to ensure that the final landing attitude is appropriate for the type of undercarriage on the aircraft. Note that it is a minimum pitch only - the landing code will control pitch above this value to try to achieve the configured landing sink rate.
|
||||
// @Units: centi-Degrees
|
||||
// @Units: cdeg
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PITCH_CD", 3, AP_Landing, pitch_cd, 0),
|
||||
|
||||
// @Param: FLARE_ALT
|
||||
// @DisplayName: Landing flare altitude
|
||||
// @Description: Altitude in autoland at which to lock heading and flare to the LAND_PITCH_CD pitch. Note that this option is secondary to LAND_FLARE_SEC. For a good landing it preferable that the flare is triggered by LAND_FLARE_SEC.
|
||||
// @Units: meters
|
||||
// @Units: m
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FLARE_ALT", 4, AP_Landing, flare_alt, 3.0f),
|
||||
@ -59,7 +59,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
||||
// @Param: FLARE_SEC
|
||||
// @DisplayName: Landing flare time
|
||||
// @Description: Vertical time before landing point at which to lock heading and flare with the motor stopped. This is vertical time, and is calculated based solely on the current height above the ground and the current descent rate. Set to 0 if you only wish to flare based on altitude (see LAND_FLARE_ALT).
|
||||
// @Units: seconds
|
||||
// @Units: s
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FLARE_SEC", 5, AP_Landing, flare_sec, 2.0f),
|
||||
@ -67,7 +67,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
||||
// @Param: PF_ALT
|
||||
// @DisplayName: Landing pre-flare altitude
|
||||
// @Description: Altitude to trigger pre-flare flight stage where LAND_PF_ARSPD controls airspeed. The pre-flare flight stage trigger works just like LAND_FLARE_ALT but higher. Disabled when LAND_PF_ARSPD is 0.
|
||||
// @Units: meters
|
||||
// @Units: m
|
||||
// @Range: 0 30
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
@ -76,7 +76,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
||||
// @Param: PF_SEC
|
||||
// @DisplayName: Landing pre-flare time
|
||||
// @Description: Vertical time to ground to trigger pre-flare flight stage where LAND_PF_ARSPD controls airspeed. This pre-flare flight stage trigger works just like LAND_FLARE_SEC but earlier. Disabled when LAND_PF_ARSPD is 0.
|
||||
// @Units: seconds
|
||||
// @Units: s
|
||||
// @Range: 0 10
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
@ -94,7 +94,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
||||
// @Param: THR_SLEW
|
||||
// @DisplayName: Landing throttle slew rate
|
||||
// @Description: This parameter sets the slew rate for the throttle during auto landing. When this is zero the THR_SLEWRATE parameter is used during landing. The value is a percentage throttle change per second, so a value of 20 means to advance the throttle over 5 seconds on landing. Values below 50 are not recommended as it may cause a stall when airspeed is low and you can not throttle up fast enough.
|
||||
// @Units: percent
|
||||
// @Units: %
|
||||
// @Range: 0 127
|
||||
// @Increment: 1
|
||||
// @User: User
|
||||
@ -103,7 +103,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
||||
// @Param: DISARMDELAY
|
||||
// @DisplayName: Landing disarm delay
|
||||
// @Description: After a landing has completed using a LAND waypoint, automatically disarm after this many seconds have passed. Use 0 to not disarm.
|
||||
// @Units: seconds
|
||||
// @Units: s
|
||||
// @Increment: 1
|
||||
// @Range: 0 127
|
||||
// @User: Advanced
|
||||
@ -127,7 +127,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
||||
// @DisplayName: Landing flap percentage
|
||||
// @Description: The amount of flaps (as a percentage) to apply in the landing approach and flare of an automatic landing
|
||||
// @Range: 0 100
|
||||
// @Units: Percent
|
||||
// @Units: %
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FLAP_PERCNT", 13, AP_Landing, flap_percent, 0),
|
||||
|
||||
|
@ -49,7 +49,7 @@ const AP_Param::GroupInfo AP_Landing_Deepstall::var_info[] = {
|
||||
// @DisplayName: Deepstall approach extension
|
||||
// @Description: The forward velocity of the aircraft while stalled
|
||||
// @Range: 10 200
|
||||
// @Units: meters
|
||||
// @Units: m
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("APP_EXT", 4, AP_Landing_Deepstall, approach_extension, 50),
|
||||
|
||||
@ -65,7 +65,7 @@ const AP_Param::GroupInfo AP_Landing_Deepstall::var_info[] = {
|
||||
// @DisplayName: Deepstall slew speed
|
||||
// @Description: The speed at which the elevator slews to deepstall
|
||||
// @Range: 0 2
|
||||
// @Units: seconds
|
||||
// @Units: s
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SLEW_SPD", 6, AP_Landing_Deepstall, slew_speed, 0.5),
|
||||
|
||||
@ -97,7 +97,7 @@ const AP_Param::GroupInfo AP_Landing_Deepstall::var_info[] = {
|
||||
// @DisplayName: Deepstall L1 period
|
||||
// @Description: Deepstall L1 navigational controller period
|
||||
// @Range: 5 50
|
||||
// @Units: meters
|
||||
// @Units: m
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("L1", 10, AP_Landing_Deepstall, L1_period, 30.0),
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user