AC_AutoTune: Fix some typos

Fixed some typos found in the code.
This commit is contained in:
Mykhailo Kuznietsov 2023-10-11 18:41:49 +11:00 committed by Peter Barker
parent 745a4df316
commit ad0b0a1c05
5 changed files with 13 additions and 13 deletions

View File

@ -158,7 +158,7 @@ protected:
AP_AHRS_View *ahrs_view,
AP_InertialNav *inertial_nav);
// send intermittant updates to user on status of tune
// send intermittent updates to user on status of tune
virtual void do_gcs_announcements() = 0;
// send post test updates to user

View File

@ -678,7 +678,7 @@ void AC_AutoTune_Heli::report_final_gains(AxisType test_axis) const
}
}
// report gain formating helper
// report gain formatting helper
void AC_AutoTune_Heli::report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float rate_ff, float angle_P, float max_accel) const
{
gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s complete", axis_string);
@ -1353,7 +1353,7 @@ void AC_AutoTune_Heli::set_gains_post_tune(AxisType test_axis)
}
// updating_rate_ff_up - adjust FF to ensure the target is reached
// FF is adjusted until rate requested is acheived
// FF is adjusted until rate requested is achieved
void AC_AutoTune_Heli::updating_rate_ff_up(float &tune_ff, float rate_target, float meas_rate, float meas_command)
{
@ -1565,7 +1565,7 @@ void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, float *freq, float *ga
// once finished with sweep of frequencies, cnt = 12 is used to then tune for max response gain
if (freq_cnt >= 12 && is_equal(start_freq,stop_freq)) {
if (gain[freq_cnt] < max_resp_gain && tune_p < AUTOTUNE_SP_MAX && !find_peak) {
// keep increasing tuning gain unless phase changes or max response gain is acheived
// keep increasing tuning gain unless phase changes or max response gain is achieved
if (phase[freq_cnt]-phase_max > 20.0f && phase[freq_cnt] < 210.0f) {
freq[freq_cnt] += 0.5 * test_freq_incr;
find_peak = true;
@ -1837,7 +1837,7 @@ void AC_AutoTune_Heli::Log_Write_AutoTuneSweep(float freq, float gain, float pha
phase);
}
// reset the test vaariables for each vehicle
// reset the test variables for each vehicle
void AC_AutoTune_Heli::reset_vehicle_test_variables()
{
// reset dwell test variables if sweep was interrupted in order to restart sweep

View File

@ -60,7 +60,7 @@ protected:
// load test gains
void load_test_gains() override;
// reset the test vaariables for heli
// reset the test variables for heli
void reset_vehicle_test_variables() override;
// reset the update gain variables for heli
@ -111,7 +111,7 @@ protected:
void Log_AutoTuneSweep() override;
void Log_Write_AutoTuneSweep(float freq, float gain, float phase);
// send intermittant updates to user on status of tune
// send intermittent updates to user on status of tune
void do_gcs_announcements() override;
// send post test updates to user
@ -161,7 +161,7 @@ private:
void dwell_test_run(uint8_t freq_resp_input, float start_frq, float stop_frq, float &dwell_gain, float &dwell_phase, DwellType dwell_type);
// updating_rate_ff_up - adjust FF to ensure the target is reached
// FF is adjusted until rate requested is acheived
// FF is adjusted until rate requested is achieved
void updating_rate_ff_up(float &tune_ff, float rate_target, float meas_rate, float meas_command);
// updating_rate_p_up - uses maximum allowable gain determined from max_gain test to determine rate p gain that does not exceed exceed max response gain
@ -185,7 +185,7 @@ private:
// exceeded_freq_range - ensures tuning remains inside frequency range
bool exceeded_freq_range(float frequency);
// report gain formating helper
// report gain formatting helper
void report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float rate_ff, float angle_P, float max_accel) const;
// updating rate FF variables

View File

@ -484,7 +484,7 @@ void AC_AutoTune_Multi::report_final_gains(AxisType test_axis) const
}
}
// report gain formating helper
// report gain formatting helper
void AC_AutoTune_Multi::report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float angle_P, float max_accel) const
{
gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s complete", axis_string);

View File

@ -53,7 +53,7 @@ protected:
// load test gains
void load_test_gains() override;
// reset the test vaariables for multi
// reset the test variables for multi
void reset_vehicle_test_variables() override {};
// reset the update gain variables for multi
@ -62,7 +62,7 @@ protected:
void test_init() override;
void test_run(AxisType test_axis, const float dir_sign) override;
// send intermittant updates to user on status of tune
// send intermittent updates to user on status of tune
void do_gcs_announcements() override;
// send post test updates to user
@ -160,7 +160,7 @@ private:
// P is increased until we achieve our target within a reasonable time
void updating_angle_p_up(float &tune_p, float tune_p_max, float tune_p_step_ratio, float angle_target, float meas_angle_max, float meas_rate_min, float meas_rate_max);
// report gain formating helper
// report gain formatting helper
void report_axis_gains(const char* axis_string, float rate_P, float rate_I, float rate_D, float angle_P, float max_accel) const;
// parameters