APM:Libraries
ControlMonitor.cpp
Go to the documentation of this file.
1 #include "AC_AttitudeControl.h"
2 #include <AP_HAL/AP_HAL.h>
3 #include <AP_Math/AP_Math.h>
4 
5 /*
6  code to monitor and report on the rate controllers, allowing for
7  notification of controller oscillation
8  */
9 
10 
11 /*
12  update a RMS estimate of controller state
13  */
15 {
16  const float filter_constant = 0.99f;
17  // we don't do the sqrt() here as it is quite expensive. That is
18  // done when reporting a result
19  rms = filter_constant * rms + (1.0f - filter_constant) * sq(value);
20 }
21 
22 /*
23  update state in _control_monitor
24  */
26 {
28  control_monitor_filter_pid(iroll.P + iroll.FF, _control_monitor.rms_roll_P);
30 
32  control_monitor_filter_pid(ipitch.P + iroll.FF, _control_monitor.rms_pitch_P);
33  control_monitor_filter_pid(ipitch.D, _control_monitor.rms_pitch_D);
34 
36  control_monitor_filter_pid(iyaw.P + iyaw.D + iyaw.FF, _control_monitor.rms_yaw);
37 }
38 
39 /*
40  log a CRTL message
41  */
43 {
44  DataFlash_Class::instance()->Log_Write("CTRL", "TimeUS,RMSRollP,RMSRollD,RMSPitchP,RMSPitchD,RMSYaw", "Qfffff",
46  (double)sqrtf(_control_monitor.rms_roll_P),
47  (double)sqrtf(_control_monitor.rms_roll_D),
48  (double)sqrtf(_control_monitor.rms_pitch_P),
49  (double)sqrtf(_control_monitor.rms_pitch_D),
50  (double)sqrtf(_control_monitor.rms_yaw));
51 
52 }
53 
54 /*
55  return current controller RMS filter value for roll
56  */
58 {
59  return sqrtf(_control_monitor.rms_roll_P + _control_monitor.rms_roll_D);
60 }
61 
62 /*
63  return current controller RMS filter value for roll_P
64  */
66 {
67  return sqrtf(_control_monitor.rms_roll_P);
68 }
69 
70 /*
71  return current controller RMS filter value for roll_D
72  */
74 {
75  return sqrtf(_control_monitor.rms_roll_D);
76 }
77 
78 /*
79  return current controller RMS filter value for pitch
80  */
82 {
83  return sqrtf(_control_monitor.rms_pitch_P + _control_monitor.rms_pitch_D);
84 }
85 
86 /*
87  return current controller RMS filter value for pitch_P
88  */
90 {
91  return sqrtf(_control_monitor.rms_pitch_P);
92 }
93 
94 /*
95  return current controller RMS filter value for pitch_D
96  */
98 {
99  return sqrtf(_control_monitor.rms_pitch_D);
100 }
101 
102 /*
103  return current controller RMS filter value for yaw
104  */
106 {
107  return sqrtf(_control_monitor.rms_yaw);
108 }
void control_monitor_log(void)
float control_monitor_rms_output_roll_P(void) const
float control_monitor_rms_output_roll_D(void) const
ArduCopter attitude control library.
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
void control_monitor_filter_pid(float value, float &rms_P)
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
uint64_t micros64()
Definition: system.cpp:162
const DataFlash_Class::PID_Info & get_pid_info(void) const
Definition: AC_PID.h:82
float control_monitor_rms_output_pitch_P(void) const
float control_monitor_rms_output_yaw(void) const
struct AC_AttitudeControl::@0 _control_monitor
virtual AC_PID & get_rate_pitch_pid()=0
virtual AC_PID & get_rate_roll_pid()=0
float sq(const T val)
Definition: AP_Math.h:170
float value
void control_monitor_update(void)
float control_monitor_rms_output_pitch_D(void) const
float control_monitor_rms_output_pitch(void) const
float control_monitor_rms_output_roll(void) const
virtual AC_PID & get_rate_yaw_pid()=0