forked from Archive/PX4-Autopilot
Merge branch 'stable' of github.com:swissfang/Firmware into swissfang
This commit is contained in:
commit
510750166a
|
@ -236,9 +236,8 @@ void TECS::_update_height_demand(float demand, float state)
|
||||||
// // _hgt_rate_dem);
|
// // _hgt_rate_dem);
|
||||||
|
|
||||||
_hgt_dem_adj = demand;//0.025f * demand + 0.975f * _hgt_dem_adj_last;
|
_hgt_dem_adj = demand;//0.025f * demand + 0.975f * _hgt_dem_adj_last;
|
||||||
|
_hgt_rate_dem = (_hgt_dem_adj-state)*_heightrate_p + _heightrate_ff * (_hgt_dem_adj - _hgt_dem_adj_last)/_DT;
|
||||||
_hgt_dem_adj_last = _hgt_dem_adj;
|
_hgt_dem_adj_last = _hgt_dem_adj;
|
||||||
|
|
||||||
_hgt_rate_dem = (_hgt_dem_adj-state)*_heightrate_p;
|
|
||||||
// Limit height rate of change
|
// Limit height rate of change
|
||||||
if (_hgt_rate_dem > _maxClimbRate) {
|
if (_hgt_rate_dem > _maxClimbRate) {
|
||||||
_hgt_rate_dem = _maxClimbRate;
|
_hgt_rate_dem = _maxClimbRate;
|
||||||
|
|
|
@ -47,6 +47,7 @@ public:
|
||||||
_rollComp(0.0f),
|
_rollComp(0.0f),
|
||||||
_spdWeight(0.5f),
|
_spdWeight(0.5f),
|
||||||
_heightrate_p(0.0f),
|
_heightrate_p(0.0f),
|
||||||
|
_heightrate_ff(0.0f),
|
||||||
_speedrate_p(0.0f),
|
_speedrate_p(0.0f),
|
||||||
_throttle_dem(0.0f),
|
_throttle_dem(0.0f),
|
||||||
_pitch_dem(0.0f),
|
_pitch_dem(0.0f),
|
||||||
|
@ -220,6 +221,10 @@ public:
|
||||||
_heightrate_p = heightrate_p;
|
_heightrate_p = heightrate_p;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void set_heightrate_ff(float heightrate_ff) {
|
||||||
|
_heightrate_ff = heightrate_ff;
|
||||||
|
}
|
||||||
|
|
||||||
void set_speedrate_p(float speedrate_p) {
|
void set_speedrate_p(float speedrate_p) {
|
||||||
_speedrate_p = speedrate_p;
|
_speedrate_p = speedrate_p;
|
||||||
}
|
}
|
||||||
|
@ -256,6 +261,7 @@ private:
|
||||||
float _rollComp;
|
float _rollComp;
|
||||||
float _spdWeight;
|
float _spdWeight;
|
||||||
float _heightrate_p;
|
float _heightrate_p;
|
||||||
|
float _heightrate_ff;
|
||||||
float _speedrate_p;
|
float _speedrate_p;
|
||||||
|
|
||||||
// throttle demand in the range from 0.0 to 1.0
|
// throttle demand in the range from 0.0 to 1.0
|
||||||
|
|
|
@ -211,6 +211,7 @@ private:
|
||||||
float max_climb_rate;
|
float max_climb_rate;
|
||||||
float climbout_diff;
|
float climbout_diff;
|
||||||
float heightrate_p;
|
float heightrate_p;
|
||||||
|
float heightrate_ff;
|
||||||
float speedrate_p;
|
float speedrate_p;
|
||||||
float throttle_damp;
|
float throttle_damp;
|
||||||
float integrator_gain;
|
float integrator_gain;
|
||||||
|
@ -256,6 +257,7 @@ private:
|
||||||
param_t max_climb_rate;
|
param_t max_climb_rate;
|
||||||
param_t climbout_diff;
|
param_t climbout_diff;
|
||||||
param_t heightrate_p;
|
param_t heightrate_p;
|
||||||
|
param_t heightrate_ff;
|
||||||
param_t speedrate_p;
|
param_t speedrate_p;
|
||||||
param_t throttle_damp;
|
param_t throttle_damp;
|
||||||
param_t integrator_gain;
|
param_t integrator_gain;
|
||||||
|
@ -494,6 +496,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
||||||
_parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT");
|
_parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT");
|
||||||
_parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP");
|
_parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP");
|
||||||
_parameter_handles.heightrate_p = param_find("FW_T_HRATE_P");
|
_parameter_handles.heightrate_p = param_find("FW_T_HRATE_P");
|
||||||
|
_parameter_handles.heightrate_ff = param_find("FW_T_HRATE_FF");
|
||||||
_parameter_handles.speedrate_p = param_find("FW_T_SRATE_P");
|
_parameter_handles.speedrate_p = param_find("FW_T_SRATE_P");
|
||||||
|
|
||||||
/* fetch initial parameter values */
|
/* fetch initial parameter values */
|
||||||
|
@ -563,6 +566,7 @@ FixedwingPositionControl::parameters_update()
|
||||||
param_get(_parameter_handles.climbout_diff, &(_parameters.climbout_diff));
|
param_get(_parameter_handles.climbout_diff, &(_parameters.climbout_diff));
|
||||||
|
|
||||||
param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p));
|
param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p));
|
||||||
|
param_get(_parameter_handles.heightrate_ff, &(_parameters.heightrate_ff));
|
||||||
param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_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_slope_angle, &(_parameters.land_slope_angle));
|
||||||
|
@ -600,6 +604,7 @@ FixedwingPositionControl::parameters_update()
|
||||||
_tecs.set_indicated_airspeed_max(_parameters.airspeed_max);
|
_tecs.set_indicated_airspeed_max(_parameters.airspeed_max);
|
||||||
_tecs.set_max_climb_rate(_parameters.max_climb_rate);
|
_tecs.set_max_climb_rate(_parameters.max_climb_rate);
|
||||||
_tecs.set_heightrate_p(_parameters.heightrate_p);
|
_tecs.set_heightrate_p(_parameters.heightrate_p);
|
||||||
|
_tecs.set_heightrate_ff(_parameters.heightrate_ff);
|
||||||
_tecs.set_speedrate_p(_parameters.speedrate_p);
|
_tecs.set_speedrate_p(_parameters.speedrate_p);
|
||||||
|
|
||||||
/* sanity check parameters */
|
/* sanity check parameters */
|
||||||
|
|
|
@ -131,8 +131,8 @@ PARAM_DEFINE_FLOAT(FW_R_LIM, 45.0f);
|
||||||
/**
|
/**
|
||||||
* Throttle limit max
|
* Throttle limit max
|
||||||
*
|
*
|
||||||
* This is the maximum throttle % that can be used by the controller.
|
* This is the maximum throttle % that can be used by the controller.
|
||||||
* For overpowered aircraft, this should be reduced to a value that
|
* For overpowered aircraft, this should be reduced to a value that
|
||||||
* provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX.
|
* provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX.
|
||||||
*
|
*
|
||||||
* @group L1 Control
|
* @group L1 Control
|
||||||
|
@ -142,10 +142,10 @@ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f);
|
||||||
/**
|
/**
|
||||||
* Throttle limit min
|
* Throttle limit min
|
||||||
*
|
*
|
||||||
* This is the minimum throttle % that can be used by the controller.
|
* This is the minimum throttle % that can be used by the controller.
|
||||||
* For electric aircraft this will normally be set to zero, but can be set
|
* For electric aircraft this will normally be set to zero, but can be set
|
||||||
* to a small non-zero value if a folding prop is fitted to prevent the
|
* to a small non-zero value if a folding prop is fitted to prevent the
|
||||||
* prop from folding and unfolding repeatedly in-flight or to provide
|
* prop from folding and unfolding repeatedly in-flight or to provide
|
||||||
* some aerodynamic drag from a turning prop to improve the descent rate.
|
* some aerodynamic drag from a turning prop to improve the descent rate.
|
||||||
*
|
*
|
||||||
* For aircraft with internal combustion engine this parameter should be set
|
* For aircraft with internal combustion engine this parameter should be set
|
||||||
|
@ -158,7 +158,7 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
|
||||||
/**
|
/**
|
||||||
* Throttle limit value before flare
|
* Throttle limit value before flare
|
||||||
*
|
*
|
||||||
* This throttle value will be set as throttle limit at FW_LND_TLALT,
|
* This throttle value will be set as throttle limit at FW_LND_TLALT,
|
||||||
* before arcraft will flare.
|
* before arcraft will flare.
|
||||||
*
|
*
|
||||||
* @group L1 Control
|
* @group L1 Control
|
||||||
|
@ -180,17 +180,17 @@ PARAM_DEFINE_FLOAT(FW_CLMBOUT_DIFF, 25.0f);
|
||||||
/**
|
/**
|
||||||
* Maximum climb rate
|
* Maximum climb rate
|
||||||
*
|
*
|
||||||
* This is the best climb rate that the aircraft can achieve with
|
* This is the best climb rate that the aircraft can achieve with
|
||||||
* the throttle set to THR_MAX and the airspeed set to the
|
* the throttle set to THR_MAX and the airspeed set to the
|
||||||
* default value. For electric aircraft make sure this number can be
|
* default value. For electric aircraft make sure this number can be
|
||||||
* achieved towards the end of flight when the battery voltage has reduced.
|
* achieved towards the end of flight when the battery voltage has reduced.
|
||||||
* The setting of this parameter can be checked by commanding a positive
|
* 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
|
* 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
|
* required to climb is close to THR_MAX and the aircraft is maintaining
|
||||||
* airspeed, then this parameter is set correctly. If the airspeed starts
|
* airspeed, then this parameter is set correctly. If the airspeed starts
|
||||||
* to reduce, then the parameter is set to high, and if the throttle
|
* to reduce, then the parameter is set to high, and if the throttle
|
||||||
* demand required to climb and maintain speed is noticeably less than
|
* 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, then either FW_T_CLMB_MAX should be increased or
|
||||||
* FW_THR_MAX reduced.
|
* FW_THR_MAX reduced.
|
||||||
*
|
*
|
||||||
* @group L1 Control
|
* @group L1 Control
|
||||||
|
@ -200,8 +200,8 @@ PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f);
|
||||||
/**
|
/**
|
||||||
* Minimum descent rate
|
* Minimum descent rate
|
||||||
*
|
*
|
||||||
* This is the sink rate of the aircraft with the throttle
|
* This is the sink rate of the aircraft with the throttle
|
||||||
* set to THR_MIN and flown at the same airspeed as used
|
* set to THR_MIN and flown at the same airspeed as used
|
||||||
* to measure FW_T_CLMB_MAX.
|
* to measure FW_T_CLMB_MAX.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group Fixed Wing TECS
|
||||||
|
@ -211,10 +211,10 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f);
|
||||||
/**
|
/**
|
||||||
* Maximum descent rate
|
* Maximum descent rate
|
||||||
*
|
*
|
||||||
* This sets the maximum descent rate that the controller will use.
|
* This sets the maximum descent rate that the controller will use.
|
||||||
* If this value is too large, the aircraft can over-speed on descent.
|
* 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
|
* This should be set to a value that can be achieved without
|
||||||
* exceeding the lower pitch angle limit and without over-speeding
|
* exceeding the lower pitch angle limit and without over-speeding
|
||||||
* the aircraft.
|
* the aircraft.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group Fixed Wing TECS
|
||||||
|
@ -224,7 +224,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
|
||||||
/**
|
/**
|
||||||
* TECS time constant
|
* TECS time constant
|
||||||
*
|
*
|
||||||
* This is the time constant of the TECS control algorithm (in seconds).
|
* This is the time constant of the TECS control algorithm (in seconds).
|
||||||
* Smaller values make it faster to respond, larger values make it slower
|
* Smaller values make it faster to respond, larger values make it slower
|
||||||
* to respond.
|
* to respond.
|
||||||
*
|
*
|
||||||
|
@ -235,7 +235,7 @@ PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f);
|
||||||
/**
|
/**
|
||||||
* TECS Throttle time constant
|
* TECS Throttle time constant
|
||||||
*
|
*
|
||||||
* This is the time constant of the TECS throttle control algorithm (in seconds).
|
* This is the time constant of the TECS throttle control algorithm (in seconds).
|
||||||
* Smaller values make it faster to respond, larger values make it slower
|
* Smaller values make it faster to respond, larger values make it slower
|
||||||
* to respond.
|
* to respond.
|
||||||
*
|
*
|
||||||
|
@ -246,7 +246,7 @@ PARAM_DEFINE_FLOAT(FW_T_THRO_CONST, 8.0f);
|
||||||
/**
|
/**
|
||||||
* Throttle damping factor
|
* Throttle damping factor
|
||||||
*
|
*
|
||||||
* This is the damping gain for the throttle demand loop.
|
* This is the damping gain for the throttle demand loop.
|
||||||
* Increase to add damping to correct for oscillations in speed and height.
|
* Increase to add damping to correct for oscillations in speed and height.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group Fixed Wing TECS
|
||||||
|
@ -256,9 +256,9 @@ PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
|
||||||
/**
|
/**
|
||||||
* Integrator gain
|
* Integrator gain
|
||||||
*
|
*
|
||||||
* This is the integrator gain on the control loop.
|
* This is the integrator gain on the control loop.
|
||||||
* Increasing this gain increases the speed at which speed
|
* Increasing this gain increases the speed at which speed
|
||||||
* and height offsets are trimmed out, but reduces damping and
|
* and height offsets are trimmed out, but reduces damping and
|
||||||
* increases overshoot.
|
* increases overshoot.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group Fixed Wing TECS
|
||||||
|
@ -269,9 +269,9 @@ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
|
||||||
* Maximum vertical acceleration
|
* Maximum vertical acceleration
|
||||||
*
|
*
|
||||||
* This is the maximum vertical acceleration (in metres/second square)
|
* This is the maximum vertical acceleration (in metres/second square)
|
||||||
* either up or down that the controller will use to correct speed
|
* 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)
|
* 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
|
* allows for reasonably aggressive pitch changes if required to recover
|
||||||
* from under-speed conditions.
|
* from under-speed conditions.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group Fixed Wing TECS
|
||||||
|
@ -281,10 +281,10 @@ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
|
||||||
/**
|
/**
|
||||||
* Complementary filter "omega" parameter for height
|
* Complementary filter "omega" parameter for height
|
||||||
*
|
*
|
||||||
* This is the cross-over frequency (in radians/second) of the complementary
|
* This is the cross-over frequency (in radians/second) of the complementary
|
||||||
* filter used to fuse vertical acceleration and barometric height to obtain
|
* filter used to fuse vertical acceleration and barometric height to obtain
|
||||||
* an estimate of height rate and height. Increasing this frequency weights
|
* 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 barometer, whilst reducing it weights
|
||||||
* the solution more towards use of the accelerometer data.
|
* the solution more towards use of the accelerometer data.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group Fixed Wing TECS
|
||||||
|
@ -294,10 +294,10 @@ PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
|
||||||
/**
|
/**
|
||||||
* Complementary filter "omega" parameter for speed
|
* Complementary filter "omega" parameter for speed
|
||||||
*
|
*
|
||||||
* This is the cross-over frequency (in radians/second) of the complementary
|
* This is the cross-over frequency (in radians/second) of the complementary
|
||||||
* filter used to fuse longitudinal acceleration and airspeed to obtain an
|
* filter used to fuse longitudinal acceleration and airspeed to obtain an
|
||||||
* improved airspeed estimate. Increasing this frequency weights the solution
|
* improved airspeed estimate. Increasing this frequency weights the solution
|
||||||
* more towards use of the arispeed sensor, whilst reducing it weights the
|
* more towards use of the arispeed sensor, whilst reducing it weights the
|
||||||
* solution more towards use of the accelerometer data.
|
* solution more towards use of the accelerometer data.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group Fixed Wing TECS
|
||||||
|
@ -307,13 +307,13 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
|
||||||
/**
|
/**
|
||||||
* Roll -> Throttle feedforward
|
* Roll -> Throttle feedforward
|
||||||
*
|
*
|
||||||
* Increasing this gain turn increases the amount of throttle that will
|
* Increasing this gain turn increases the amount of throttle that will
|
||||||
* be used to compensate for the additional drag created by turning.
|
* be used to compensate for the additional drag created by turning.
|
||||||
* Ideally this should be set to approximately 10 x the extra sink rate
|
* 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
|
* 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
|
* the aircraft initially loses energy in turns and reduce if the
|
||||||
* aircraft initially gains energy in turns. Efficient high aspect-ratio
|
* aircraft initially gains energy in turns. Efficient high aspect-ratio
|
||||||
* aircraft (eg powered sailplanes) can use a lower value, whereas
|
* aircraft (eg powered sailplanes) can use a lower value, whereas
|
||||||
* inefficient low aspect-ratio models (eg delta wings) can use a higher value.
|
* inefficient low aspect-ratio models (eg delta wings) can use a higher value.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group Fixed Wing TECS
|
||||||
|
@ -323,15 +323,15 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f);
|
||||||
/**
|
/**
|
||||||
* Speed <--> Altitude priority
|
* Speed <--> Altitude priority
|
||||||
*
|
*
|
||||||
* This parameter adjusts the amount of weighting that the pitch control
|
* 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
|
* 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
|
* pitch control to control height and ignore speed errors. This will
|
||||||
* normally improve height accuracy but give larger airspeed errors.
|
* normally improve height accuracy but give larger airspeed errors.
|
||||||
* Setting it to 2.0 will cause the pitch control loop to control speed
|
* Setting it to 2.0 will cause the pitch control loop to control speed
|
||||||
* and ignore height errors. This will normally reduce airspeed errors,
|
* and ignore height errors. This will normally reduce airspeed errors,
|
||||||
* but give larger height errors. The default value of 1.0 allows the pitch
|
* but give larger height errors. The default value of 1.0 allows the pitch
|
||||||
* control to simultaneously control height and speed.
|
* control to simultaneously control height and speed.
|
||||||
* Note to Glider Pilots - set this parameter to 2.0 (The glider will
|
* Note to Glider Pilots - set this parameter to 2.0 (The glider will
|
||||||
* adjust its pitch angle to maintain airspeed, ignoring changes in height).
|
* adjust its pitch angle to maintain airspeed, ignoring changes in height).
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group Fixed Wing TECS
|
||||||
|
@ -341,9 +341,9 @@ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
|
||||||
/**
|
/**
|
||||||
* Pitch damping factor
|
* Pitch damping factor
|
||||||
*
|
*
|
||||||
* This is the damping gain for the pitch demand loop. Increase to add
|
* 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
|
* 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
|
* will work well provided the pitch to servo controller has been tuned
|
||||||
* properly.
|
* properly.
|
||||||
*
|
*
|
||||||
* @group Fixed Wing TECS
|
* @group Fixed Wing TECS
|
||||||
|
@ -357,6 +357,13 @@ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
|
PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Height rate FF factor
|
||||||
|
*
|
||||||
|
* @group Fixed Wing TECS
|
||||||
|
*/
|
||||||
|
PARAM_DEFINE_FLOAT(FW_T_HRATE_FF, 0.0f);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Speed rate P factor
|
* Speed rate P factor
|
||||||
*
|
*
|
||||||
|
|
Loading…
Reference in New Issue