FW controllers: make param description more concise

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
Silvan Fuhrer 2023-03-02 22:49:25 +01:00
parent 4be74befd2
commit ec38ec660c
5 changed files with 29 additions and 72 deletions

View File

@ -82,10 +82,7 @@ PARAM_DEFINE_FLOAT(FW_R_TC, 0.4f);
PARAM_DEFINE_FLOAT(FW_P_TC, 0.4f);
/**
* Maximum positive / up pitch rate.
*
* This limits the maximum pitch up angular rate the controller will output (in
* degrees per second).
* Maximum positive / up pitch rate setpoint
*
* @unit deg/s
* @min 0.0
@ -97,10 +94,7 @@ PARAM_DEFINE_FLOAT(FW_P_TC, 0.4f);
PARAM_DEFINE_FLOAT(FW_P_RMAX_POS, 60.0f);
/**
* Maximum negative / down pitch rate.
*
* This limits the maximum pitch down up angular rate the controller will
* output (in degrees per second).
* Maximum negative / down pitch rate setpoint
*
* @unit deg/s
* @min 0.0
@ -112,10 +106,7 @@ PARAM_DEFINE_FLOAT(FW_P_RMAX_POS, 60.0f);
PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 60.0f);
/**
* Maximum roll rate
*
* This limits the maximum roll rate the controller will output (in degrees per
* second).
* Maximum roll rate setpoint
*
* @unit deg/s
* @min 0.0
@ -127,10 +118,7 @@ PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 60.0f);
PARAM_DEFINE_FLOAT(FW_R_RMAX, 70.0f);
/**
* Maximum yaw rate
*
* This limits the maximum yaw rate the controller will output (in degrees per
* second).
* Maximum yaw rate setpoint
*
* @unit deg/s
* @min 0.0

View File

@ -180,7 +180,7 @@ PARAM_DEFINE_FLOAT(NPFG_PERIOD_SF, 1.5f);
/**
* Trim throttle
*
* This is the throttle setting required to achieve FW_AIRSPD_TRIM during level flight. Most airframes have a value of 0.5-0.7.
* This is the throttle setting required to achieve FW_AIRSPD_TRIM during level flight.
*
* @unit norm
* @min 0.0
@ -207,7 +207,7 @@ PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f);
/**
* Minimum pitch angle
*
* The minimum pitch angle setpoint for autonomous modes including altitude and position control.
* The minimum pitch angle setpoint for a height-rate or altitude controlled mode.
*
* @unit deg
* @min -60.0
@ -221,7 +221,7 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -30.0f);
/**
* Maximum pitch angle
*
* The maximum pitch angle setpoint for autonomous modes including altitude and position control.
* The maximum pitch angle setpoint setpoint for a height-rate or altitude controlled mode.
*
* @unit deg
* @min 0.0
@ -235,7 +235,7 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 30.0f);
/**
* Maximum roll angle
*
* The maximum roll angle setpoint for autonomous modes including altitude and position control.
* The maximum roll angle setpoint for setpoint for a height-rate or altitude controlled mode.
*
* @unit deg
* @min 35.0
@ -442,8 +442,7 @@ 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 (i.e. giving efficiency and low motor wear at
* high altitudes but control accuracy during landing). During landing, the TECS
* landing than during normal flight. During landing, the TECS
* altitude time constant (FW_T_ALT_TC) is multiplied by this value.
*
* @unit
@ -464,18 +463,10 @@ PARAM_DEFINE_FLOAT(FW_LND_THRTC_SC, 1.0f);
/**
* Maximum climb rate
*
* This is the best climb rate that the aircraft can achieve with
* This is the maximum climb rate that the aircraft can achieve with
* the throttle set to THR_MAX and the airspeed set to the
* default value. For electric aircraft make sure this number can be
* trim value. For electric aircraft make sure this number can be
* achieved towards the end of flight when the battery voltage has reduced.
* The setting of this parameter can be checked by commanding a positive
* altitude change of 100m in loiter, RTL or guided mode. If the throttle
* required to climb is close to THR_MAX and the aircraft is maintaining
* airspeed, then this parameter is set correctly. If the airspeed starts
* to reduce, then the parameter is set to high, and if the throttle
* demand required to climb and maintain speed is noticeably less than
* FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or
* FW_THR_MAX reduced.
*
* @unit m/s
* @min 1.0
@ -663,8 +654,7 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 15.0f);
* and ignore height errors. This will normally reduce airspeed errors,
* but give larger height errors. The default value of 1.0 allows the pitch
* control to simultaneously control height and speed.
* Note to Glider Pilots - set this parameter to 2.0 (The glider will
* adjust its pitch angle to maintain airspeed, ignoring changes in height).
* Set to 2 for gliders.
*
* @min 0.0
* @max 2.0
@ -777,7 +767,6 @@ 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.
*
@ -825,7 +814,6 @@ 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).
* Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0.
*
* @unit deg
* @min 0.0

View File

@ -69,8 +69,7 @@ PARAM_DEFINE_FLOAT(FW_LAUN_AC_T, 0.05f);
/**
* Motor delay
*
* Delay between starting attitude control and powering up the throttle (giving throttle control to the controller)
* Before this timespan is up the throttle will be set to FW_THR_IDLE, set to 0 to deactivate
* Start the motor(s) this amount of seconds after launch is detected.
*
* @unit s
* @min 0.0

View File

@ -65,8 +65,6 @@ PARAM_DEFINE_INT32(RWTO_HDG, 0);
/**
* Max throttle during runway takeoff.
*
* Can be used to test taxi on runway
*
* @unit norm
* @min 0.0
* @max 1.0

View File

@ -69,8 +69,6 @@ PARAM_DEFINE_FLOAT(FW_AIRSPD_MIN, 10.0f);
* Maximum Airspeed (CAS)
*
* The maximal airspeed (calibrated airspeed) the user is able to command.
* Further, if the airspeed is above this value, the TECS controller will try to decrease
* airspeed more aggressively.
*
* @unit m/s
* @min 0.5
@ -84,21 +82,20 @@ PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 20.0f);
/**
* Airspeed mode
*
* For small wings or VTOL without airspeed sensor this parameter can be used to
* On vehicles without airspeed sensor this parameter can be used to
* enable flying without an airspeed reading
*
* @value 0 Normal (use airspeed if available)
* @value 1 Airspeed disabled
* @value 0 Use airspeed in controller
* @value 1 Do not use airspeed in controller
* @group FW Attitude Control
*/
PARAM_DEFINE_INT32(FW_ARSP_MODE, 0);
/**
* Cruise Airspeed (CAS)
* Trim (Cruise) Airspeed
*
* The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active,
* this is the default airspeed setpoint that the controller will try to achieve if
* no other airspeed setpoint sources are present (e.g. through non-centered RC sticks).
* this is the default airspeed setpoint that the controller will try to achieve.
*
* @unit m/s
* @min 0.5
@ -128,8 +125,6 @@ PARAM_DEFINE_FLOAT(FW_AIRSPD_STALL, 7.0f);
/**
* Pitch rate proportional gain.
*
* Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.
*
* @unit %/rad/s
* @min 0.0
* @max 1.0
@ -142,7 +137,8 @@ PARAM_DEFINE_FLOAT(FW_PR_P, 0.08f);
/**
* Pitch rate derivative gain.
*
* Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
* Pitch rate differential gain. Small values help reduce fast oscillations.
* If value is too big oscillations will appear again.
*
* @unit %/rad/s
* @min 0.0
@ -185,8 +181,6 @@ PARAM_DEFINE_FLOAT(FW_PR_IMAX, 0.4f);
/**
* Roll rate proportional Gain
*
* Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.
*
* @unit %/rad/s
* @min 0.0
* @max 1.0
@ -199,7 +193,8 @@ PARAM_DEFINE_FLOAT(FW_RR_P, 0.05f);
/**
* Roll rate derivative Gain
*
* Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
* Roll rate differential gain. Small values help reduce fast oscillations.
* If value is too big oscillations will appear again.
*
* @unit %/rad/s
* @min 0.0
@ -241,8 +236,6 @@ PARAM_DEFINE_FLOAT(FW_RR_IMAX, 0.2f);
/**
* Yaw rate proportional gain
*
* Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.
*
* @unit %/rad/s
* @min 0.0
* @max 1.0
@ -255,7 +248,8 @@ PARAM_DEFINE_FLOAT(FW_YR_P, 0.05f);
/**
* Yaw rate derivative gain
*
* Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
* Yaw rate differential gain. Small values help reduce fast oscillations.
* If value is too big oscillations will appear again.
*
* @unit %/rad/s
* @min 0.0
@ -353,10 +347,7 @@ PARAM_DEFINE_FLOAT(FW_YR_FF, 0.3f);
PARAM_DEFINE_FLOAT(FW_ACRO_X_MAX, 90);
/**
* Acro body y max rate.
*
* This is the body y rate the controller is trying to achieve if the user applies full pitch
* stick input in acro mode.
* Acro body pitch max rate setpoint.
*
* @min 45
* @max 720
@ -366,10 +357,7 @@ PARAM_DEFINE_FLOAT(FW_ACRO_X_MAX, 90);
PARAM_DEFINE_FLOAT(FW_ACRO_Y_MAX, 90);
/**
* Acro body z max rate.
*
* This is the body z rate the controller is trying to achieve if the user applies full yaw
* stick input in acro mode.
* Acro body yaw max rate setpoint.
*
* @min 10
* @max 180
@ -379,13 +367,10 @@ PARAM_DEFINE_FLOAT(FW_ACRO_Y_MAX, 90);
PARAM_DEFINE_FLOAT(FW_ACRO_Z_MAX, 45);
/**
* Whether to scale throttle by battery power level
* Enable throttle scale by battery level
*
* This compensates for voltage drop of the battery over time by attempting to
* normalize performance across the operating range of the battery. The fixed wing
* should constantly behave as if it was fully charged with reduced max thrust
* at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery,
* it will still be 0.5 at 60% battery.
* normalize performance across the operating range of the battery.
*
* @boolean
* @group FW Rate Control
@ -630,8 +615,7 @@ PARAM_DEFINE_FLOAT(FW_MAN_Y_SC, 1.0f);
*
* This gain can be used to counteract the "adverse yaw" effect for fixed wings.
* When the plane enters a roll it will tend to yaw the nose out of the turn.
* This gain enables the use of a yaw actuator (rudder, airbrakes, ...) to counteract
* this effect.
* This gain enables the use of a yaw actuator to counteract this effect.
*
* @min 0.0
* @decimal 1