mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
APM_Control: adjust min value for tconst
This commit is contained in:
parent
93abd44446
commit
fa88967b6e
@ -96,11 +96,11 @@ static const struct {
|
|||||||
{ 0.70, 50 }, // level 4
|
{ 0.70, 50 }, // level 4
|
||||||
{ 0.60, 60 }, // level 5
|
{ 0.60, 60 }, // level 5
|
||||||
{ 0.50, 75 }, // level 6
|
{ 0.50, 75 }, // level 6
|
||||||
{ 0.25, 90 }, // level 7
|
{ 0.30, 90 }, // level 7
|
||||||
{ 0.12, 120 }, // level 8
|
{ 0.2, 120 }, // level 8
|
||||||
{ 0.06, 160 }, // level 9
|
{ 0.15, 160 }, // level 9
|
||||||
{ 0.03, 210 }, // level 10
|
{ 0.1, 210 }, // level 10
|
||||||
{ 0.01, 300 }, // (yes, it goes to 11)
|
{ 0.1, 300 }, // (yes, it goes to 11)
|
||||||
};
|
};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -148,7 +148,6 @@ void AP_AutoTune::stop(void)
|
|||||||
running = false;
|
running = false;
|
||||||
save_gains(restore);
|
save_gains(restore);
|
||||||
current = restore;
|
current = restore;
|
||||||
rpid.set_slew_limit_scale(45);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -287,8 +287,8 @@ int32_t AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool
|
|||||||
float rate_offset;
|
float rate_offset;
|
||||||
bool inverted;
|
bool inverted;
|
||||||
|
|
||||||
if (gains.tau < 0.01f) {
|
if (gains.tau < 0.05f) {
|
||||||
gains.tau.set(0.01f);
|
gains.tau.set(0.05f);
|
||||||
}
|
}
|
||||||
|
|
||||||
rate_offset = _get_coordination_rate_offset(aspeed, inverted);
|
rate_offset = _get_coordination_rate_offset(aspeed, inverted);
|
||||||
|
@ -221,8 +221,8 @@ int32_t AP_RollController::get_rate_out(float desired_rate, float scaler)
|
|||||||
*/
|
*/
|
||||||
int32_t AP_RollController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
|
int32_t AP_RollController::get_servo_out(int32_t angle_err, float scaler, bool disable_integrator)
|
||||||
{
|
{
|
||||||
if (gains.tau < 0.01f) {
|
if (gains.tau < 0.05f) {
|
||||||
gains.tau.set(0.01f);
|
gains.tau.set(0.05f);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Calculate the desired roll rate (deg/sec) from the angle error
|
// Calculate the desired roll rate (deg/sec) from the angle error
|
||||||
|
Loading…
Reference in New Issue
Block a user