mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
APM_Control: fixed use of configured() vs configured_in_storage()
This commit is contained in:
parent
e807a74976
commit
aafec1fbe7
@ -356,7 +356,7 @@ void AP_PitchController::reset_I()
|
|||||||
void AP_PitchController::convert_pid()
|
void AP_PitchController::convert_pid()
|
||||||
{
|
{
|
||||||
AP_Float &ff = rate_pid.ff();
|
AP_Float &ff = rate_pid.ff();
|
||||||
if (ff.configured_in_storage()) {
|
if (ff.configured()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -258,7 +258,7 @@ void AP_RollController::reset_I()
|
|||||||
void AP_RollController::convert_pid()
|
void AP_RollController::convert_pid()
|
||||||
{
|
{
|
||||||
AP_Float &ff = rate_pid.ff();
|
AP_Float &ff = rate_pid.ff();
|
||||||
if (ff.configured_in_storage()) {
|
if (ff.configured()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
float old_ff=0, old_p=1.0, old_i=0.3, old_d=0.08;
|
float old_ff=0, old_p=1.0, old_i=0.3, old_d=0.08;
|
||||||
|
Loading…
Reference in New Issue
Block a user