ControlMonitor.cpp 3.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108
  1. #include "AC_AttitudeControl.h"
  2. #include <AP_HAL/AP_HAL.h>
  3. #include <AP_Math/AP_Math.h>
  4. /*
  5. code to monitor and report on the rate controllers, allowing for
  6. notification of controller oscillation
  7. */
  8. /*
  9. update a RMS estimate of controller state
  10. */
  11. void AC_AttitudeControl::control_monitor_filter_pid(float value, float &rms)
  12. {
  13. const float filter_constant = 0.99f;
  14. // we don't do the sqrt() here as it is quite expensive. That is
  15. // done when reporting a result
  16. rms = filter_constant * rms + (1.0f - filter_constant) * sq(value);
  17. }
  18. /*
  19. update state in _control_monitor
  20. */
  21. void AC_AttitudeControl::control_monitor_update(void)
  22. {
  23. const AP_Logger::PID_Info &iroll = get_rate_roll_pid().get_pid_info();
  24. control_monitor_filter_pid(iroll.P + iroll.FF, _control_monitor.rms_roll_P);
  25. control_monitor_filter_pid(iroll.D, _control_monitor.rms_roll_D);
  26. const AP_Logger::PID_Info &ipitch = get_rate_pitch_pid().get_pid_info();
  27. control_monitor_filter_pid(ipitch.P + iroll.FF, _control_monitor.rms_pitch_P);
  28. control_monitor_filter_pid(ipitch.D, _control_monitor.rms_pitch_D);
  29. const AP_Logger::PID_Info &iyaw = get_rate_yaw_pid().get_pid_info();
  30. control_monitor_filter_pid(iyaw.P + iyaw.D + iyaw.FF, _control_monitor.rms_yaw);
  31. }
  32. /*
  33. log a CRTL message
  34. */
  35. void AC_AttitudeControl::control_monitor_log(void)
  36. {
  37. AP::logger().Write("CTRL", "TimeUS,RMSRollP,RMSRollD,RMSPitchP,RMSPitchD,RMSYaw", "Qfffff",
  38. AP_HAL::micros64(),
  39. (double)safe_sqrt(_control_monitor.rms_roll_P),
  40. (double)safe_sqrt(_control_monitor.rms_roll_D),
  41. (double)safe_sqrt(_control_monitor.rms_pitch_P),
  42. (double)safe_sqrt(_control_monitor.rms_pitch_D),
  43. (double)safe_sqrt(_control_monitor.rms_yaw));
  44. }
  45. /*
  46. return current controller RMS filter value for roll
  47. */
  48. float AC_AttitudeControl::control_monitor_rms_output_roll(void) const
  49. {
  50. return safe_sqrt(_control_monitor.rms_roll_P + _control_monitor.rms_roll_D);
  51. }
  52. /*
  53. return current controller RMS filter value for roll_P
  54. */
  55. float AC_AttitudeControl::control_monitor_rms_output_roll_P(void) const
  56. {
  57. return safe_sqrt(_control_monitor.rms_roll_P);
  58. }
  59. /*
  60. return current controller RMS filter value for roll_D
  61. */
  62. float AC_AttitudeControl::control_monitor_rms_output_roll_D(void) const
  63. {
  64. return safe_sqrt(_control_monitor.rms_roll_D);
  65. }
  66. /*
  67. return current controller RMS filter value for pitch
  68. */
  69. float AC_AttitudeControl::control_monitor_rms_output_pitch(void) const
  70. {
  71. return safe_sqrt(_control_monitor.rms_pitch_P + _control_monitor.rms_pitch_D);
  72. }
  73. /*
  74. return current controller RMS filter value for pitch_P
  75. */
  76. float AC_AttitudeControl::control_monitor_rms_output_pitch_P(void) const
  77. {
  78. return safe_sqrt(_control_monitor.rms_pitch_P);
  79. }
  80. /*
  81. return current controller RMS filter value for pitch_D
  82. */
  83. float AC_AttitudeControl::control_monitor_rms_output_pitch_D(void) const
  84. {
  85. return safe_sqrt(_control_monitor.rms_pitch_D);
  86. }
  87. /*
  88. return current controller RMS filter value for yaw
  89. */
  90. float AC_AttitudeControl::control_monitor_rms_output_yaw(void) const
  91. {
  92. return safe_sqrt(_control_monitor.rms_yaw);
  93. }