Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_AttitudeControl/ControlMonitor.cpp
Views: 1798
#include "AC_AttitudeControl.h"1#include <AP_HAL/AP_HAL.h>2#include <AP_Math/AP_Math.h>3#include <AP_Logger/AP_Logger.h>45/*6code to monitor and report on the rate controllers, allowing for7notification of controller oscillation8*/91011/*12update a RMS estimate of controller state13*/14void AC_AttitudeControl::control_monitor_filter_pid(float value, float &rms)15{16const float filter_constant = 0.99f;17// we don't do the sqrt() here as it is quite expensive. That is18// done when reporting a result19rms = filter_constant * rms + (1.0f - filter_constant) * sq(value);20}2122/*23update state in _control_monitor24*/25void AC_AttitudeControl::control_monitor_update(void)26{27const AP_PIDInfo &iroll = get_rate_roll_pid().get_pid_info();28control_monitor_filter_pid(iroll.P + iroll.FF, _control_monitor.rms_roll_P);29control_monitor_filter_pid(iroll.D, _control_monitor.rms_roll_D);3031const AP_PIDInfo &ipitch = get_rate_pitch_pid().get_pid_info();32control_monitor_filter_pid(ipitch.P + ipitch.FF, _control_monitor.rms_pitch_P);33control_monitor_filter_pid(ipitch.D, _control_monitor.rms_pitch_D);3435const AP_PIDInfo &iyaw = get_rate_yaw_pid().get_pid_info();36control_monitor_filter_pid(iyaw.P + iyaw.D + iyaw.FF, _control_monitor.rms_yaw);37}3839#if HAL_LOGGING_ENABLED40/*41log a CTRL message42*/43void AC_AttitudeControl::control_monitor_log(void) const44{45// @LoggerMessage: CTRL46// @Description: Attitude Control oscillation monitor diagnostics47// @Field: TimeUS: Time since system startup48// @Field: RMSRollP: LPF Root-Mean-Squared Roll Rate controller P gain49// @Field: RMSRollD: LPF Root-Mean-Squared Roll rate controller D gain50// @Field: RMSPitchP: LPF Root-Mean-Squared Pitch Rate controller P gain51// @Field: RMSPitchD: LPF Root-Mean-Squared Pitch Rate controller D gain52// @Field: RMSYaw: LPF Root-Mean-Squared Yaw Rate controller P+D gain53AP::logger().WriteStreaming("CTRL", "TimeUS,RMSRollP,RMSRollD,RMSPitchP,RMSPitchD,RMSYaw", "Qfffff",54AP_HAL::micros64(),55(double)safe_sqrt(_control_monitor.rms_roll_P),56(double)safe_sqrt(_control_monitor.rms_roll_D),57(double)safe_sqrt(_control_monitor.rms_pitch_P),58(double)safe_sqrt(_control_monitor.rms_pitch_D),59(double)safe_sqrt(_control_monitor.rms_yaw));6061}62#endif // HAL_LOGGING_ENABLED6364/*65return current controller RMS filter value for roll66*/67float AC_AttitudeControl::control_monitor_rms_output_roll(void) const68{69return safe_sqrt(_control_monitor.rms_roll_P + _control_monitor.rms_roll_D);70}7172/*73return current controller RMS filter value for roll_P74*/75float AC_AttitudeControl::control_monitor_rms_output_roll_P(void) const76{77return safe_sqrt(_control_monitor.rms_roll_P);78}7980/*81return current controller RMS filter value for roll_D82*/83float AC_AttitudeControl::control_monitor_rms_output_roll_D(void) const84{85return safe_sqrt(_control_monitor.rms_roll_D);86}8788/*89return current controller RMS filter value for pitch90*/91float AC_AttitudeControl::control_monitor_rms_output_pitch(void) const92{93return safe_sqrt(_control_monitor.rms_pitch_P + _control_monitor.rms_pitch_D);94}9596/*97return current controller RMS filter value for pitch_P98*/99float AC_AttitudeControl::control_monitor_rms_output_pitch_P(void) const100{101return safe_sqrt(_control_monitor.rms_pitch_P);102}103104/*105return current controller RMS filter value for pitch_D106*/107float AC_AttitudeControl::control_monitor_rms_output_pitch_D(void) const108{109return safe_sqrt(_control_monitor.rms_pitch_D);110}111112/*113return current controller RMS filter value for yaw114*/115float AC_AttitudeControl::control_monitor_rms_output_yaw(void) const116{117return safe_sqrt(_control_monitor.rms_yaw);118}119120121