forked from PX4/PX4-Autopilot
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathsdlog2.c
2009 lines (1669 loc) · 63.1 KB
/
sdlog2.c
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file sdlog2.c
*
* Simple SD logger for flight data. Buffers new sensor values and
* does the heavy SD I/O in a low-priority worker thread.
*
* @author Lorenz Meier <[email protected]>
* @author Anton Babushkin <[email protected]>
* @author Ban Siesta <[email protected]>
*/
#include <nuttx/config.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <sys/prctl.h>
#include <sys/statfs.h>
#include <fcntl.h>
#include <errno.h>
#include <unistd.h>
#include <stdio.h>
#include <poll.h>
#include <stdlib.h>
#include <string.h>
#include <ctype.h>
#include <systemlib/err.h>
#include <unistd.h>
#include <drivers/drv_hrt.h>
#include <math.h>
#include <time.h>
#include <drivers/drv_range_finder.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
#include <uORB/topics/vehicle_rates_setpoint.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_controls_0.h>
#include <uORB/topics/actuator_controls_1.h>
#include <uORB/topics/actuator_controls_2.h>
#include <uORB/topics/actuator_controls_3.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/satellite_info.h>
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vision_position_estimate.h>
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/rc_channels.h>
#include <uORB/topics/esc_status.h>
#include <uORB/topics/telemetry_status.h>
#include <uORB/topics/estimator_status.h>
#include <uORB/topics/tecs_status.h>
#include <uORB/topics/system_power.h>
#include <uORB/topics/servorail_status.h>
#include <uORB/topics/wind_estimate.h>
#include <uORB/topics/encoders.h>
#include <uORB/topics/vtol_vehicle_status.h>
#include <uORB/topics/time_offset.h>
#include <uORB/topics/mc_att_ctrl_status.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
#include <systemlib/perf_counter.h>
#include <version/version.h>
#include <mavlink/mavlink_log.h>
#include "logbuffer.h"
#include "sdlog2_format.h"
#include "sdlog2_messages.h"
#define PX4_EPOCH_SECS 1234567890ULL
/**
* Logging rate.
*
* A value of -1 indicates the commandline argument
* should be obeyed. A value of 0 sets the minimum rate,
* any other value is interpreted as rate in Hertz. This
* parameter is only read out before logging starts (which
* commonly is before arming).
*
* @min -1
* @max 1
* @group SD Logging
*/
PARAM_DEFINE_INT32(SDLOG_RATE, -1);
/**
* Enable extended logging mode.
*
* A value of -1 indicates the commandline argument
* should be obeyed. A value of 0 disables extended
* logging mode, a value of 1 enables it. This
* parameter is only read out before logging starts
* (which commonly is before arming).
*
* @min -1
* @max 1
* @group SD Logging
*/
PARAM_DEFINE_INT32(SDLOG_EXT, -1);
#define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \
log_msgs_written++; \
} else { \
log_msgs_skipped++; \
}
#define LOG_ORB_SUBSCRIBE(_var, _topic) subs.##_var##_sub = orb_subscribe(ORB_ID(##_topic##)); \
fds[fdsc_count].fd = subs.##_var##_sub; \
fds[fdsc_count].events = POLLIN; \
fdsc_count++;
#define MIN(X,Y) ((X) < (Y) ? (X) : (Y))
static bool main_thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */
static const unsigned MAX_NO_LOGFOLDER = 999; /**< Maximum number of log dirs */
static const unsigned MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
static const int LOG_BUFFER_SIZE_DEFAULT = 8192;
static const int MAX_WRITE_CHUNK = 512;
static const int MIN_BYTES_TO_WRITE = 512;
static bool _extended_logging = false;
#define MOUNTPOINT "/fs/microsd"
static const char *mountpoint = MOUNTPOINT;
static const char *log_root = MOUNTPOINT "/log";
static int mavlink_fd = -1;
struct logbuffer_s lb;
/* mutex / condition to synchronize threads */
static pthread_mutex_t logbuffer_mutex;
static pthread_cond_t logbuffer_cond;
static char log_dir[32];
/* statistics counters */
static uint64_t start_time = 0;
static unsigned long log_bytes_written = 0;
static unsigned long last_checked_bytes_written = 0;
static unsigned long log_msgs_written = 0;
static unsigned long log_msgs_skipped = 0;
/* GPS time, used for log files naming */
static uint64_t gps_time = 0;
/* current state of logging */
static bool logging_enabled = false;
/* use date/time for naming directories and files (-t option) */
static bool log_name_timestamp = false;
/* helper flag to track system state changes */
static bool flag_system_armed = false;
/* flag if warning about MicroSD card being almost full has already been sent */
static bool space_warning_sent = false;
static pthread_t logwriter_pthread = 0;
static pthread_attr_t logwriter_attr;
static perf_counter_t perf_write;
/**
* Log buffer writing thread. Open and close file here.
*/
static void *logwriter_thread(void *arg);
/**
* SD log management function.
*/
__EXPORT int sdlog2_main(int argc, char *argv[]);
static bool copy_if_updated(orb_id_t topic, int handle, void *buffer);
/**
* Mainloop of sd log deamon.
*/
int sdlog2_thread_main(int argc, char *argv[]);
/**
* Print the correct usage.
*/
static void sdlog2_usage(const char *reason);
/**
* Print the current status.
*/
static void sdlog2_status(void);
/**
* Start logging: create new file and start log writer thread.
*/
static void sdlog2_start_log(void);
/**
* Stop logging: stop log writer thread and close log file.
*/
static void sdlog2_stop_log(void);
/**
* Write a header to log file: list of message formats.
*/
static int write_formats(int fd);
/**
* Write version message to log file.
*/
static int write_version(int fd);
/**
* Write parameters to log file.
*/
static int write_parameters(int fd);
static bool file_exist(const char *filename);
static int file_copy(const char *file_old, const char *file_new);
/**
* Check if there is still free space available
*/
static int check_free_space(void);
static void handle_command(struct vehicle_command_s *cmd);
static void handle_status(struct vehicle_status_s *cmd);
/**
* Create dir for current logging session. Store dir name in 'log_dir'.
*/
static int create_log_dir(void);
/**
* Select first free log file name and open it.
*/
static int open_log_file(void);
static int open_perf_file(const char* str);
static void
sdlog2_usage(const char *reason)
{
if (reason) {
fprintf(stderr, "%s\n", reason);
}
errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t -x\n"
"\t-r\tLog rate in Hz, 0 means unlimited rate\n"
"\t-b\tLog buffer size in KiB, default is 8\n"
"\t-e\tEnable logging by default (if not, can be started by command)\n"
"\t-a\tLog only when armed (can be still overriden by command)\n"
"\t-t\tUse date/time for naming log directories and files\n"
"\t-x\tExtended logging");
}
/**
* The logger deamon app only briefly exists to start
* the background job. The stack size assigned in the
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
* to task_spawn().
*/
int sdlog2_main(int argc, char *argv[])
{
if (argc < 2) {
sdlog2_usage("missing command");
}
if (!strcmp(argv[1], "start")) {
if (thread_running) {
warnx("already running");
/* this is not an error */
exit(0);
}
main_thread_should_exit = false;
deamon_task = task_spawn_cmd("sdlog2",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT - 30,
3000,
sdlog2_thread_main,
(char * const *)argv);
exit(0);
}
if (!strcmp(argv[1], "stop")) {
if (!thread_running) {
warnx("not started");
}
main_thread_should_exit = true;
exit(0);
}
if (!thread_running) {
warnx("not started\n");
return 1;
}
if (!strcmp(argv[1], "status")) {
sdlog2_status();
return 0;
}
if (!strcmp(argv[1], "on")) {
struct vehicle_command_s cmd;
cmd.command = VEHICLE_CMD_PREFLIGHT_STORAGE;
cmd.param3 = 1;
int fd = orb_advertise(ORB_ID(vehicle_command), &cmd);
close(fd);
return 0;
}
if (!strcmp(argv[1], "off")) {
struct vehicle_command_s cmd;
cmd.command = VEHICLE_CMD_PREFLIGHT_STORAGE;
cmd.param3 = 0;
int fd = orb_advertise(ORB_ID(vehicle_command), &cmd);
close(fd);
return 0;
}
sdlog2_usage("unrecognized command");
exit(1);
}
int create_log_dir()
{
/* create dir on sdcard if needed */
uint16_t dir_number = 1; // start with dir sess001
int mkdir_ret;
struct timespec ts;
clock_gettime(CLOCK_REALTIME, &ts);
/* use RTC time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.px4log */
time_t utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
struct tm tt;
struct tm *ttp = gmtime_r(&utc_time_sec, &tt);
if (log_name_timestamp && ttp && (utc_time_sec > PX4_EPOCH_SECS)) {
int n = snprintf(log_dir, sizeof(log_dir), "%s/", log_root);
strftime(log_dir + n, sizeof(log_dir) - n, "%Y-%m-%d", &tt);
mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
if ((mkdir_ret != OK) && (errno != EEXIST)) {
warn("failed creating new dir: %s", log_dir);
return -1;
}
} else {
/* look for the next dir that does not exist */
while (dir_number <= MAX_NO_LOGFOLDER) {
/* format log dir: e.g. /fs/microsd/sess001 */
sprintf(log_dir, "%s/sess%03u", log_root, dir_number);
mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
if (mkdir_ret == 0) {
warnx("log dir created: %s", log_dir);
break;
} else if (errno != EEXIST) {
warn("failed creating new dir: %s", log_dir);
return -1;
}
/* dir exists already */
dir_number++;
continue;
}
if (dir_number >= MAX_NO_LOGFOLDER) {
/* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */
warnx("all %d possible dirs exist already", MAX_NO_LOGFOLDER);
return -1;
}
}
/* print logging path, important to find log file later */
mavlink_and_console_log_info(mavlink_fd, "[sdlog2] log dir: %s", log_dir);
return 0;
}
int open_log_file()
{
/* string to hold the path to the log */
char log_file_name[32] = "";
char log_file_path[64] = "";
struct timespec ts;
clock_gettime(CLOCK_REALTIME, &ts);
/* use RTC time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.px4log */
time_t utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
struct tm tt;
struct tm *ttp = gmtime_r(&utc_time_sec, &tt);
/* start logging if we have a valid time and the time is not in the past */
if (log_name_timestamp && ttp && (utc_time_sec > PX4_EPOCH_SECS)) {
strftime(log_file_name, sizeof(log_file_name), "%H_%M_%S.px4log", &tt);
snprintf(log_file_path, sizeof(log_file_path), "%s/%s", log_dir, log_file_name);
} else {
uint16_t file_number = 1; // start with file log001
/* look for the next file that does not exist */
while (file_number <= MAX_NO_LOGFILE) {
/* format log file path: e.g. /fs/microsd/sess001/log001.px4log */
snprintf(log_file_name, sizeof(log_file_name), "log%03u.px4log", file_number);
snprintf(log_file_path, sizeof(log_file_path), "%s/%s", log_dir, log_file_name);
if (!file_exist(log_file_path)) {
break;
}
file_number++;
}
if (file_number > MAX_NO_LOGFILE) {
/* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE);
return -1;
}
}
int fd = open(log_file_path, O_CREAT | O_WRONLY | O_DSYNC);
if (fd < 0) {
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] failed opening: %s", log_file_name);
} else {
mavlink_and_console_log_info(mavlink_fd, "[sdlog2] starting: %s", log_file_name);
}
return fd;
}
int open_perf_file(const char* str)
{
/* string to hold the path to the log */
char log_file_name[32] = "";
char log_file_path[64] = "";
struct timespec ts;
clock_gettime(CLOCK_REALTIME, &ts);
/* use RTC time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.txt */
time_t utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9);
struct tm tt;
struct tm *ttp = gmtime_r(&utc_time_sec, &tt);
if (log_name_timestamp && ttp && (utc_time_sec > PX4_EPOCH_SECS)) {
strftime(log_file_name, sizeof(log_file_name), "perf%H_%M_%S.txt", &tt);
snprintf(log_file_path, sizeof(log_file_path), "%s/%s_%s", log_dir, str, log_file_name);
} else {
unsigned file_number = 1; // start with file log001
/* look for the next file that does not exist */
while (file_number <= MAX_NO_LOGFILE) {
/* format log file path: e.g. /fs/microsd/sess001/log001.txt */
snprintf(log_file_name, sizeof(log_file_name), "perf%03u.txt", file_number);
snprintf(log_file_path, sizeof(log_file_path), "%s/%s_%s", log_dir, str, log_file_name);
if (!file_exist(log_file_path)) {
break;
}
file_number++;
}
if (file_number > MAX_NO_LOGFILE) {
/* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE);
return -1;
}
}
int fd = open(log_file_path, O_CREAT | O_WRONLY | O_DSYNC);
if (fd < 0) {
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] failed opening: %s", log_file_name);
}
return fd;
}
static void *logwriter_thread(void *arg)
{
/* set name */
prctl(PR_SET_NAME, "sdlog2_writer", 0);
int log_fd = open_log_file();
if (log_fd < 0) {
return NULL;
}
struct logbuffer_s *logbuf = (struct logbuffer_s *)arg;
/* write log messages formats, version and parameters */
log_bytes_written += write_formats(log_fd);
log_bytes_written += write_version(log_fd);
log_bytes_written += write_parameters(log_fd);
fsync(log_fd);
int poll_count = 0;
void *read_ptr;
int n = 0;
bool should_wait = false;
bool is_part = false;
while (true) {
/* make sure threads are synchronized */
pthread_mutex_lock(&logbuffer_mutex);
/* update read pointer if needed */
if (n > 0) {
logbuffer_mark_read(&lb, n);
}
/* only wait if no data is available to process */
if (should_wait && !logwriter_should_exit) {
/* blocking wait for new data at this line */
pthread_cond_wait(&logbuffer_cond, &logbuffer_mutex);
}
/* only get pointer to thread-safe data, do heavy I/O a few lines down */
int available = logbuffer_get_ptr(logbuf, &read_ptr, &is_part);
/* continue */
pthread_mutex_unlock(&logbuffer_mutex);
if (available > 0) {
/* do heavy IO here */
if (available > MAX_WRITE_CHUNK) {
n = MAX_WRITE_CHUNK;
} else {
n = available;
}
perf_begin(perf_write);
n = write(log_fd, read_ptr, n);
perf_end(perf_write);
should_wait = (n == available) && !is_part;
if (n < 0) {
main_thread_should_exit = true;
err(1, "error writing log file");
}
if (n > 0) {
log_bytes_written += n;
}
} else {
n = 0;
/* exit only with empty buffer */
if (main_thread_should_exit || logwriter_should_exit) {
break;
}
should_wait = true;
}
if (++poll_count == 10) {
fsync(log_fd);
poll_count = 0;
}
if (log_bytes_written - last_checked_bytes_written > 20*1024*1024) {
/* check if space is available, if not stop everything */
if (check_free_space() != OK) {
logwriter_should_exit = true;
main_thread_should_exit = true;
}
last_checked_bytes_written = log_bytes_written;
}
}
fsync(log_fd);
close(log_fd);
return NULL;
}
void sdlog2_start_log()
{
if (logging_enabled) {
return;
}
/* create log dir if needed */
if (create_log_dir() != 0) {
mavlink_and_console_log_critical(mavlink_fd, "[sdlog2] error creating log dir");
exit(1);
}
/* initialize statistics counter */
log_bytes_written = 0;
start_time = hrt_absolute_time();
log_msgs_written = 0;
log_msgs_skipped = 0;
/* initialize log buffer emptying thread */
pthread_attr_init(&logwriter_attr);
struct sched_param param;
/* low priority, as this is expensive disk I/O */
param.sched_priority = SCHED_PRIORITY_DEFAULT - 40;
(void)pthread_attr_setschedparam(&logwriter_attr, ¶m);
pthread_attr_setstacksize(&logwriter_attr, 2048);
logwriter_should_exit = false;
/* allocate write performance counter */
perf_write = perf_alloc(PC_ELAPSED, "sd write");
/* start log buffer emptying thread */
if (0 != pthread_create(&logwriter_pthread, &logwriter_attr, logwriter_thread, &lb)) {
errx(1, "error creating logwriter thread");
}
/* write all performance counters */
int perf_fd = open_perf_file("preflight");
dprintf(perf_fd, "PERFORMANCE COUNTERS PRE-FLIGHT\n\n");
perf_print_all(perf_fd);
close(perf_fd);
/* reset performance counters to get in-flight min and max values in post flight log */
perf_reset_all();
logging_enabled = true;
}
void sdlog2_stop_log()
{
if (!logging_enabled) {
return;
}
logging_enabled = false;
/* wake up write thread one last time */
pthread_mutex_lock(&logbuffer_mutex);
logwriter_should_exit = true;
pthread_cond_signal(&logbuffer_cond);
/* unlock, now the writer thread may return */
pthread_mutex_unlock(&logbuffer_mutex);
/* wait for write thread to return */
int ret;
if ((ret = pthread_join(logwriter_pthread, NULL)) != 0) {
warnx("error joining logwriter thread: %i", ret);
}
logwriter_pthread = 0;
pthread_attr_destroy(&logwriter_attr);
/* write all performance counters */
int perf_fd = open_perf_file("postflight");
dprintf(perf_fd, "PERFORMANCE COUNTERS POST-FLIGHT\n\n");
perf_print_all(perf_fd);
close(perf_fd);
/* free log writer performance counter */
perf_free(perf_write);
mavlink_and_console_log_info(mavlink_fd, "[sdlog2] logging stopped");
sdlog2_status();
}
int write_formats(int fd)
{
/* construct message format packet */
struct {
LOG_PACKET_HEADER;
struct log_format_s body;
} log_msg_format = {
LOG_PACKET_HEADER_INIT(LOG_FORMAT_MSG),
};
int written = 0;
/* fill message format packet for each format and write it */
for (unsigned i = 0; i < log_formats_num; i++) {
log_msg_format.body = log_formats[i];
written += write(fd, &log_msg_format, sizeof(log_msg_format));
}
return written;
}
int write_version(int fd)
{
/* construct version message */
struct {
LOG_PACKET_HEADER;
struct log_VER_s body;
} log_msg_VER = {
LOG_PACKET_HEADER_INIT(LOG_VER_MSG),
};
/* fill version message and write it */
strncpy(log_msg_VER.body.fw_git, GIT_VERSION, sizeof(log_msg_VER.body.fw_git));
strncpy(log_msg_VER.body.arch, HW_ARCH, sizeof(log_msg_VER.body.arch));
return write(fd, &log_msg_VER, sizeof(log_msg_VER));
}
int write_parameters(int fd)
{
/* construct parameter message */
struct {
LOG_PACKET_HEADER;
struct log_PARM_s body;
} log_msg_PARM = {
LOG_PACKET_HEADER_INIT(LOG_PARM_MSG),
};
int written = 0;
param_t params_cnt = param_count();
for (param_t param = 0; param < params_cnt; param++) {
/* fill parameter message and write it */
strncpy(log_msg_PARM.body.name, param_name(param), sizeof(log_msg_PARM.body.name));
float value = NAN;
switch (param_type(param)) {
case PARAM_TYPE_INT32: {
int32_t i;
param_get(param, &i);
value = i; // cast integer to float
break;
}
case PARAM_TYPE_FLOAT:
param_get(param, &value);
break;
default:
break;
}
log_msg_PARM.body.value = value;
written += write(fd, &log_msg_PARM, sizeof(log_msg_PARM));
}
return written;
}
bool copy_if_updated(orb_id_t topic, int handle, void *buffer)
{
bool updated;
orb_check(handle, &updated);
if (updated) {
orb_copy(topic, handle, buffer);
}
return updated;
}
int sdlog2_thread_main(int argc, char *argv[])
{
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
if (mavlink_fd < 0) {
warnx("ERR: log stream, start mavlink app first");
}
/* delay = 1 / rate (rate defined by -r option), default log rate: 50 Hz */
useconds_t sleep_delay = 20000;
int log_buffer_size = LOG_BUFFER_SIZE_DEFAULT;
logging_enabled = false;
/* enable logging on start (-e option) */
bool log_on_start = false;
/* enable logging when armed (-a option) */
bool log_when_armed = false;
log_name_timestamp = false;
flag_system_armed = false;
/* work around some stupidity in task_create's argv handling */
argc -= 2;
argv += 2;
int ch;
/* don't exit from getopt loop to leave getopt global variables in consistent state,
* set error flag instead */
bool err_flag = false;
while ((ch = getopt(argc, argv, "r:b:eatx")) != EOF) {
switch (ch) {
case 'r': {
unsigned long r = strtoul(optarg, NULL, 10);
if (r == 0) {
r = 1;
}
sleep_delay = 1000000 / r;
}
break;
case 'b': {
unsigned long s = strtoul(optarg, NULL, 10);
if (s < 1) {
s = 1;
}
log_buffer_size = 1024 * s;
}
break;
case 'e':
log_on_start = true;
break;
case 'a':
log_when_armed = true;
break;
case 't':
log_name_timestamp = true;
break;
case 'x':
_extended_logging = true;
break;
case '?':
if (optopt == 'c') {
warnx("option -%c requires an argument", optopt);
} else if (isprint(optopt)) {
warnx("unknown option `-%c'", optopt);
} else {
warnx("unknown option character `\\x%x'", optopt);
}
err_flag = true;
break;
default:
warnx("unrecognized flag");
err_flag = true;
break;
}
}
if (err_flag) {
sdlog2_usage(NULL);
}
gps_time = 0;
/* interpret logging params */
param_t log_rate_ph = param_find("SDLOG_RATE");
if (log_rate_ph != PARAM_INVALID) {
int32_t param_log_rate;
param_get(log_rate_ph, ¶m_log_rate);
if (param_log_rate > 0) {
/* we can't do more than ~ 500 Hz, even with a massive buffer */
if (param_log_rate > 500) {
param_log_rate = 500;
}
sleep_delay = 1000000 / param_log_rate;
} else if (param_log_rate == 0) {
/* we need at minimum 10 Hz to be able to see anything */
sleep_delay = 1000000 / 10;
}
}
param_t log_ext_ph = param_find("SDLOG_EXT");
if (log_ext_ph != PARAM_INVALID) {
int32_t param_log_extended;
param_get(log_ext_ph, ¶m_log_extended);
if (param_log_extended > 0) {
_extended_logging = true;
} else if (param_log_extended == 0) {
_extended_logging = false;
}
/* any other value means to ignore the parameter, so no else case */
}
if (check_free_space() != OK) {
errx(1, "ERR: MicroSD almost full");
}
/* create log root dir */
int mkdir_ret = mkdir(log_root, S_IRWXU | S_IRWXG | S_IRWXO);
if (mkdir_ret != 0 && errno != EEXIST) {
err(1, "ERR: failed creating log dir: %s", log_root);
}
/* copy conversion scripts */
const char *converter_in = "/etc/logging/conv.zip";
char *converter_out = malloc(64);
snprintf(converter_out, 64, "%s/conv.zip", log_root);
if (file_copy(converter_in, converter_out) != OK) {
warn("unable to copy conversion scripts");
}
free(converter_out);
/* initialize log buffer with specified size */
warnx("log buffer size: %i bytes", log_buffer_size);
if (OK != logbuffer_init(&lb, log_buffer_size)) {
errx(1, "can't allocate log buffer, exiting");
}
struct vehicle_status_s buf_status;
struct vehicle_gps_position_s buf_gps_pos;
memset(&buf_status, 0, sizeof(buf_status));
memset(&buf_gps_pos, 0, sizeof(buf_gps_pos));
/* warning! using union here to save memory, elements should be used separately! */
union {