Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add options to prevent spamming Tuning Error messsages when not actually tuning or desired #18609

Merged
merged 2 commits into from Sep 20, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
2 changes: 1 addition & 1 deletion libraries/AC_AttitudeControl/ControlMonitor.cpp
Expand Up @@ -29,7 +29,7 @@ void AC_AttitudeControl::control_monitor_update(void)
control_monitor_filter_pid(iroll.D, _control_monitor.rms_roll_D);

const AP_Logger::PID_Info &ipitch = get_rate_pitch_pid().get_pid_info();
control_monitor_filter_pid(ipitch.P + iroll.FF, _control_monitor.rms_pitch_P);
control_monitor_filter_pid(ipitch.P + ipitch.FF, _control_monitor.rms_pitch_P);
control_monitor_filter_pid(ipitch.D, _control_monitor.rms_pitch_D);

const AP_Logger::PID_Info &iyaw = get_rate_yaw_pid().get_pid_info();
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Tuning/AP_Tuning.cpp
Expand Up @@ -49,7 +49,7 @@ const AP_Param::GroupInfo AP_Tuning::var_info[] = {

// @Param: ERR_THRESH
// @DisplayName: Controller error threshold
// @Description: This sets the controller error threshold above which an alarm will sound and a message will be sent to the GCS to warn of controller instability
// @Description: This sets the controller error threshold above which an alarm will sound and a message will be sent to the GCS to warn of controller instability while tuning. The error is the rms value of the P+D corrections in the loop. High values in hover indicate possible instability due to too high PID gains or excessively high D to P gain ratios.-1 will disable this message.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do we really sound an alarm?!

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

do not know...dont have buzzers on my planes....

// @Range: 0 1
// @User: Standard
AP_GROUPINFO("ERR_THRESH", 7, AP_Tuning, error_threshold, 0.15f),
Expand Down Expand Up @@ -342,7 +342,7 @@ const char *AP_Tuning::get_tuning_name(uint8_t parm)
void AP_Tuning::check_controller_error(void)
{
float err = controller_error(current_parm);
if (err > error_threshold) {
if (err > error_threshold && !mid_point_wait && error_threshold > 0) {
uint32_t now = AP_HAL::millis();
if (now - last_controller_error_ms > 2000 && hal.util->get_soft_armed()) {
AP_Notify::events.tune_error = 1;
Expand Down