AC_AutoTune: init angle dwell test with proper init method

This commit is contained in:
Bill Geyer 2021-12-21 23:39:47 -05:00 committed by Bill Geyer
parent 7bccaac327
commit 790a77d44a
1 changed files with 2 additions and 2 deletions

View File

@ -162,11 +162,11 @@ void AC_AutoTune_Heli::test_init()
if (!is_equal(start_freq,stop_freq)) { if (!is_equal(start_freq,stop_freq)) {
// initialize determine gain function // initialize determine gain function
freqresp_angle.init(AC_AutoTune_FreqResp::InputType::SWEEP); freqresp_angle.init(AC_AutoTune_FreqResp::InputType::SWEEP);
dwell_test_init(stop_freq); angle_dwell_test_init(stop_freq);
} else { } else {
// initialize determine gain function // initialize determine gain function
freqresp_angle.init(AC_AutoTune_FreqResp::InputType::DWELL); freqresp_angle.init(AC_AutoTune_FreqResp::InputType::DWELL);
dwell_test_init(start_freq); angle_dwell_test_init(start_freq);
} }
// TODO add time limit for sweep test // TODO add time limit for sweep test