CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_AttitudeControl/ControlMonitor.cpp
Views: 1798
1
#include "AC_AttitudeControl.h"
2
#include <AP_HAL/AP_HAL.h>
3
#include <AP_Math/AP_Math.h>
4
#include <AP_Logger/AP_Logger.h>
5
6
/*
7
code to monitor and report on the rate controllers, allowing for
8
notification of controller oscillation
9
*/
10
11
12
/*
13
update a RMS estimate of controller state
14
*/
15
void AC_AttitudeControl::control_monitor_filter_pid(float value, float &rms)
16
{
17
const float filter_constant = 0.99f;
18
// we don't do the sqrt() here as it is quite expensive. That is
19
// done when reporting a result
20
rms = filter_constant * rms + (1.0f - filter_constant) * sq(value);
21
}
22
23
/*
24
update state in _control_monitor
25
*/
26
void AC_AttitudeControl::control_monitor_update(void)
27
{
28
const AP_PIDInfo &iroll = get_rate_roll_pid().get_pid_info();
29
control_monitor_filter_pid(iroll.P + iroll.FF, _control_monitor.rms_roll_P);
30
control_monitor_filter_pid(iroll.D, _control_monitor.rms_roll_D);
31
32
const AP_PIDInfo &ipitch = get_rate_pitch_pid().get_pid_info();
33
control_monitor_filter_pid(ipitch.P + ipitch.FF, _control_monitor.rms_pitch_P);
34
control_monitor_filter_pid(ipitch.D, _control_monitor.rms_pitch_D);
35
36
const AP_PIDInfo &iyaw = get_rate_yaw_pid().get_pid_info();
37
control_monitor_filter_pid(iyaw.P + iyaw.D + iyaw.FF, _control_monitor.rms_yaw);
38
}
39
40
#if HAL_LOGGING_ENABLED
41
/*
42
log a CTRL message
43
*/
44
void AC_AttitudeControl::control_monitor_log(void) const
45
{
46
// @LoggerMessage: CTRL
47
// @Description: Attitude Control oscillation monitor diagnostics
48
// @Field: TimeUS: Time since system startup
49
// @Field: RMSRollP: LPF Root-Mean-Squared Roll Rate controller P gain
50
// @Field: RMSRollD: LPF Root-Mean-Squared Roll rate controller D gain
51
// @Field: RMSPitchP: LPF Root-Mean-Squared Pitch Rate controller P gain
52
// @Field: RMSPitchD: LPF Root-Mean-Squared Pitch Rate controller D gain
53
// @Field: RMSYaw: LPF Root-Mean-Squared Yaw Rate controller P+D gain
54
AP::logger().WriteStreaming("CTRL", "TimeUS,RMSRollP,RMSRollD,RMSPitchP,RMSPitchD,RMSYaw", "Qfffff",
55
AP_HAL::micros64(),
56
(double)safe_sqrt(_control_monitor.rms_roll_P),
57
(double)safe_sqrt(_control_monitor.rms_roll_D),
58
(double)safe_sqrt(_control_monitor.rms_pitch_P),
59
(double)safe_sqrt(_control_monitor.rms_pitch_D),
60
(double)safe_sqrt(_control_monitor.rms_yaw));
61
62
}
63
#endif // HAL_LOGGING_ENABLED
64
65
/*
66
return current controller RMS filter value for roll
67
*/
68
float AC_AttitudeControl::control_monitor_rms_output_roll(void) const
69
{
70
return safe_sqrt(_control_monitor.rms_roll_P + _control_monitor.rms_roll_D);
71
}
72
73
/*
74
return current controller RMS filter value for roll_P
75
*/
76
float AC_AttitudeControl::control_monitor_rms_output_roll_P(void) const
77
{
78
return safe_sqrt(_control_monitor.rms_roll_P);
79
}
80
81
/*
82
return current controller RMS filter value for roll_D
83
*/
84
float AC_AttitudeControl::control_monitor_rms_output_roll_D(void) const
85
{
86
return safe_sqrt(_control_monitor.rms_roll_D);
87
}
88
89
/*
90
return current controller RMS filter value for pitch
91
*/
92
float AC_AttitudeControl::control_monitor_rms_output_pitch(void) const
93
{
94
return safe_sqrt(_control_monitor.rms_pitch_P + _control_monitor.rms_pitch_D);
95
}
96
97
/*
98
return current controller RMS filter value for pitch_P
99
*/
100
float AC_AttitudeControl::control_monitor_rms_output_pitch_P(void) const
101
{
102
return safe_sqrt(_control_monitor.rms_pitch_P);
103
}
104
105
/*
106
return current controller RMS filter value for pitch_D
107
*/
108
float AC_AttitudeControl::control_monitor_rms_output_pitch_D(void) const
109
{
110
return safe_sqrt(_control_monitor.rms_pitch_D);
111
}
112
113
/*
114
return current controller RMS filter value for yaw
115
*/
116
float AC_AttitudeControl::control_monitor_rms_output_yaw(void) const
117
{
118
return safe_sqrt(_control_monitor.rms_yaw);
119
}
120
121