mirror of https://github.com/ArduPilot/ardupilot
AP_TECS: fixed parameter doc formatting
This commit is contained in:
parent
f1f9b98008
commit
87f6cc715d
|
@ -18,33 +18,21 @@ const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = {
|
|||
|
||||
// @Param: CLMB_MAX
|
||||
// @DisplayName: Maximum Climb Rate (metres/sec)
|
||||
// @Description: This is the best 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 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 require to climb and maintain speed is noticeably less than THR_MAX, then
|
||||
// either CLMB_MAX should be increased or THR_MAX reduced.
|
||||
// @Description: This is the best 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 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 require to climb and maintain speed is noticeably less than THR_MAX, then either CLMB_MAX should be increased or THR_MAX reduced.
|
||||
// @Increment: 0.1
|
||||
// @User: User
|
||||
AP_GROUPINFO("CLMB_MAX", 0, AP_TECS, _maxClimbRate, 5.0f),
|
||||
|
||||
// @Param: SINK_MIN
|
||||
// @DisplayName: Minimum Sink Rate (metres/sec)
|
||||
// @Description: This is the sink rate of the aircraft with the throttle set to THR_MIN
|
||||
// and the same airspeed as used to measure CLMB_MAX.
|
||||
// @Description: This is the sink rate of the aircraft with the throttle set to THR_MIN and the same airspeed as used to measure CLMB_MAX.
|
||||
// @Increment: 0.1
|
||||
// @User: User
|
||||
AP_GROUPINFO("SINK_MIN", 1, AP_TECS, _minSinkRate, 2.0f),
|
||||
|
||||
// @Param: TIME_CONST
|
||||
// @DisplayName: Controller time constant (sec)
|
||||
// @Description: This is the time constant of the TECS control algorithm.
|
||||
// Smaller values make it faster to respond, large values make it slower
|
||||
// to respond.
|
||||
// @Description: This is the time constant of the TECS control algorithm. Smaller values make it faster to respond, large values make it slower to respond.
|
||||
// @Range: 3.0-10.0
|
||||
// @Increment: 0.2
|
||||
// @User: Advanced
|
||||
|
@ -52,8 +40,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = {
|
|||
|
||||
// @Param: THR_DAMP
|
||||
// @DisplayName: Controller throttle damping
|
||||
// @Description: This is the damping gain for the throttle demand loop.
|
||||
// Increase to add damping to correct for oscillations in speed and height.
|
||||
// @Description: This is the damping gain for the throttle demand loop. Increase to add damping to correct for oscillations in speed and height.
|
||||
// @Range: 0.1-1.0
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
|
@ -61,8 +48,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = {
|
|||
|
||||
// @Param: INTEG_GAIN
|
||||
// @DisplayName: Controller integrator
|
||||
// @Description: This is the integrator gain on the control loop.
|
||||
// Increase to increase the rate at which speed and height offsets are trimmed out
|
||||
// @Description: This is the integrator gain on the control loop. Increase to increase the rate at which speed and height offsets are trimmed out
|
||||
// @Range: 0.0-0.5
|
||||
// @Increment: 0.02
|
||||
// @User: Advanced
|
||||
|
@ -70,8 +56,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = {
|
|||
|
||||
// @Param: VERT_ACC
|
||||
// @DisplayName: Vertical Acceleration Limit (metres/sec^2)
|
||||
// @Description: This is the maximum vertical acceleration either up or down
|
||||
// that the controller will use to correct speed or height errors.
|
||||
// @Description: This is the maximum vertical acceleration either up or down that the controller will use to correct speed or height errors.
|
||||
// @Range: 1.0-10.0
|
||||
// @Increment: 0.5
|
||||
// @User: Advanced
|
||||
|
@ -79,9 +64,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = {
|
|||
|
||||
// @Param: HGT_OMEGA
|
||||
// @DisplayName: Height complementary filter frequency (radians/sec)
|
||||
// @Description: This is the cross-over frequency of the complementary
|
||||
// flter used to fuse vertical acceleration and baro alt to obtain an
|
||||
// estimate of height rate and height.
|
||||
// @Description: This is the cross-over frequency of the complementary filter used to fuse vertical acceleration and baro alt to obtain an estimate of height rate and height.
|
||||
// @Range: 1.0-5.0
|
||||
// @Increment: 0.05
|
||||
// @User: Advanced
|
||||
|
@ -89,9 +72,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = {
|
|||
|
||||
// @Param: SPD_OMEGA
|
||||
// @DisplayName: Speed complementary filter frequency (radians/sec)
|
||||
// @Description: This is the cross-over frequency of the complementary
|
||||
// flter used to fuse longitudinal acceleration and airspeed to obtain
|
||||
// a lower noise and lag estimate of airspeed.
|
||||
// @Description: This is the cross-over frequency of the complementary filter used to fuse longitudinal acceleration and airspeed to obtain a lower noise and lag estimate of airspeed.
|
||||
// @Range: 0.5-2.0
|
||||
// @Increment: 0.05
|
||||
// @User: Advanced
|
||||
|
@ -99,13 +80,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = {
|
|||
|
||||
// @Param: RLL2THR
|
||||
// @DisplayName: Bank angle compensation gain
|
||||
// @Description: 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.
|
||||
// @Description: 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.
|
||||
// @Range: 5.0 to 30.0
|
||||
// @Increment: 1.0
|
||||
// @User: Advanced
|
||||
|
@ -113,12 +88,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = {
|
|||
|
||||
// @Param: SPDWEIGHT
|
||||
// @DisplayName: Weighting applied to speed control
|
||||
// @Description: This parameter 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.
|
||||
// Setting it to 2.0 will cause the pitch control loop to control speed and ignore height errors.
|
||||
// This will normally reduce airsped errors, but give larger height errors.
|
||||
// A value of 1.0 gives a balanced response and is the default.
|
||||
// @Description: This parameter 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. Setting it to 2.0 will cause the pitch control loop to control speed and ignore height errors. This will normally reduce airsped errors, but give larger height errors. A value of 1.0 gives a balanced response and is the default.
|
||||
// @Range: 0.0 to 2.0
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
|
@ -126,8 +96,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = {
|
|||
|
||||
// @Param: PTCH_DAMP
|
||||
// @DisplayName: Controller pitch damping
|
||||
// @Description: This is the damping gain for the pitch demand loop.
|
||||
// Increase to add damping to correct for oscillations in speed and height.
|
||||
// @Description: This is the damping gain for the pitch demand loop. Increase to add damping to correct for oscillations in speed and height.
|
||||
// @Range: 0.1-1.0
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
|
@ -135,9 +104,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = {
|
|||
|
||||
// @Param: SINK_MAX
|
||||
// @DisplayName: Maximum Descent Rate (metres/sec)
|
||||
// @Description: This sets the maximum descent rate that the controller will use. If this value is
|
||||
// too large, the aircraft will reach the pitch angle limit first and be enable to achieve the descent
|
||||
// rate. This should be set to a value that can be achieved at the lower pitch angle limit.
|
||||
// @Description: This sets the maximum descent rate that the controller will use. If this value is too large, the aircraft will reach the pitch angle limit first and be enable to achieve the descent rate. This should be set to a value that can be achieved at the lower pitch angle limit.
|
||||
// @Increment: 0.1
|
||||
// @User: User
|
||||
AP_GROUPINFO("SINK_MAX", 11, AP_TECS, _maxSinkRate, 5.0f),
|
||||
|
|
Loading…
Reference in New Issue