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/LogStructure.h
Views: 1798
1
#pragma once
2
3
#include <AP_Logger/LogStructure.h>
4
5
#define LOG_IDS_FROM_AC_ATTITUDECONTROL \
6
LOG_PSCN_MSG, \
7
LOG_PSCE_MSG, \
8
LOG_PSCD_MSG, \
9
LOG_PSON_MSG, \
10
LOG_PSOE_MSG, \
11
LOG_PSOD_MSG, \
12
LOG_PSOT_MSG, \
13
LOG_ANG_MSG
14
15
// @LoggerMessage: PSCN
16
// @Description: Position Control North
17
// @Field: TimeUS: Time since system startup
18
// @Field: DPN: Desired position relative to EKF origin
19
// @Field: TPN: Target position relative to EKF origin
20
// @Field: PN: Position relative to EKF origin
21
// @Field: DVN: Desired velocity North
22
// @Field: TVN: Target velocity North
23
// @Field: VN: Velocity North
24
// @Field: DAN: Desired acceleration North
25
// @Field: TAN: Target acceleration North
26
// @Field: AN: Acceleration North
27
28
// @LoggerMessage: PSCE
29
// @Description: Position Control East
30
// @Field: TimeUS: Time since system startup
31
// @Field: DPE: Desired position relative to EKF origin + Offsets
32
// @Field: TPE: Target position relative to EKF origin
33
// @Field: PE: Position relative to EKF origin
34
// @Field: DVE: Desired velocity East
35
// @Field: TVE: Target velocity East
36
// @Field: VE: Velocity East
37
// @Field: DAE: Desired acceleration East
38
// @Field: TAE: Target acceleration East
39
// @Field: AE: Acceleration East
40
41
// @LoggerMessage: PSCD
42
// @Description: Position Control Down
43
// @Field: TimeUS: Time since system startup
44
// @Field: DPD: Desired position relative to EKF origin + Offsets
45
// @Field: TPD: Target position relative to EKF origin
46
// @Field: PD: Position relative to EKF origin
47
// @Field: DVD: Desired velocity Down
48
// @Field: TVD: Target velocity Down
49
// @Field: VD: Velocity Down
50
// @Field: DAD: Desired acceleration Down
51
// @Field: TAD: Target acceleration Down
52
// @Field: AD: Acceleration Down
53
54
55
// position controller per-axis logging
56
struct PACKED log_PSCx {
57
LOG_PACKET_HEADER;
58
uint64_t time_us;
59
float pos_desired;
60
float pos_target;
61
float pos;
62
float vel_desired;
63
float vel_target;
64
float vel;
65
float accel_desired;
66
float accel_target;
67
float accel;
68
};
69
70
// @LoggerMessage: PSON
71
// @Description: Position Control Offsets North
72
// @Field: TimeUS: Time since system startup
73
// @Field: TPON: Target position offset North
74
// @Field: PON: Position offset North
75
// @Field: TVON: Target velocity offset North
76
// @Field: VON: Velocity offset North
77
// @Field: TAON: Target acceleration offset North
78
// @Field: AON: Acceleration offset North
79
80
// @LoggerMessage: PSOE
81
// @Description: Position Control Offsets East
82
// @Field: TimeUS: Time since system startup
83
// @Field: TPOE: Target position offset East
84
// @Field: POE: Position offset East
85
// @Field: TVOE: Target velocity offset East
86
// @Field: VOE: Velocity offset East
87
// @Field: TAOE: Target acceleration offset East
88
// @Field: AOE: Acceleration offset East
89
90
// @LoggerMessage: PSOD
91
// @Description: Position Control Offsets Down
92
// @Field: TimeUS: Time since system startup
93
// @Field: TPOD: Target position offset Down
94
// @Field: POD: Position offset Down
95
// @Field: TVOD: Target velocity offset Down
96
// @Field: VOD: Velocity offset Down
97
// @Field: TAOD: Target acceleration offset Down
98
// @Field: AOD: Acceleration offset Down
99
100
// @LoggerMessage: PSOT
101
// @Description: Position Control Offsets Terrain (Down)
102
// @Field: TimeUS: Time since system startup
103
// @Field: TPOT: Target position offset Terrain
104
// @Field: POT: Position offset Terrain
105
// @Field: TVOT: Target velocity offset Terrain
106
// @Field: VOT: Velocity offset Terrain
107
// @Field: TAOT: Target acceleration offset Terrain
108
// @Field: AOT: Acceleration offset Terrain
109
110
// position controller per-axis offset logging
111
struct PACKED log_PSOx {
112
LOG_PACKET_HEADER;
113
uint64_t time_us;
114
float pos_target_offset;
115
float pos_offset;
116
float vel_target_offset;
117
float vel_offset;
118
float accel_target_offset;
119
float accel_offset;
120
};
121
122
// @LoggerMessage: RATE
123
// @Description: Desired and achieved vehicle attitude rates. Not logged in Fixed Wing Plane modes.
124
// @Field: TimeUS: Time since system startup
125
// @Field: RDes: vehicle desired roll rate
126
// @Field: R: achieved vehicle roll rate
127
// @Field: ROut: normalized output for Roll
128
// @Field: PDes: vehicle desired pitch rate
129
// @Field: P: vehicle pitch rate
130
// @Field: POut: normalized output for Pitch
131
// @Field: Y: achieved vehicle yaw rate
132
// @Field: YOut: normalized output for Yaw
133
// @Field: YDes: vehicle desired yaw rate
134
// @Field: ADes: desired vehicle vertical acceleration
135
// @Field: A: achieved vehicle vertical acceleration
136
// @Field: AOut: percentage of vertical thrust output current being used
137
// @Field: AOutSlew: vertical thrust output slew rate
138
struct PACKED log_Rate {
139
LOG_PACKET_HEADER;
140
uint64_t time_us;
141
float control_roll;
142
float roll;
143
float roll_out;
144
float control_pitch;
145
float pitch;
146
float pitch_out;
147
float control_yaw;
148
float yaw;
149
float yaw_out;
150
float control_accel;
151
float accel;
152
float accel_out;
153
float throttle_slew;
154
};
155
156
// @LoggerMessage: ANG
157
// @Description: Attitude control attitude
158
// @Field: TimeUS: Timestamp of the current Attitude loop
159
// @Field: DesRoll: vehicle desired roll
160
// @Field: Roll: achieved vehicle roll
161
// @Field: DesPitch: vehicle desired pitch
162
// @Field: Pitch: achieved vehicle pitch
163
// @Field: DesYaw: vehicle desired yaw
164
// @Field: Yaw: achieved vehicle yaw
165
// @Field: Dt: attitude delta time
166
struct PACKED log_ANG {
167
LOG_PACKET_HEADER;
168
uint64_t time_us;
169
float control_roll;
170
float roll;
171
float control_pitch;
172
float pitch;
173
float control_yaw;
174
float yaw;
175
float sensor_dt;
176
};
177
178
#define PSCx_FMT "Qfffffffff"
179
#define PSCx_UNITS "smmmnnnooo"
180
#define PSCx_MULTS "F000000000"
181
182
#define PSOx_FMT "Qffffff"
183
#define PSOx_UNITS "smmnnoo"
184
#define PSOx_MULTS "F000000"
185
186
#define LOG_STRUCTURE_FROM_AC_ATTITUDECONTROL \
187
{ LOG_PSCN_MSG, sizeof(log_PSCx), \
188
"PSCN", PSCx_FMT, "TimeUS,DPN,TPN,PN,DVN,TVN,VN,DAN,TAN,AN", PSCx_UNITS, PSCx_MULTS }, \
189
{ LOG_PSCE_MSG, sizeof(log_PSCx), \
190
"PSCE", PSCx_FMT, "TimeUS,DPE,TPE,PE,DVE,TVE,VE,DAE,TAE,AE", PSCx_UNITS, PSCx_MULTS }, \
191
{ LOG_PSCD_MSG, sizeof(log_PSCx), \
192
"PSCD", PSCx_FMT, "TimeUS,DPD,TPD,PD,DVD,TVD,VD,DAD,TAD,AD", PSCx_UNITS, PSCx_MULTS }, \
193
{ LOG_PSON_MSG, sizeof(log_PSOx), \
194
"PSON", PSOx_FMT, "TimeUS,TPON,PON,TVON,VON,TAON,AON", PSOx_UNITS, PSOx_MULTS }, \
195
{ LOG_PSOE_MSG, sizeof(log_PSOx), \
196
"PSOE", PSOx_FMT, "TimeUS,TPOE,POE,TVOE,VOE,TAOE,AOE", PSOx_UNITS, PSOx_MULTS }, \
197
{ LOG_PSOD_MSG, sizeof(log_PSOx), \
198
"PSOD", PSOx_FMT, "TimeUS,TPOD,POD,TVOD,VOD,TAOD,AOD", PSOx_UNITS, PSOx_MULTS }, \
199
{ LOG_PSOT_MSG, sizeof(log_PSOx), \
200
"PSOT", PSOx_FMT, "TimeUS,TPOT,POT,TVOT,VOT,TAOT,AOT", PSOx_UNITS, PSOx_MULTS }, \
201
{ LOG_RATE_MSG, sizeof(log_Rate), \
202
"RATE", "Qfffffffffffff", "TimeUS,RDes,R,ROut,PDes,P,POut,YDes,Y,YOut,ADes,A,AOut,AOutSlew", "skk-kk-kk-oo--", "F?????????BB--" , true }, \
203
{ LOG_ANG_MSG, sizeof(log_ANG),\
204
"ANG", "Qfffffff", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,Dt", "sddddhhs", "F0000000" , true }
205
206