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/ArduCopter/Log.cpp
Views: 1798
1
#include "Copter.h"
2
#include <AP_InertialSensor/AP_InertialSensor_rate_config.h>
3
4
#if HAL_LOGGING_ENABLED
5
6
// Code to Write and Read packets from AP_Logger log memory
7
// Code to interact with the user to dump or erase logs
8
9
struct PACKED log_Control_Tuning {
10
LOG_PACKET_HEADER;
11
uint64_t time_us;
12
float throttle_in;
13
float angle_boost;
14
float throttle_out;
15
float throttle_hover;
16
float desired_alt;
17
float inav_alt;
18
int32_t baro_alt;
19
float desired_rangefinder_alt;
20
float rangefinder_alt;
21
float terr_alt;
22
int16_t target_climb_rate;
23
int16_t climb_rate;
24
};
25
26
// Write a control tuning packet
27
void Copter::Log_Write_Control_Tuning()
28
{
29
// get terrain altitude
30
float terr_alt = 0.0f;
31
#if AP_TERRAIN_AVAILABLE
32
if (!terrain.height_above_terrain(terr_alt, true)) {
33
terr_alt = logger.quiet_nan();
34
}
35
#endif
36
float des_alt_m = 0.0f;
37
int16_t target_climb_rate_cms = 0;
38
if (!flightmode->has_manual_throttle()) {
39
des_alt_m = pos_control->get_pos_target_z_cm() * 0.01f;
40
target_climb_rate_cms = pos_control->get_vel_target_z_cms();
41
}
42
43
float desired_rangefinder_alt;
44
#if AP_RANGEFINDER_ENABLED
45
if (!surface_tracking.get_target_dist_for_logging(desired_rangefinder_alt)) {
46
desired_rangefinder_alt = AP::logger().quiet_nan();
47
}
48
#else
49
// get surface tracking alts
50
desired_rangefinder_alt = AP::logger().quiet_nan();
51
#endif
52
53
struct log_Control_Tuning pkt = {
54
LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),
55
time_us : AP_HAL::micros64(),
56
throttle_in : attitude_control->get_throttle_in(),
57
angle_boost : attitude_control->angle_boost(),
58
throttle_out : motors->get_throttle(),
59
throttle_hover : motors->get_throttle_hover(),
60
desired_alt : des_alt_m,
61
inav_alt : inertial_nav.get_position_z_up_cm() * 0.01f,
62
baro_alt : baro_alt,
63
desired_rangefinder_alt : desired_rangefinder_alt,
64
#if AP_RANGEFINDER_ENABLED
65
rangefinder_alt : surface_tracking.get_dist_for_logging(),
66
#else
67
rangefinder_alt : AP::logger().quiet_nanf(),
68
#endif
69
terr_alt : terr_alt,
70
target_climb_rate : target_climb_rate_cms,
71
climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()) // float -> int16_t
72
};
73
logger.WriteBlock(&pkt, sizeof(pkt));
74
}
75
76
// Write an attitude packet
77
void Copter::Log_Write_Attitude()
78
{
79
attitude_control->Write_ANG();
80
}
81
82
void Copter::Log_Write_Rate()
83
{
84
attitude_control->Write_Rate(*pos_control);
85
}
86
87
// Write PIDS packets
88
void Copter::Log_Write_PIDS()
89
{
90
if (should_log(MASK_LOG_PID)) {
91
logger.Write_PID(LOG_PIDR_MSG, attitude_control->get_rate_roll_pid().get_pid_info());
92
logger.Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info());
93
logger.Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info());
94
logger.Write_PID(LOG_PIDA_MSG, pos_control->get_accel_z_pid().get_pid_info() );
95
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS())) {
96
logger.Write_PID(LOG_PIDN_MSG, pos_control->get_vel_xy_pid().get_pid_info_x());
97
logger.Write_PID(LOG_PIDE_MSG, pos_control->get_vel_xy_pid().get_pid_info_y());
98
}
99
}
100
}
101
102
// Write an EKF and POS packet
103
void Copter::Log_Write_EKF_POS()
104
{
105
AP::ahrs().Log_Write();
106
}
107
108
struct PACKED log_Data_Int16t {
109
LOG_PACKET_HEADER;
110
uint64_t time_us;
111
uint8_t id;
112
int16_t data_value;
113
};
114
115
// Write an int16_t data packet
116
UNUSED_FUNCTION
117
void Copter::Log_Write_Data(LogDataID id, int16_t value)
118
{
119
if (should_log(MASK_LOG_ANY)) {
120
struct log_Data_Int16t pkt = {
121
LOG_PACKET_HEADER_INIT(LOG_DATA_INT16_MSG),
122
time_us : AP_HAL::micros64(),
123
id : (uint8_t)id,
124
data_value : value
125
};
126
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
127
}
128
}
129
130
struct PACKED log_Data_UInt16t {
131
LOG_PACKET_HEADER;
132
uint64_t time_us;
133
uint8_t id;
134
uint16_t data_value;
135
};
136
137
// Write an uint16_t data packet
138
UNUSED_FUNCTION
139
void Copter::Log_Write_Data(LogDataID id, uint16_t value)
140
{
141
if (should_log(MASK_LOG_ANY)) {
142
struct log_Data_UInt16t pkt = {
143
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT16_MSG),
144
time_us : AP_HAL::micros64(),
145
id : (uint8_t)id,
146
data_value : value
147
};
148
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
149
}
150
}
151
152
struct PACKED log_Data_Int32t {
153
LOG_PACKET_HEADER;
154
uint64_t time_us;
155
uint8_t id;
156
int32_t data_value;
157
};
158
159
// Write an int32_t data packet
160
void Copter::Log_Write_Data(LogDataID id, int32_t value)
161
{
162
if (should_log(MASK_LOG_ANY)) {
163
struct log_Data_Int32t pkt = {
164
LOG_PACKET_HEADER_INIT(LOG_DATA_INT32_MSG),
165
time_us : AP_HAL::micros64(),
166
id : (uint8_t)id,
167
data_value : value
168
};
169
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
170
}
171
}
172
173
struct PACKED log_Data_UInt32t {
174
LOG_PACKET_HEADER;
175
uint64_t time_us;
176
uint8_t id;
177
uint32_t data_value;
178
};
179
180
// Write a uint32_t data packet
181
void Copter::Log_Write_Data(LogDataID id, uint32_t value)
182
{
183
if (should_log(MASK_LOG_ANY)) {
184
struct log_Data_UInt32t pkt = {
185
LOG_PACKET_HEADER_INIT(LOG_DATA_UINT32_MSG),
186
time_us : AP_HAL::micros64(),
187
id : (uint8_t)id,
188
data_value : value
189
};
190
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
191
}
192
}
193
194
struct PACKED log_Data_Float {
195
LOG_PACKET_HEADER;
196
uint64_t time_us;
197
uint8_t id;
198
float data_value;
199
};
200
201
// Write a float data packet
202
UNUSED_FUNCTION
203
void Copter::Log_Write_Data(LogDataID id, float value)
204
{
205
if (should_log(MASK_LOG_ANY)) {
206
struct log_Data_Float pkt = {
207
LOG_PACKET_HEADER_INIT(LOG_DATA_FLOAT_MSG),
208
time_us : AP_HAL::micros64(),
209
id : (uint8_t)id,
210
data_value : value
211
};
212
logger.WriteCriticalBlock(&pkt, sizeof(pkt));
213
}
214
}
215
216
struct PACKED log_ParameterTuning {
217
LOG_PACKET_HEADER;
218
uint64_t time_us;
219
uint8_t parameter; // parameter we are tuning, e.g. 39 is CH6_CIRCLE_RATE
220
float tuning_value; // normalized value used inside tuning() function
221
float tuning_min; // tuning minimum value
222
float tuning_max; // tuning maximum value
223
};
224
225
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max)
226
{
227
struct log_ParameterTuning pkt_tune = {
228
LOG_PACKET_HEADER_INIT(LOG_PARAMTUNE_MSG),
229
time_us : AP_HAL::micros64(),
230
parameter : param,
231
tuning_value : tuning_val,
232
tuning_min : tune_min,
233
tuning_max : tune_max
234
};
235
236
logger.WriteBlock(&pkt_tune, sizeof(pkt_tune));
237
}
238
239
void Copter::Log_Video_Stabilisation()
240
{
241
if (!should_log(MASK_LOG_VIDEO_STABILISATION)) {
242
return;
243
}
244
ahrs.write_video_stabilisation();
245
}
246
247
struct PACKED log_SysIdD {
248
LOG_PACKET_HEADER;
249
uint64_t time_us;
250
float waveform_time;
251
float waveform_sample;
252
float waveform_freq;
253
float angle_x;
254
float angle_y;
255
float angle_z;
256
float accel_x;
257
float accel_y;
258
float accel_z;
259
};
260
261
// Write an rate packet
262
void Copter::Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z)
263
{
264
#if MODE_SYSTEMID_ENABLED
265
struct log_SysIdD pkt_sidd = {
266
LOG_PACKET_HEADER_INIT(LOG_SYSIDD_MSG),
267
time_us : AP_HAL::micros64(),
268
waveform_time : waveform_time,
269
waveform_sample : waveform_sample,
270
waveform_freq : waveform_freq,
271
angle_x : angle_x,
272
angle_y : angle_y,
273
angle_z : angle_z,
274
accel_x : accel_x,
275
accel_y : accel_y,
276
accel_z : accel_z
277
};
278
logger.WriteBlock(&pkt_sidd, sizeof(pkt_sidd));
279
#endif
280
}
281
282
struct PACKED log_SysIdS {
283
LOG_PACKET_HEADER;
284
uint64_t time_us;
285
uint8_t systemID_axis;
286
float waveform_magnitude;
287
float frequency_start;
288
float frequency_stop;
289
float time_fade_in;
290
float time_const_freq;
291
float time_record;
292
float time_fade_out;
293
};
294
295
// Write an rate packet
296
void Copter::Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out)
297
{
298
#if MODE_SYSTEMID_ENABLED
299
struct log_SysIdS pkt_sids = {
300
LOG_PACKET_HEADER_INIT(LOG_SYSIDS_MSG),
301
time_us : AP_HAL::micros64(),
302
systemID_axis : systemID_axis,
303
waveform_magnitude : waveform_magnitude,
304
frequency_start : frequency_start,
305
frequency_stop : frequency_stop,
306
time_fade_in : time_fade_in,
307
time_const_freq : time_const_freq,
308
time_record : time_record,
309
time_fade_out : time_fade_out
310
};
311
logger.WriteBlock(&pkt_sids, sizeof(pkt_sids));
312
#endif
313
}
314
315
// guided position target logging
316
struct PACKED log_Guided_Position_Target {
317
LOG_PACKET_HEADER;
318
uint64_t time_us;
319
uint8_t type;
320
float pos_target_x;
321
float pos_target_y;
322
float pos_target_z;
323
uint8_t terrain;
324
float vel_target_x;
325
float vel_target_y;
326
float vel_target_z;
327
float accel_target_x;
328
float accel_target_y;
329
float accel_target_z;
330
};
331
332
// guided attitude target logging
333
struct PACKED log_Guided_Attitude_Target {
334
LOG_PACKET_HEADER;
335
uint64_t time_us;
336
uint8_t type;
337
float roll;
338
float pitch;
339
float yaw;
340
float roll_rate;
341
float pitch_rate;
342
float yaw_rate;
343
float thrust;
344
float climb_rate;
345
};
346
347
// rate thread dt stats
348
struct PACKED log_Rate_Thread_Dt {
349
LOG_PACKET_HEADER;
350
uint64_t time_us;
351
float dt;
352
float dtAvg;
353
float dtMax;
354
float dtMin;
355
};
356
357
// Write a Guided mode position target
358
// pos_target is lat, lon, alt OR offset from ekf origin in cm
359
// terrain should be 0 if pos_target.z is alt-above-ekf-origin, 1 if alt-above-terrain
360
// vel_target is cm/s
361
void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode target_type, const Vector3f& pos_target, bool terrain_alt, const Vector3f& vel_target, const Vector3f& accel_target)
362
{
363
const log_Guided_Position_Target pkt {
364
LOG_PACKET_HEADER_INIT(LOG_GUIDED_POSITION_TARGET_MSG),
365
time_us : AP_HAL::micros64(),
366
type : (uint8_t)target_type,
367
pos_target_x : pos_target.x,
368
pos_target_y : pos_target.y,
369
pos_target_z : pos_target.z,
370
terrain : terrain_alt,
371
vel_target_x : vel_target.x,
372
vel_target_y : vel_target.y,
373
vel_target_z : vel_target.z,
374
accel_target_x : accel_target.x,
375
accel_target_y : accel_target.y,
376
accel_target_z : accel_target.z
377
};
378
logger.WriteBlock(&pkt, sizeof(pkt));
379
}
380
381
// Write a Guided mode attitude target
382
// roll, pitch and yaw are in radians
383
// ang_vel: angular velocity, [roll rate, pitch_rate, yaw_rate] in radians/sec
384
// thrust is between 0 to 1
385
// climb_rate is in (m/s)
386
void Copter::Log_Write_Guided_Attitude_Target(ModeGuided::SubMode target_type, float roll, float pitch, float yaw, const Vector3f &ang_vel, float thrust, float climb_rate)
387
{
388
const log_Guided_Attitude_Target pkt {
389
LOG_PACKET_HEADER_INIT(LOG_GUIDED_ATTITUDE_TARGET_MSG),
390
time_us : AP_HAL::micros64(),
391
type : (uint8_t)target_type,
392
roll : degrees(roll), // rad to deg
393
pitch : degrees(pitch), // rad to deg
394
yaw : degrees(yaw), // rad to deg
395
roll_rate : degrees(ang_vel.x), // rad/s to deg/s
396
pitch_rate : degrees(ang_vel.y), // rad/s to deg/s
397
yaw_rate : degrees(ang_vel.z), // rad/s to deg/s
398
thrust : thrust,
399
climb_rate : climb_rate
400
};
401
logger.WriteBlock(&pkt, sizeof(pkt));
402
}
403
404
void Copter::Log_Write_Rate_Thread_Dt(float dt, float dtAvg, float dtMax, float dtMin)
405
{
406
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
407
const log_Rate_Thread_Dt pkt {
408
LOG_PACKET_HEADER_INIT(LOG_RATE_THREAD_DT_MSG),
409
time_us : AP_HAL::micros64(),
410
dt : dt,
411
dtAvg : dtAvg,
412
dtMax : dtMax,
413
dtMin : dtMin
414
};
415
logger.WriteBlock(&pkt, sizeof(pkt));
416
#endif
417
}
418
419
// type and unit information can be found in
420
// libraries/AP_Logger/Logstructure.h; search for "log_Units" for
421
// units and "Format characters" for field type information
422
const struct LogStructure Copter::log_structure[] = {
423
LOG_COMMON_STRUCTURES,
424
425
// @LoggerMessage: PTUN
426
// @Description: Parameter Tuning information
427
// @URL: https://ardupilot.org/copter/docs/tuning.html#in-flight-tuning
428
// @Field: TimeUS: Time since system startup
429
// @Field: Param: Parameter being tuned
430
// @Field: TunVal: Normalized value used inside tuning() function
431
// @Field: TunMin: Tuning minimum limit
432
// @Field: TunMax: Tuning maximum limit
433
434
{ LOG_PARAMTUNE_MSG, sizeof(log_ParameterTuning),
435
"PTUN", "QBfff", "TimeUS,Param,TunVal,TunMin,TunMax", "s----", "F----" },
436
437
// @LoggerMessage: CTUN
438
// @Description: Control Tuning information
439
// @Field: TimeUS: Time since system startup
440
// @Field: ThI: throttle input
441
// @Field: ABst: angle boost
442
// @Field: ThO: throttle output
443
// @Field: ThH: calculated hover throttle
444
// @Field: DAlt: desired altitude
445
// @Field: Alt: achieved altitude
446
// @Field: BAlt: barometric altitude
447
// @Field: DSAlt: desired rangefinder altitude
448
// @Field: SAlt: achieved rangefinder altitude
449
// @Field: TAlt: terrain altitude
450
// @Field: DCRt: desired climb rate
451
// @Field: CRt: climb rate
452
453
// @LoggerMessage: D16
454
// @Description: Generic 16-bit-signed-integer storage
455
// @Field: TimeUS: Time since system startup
456
// @Field: Id: Data type identifier
457
// @Field: Value: Value
458
459
// @LoggerMessage: DU16
460
// @Description: Generic 16-bit-unsigned-integer storage
461
// @Field: TimeUS: Time since system startup
462
// @Field: Id: Data type identifier
463
// @Field: Value: Value
464
465
// @LoggerMessage: D32
466
// @Description: Generic 32-bit-signed-integer storage
467
// @Field: TimeUS: Time since system startup
468
// @Field: Id: Data type identifier
469
// @Field: Value: Value
470
471
// @LoggerMessage: DFLT
472
// @Description: Generic float storage
473
// @Field: TimeUS: Time since system startup
474
// @Field: Id: Data type identifier
475
// @Field: Value: Value
476
477
// @LoggerMessage: DU32
478
// @Description: Generic 32-bit-unsigned-integer storage
479
// @Field: TimeUS: Time since system startup
480
// @Field: Id: Data type identifier
481
// @Field: Value: Value
482
483
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
484
"CTUN", "Qffffffefffhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00B000BB" , true },
485
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
486
"D16", "QBh", "TimeUS,Id,Value", "s--", "F--" },
487
{ LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
488
"DU16", "QBH", "TimeUS,Id,Value", "s--", "F--" },
489
{ LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),
490
"D32", "QBi", "TimeUS,Id,Value", "s--", "F--" },
491
{ LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),
492
"DU32", "QBI", "TimeUS,Id,Value", "s--", "F--" },
493
{ LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),
494
"DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" },
495
496
// @LoggerMessage: SIDD
497
// @Description: System ID data
498
// @Field: TimeUS: Time since system startup
499
// @Field: Time: Time reference for waveform
500
// @Field: Targ: Current waveform sample
501
// @Field: F: Instantaneous waveform frequency
502
// @Field: Gx: Delta angle, X-Axis
503
// @Field: Gy: Delta angle, Y-Axis
504
// @Field: Gz: Delta angle, Z-Axis
505
// @Field: Ax: Delta velocity, X-Axis
506
// @Field: Ay: Delta velocity, Y-Axis
507
// @Field: Az: Delta velocity, Z-Axis
508
509
{ LOG_SYSIDD_MSG, sizeof(log_SysIdD),
510
"SIDD", "Qfffffffff", "TimeUS,Time,Targ,F,Gx,Gy,Gz,Ax,Ay,Az", "ss-zkkkooo", "F---------" , true },
511
512
// @LoggerMessage: SIDS
513
// @Description: System ID settings
514
// @Field: TimeUS: Time since system startup
515
// @Field: Ax: The axis which is being excited
516
// @Field: Mag: Magnitude of the chirp waveform
517
// @Field: FSt: Frequency at the start of chirp
518
// @Field: FSp: Frequency at the end of chirp
519
// @Field: TFin: Time to reach maximum amplitude of chirp
520
// @Field: TC: Time at constant frequency before chirp starts
521
// @Field: TR: Time taken to complete chirp waveform
522
// @Field: TFout: Time to reach zero amplitude after chirp finishes
523
524
{ LOG_SYSIDS_MSG, sizeof(log_SysIdS),
525
"SIDS", "QBfffffff", "TimeUS,Ax,Mag,FSt,FSp,TFin,TC,TR,TFout", "s--ssssss", "F--------" , true },
526
527
// @LoggerMessage: GUIP
528
// @Description: Guided mode position target information
529
// @Field: TimeUS: Time since system startup
530
// @Field: Type: Type of guided mode
531
// @Field: pX: Target position, X-Axis
532
// @Field: pY: Target position, Y-Axis
533
// @Field: pZ: Target position, Z-Axis
534
// @Field: Terrain: Target position, Z-Axis is alt above terrain
535
// @Field: vX: Target velocity, X-Axis
536
// @Field: vY: Target velocity, Y-Axis
537
// @Field: vZ: Target velocity, Z-Axis
538
// @Field: aX: Target acceleration, X-Axis
539
// @Field: aY: Target acceleration, Y-Axis
540
// @Field: aZ: Target acceleration, Z-Axis
541
542
{ LOG_GUIDED_POSITION_TARGET_MSG, sizeof(log_Guided_Position_Target),
543
"GUIP", "QBfffbffffff", "TimeUS,Type,pX,pY,pZ,Terrain,vX,vY,vZ,aX,aY,aZ", "s-mmm-nnnooo", "F-BBB-BBBBBB" , true },
544
545
// @LoggerMessage: GUIA
546
// @Description: Guided mode attitude target information
547
// @Field: TimeUS: Time since system startup
548
// @Field: Type: Type of guided mode
549
// @Field: Roll: Target attitude, Roll
550
// @Field: Pitch: Target attitude, Pitch
551
// @Field: Yaw: Target attitude, Yaw
552
// @Field: RollRt: Roll rate
553
// @Field: PitchRt: Pitch rate
554
// @Field: YawRt: Yaw rate
555
// @Field: Thrust: Thrust
556
// @Field: ClimbRt: Climb rate
557
558
{ LOG_GUIDED_ATTITUDE_TARGET_MSG, sizeof(log_Guided_Attitude_Target),
559
"GUIA", "QBffffffff", "TimeUS,Type,Roll,Pitch,Yaw,RollRt,PitchRt,YawRt,Thrust,ClimbRt", "s-dddkkk-n", "F-000000-0" , true },
560
561
// @LoggerMessage: RTDT
562
// @Description: Attitude controller time deltas
563
// @Field: TimeUS: Time since system startup
564
// @Field: dt: current time delta
565
// @Field: dtAvg: current time delta average
566
// @Field: dtMax: Max time delta since last log output
567
// @Field: dtMin: Min time delta since last log output
568
569
{ LOG_RATE_THREAD_DT_MSG, sizeof(log_Rate_Thread_Dt),
570
"RTDT", "Qffff", "TimeUS,dt,dtAvg,dtMax,dtMin", "sssss", "F----" , true },
571
572
};
573
574
uint8_t Copter::get_num_log_structures() const
575
{
576
return ARRAY_SIZE(log_structure);
577
}
578
579
void Copter::Log_Write_Vehicle_Startup_Messages()
580
{
581
// only 200(?) bytes are guaranteed by AP_Logger
582
char frame_and_type_string[30];
583
copter.motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));
584
logger.Write_MessageF("%s", frame_and_type_string);
585
logger.Write_Mode((uint8_t)flightmode->mode_number(), control_mode_reason);
586
ahrs.Log_Write_Home_And_Origin();
587
gps.Write_AP_Logger_Log_Startup_messages();
588
}
589
590
#endif // HAL_LOGGING_ENABLED
591
592