FW Position control: clean up param descriptions

Mostly to save flash, but also to improve generally.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
Silvan Fuhrer
2024-06-12 09:46:02 +02:00
committed by Roman Bapst
parent aed0fd41cf
commit 77709c2948
3 changed files with 51 additions and 98 deletions
@@ -131,7 +131,6 @@ private:
(ParamFloat<px4::params::WEIGHT_GROSS>) _param_weight_gross,
(ParamFloat<px4::params::FW_SERVICE_CEIL>) _param_service_ceiling,
(ParamFloat<px4::params::FW_THR_TRIM>) _param_fw_thr_trim,
(ParamFloat<px4::params::FW_THR_IDLE>) _param_fw_thr_idle,
(ParamFloat<px4::params::FW_THR_MAX>) _param_fw_thr_max,
(ParamFloat<px4::params::FW_THR_MIN>) _param_fw_thr_min,
(ParamFloat<px4::params::FW_THR_ASPD_MIN>) _param_fw_thr_aspd_min,
@@ -990,7 +990,6 @@ private:
(ParamFloat<px4::params::FW_FLAPS_LND_SCL>) _param_fw_flaps_lnd_scl,
(ParamFloat<px4::params::FW_FLAPS_TO_SCL>) _param_fw_flaps_to_scl,
(ParamFloat<px4::params::FW_SPOILERS_LND>) _param_fw_spoilers_lnd,
(ParamFloat<px4::params::FW_SPOILERS_DESC>) _param_fw_spoilers_desc,
(ParamInt<px4::params::FW_POS_STK_CONF>) _param_fw_pos_stk_conf,
@@ -193,9 +193,9 @@ PARAM_DEFINE_FLOAT(NPFG_PERIOD_SF, 1.5f);
PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f);
/**
* Minimum pitch angle
* Minimum pitch angle setpoint
*
* The minimum pitch angle setpoint for a height-rate or altitude controlled mode.
* Applies in any altitude controlled flight mode.
*
* @unit deg
* @min -60.0
@@ -207,9 +207,9 @@ PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f);
PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -30.0f);
/**
* Maximum pitch angle
* Maximum pitch angle setpoint
*
* The maximum pitch angle setpoint setpoint for a height-rate or altitude controlled mode.
* Applies in any altitude controlled flight mode.
*
* @unit deg
* @min 0.0
@@ -221,9 +221,9 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -30.0f);
PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 30.0f);
/**
* Maximum roll angle
* Maximum roll angle setpoint
*
* The maximum roll angle setpoint for setpoint for a height-rate or altitude controlled mode.
* Applies in any altitude controlled flight mode.
*
* @unit deg
* @min 35.0
@@ -237,7 +237,7 @@ PARAM_DEFINE_FLOAT(FW_R_LIM, 50.0f);
/**
* Throttle limit max
*
* Maximum throttle limit in altitude controlled modes.
* Applies in any altitude controlled flight mode.
* Should be set accordingly to achieve FW_T_CLMB_MAX.
*
* @unit norm
@@ -252,13 +252,10 @@ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f);
/**
* Throttle limit min
*
* Minimum throttle limit in altitude controlled modes.
* Applies in any altitude controlled flight mode.
* Usually set to 0 but can be increased to prevent the motor from stopping when
* descending, which can increase achievable descent rates.
*
* For aircraft with internal combustion engine this parameter should be set
* for desired idle rpm.
*
* @unit norm
* @min 0.0
* @max 1.0
@@ -271,13 +268,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
/**
* Idle throttle
*
* This is the minimum throttle while on the ground
*
* For aircraft with internal combustion engines, this parameter should be set
* above the desired idle rpm. For electric motors, idle should typically be set
* to zero.
*
* Note that in automatic modes, "landed" conditions will engage idle throttle.
* This is the minimum throttle while on the ground ("landed") in auto modes.
*
* @unit norm
* @min 0.0
@@ -318,9 +309,9 @@ PARAM_DEFINE_FLOAT(FW_TKO_PITCH_MIN, 10.0f);
/**
* Takeoff Airspeed
*
* The calibrated airspeed setpoint TECS will stabilize to during the takeoff climbout.
* The calibrated airspeed setpoint during the takeoff climbout.
*
* If set <= 0.0, FW_AIRSPD_MIN will be set by default.
* If set <= 0, FW_AIRSPD_MIN will be set by default.
*
* @unit m/s
* @min -1.0
@@ -344,7 +335,9 @@ PARAM_DEFINE_FLOAT(FW_TKO_AIRSPD, -1.0f);
PARAM_DEFINE_FLOAT(FW_LND_FLALT, 0.5f);
/**
* Use terrain estimation during landing. This is critical for detecting when to flare, and should be enabled if possible.
* Use terrain estimation during landing.
*
* This is critical for detecting when to flare, and should be enabled if possible.
*
* NOTE: terrain estimate is currently solely derived from a distance sensor.
*
@@ -365,9 +358,9 @@ PARAM_DEFINE_INT32(FW_LND_USETER, 1);
/**
* Early landing configuration deployment
*
* When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated
* on the final approach to landing. When enabled, it is already activated when entering the
* final loiter-down (loiter-to-alt) waypoint before the landing approach.
* Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in
* the loiter-down waypoint before the final approach.
* Otherwise is enabled only in the final approach.
*
* @boolean
*
@@ -378,8 +371,7 @@ PARAM_DEFINE_INT32(FW_LND_EARLYCFG, 0);
/**
* Flare, minimum pitch
*
* Minimum pitch during flare, a positive sign means nose up
* Applied once flaring is triggered
* Minimum pitch during landing flare.
*
* @unit deg
* @min -5
@@ -393,8 +385,7 @@ PARAM_DEFINE_FLOAT(FW_LND_FL_PMIN, 2.5f);
/**
* Flare, maximum pitch
*
* Maximum pitch during flare, a positive sign means nose up
* Applied once flaring is triggered
* Maximum pitch during landing flare.
*
* @unit deg
* @min 0
@@ -410,7 +401,7 @@ PARAM_DEFINE_FLOAT(FW_LND_FL_PMAX, 15.0f);
*
* The calibrated airspeed setpoint during landing.
*
* If set <= 0.0, landing airspeed = FW_AIRSPD_MIN by default.
* If set <= 0, landing airspeed = FW_AIRSPD_MIN by default.
*
* @unit m/s
* @min -1.0
@@ -423,9 +414,8 @@ PARAM_DEFINE_FLOAT(FW_LND_AIRSPD, -1.f);
/**
* Altitude time constant factor for landing
*
* Set this parameter to less than 1.0 to make TECS react faster to altitude errors during
* landing than during normal flight. During landing, the TECS
* altitude time constant (FW_T_ALT_TC) is multiplied by this value.
* During landing, the TECS altitude time constant (FW_T_ALT_TC)
* is multiplied by this value.
*
* @unit
* @min 0.2
@@ -445,10 +435,6 @@ PARAM_DEFINE_FLOAT(FW_LND_THRTC_SC, 1.0f);
* Maximum descent rate
*
* This sets the maximum descent rate that the controller will use.
* If this value is too large, the aircraft can over-speed on descent.
* This should be set to a value that can be achieved without
* exceeding the lower pitch angle limit and without over-speeding
* the aircraft.
*
* @unit m/s
* @min 1.0
@@ -463,7 +449,6 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
* Throttle damping factor
*
* This is the damping gain for the throttle demand loop.
* Increase to add damping to correct for oscillations in speed and height.
*
* @min 0.0
* @max 1.0
@@ -476,7 +461,6 @@ PARAM_DEFINE_FLOAT(FW_T_THR_DAMPING, 0.05f);
/**
* Integrator gain throttle
*
* Integrator gain on the throttle part of the control loop.
* Increase it to trim out speed and height offsets faster,
* with the downside of possible overshoots and oscillations.
*
@@ -491,7 +475,6 @@ PARAM_DEFINE_FLOAT(FW_T_THR_INTEG, 0.02f);
/**
* Integrator gain pitch
*
* Integrator gain on the pitch part of the control loop.
* Increase it to trim out speed and height offsets faster,
* with the downside of possible overshoots and oscillations.
*
@@ -506,11 +489,9 @@ PARAM_DEFINE_FLOAT(FW_T_I_GAIN_PIT, 0.1f);
/**
* Maximum vertical acceleration
*
* This is the maximum vertical acceleration (in m/s/s)
* This is the maximum vertical acceleration
* either up or down that the controller will use to correct speed
* or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g)
* allows for reasonably aggressive pitch changes if required to recover
* from under-speed conditions.
* or height errors.
*
* @unit m/s^2
* @min 1.0
@@ -522,9 +503,9 @@ PARAM_DEFINE_FLOAT(FW_T_I_GAIN_PIT, 0.1f);
PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
/**
* Airspeed measurement standard deviation for airspeed filter.
* Airspeed measurement standard deviation
*
* This is the measurement standard deviation for the airspeed used in the airspeed filter in TECS.
* For the airspeed filter in TECS.
*
* @unit m/s
* @min 0.01
@@ -536,9 +517,9 @@ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.2f);
/**
* Airspeed rate measurement standard deviation for airspeed filter.
* Airspeed rate measurement standard deviation
*
* This is the measurement standard deviation for the airspeed rate used in the airspeed filter in TECS.
* For the airspeed filter in TECS.
*
* @unit m/s^2
* @min 0.01
@@ -550,12 +531,10 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_STD, 0.2f);
PARAM_DEFINE_FLOAT(FW_T_SPD_DEV_STD, 0.2f);
/**
* Process noise standard deviation for the airspeed rate in the airspeed filter.
* Process noise standard deviation for the airspeed rate
*
* This is the process noise standard deviation in the airspeed filter filter defining the noise in the
* airspeed rate for the constant airspeed rate model. This is used to define how much the airspeed and
* the airspeed rate are filtered. The smaller the value the more the measurements are smoothed with the
* drawback for delays.
* This is defining the noise in the airspeed rate for the constant airspeed rate model
* of the TECS airspeed filter.
*
* @unit m/s^2
* @min 0.01
@@ -570,14 +549,9 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_PRC_STD, 0.2f);
/**
* Roll -> Throttle feedforward
*
* Increasing this gain turn increases the amount of throttle that will
* be used to compensate for the additional drag created by turning.
* Ideally this should be set to approximately 10 x the extra sink rate
* in m/s created by a 45 degree bank turn. Increase this gain if
* the aircraft initially loses energy in turns and reduce if the
* aircraft initially gains energy in turns. Efficient high aspect-ratio
* aircraft (eg powered sailplanes) can use a lower value, whereas
* inefficient low aspect-ratio models (eg delta wings) can use a higher value.
* Is used to compensate for the additional drag created by turning.
* Increase this gain if the aircraft initially loses energy in turns
* and reduce if the aircraft initially gains energy in turns.
*
* @min 0.0
* @max 20.0
@@ -590,13 +564,11 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f);
/**
* Speed <--> Altitude priority
*
* This parameter adjusts the amount of weighting that the pitch control
* Adjusts the amount of weighting that the pitch control
* applies to speed vs height errors. Setting it to 0.0 will cause the
* pitch control to control height and ignore speed errors. This will
* normally improve height accuracy but give larger airspeed errors.
* pitch control to control height and ignore speed errors.
* Setting it to 2.0 will cause the pitch control loop to control speed
* and ignore height errors. This will normally reduce airspeed errors,
* but give larger height errors. The default value of 1.0 allows the pitch
* and ignore height errors. The default value of 1.0 allows the pitch
* control to simultaneously control height and speed.
* Set to 2 for gliders.
*
@@ -609,12 +581,7 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f);
PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
/**
* Pitch damping factor
*
* This is the damping gain for the pitch demand loop. Increase to add
* damping to correct for oscillations in height. The default value of 0.0
* will work well provided the pitch to servo controller has been tuned
* properly.
* Pitch damping gain
*
* @min 0.0
* @max 2.0
@@ -635,7 +602,10 @@ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.1f);
PARAM_DEFINE_FLOAT(FW_T_ALT_TC, 5.0f);
/**
* Minimum altitude error needed to descend with max airspeed. A negative value disables fast descend.
* Fast descend: minimum altitude error
*
* Minimum altitude error needed to descend with max airspeed and minimal throttle.
* A negative value disables fast descend.
*
* @min -1.0
* @decimal 0
@@ -680,9 +650,9 @@ PARAM_DEFINE_FLOAT(FW_T_TAS_TC, 5.0f);
PARAM_DEFINE_FLOAT(FW_GND_SPD_MIN, 5.0f);
/**
* RC stick configuration fixed-wing.
* Custom stick configuration
*
* Set RC/joystick configuration for fixed-wing manual position and altitude controlled flight.
* Applies in manual Position and Altitude flight modes.
*
* @min 0
* @max 3
@@ -720,9 +690,8 @@ PARAM_DEFINE_FLOAT(FW_T_SEB_R_FF, 1.0f);
/**
* Default target climbrate.
*
* The default rate at which the vehicle will climb in autonomous modes to achieve altitude setpoints.
* In manual modes this defines the maximum rate at which the altitude setpoint can be increased.
*
* In auto modes: default climb rate output by controller to achieve altitude setpoints.
* In manual modes: maximum climb rate setpoint.
*
* @unit m/s
* @min 0.5
@@ -736,9 +705,8 @@ PARAM_DEFINE_FLOAT(FW_T_CLMB_R_SP, 3.0f);
/**
* Default target sinkrate.
*
*
* The default rate at which the vehicle will sink in autonomous modes to achieve altitude setpoints.
* In manual modes this defines the maximum rate at which the altitude setpoint can be decreased.
* In auto modes: default sink rate output by controller to achieve altitude setpoints.
* In manual modes: maximum sink rate setpoint.
*
* @unit m/s
* @min 0.5
@@ -752,7 +720,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_R_SP, 2.0f);
/**
* GPS failure loiter time
*
* The time in seconds the system should do open loop loiter and wait for GPS recovery
* The time the system should do open loop loiter and wait for GPS recovery
* before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R.
* Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0.
*
@@ -766,7 +734,7 @@ PARAM_DEFINE_INT32(FW_GPSF_LT, 30);
/**
* GPS failure fixed roll angle
*
* Roll in degrees during the loiter after the vehicle has lost GPS in an auto mode (e.g. mission or loiter).
* Roll angle in GPS failure loiter mode.
*
* @unit deg
* @min 0.0
@@ -875,7 +843,7 @@ PARAM_DEFINE_FLOAT(FW_LND_TD_OFF, 3.0);
* Approach path nudging: shifts the touchdown point laterally along with the entire approach path
*
* This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the
* desired landing vector. Nuding is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is
* desired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is
* relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle).
*
* @min 0
@@ -914,7 +882,6 @@ PARAM_DEFINE_INT32(FW_LND_ABORT, 3);
* Multiplying this factor with the current absolute wind estimate gives the airspeed offset
* added to the minimum airspeed setpoint limit. This helps to make the
* system more robust against disturbances (turbulence) in high wind.
* Only applies to AUTO flight mode.
*
* @min 0
* @decimal 2
@@ -975,15 +942,3 @@ PARAM_DEFINE_FLOAT(FW_FLAPS_LND_SCL, 1.0f);
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_SPOILERS_LND, 0.f);
/**
* Spoiler descend setting
*
* @unit norm
* @min 0.0
* @max 1.0
* @decimal 2
* @increment 0.01
* @group FW Attitude Control
*/
PARAM_DEFINE_FLOAT(FW_SPOILERS_DESC, 0.f);