mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_Autotune_Heli: print gains on axis completion
This commit is contained in:
parent
2ccf8af2bd
commit
607a7bfd70
@ -706,6 +706,31 @@ void AC_AutoTune_Heli::save_tuning_gains()
|
||||
reset();
|
||||
}
|
||||
|
||||
// report final gains for a given axis to GCS
|
||||
void AC_AutoTune_Heli::report_final_gains(AxisType test_axis) const
|
||||
{
|
||||
switch (test_axis) {
|
||||
case ROLL:
|
||||
report_axis_gains("Roll", tune_roll_rp, tune_roll_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_roll_rd, tune_roll_rff, tune_roll_sp, tune_roll_accel);
|
||||
break;
|
||||
case PITCH:
|
||||
report_axis_gains("Pitch", tune_pitch_rp, tune_pitch_rff*AUTOTUNE_FFI_RATIO_FINAL, tune_pitch_rd, tune_pitch_rff, tune_pitch_sp, tune_pitch_accel);
|
||||
break;
|
||||
case YAW:
|
||||
report_axis_gains("Yaw", tune_yaw_rp, tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL, tune_yaw_rd, tune_yaw_rff, tune_yaw_sp, tune_yaw_accel);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// report gain formating 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);
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s Rate: P:%0.4f, I:%0.4f, D:%0.5f, FF:%0.4f",axis_string,rate_P,rate_I,rate_D,rate_ff);
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE,"AutoTune: %s Angle P:%0.2f, Max Accel:%0.0f",axis_string,angle_P,max_accel);
|
||||
}
|
||||
|
||||
|
||||
void AC_AutoTune_Heli::rate_ff_test_init()
|
||||
{
|
||||
ff_test_phase = 0;
|
||||
|
@ -110,6 +110,9 @@ protected:
|
||||
// send post test updates to user
|
||||
void do_post_test_gcs_announcements() override;
|
||||
|
||||
// report final gains for a given axis to GCS
|
||||
void report_final_gains(AxisType test_axis) const override;
|
||||
|
||||
// set the tuning test sequence
|
||||
void set_tune_sequence() override;
|
||||
|
||||
@ -173,6 +176,9 @@ private:
|
||||
// exceeded_freq_range - ensures tuning remains inside frequency range
|
||||
bool exceeded_freq_range(float frequency);
|
||||
|
||||
// report gain formating 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
|
||||
// flag for completion of the initial direction for the feedforward test
|
||||
bool first_dir_complete;
|
||||
|
Loading…
Reference in New Issue
Block a user