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/Blimp/Log.cpp
Views: 1798
1
#include "Blimp.h"
2
3
#if HAL_LOGGING_ENABLED
4
5
// Code to Write and Read packets from AP_Logger log memory
6
// Code to interact with the user to dump or erase logs
7
8
struct PACKED log_FINI {
9
LOG_PACKET_HEADER;
10
uint64_t time_us;
11
float Right;
12
float Front;
13
float Down;
14
float Yaw;
15
};
16
17
struct PACKED log_FINO {
18
LOG_PACKET_HEADER;
19
uint64_t time_us;
20
float Fin1_Amp;
21
float Fin1_Off;
22
float Fin2_Amp;
23
float Fin2_Off;
24
float Fin3_Amp;
25
float Fin3_Off;
26
float Fin4_Amp;
27
float Fin4_Off;
28
};
29
30
//Write a fin input packet
31
void Blimp::Write_FINI(float right, float front, float down, float yaw)
32
{
33
const struct log_FINI pkt {
34
LOG_PACKET_HEADER_INIT(LOG_FINI_MSG),
35
time_us : AP_HAL::micros64(),
36
Right : right,
37
Front : front,
38
Down : down,
39
Yaw : yaw
40
};
41
logger.WriteBlock(&pkt, sizeof(pkt));
42
}
43
44
//Write a fin output packet
45
void Blimp::Write_FINO(float *amp, float *off)
46
{
47
const struct log_FINO pkt {
48
LOG_PACKET_HEADER_INIT(LOG_FINO_MSG),
49
time_us : AP_HAL::micros64(),
50
Fin1_Amp : amp[0],
51
Fin1_Off : off[0],
52
Fin2_Amp : amp[1],
53
Fin2_Off : off[1],
54
Fin3_Amp : amp[2],
55
Fin3_Off : off[2],
56
Fin4_Amp : amp[3],
57
Fin4_Off : off[3],
58
};
59
logger.WriteBlock(&pkt, sizeof(pkt));
60
}
61
62
struct PACKED log_Control_Tuning {
63
LOG_PACKET_HEADER;
64
uint64_t time_us;
65
float throttle_in;
66
float angle_boost;
67
float throttle_out;
68
float throttle_hover;
69
float desired_alt;
70
float inav_alt;
71
int32_t baro_alt;
72
float desired_rangefinder_alt;
73
float rangefinder_alt;
74
float terr_alt;
75
int16_t target_climb_rate;
76
int16_t climb_rate;
77
};
78
79
// Write PID packets
80
void Blimp::Log_Write_PIDs()
81
{
82
logger.Write_PID(LOG_PIVN_MSG, pid_vel_xy.get_pid_info_x());
83
logger.Write_PID(LOG_PIVE_MSG, pid_vel_xy.get_pid_info_y());
84
logger.Write_PID(LOG_PIVD_MSG, pid_vel_z.get_pid_info());
85
logger.Write_PID(LOG_PIVY_MSG, pid_vel_yaw.get_pid_info());
86
logger.Write_PID(LOG_PIDN_MSG, pid_pos_xy.get_pid_info_x());
87
logger.Write_PID(LOG_PIDE_MSG, pid_pos_xy.get_pid_info_y());
88
logger.Write_PID(LOG_PIDD_MSG, pid_pos_z.get_pid_info());
89
logger.Write_PID(LOG_PIDY_MSG, pid_pos_yaw.get_pid_info());
90
}
91
92
// Write an attitude packet
93
void Blimp::Log_Write_Attitude()
94
{
95
//Attitude targets are all zero since Blimp doesn't have attitude control,
96
//but the rest of the log message is useful.
97
ahrs.Write_Attitude(Vector3f{0,0,0});
98
}
99
100
// Write an EKF and POS packet
101
void Blimp::Log_Write_EKF_POS()
102
{
103
AP::ahrs().Log_Write();
104
}
105
106
struct PACKED log_Data_Int16t {
107
LOG_PACKET_HEADER;
108
uint64_t time_us;
109
uint8_t id;
110
int16_t data_value;
111
};
112
113
// Write an int16_t data packet
114
UNUSED_FUNCTION
115
void Blimp::Log_Write_Data(LogDataID id, int16_t value)
116
{
117
if (should_log(MASK_LOG_ANY)) {
118
struct log_Data_Int16t pkt = {
119
LOG_PACKET_HEADER_INIT(LOG_DATA_INT16_MSG),
120
time_us : AP_HAL::micros64(),
121
id : (uint8_t)id,
122
data_value : value
123
};
124
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
125
}
126
}
127
128
struct PACKED log_Data_UInt16t {
129
LOG_PACKET_HEADER;
130
uint64_t time_us;
131
uint8_t id;
132
uint16_t data_value;
133
};
134
135
// Write an uint16_t data packet
136
UNUSED_FUNCTION
137
void Blimp::Log_Write_Data(LogDataID id, uint16_t value)
138
{
139
if (should_log(MASK_LOG_ANY)) {
140
struct log_Data_UInt16t pkt = {
141
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT16_MSG),
142
time_us : AP_HAL::micros64(),
143
id : (uint8_t)id,
144
data_value : value
145
};
146
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
147
}
148
}
149
150
struct PACKED log_Data_Int32t {
151
LOG_PACKET_HEADER;
152
uint64_t time_us;
153
uint8_t id;
154
int32_t data_value;
155
};
156
157
// Write an int32_t data packet
158
void Blimp::Log_Write_Data(LogDataID id, int32_t value)
159
{
160
if (should_log(MASK_LOG_ANY)) {
161
struct log_Data_Int32t pkt = {
162
LOG_PACKET_HEADER_INIT(LOG_DATA_INT32_MSG),
163
time_us : AP_HAL::micros64(),
164
id : (uint8_t)id,
165
data_value : value
166
};
167
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
168
}
169
}
170
171
struct PACKED log_Data_UInt32t {
172
LOG_PACKET_HEADER;
173
uint64_t time_us;
174
uint8_t id;
175
uint32_t data_value;
176
};
177
178
// Write a uint32_t data packet
179
void Blimp::Log_Write_Data(LogDataID id, uint32_t value)
180
{
181
if (should_log(MASK_LOG_ANY)) {
182
struct log_Data_UInt32t pkt = {
183
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT32_MSG),
184
time_us : AP_HAL::micros64(),
185
id : (uint8_t)id,
186
data_value : value
187
};
188
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
189
}
190
}
191
192
struct PACKED log_Data_Float {
193
LOG_PACKET_HEADER;
194
uint64_t time_us;
195
uint8_t id;
196
float data_value;
197
};
198
199
// Write a float data packet
200
UNUSED_FUNCTION
201
void Blimp::Log_Write_Data(LogDataID id, float value)
202
{
203
if (should_log(MASK_LOG_ANY)) {
204
struct log_Data_Float pkt = {
205
LOG_PACKET_HEADER_INIT(LOG_DATA_FLOAT_MSG),
206
time_us : AP_HAL::micros64(),
207
id : (uint8_t)id,
208
data_value : value
209
};
210
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
211
}
212
}
213
214
struct PACKED log_ParameterTuning {
215
LOG_PACKET_HEADER;
216
uint64_t time_us;
217
uint8_t parameter; // parameter we are tuning, e.g. 39 is CH6_CIRCLE_RATE
218
float tuning_value; // normalized value used inside tuning() function
219
float tuning_min; // tuning minimum value
220
float tuning_max; // tuning maximum value
221
};
222
223
void Blimp::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max)
224
{
225
struct log_ParameterTuning pkt_tune = {
226
LOG_PACKET_HEADER_INIT(LOG_PARAMTUNE_MSG),
227
time_us : AP_HAL::micros64(),
228
parameter : param,
229
tuning_value : tuning_val,
230
tuning_min : tune_min,
231
tuning_max : tune_max
232
};
233
234
logger.WriteBlock(&pkt_tune, sizeof(pkt_tune));
235
}
236
237
// type and unit information can be found in
238
// libraries/AP_Logger/Logstructure.h; search for "log_Units" for
239
// units and "Format characters" for field type information
240
const struct LogStructure Blimp::log_structure[] = {
241
LOG_COMMON_STRUCTURES,
242
243
// @LoggerMessage: FINI
244
// @Description: Fin input
245
// @Field: TimeUS: Time since system startup
246
// @Field: R: Right
247
// @Field: F: Front
248
// @Field: D: Down
249
// @Field: Y: Yaw
250
251
{
252
LOG_FINI_MSG, sizeof(log_FINI),
253
"FINI", "Qffff", "TimeUS,R,F,D,Y", "s----", "F----"
254
},
255
256
// @LoggerMessage: FINO
257
// @Description: Fin output
258
// @Field: TimeUS: Time since system startup
259
// @Field: F1A: Fin 1 Amplitude
260
// @Field: F1O: Fin 1 Offset
261
// @Field: F2A: Fin 2 Amplitude
262
// @Field: F2O: Fin 2 Offset
263
// @Field: F3A: Fin 3 Amplitude
264
// @Field: F3O: Fin 3 Offset
265
// @Field: F4A: Fin 4 Amplitude
266
// @Field: F4O: Fin 4 Offset
267
268
{
269
LOG_FINO_MSG, sizeof(log_FINO),
270
"FINO", "Qffffffff", "TimeUS,F1A,F1O,F2A,F2O,F3A,F3O,F4A,F4O", "s--------", "F--------"
271
},
272
273
// @LoggerMessage: PIDD,PIVN,PIVE,PIVD,PIVY
274
// @Description: Proportional/Integral/Derivative gain values
275
// @Field: TimeUS: Time since system startup
276
// @Field: Tar: desired value
277
// @Field: Act: achieved value
278
// @Field: Err: error between target and achieved
279
// @Field: P: proportional part of PID
280
// @Field: I: integral part of PID
281
// @Field: D: derivative part of PID
282
// @Field: FF: controller feed-forward portion of response
283
// @Field: DFF: controller derivative feed-forward portion of response
284
// @Field: Dmod: scaler applied to D gain to reduce limit cycling
285
// @Field: SRate: slew rate
286
// @Field: Flags: bitmask of PID state flags
287
// @FieldBitmaskEnum: Flags: log_PID_Flags
288
{
289
LOG_PIDD_MSG, sizeof(log_PID),
290
"PIDD", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS
291
},
292
{
293
LOG_PIVN_MSG, sizeof(log_PID),
294
"PIVN", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS
295
},
296
{
297
LOG_PIVE_MSG, sizeof(log_PID),
298
"PIVE", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS
299
},
300
{
301
LOG_PIVD_MSG, sizeof(log_PID),
302
"PIVD", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS
303
},
304
{
305
LOG_PIVY_MSG, sizeof(log_PID),
306
"PIVY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS
307
},
308
309
// @LoggerMessage: PTUN
310
// @Description: Parameter Tuning information
311
// @URL: https://ardupilot.org/blimp/docs/tuning.html#in-flight-tuning
312
// @Field: TimeUS: Time since system startup
313
// @Field: Param: Parameter being tuned
314
// @Field: TunVal: Normalized value used inside tuning() function
315
// @Field: TunMin: Tuning minimum limit
316
// @Field: TunMax: Tuning maximum limit
317
318
{
319
LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning),
320
"PTUN", "QBfff", "TimeUS,Param,TunVal,TunMin,TunMax", "s----", "F----"
321
},
322
323
// @LoggerMessage: CTUN
324
// @Description: Control Tuning information
325
// @Field: TimeUS: Time since system startup
326
// @Field: ThI: throttle input
327
// @Field: ABst: angle boost
328
// @Field: ThO: throttle output
329
// @Field: ThH: calculated hover throttle
330
// @Field: DAlt: desired altitude
331
// @Field: Alt: achieved altitude
332
// @Field: BAlt: barometric altitude
333
// @Field: DSAlt: desired rangefinder altitude
334
// @Field: SAlt: achieved rangefinder altitude
335
// @Field: TAlt: terrain altitude
336
// @Field: DCRt: desired climb rate
337
// @Field: CRt: climb rate
338
339
// @LoggerMessage: D16
340
// @Description: Generic 16-bit-signed-integer storage
341
// @Field: TimeUS: Time since system startup
342
// @Field: Id: Data type identifier
343
// @Field: Value: Value
344
345
// @LoggerMessage: DU16
346
// @Description: Generic 16-bit-unsigned-integer storage
347
// @Field: TimeUS: Time since system startup
348
// @Field: Id: Data type identifier
349
// @Field: Value: Value
350
351
// @LoggerMessage: D32
352
// @Description: Generic 32-bit-signed-integer storage
353
// @Field: TimeUS: Time since system startup
354
// @Field: Id: Data type identifier
355
// @Field: Value: Value
356
357
// @LoggerMessage: DFLT
358
// @Description: Generic float storage
359
// @Field: TimeUS: Time since system startup
360
// @Field: Id: Data type identifier
361
// @Field: Value: Value
362
363
// @LoggerMessage: DU32
364
// @Description: Generic 32-bit-unsigned-integer storage
365
// @Field: TimeUS: Time since system startup
366
// @Field: Id: Data type identifier
367
// @Field: Value: Value
368
369
{
370
LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
371
"CTUN", "Qffffffefffhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B000BB"
372
},
373
374
{
375
LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
376
"D16", "QBh", "TimeUS,Id,Value", "s--", "F--"
377
},
378
{
379
LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
380
"DU16", "QBH", "TimeUS,Id,Value", "s--", "F--"
381
},
382
{
383
LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),
384
"D32", "QBi", "TimeUS,Id,Value", "s--", "F--"
385
},
386
{
387
LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),
388
"DU32", "QBI", "TimeUS,Id,Value", "s--", "F--"
389
},
390
{
391
LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),
392
"DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--"
393
},
394
};
395
396
uint8_t Blimp::get_num_log_structures() const
397
{
398
return ARRAY_SIZE(log_structure);
399
400
}
401
402
void Blimp::Log_Write_Vehicle_Startup_Messages()
403
{
404
// only 200(?) bytes are guaranteed by AP_Logger
405
logger.Write_MessageF("Frame: %s", get_frame_string());
406
logger.Write_Mode((uint8_t)control_mode, control_mode_reason);
407
ahrs.Log_Write_Home_And_Origin();
408
gps.Write_AP_Logger_Log_Startup_messages();
409
}
410
411
#endif // HAL_LOGGING_ENABLED
412
413