Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/Log.cpp
9388 views
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
float 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 = AP_Logger::quiet_nanf();
34
}
35
#endif
36
float des_alt_m = 0.0f;
37
float target_climb_rate_ms = 0;
38
if (!flightmode->has_manual_throttle()) {
39
des_alt_m = pos_control->get_pos_target_U_m();
40
target_climb_rate_ms = pos_control->get_vel_target_U_ms();
41
}
42
43
float desired_rangefinder_alt_m;
44
#if AP_RANGEFINDER_ENABLED
45
if (!surface_tracking.get_target_dist_for_logging(desired_rangefinder_alt_m)) {
46
desired_rangefinder_alt_m = AP_Logger::quiet_nanf();
47
}
48
#else
49
// get surface tracking alts
50
desired_rangefinder_alt_m = AP_Logger::quiet_nanf();
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 : float(pos_control->get_pos_estimate_U_m()),
62
baro_alt : baro_alt_m,
63
desired_rangefinder_alt : desired_rangefinder_alt_m,
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 : int16_t(target_climb_rate_ms * 100.0),
71
climb_rate : int16_t(pos_control->get_vel_estimate_U_ms() * 100.0) // 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->D_get_accel_pid().get_pid_info() );
95
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_position() || landing_with_GPS())) {
96
logger.Write_PID(LOG_PIDN_MSG, pos_control->NE_get_vel_pid().get_pid_info_x());
97
logger.Write_PID(LOG_PIDE_MSG, pos_control->NE_get_vel_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_PTUN {
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
float norm_in; // normalized control input (-1 to 1)
224
};
225
226
void Copter::Log_Write_PTUN(uint8_t param, float tuning_val, float tune_min, float tune_max, float norm_in)
227
{
228
const struct log_PTUN pkt_tune {
229
LOG_PACKET_HEADER_INIT(LOG_PARAMTUNE_MSG),
230
time_us : AP_HAL::micros64(),
231
parameter : param,
232
tuning_value : tuning_val,
233
tuning_min : tune_min,
234
tuning_max : tune_max,
235
norm_in : norm_in
236
};
237
238
logger.WriteBlock(&pkt_tune, sizeof(pkt_tune));
239
}
240
241
void Copter::Log_Video_Stabilisation()
242
{
243
if (!should_log(MASK_LOG_VIDEO_STABILISATION)) {
244
return;
245
}
246
ahrs.write_video_stabilisation();
247
}
248
249
struct PACKED log_SysIdD {
250
LOG_PACKET_HEADER;
251
uint64_t time_us;
252
float waveform_time;
253
float waveform_sample;
254
float waveform_freq;
255
float angle_x;
256
float angle_y;
257
float angle_z;
258
float accel_x;
259
float accel_y;
260
float accel_z;
261
};
262
263
// Write an rate packet
264
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)
265
{
266
#if MODE_SYSTEMID_ENABLED
267
struct log_SysIdD pkt_sidd = {
268
LOG_PACKET_HEADER_INIT(LOG_SYSIDD_MSG),
269
time_us : AP_HAL::micros64(),
270
waveform_time : waveform_time,
271
waveform_sample : waveform_sample,
272
waveform_freq : waveform_freq,
273
angle_x : angle_x,
274
angle_y : angle_y,
275
angle_z : angle_z,
276
accel_x : accel_x,
277
accel_y : accel_y,
278
accel_z : accel_z
279
};
280
logger.WriteBlock(&pkt_sidd, sizeof(pkt_sidd));
281
#endif
282
}
283
284
struct PACKED log_SysIdS {
285
LOG_PACKET_HEADER;
286
uint64_t time_us;
287
uint8_t systemID_axis;
288
float waveform_magnitude;
289
float frequency_start;
290
float frequency_stop;
291
float time_fade_in;
292
float time_const_freq;
293
float time_record;
294
float time_fade_out;
295
};
296
297
// Write an rate packet
298
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)
299
{
300
#if MODE_SYSTEMID_ENABLED
301
struct log_SysIdS pkt_sids = {
302
LOG_PACKET_HEADER_INIT(LOG_SYSIDS_MSG),
303
time_us : AP_HAL::micros64(),
304
systemID_axis : systemID_axis,
305
waveform_magnitude : waveform_magnitude,
306
frequency_start : frequency_start,
307
frequency_stop : frequency_stop,
308
time_fade_in : time_fade_in,
309
time_const_freq : time_const_freq,
310
time_record : time_record,
311
time_fade_out : time_fade_out
312
};
313
logger.WriteBlock(&pkt_sids, sizeof(pkt_sids));
314
#endif
315
}
316
317
// guided position target logging
318
struct PACKED log_Guided_Position_Target {
319
LOG_PACKET_HEADER;
320
uint64_t time_us;
321
uint8_t type;
322
float pos_target_x;
323
float pos_target_y;
324
float pos_target_z;
325
uint8_t terrain;
326
float vel_target_x;
327
float vel_target_y;
328
float vel_target_z;
329
float accel_target_x;
330
float accel_target_y;
331
float accel_target_z;
332
};
333
334
// guided attitude target logging
335
struct PACKED log_Guided_Attitude_Target {
336
LOG_PACKET_HEADER;
337
uint64_t time_us;
338
uint8_t type;
339
float roll;
340
float pitch;
341
float yaw;
342
float roll_rate;
343
float pitch_rate;
344
float yaw_rate;
345
float thrust;
346
float climb_rate;
347
};
348
349
// rate thread dt stats
350
struct PACKED log_Rate_Thread_Dt {
351
LOG_PACKET_HEADER;
352
uint64_t time_us;
353
float dt;
354
float dtAvg;
355
float dtMax;
356
float dtMin;
357
};
358
359
// Write a Guided mode position target
360
// pos_target_ned_m is lat, lon, alt OR offset from ekf origin in m
361
// terrain should be 0 if pos_target_ned_m.z is alt-above-ekf-origin, 1 if alt-above-terrain
362
// vel_target_ms is m/s
363
void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode submode, const Vector3p& pos_target_ned_m, bool is_terrain_alt, const Vector3f& vel_target_ms, const Vector3f& accel_target_mss)
364
{
365
const log_Guided_Position_Target pkt {
366
LOG_PACKET_HEADER_INIT(LOG_GUIDED_POSITION_TARGET_MSG),
367
time_us : AP_HAL::micros64(),
368
type : (uint8_t)submode,
369
pos_target_x : (float)pos_target_ned_m.x,
370
pos_target_y : (float)pos_target_ned_m.y,
371
pos_target_z : (float)pos_target_ned_m.z,
372
terrain : is_terrain_alt,
373
vel_target_x : vel_target_ms.x,
374
vel_target_y : vel_target_ms.y,
375
vel_target_z : vel_target_ms.z,
376
accel_target_x : accel_target_mss.x,
377
accel_target_y : accel_target_mss.y,
378
accel_target_z : accel_target_mss.z
379
};
380
logger.WriteBlock(&pkt, sizeof(pkt));
381
}
382
383
// Write a Guided mode attitude target
384
// roll_rad, pitch_rad and yaw_rad are in radians
385
// ang_vel_rads: angular velocity, [roll rate, pitch_rate, yaw_rate] in radians/sec
386
// thrust is between 0 to 1
387
// climb_rate is in (m/s)
388
void Copter::Log_Write_Guided_Attitude_Target(ModeGuided::SubMode submode, float roll_rad, float pitch_rad, float yaw_rad, const Vector3f &ang_vel_rads, float thrust, float climb_rate_ms)
389
{
390
const log_Guided_Attitude_Target pkt {
391
LOG_PACKET_HEADER_INIT(LOG_GUIDED_ATTITUDE_TARGET_MSG),
392
time_us : AP_HAL::micros64(),
393
type : (uint8_t)submode,
394
roll : degrees(roll_rad), // rad to deg
395
pitch : degrees(pitch_rad), // rad to deg
396
yaw : degrees(yaw_rad), // rad to deg
397
roll_rate : degrees(ang_vel_rads.x), // rad/s to deg/s
398
pitch_rate : degrees(ang_vel_rads.y), // rad/s to deg/s
399
yaw_rate : degrees(ang_vel_rads.z), // rad/s to deg/s
400
thrust : thrust,
401
climb_rate : climb_rate_ms
402
};
403
logger.WriteBlock(&pkt, sizeof(pkt));
404
}
405
406
void Copter::Log_Write_Rate_Thread_Dt(float dt, float dtAvg, float dtMax, float dtMin)
407
{
408
#if AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED
409
const log_Rate_Thread_Dt pkt {
410
LOG_PACKET_HEADER_INIT(LOG_RATE_THREAD_DT_MSG),
411
time_us : AP_HAL::micros64(),
412
dt : dt,
413
dtAvg : dtAvg,
414
dtMax : dtMax,
415
dtMin : dtMin
416
};
417
logger.WriteBlock(&pkt, sizeof(pkt));
418
#endif
419
}
420
421
// type and unit information can be found in
422
// libraries/AP_Logger/Logstructure.h; search for "log_Units" for
423
// units and "Format characters" for field type information
424
const struct LogStructure Copter::log_structure[] = {
425
LOG_COMMON_STRUCTURES,
426
427
// @LoggerMessage: PTUN
428
// @Description: Parameter Tuning information
429
// @URL: https://ardupilot.org/copter/docs/tuning.html#in-flight-tuning
430
// @Field: TimeUS: Time since system startup
431
// @Field: Param: Parameter being tuned
432
// @Field: TunVal: Normalized value used inside tuning() function
433
// @Field: TunMin: Tuning minimum limit
434
// @Field: TunMax: Tuning maximum limit
435
// @Field: NIn: normalaised control input (normalised -1 to 1 value)
436
437
{ LOG_PARAMTUNE_MSG, sizeof(log_PTUN),
438
"PTUN", "QBffff", "TimeUS,Param,TunVal,TunMin,TunMax,NIn", "s#----", "F-----" },
439
440
// @LoggerMessage: CTUN
441
// @Description: Control Tuning information
442
// @Field: TimeUS: Time since system startup
443
// @Field: ThI: throttle input
444
// @Field: ABst: angle boost
445
// @Field: ThO: throttle output
446
// @Field: ThH: calculated hover throttle
447
// @Field: DAlt: desired altitude
448
// @Field: Alt: achieved altitude
449
// @Field: BAlt: barometric altitude
450
// @Field: DSAlt: desired rangefinder altitude
451
// @Field: SAlt: achieved rangefinder altitude
452
// @Field: TAlt: terrain altitude
453
// @Field: DCRt: desired climb rate
454
// @Field: CRt: climb rate
455
456
// @LoggerMessage: D16
457
// @Description: Generic 16-bit-signed-integer storage
458
// @Field: TimeUS: Time since system startup
459
// @Field: Id: Data type identifier
460
// @Field: Value: Value
461
462
// @LoggerMessage: DU16
463
// @Description: Generic 16-bit-unsigned-integer storage
464
// @Field: TimeUS: Time since system startup
465
// @Field: Id: Data type identifier
466
// @Field: Value: Value
467
468
// @LoggerMessage: D32
469
// @Description: Generic 32-bit-signed-integer storage
470
// @Field: TimeUS: Time since system startup
471
// @Field: Id: Data type identifier
472
// @Field: Value: Value
473
474
// @LoggerMessage: DFLT
475
// @Description: Generic float storage
476
// @Field: TimeUS: Time since system startup
477
// @Field: Id: Data type identifier
478
// @Field: Value: Value
479
480
// @LoggerMessage: DU32
481
// @Description: Generic 32-bit-unsigned-integer storage
482
// @Field: TimeUS: Time since system startup
483
// @Field: Id: Data type identifier
484
// @Field: Value: Value
485
486
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
487
"CTUN", "Qffffffffffhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----000000BB" , true },
488
{ LOG_DATA_INT16_MSG, sizeof(log_Data_Int16t),
489
"D16", "QBh", "TimeUS,Id,Value", "s--", "F--" },
490
{ LOG_DATA_UINT16_MSG, sizeof(log_Data_UInt16t),
491
"DU16", "QBH", "TimeUS,Id,Value", "s--", "F--" },
492
{ LOG_DATA_INT32_MSG, sizeof(log_Data_Int32t),
493
"D32", "QBi", "TimeUS,Id,Value", "s--", "F--" },
494
{ LOG_DATA_UINT32_MSG, sizeof(log_Data_UInt32t),
495
"DU32", "QBI", "TimeUS,Id,Value", "s--", "F--" },
496
{ LOG_DATA_FLOAT_MSG, sizeof(log_Data_Float),
497
"DFLT", "QBf", "TimeUS,Id,Value", "s--", "F--" },
498
499
// @LoggerMessage: SIDD
500
// @Description: System ID data
501
// @Field: TimeUS: Time since system startup
502
// @Field: Time: Time reference for waveform
503
// @Field: Targ: Current waveform sample
504
// @Field: F: Instantaneous waveform frequency
505
// @Field: Gx: Delta angle, X-Axis
506
// @Field: Gy: Delta angle, Y-Axis
507
// @Field: Gz: Delta angle, Z-Axis
508
// @Field: Ax: Delta velocity, X-Axis
509
// @Field: Ay: Delta velocity, Y-Axis
510
// @Field: Az: Delta velocity, Z-Axis
511
512
{ LOG_SYSIDD_MSG, sizeof(log_SysIdD),
513
"SIDD", "Qfffffffff", "TimeUS,Time,Targ,F,Gx,Gy,Gz,Ax,Ay,Az", "ss-zkkkooo", "F---------" , true },
514
515
// @LoggerMessage: SIDS
516
// @Description: System ID settings
517
// @Field: TimeUS: Time since system startup
518
// @Field: Ax: The axis which is being excited
519
// @Field: Mag: Magnitude of the chirp waveform
520
// @Field: FSt: Frequency at the start of chirp
521
// @Field: FSp: Frequency at the end of chirp
522
// @Field: TFin: Time to reach maximum amplitude of chirp
523
// @Field: TC: Time at constant frequency before chirp starts
524
// @Field: TR: Time taken to complete chirp waveform
525
// @Field: TFout: Time to reach zero amplitude after chirp finishes
526
527
{ LOG_SYSIDS_MSG, sizeof(log_SysIdS),
528
"SIDS", "QBfffffff", "TimeUS,Ax,Mag,FSt,FSp,TFin,TC,TR,TFout", "s--ssssss", "F--------" , true },
529
530
// @LoggerMessage: GUIP
531
// @Description: Guided mode position target information
532
// @Field: TimeUS: Time since system startup
533
// @Field: Type: Type of guided mode
534
// @Field: pX: Target position, X-Axis
535
// @Field: pY: Target position, Y-Axis
536
// @Field: pZ: Target position, Z-Axis
537
// @Field: Terrain: Target position, Z-Axis is alt above terrain
538
// @Field: vX: Target velocity, X-Axis
539
// @Field: vY: Target velocity, Y-Axis
540
// @Field: vZ: Target velocity, Z-Axis
541
// @Field: aX: Target acceleration, X-Axis
542
// @Field: aY: Target acceleration, Y-Axis
543
// @Field: aZ: Target acceleration, Z-Axis
544
545
{ LOG_GUIDED_POSITION_TARGET_MSG, sizeof(log_Guided_Position_Target),
546
"GUIP", "QBfffbffffff", "TimeUS,Type,pX,pY,pZ,Terrain,vX,vY,vZ,aX,aY,aZ", "s-mmm-nnnooo", "F-000-000000" , true },
547
548
// @LoggerMessage: GUIA
549
// @Description: Guided mode attitude target information
550
// @Field: TimeUS: Time since system startup
551
// @Field: Type: Type of guided mode
552
// @Field: Roll: Target attitude, Roll
553
// @Field: Pitch: Target attitude, Pitch
554
// @Field: Yaw: Target attitude, Yaw
555
// @Field: RollRt: Roll rate
556
// @Field: PitchRt: Pitch rate
557
// @Field: YawRt: Yaw rate
558
// @Field: Thrust: Thrust
559
// @Field: ClimbRt: Climb rate
560
561
{ LOG_GUIDED_ATTITUDE_TARGET_MSG, sizeof(log_Guided_Attitude_Target),
562
"GUIA", "QBffffffff", "TimeUS,Type,Roll,Pitch,Yaw,RollRt,PitchRt,YawRt,Thrust,ClimbRt", "s-dddkkk-n", "F-000000-0" , true },
563
564
// @LoggerMessage: RTDT
565
// @Description: Attitude controller time deltas
566
// @Field: TimeUS: Time since system startup
567
// @Field: dt: current time delta
568
// @Field: dtAvg: current time delta average
569
// @Field: dtMax: Max time delta since last log output
570
// @Field: dtMin: Min time delta since last log output
571
572
{ LOG_RATE_THREAD_DT_MSG, sizeof(log_Rate_Thread_Dt),
573
"RTDT", "Qffff", "TimeUS,dt,dtAvg,dtMax,dtMin", "sssss", "F----" , true },
574
575
};
576
577
uint8_t Copter::get_num_log_structures() const
578
{
579
return ARRAY_SIZE(log_structure);
580
}
581
582
void Copter::Log_Write_Vehicle_Startup_Messages()
583
{
584
// only 200(?) bytes are guaranteed by AP_Logger
585
char frame_and_type_string[30];
586
copter.motors->get_frame_and_type_string(frame_and_type_string, ARRAY_SIZE(frame_and_type_string));
587
logger.Write_MessageF("%s", frame_and_type_string);
588
logger.Write_Mode((uint8_t)flightmode->mode_number(), control_mode_reason);
589
ahrs.Log_Write_Home_And_Origin();
590
gps.Write_AP_Logger_Log_Startup_messages();
591
}
592
593
#endif // HAL_LOGGING_ENABLED
594
595