forked from Archive/PX4-Autopilot
Revert "Remove all unused TECS parameters"
This reverts commit ce78b39969
.
Conflicts:
src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
This commit is contained in:
parent
628b735bc1
commit
129c93f22f
|
@ -199,6 +199,19 @@ private:
|
|||
float l1_period;
|
||||
float l1_damping;
|
||||
|
||||
float time_const;
|
||||
float min_sink_rate;
|
||||
float max_sink_rate;
|
||||
float max_climb_rate;
|
||||
float throttle_damp;
|
||||
float integrator_gain;
|
||||
float vertical_accel_limit;
|
||||
float height_comp_filter_omega;
|
||||
float speed_comp_filter_omega;
|
||||
float roll_throttle_compensation;
|
||||
float speed_weight;
|
||||
float pitch_damping;
|
||||
|
||||
float airspeed_min;
|
||||
float airspeed_trim;
|
||||
float airspeed_max;
|
||||
|
@ -226,6 +239,19 @@ private:
|
|||
param_t l1_period;
|
||||
param_t l1_damping;
|
||||
|
||||
param_t time_const;
|
||||
param_t min_sink_rate;
|
||||
param_t max_sink_rate;
|
||||
param_t max_climb_rate;
|
||||
param_t throttle_damp;
|
||||
param_t integrator_gain;
|
||||
param_t vertical_accel_limit;
|
||||
param_t height_comp_filter_omega;
|
||||
param_t speed_comp_filter_omega;
|
||||
param_t roll_throttle_compensation;
|
||||
param_t speed_weight;
|
||||
param_t pitch_damping;
|
||||
|
||||
param_t airspeed_min;
|
||||
param_t airspeed_trim;
|
||||
param_t airspeed_max;
|
||||
|
@ -438,6 +464,21 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
|||
_parameter_handles.land_heading_hold_horizontal_distance = param_find("FW_LND_HHDIST");
|
||||
_parameter_handles.range_finder_rel_alt = param_find("FW_LND_RFRALT");
|
||||
|
||||
_parameter_handles.time_const = param_find("FW_T_TIME_CONST");
|
||||
_parameter_handles.min_sink_rate = param_find("FW_T_SINK_MIN");
|
||||
_parameter_handles.max_sink_rate = param_find("FW_T_SINK_MAX");
|
||||
_parameter_handles.max_climb_rate = param_find("FW_T_CLMB_MAX");
|
||||
_parameter_handles.throttle_damp = param_find("FW_T_THR_DAMP");
|
||||
_parameter_handles.integrator_gain = param_find("FW_T_INTEG_GAIN");
|
||||
_parameter_handles.vertical_accel_limit = param_find("FW_T_VERT_ACC");
|
||||
_parameter_handles.height_comp_filter_omega = param_find("FW_T_HGT_OMEGA");
|
||||
_parameter_handles.speed_comp_filter_omega = param_find("FW_T_SPD_OMEGA");
|
||||
_parameter_handles.roll_throttle_compensation = param_find("FW_T_RLL2THR");
|
||||
_parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT");
|
||||
_parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP");
|
||||
_parameter_handles.heightrate_p = param_find("FW_T_HRATE_P");
|
||||
_parameter_handles.speedrate_p = param_find("FW_T_SRATE_P");
|
||||
|
||||
/* fetch initial parameter values */
|
||||
parameters_update();
|
||||
}
|
||||
|
@ -488,6 +529,22 @@ FixedwingPositionControl::parameters_update()
|
|||
|
||||
param_get(_parameter_handles.throttle_land_max, &(_parameters.throttle_land_max));
|
||||
|
||||
param_get(_parameter_handles.time_const, &(_parameters.time_const));
|
||||
param_get(_parameter_handles.min_sink_rate, &(_parameters.min_sink_rate));
|
||||
param_get(_parameter_handles.max_sink_rate, &(_parameters.max_sink_rate));
|
||||
param_get(_parameter_handles.throttle_damp, &(_parameters.throttle_damp));
|
||||
param_get(_parameter_handles.integrator_gain, &(_parameters.integrator_gain));
|
||||
param_get(_parameter_handles.vertical_accel_limit, &(_parameters.vertical_accel_limit));
|
||||
param_get(_parameter_handles.height_comp_filter_omega, &(_parameters.height_comp_filter_omega));
|
||||
param_get(_parameter_handles.speed_comp_filter_omega, &(_parameters.speed_comp_filter_omega));
|
||||
param_get(_parameter_handles.roll_throttle_compensation, &(_parameters.roll_throttle_compensation));
|
||||
param_get(_parameter_handles.speed_weight, &(_parameters.speed_weight));
|
||||
param_get(_parameter_handles.pitch_damping, &(_parameters.pitch_damping));
|
||||
param_get(_parameter_handles.max_climb_rate, &(_parameters.max_climb_rate));
|
||||
|
||||
param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p));
|
||||
param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_p));
|
||||
|
||||
param_get(_parameter_handles.land_slope_angle, &(_parameters.land_slope_angle));
|
||||
param_get(_parameter_handles.land_H1_virt, &(_parameters.land_H1_virt));
|
||||
param_get(_parameter_handles.land_flare_alt_relative, &(_parameters.land_flare_alt_relative));
|
||||
|
|
|
@ -154,6 +154,182 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
|
|||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f);
|
||||
|
||||
/**
|
||||
* Maximum climb rate
|
||||
*
|
||||
* 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 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.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f);
|
||||
|
||||
/**
|
||||
* Minimum descent rate
|
||||
*
|
||||
* This is the sink rate of the aircraft with the throttle
|
||||
* set to THR_MIN and flown at the same airspeed as used
|
||||
* to measure FW_T_CLMB_MAX.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.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.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
|
||||
|
||||
/**
|
||||
* TECS time constant
|
||||
*
|
||||
* This is the time constant of the TECS control algorithm (in seconds).
|
||||
* Smaller values make it faster to respond, larger values make it slower
|
||||
* to respond.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 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.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
|
||||
|
||||
/**
|
||||
* Integrator gain
|
||||
*
|
||||
* This is the integrator gain on the control loop.
|
||||
* Increasing this gain increases the speed at which speed
|
||||
* and height offsets are trimmed out, but reduces damping and
|
||||
* increases overshoot.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
|
||||
|
||||
/**
|
||||
* Maximum vertical acceleration
|
||||
*
|
||||
* This is the maximum vertical acceleration (in metres/second square)
|
||||
* 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.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
|
||||
|
||||
/**
|
||||
* Complementary filter "omega" parameter for height
|
||||
*
|
||||
* This is the cross-over frequency (in radians/second) of the complementary
|
||||
* filter used to fuse vertical acceleration and barometric height to obtain
|
||||
* an estimate of height rate and height. Increasing this frequency weights
|
||||
* the solution more towards use of the barometer, whilst reducing it weights
|
||||
* the solution more towards use of the accelerometer data.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
|
||||
|
||||
/**
|
||||
* Complementary filter "omega" parameter for speed
|
||||
*
|
||||
* This is the cross-over frequency (in radians/second) of the complementary
|
||||
* filter used to fuse longitudinal acceleration and airspeed to obtain an
|
||||
* improved airspeed estimate. Increasing this frequency weights the solution
|
||||
* more towards use of the arispeed sensor, whilst reducing it weights the
|
||||
* solution more towards use of the accelerometer data.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
|
||||
|
||||
/**
|
||||
* 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.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f);
|
||||
|
||||
/**
|
||||
* Speed <--> Altitude priority
|
||||
*
|
||||
* 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 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).
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
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.
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
|
||||
|
||||
/**
|
||||
* Height rate P factor
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
|
||||
|
||||
/**
|
||||
* Speed rate P factor
|
||||
*
|
||||
* @group L1 Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f);
|
||||
|
||||
/**
|
||||
* Landing slope angle
|
||||
*
|
||||
|
|
Loading…
Reference in New Issue