-
Notifications
You must be signed in to change notification settings - Fork 30
/
loganalyzer.h
107 lines (80 loc) · 2.6 KB
/
loganalyzer.h
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
#ifndef LOGANALYZER_H
#define LOGANALYZER_H
/*
* loganalyzer
*
* Receive telemetry (mavlink) via UDP from Solo, and create dataflash log files
*
* Initiate a remote-dataflash stream
*/
// if you modify this, modify the debian metadata using e.g.
// debchange -r -e (FIXME)
#define DRONEKIT_LA_VERSION "0.5"
#include "INIReader.h"
#include "mavlink_message_handler.h"
#include "mavlink_reader.h"
#include "mavlink_writer.h"
#include "telem_forwarder_client.h"
#include "analyze.h"
#include "common_tool.h"
class LogAnalyzer : Common_Tool {
public:
LogAnalyzer() :
Common_Tool()
{ }
Analyze *create_analyze();
void parse_path(const char *path);
void run();
void parse_arguments(int argc, char *argv[]);
private:
bool _pure_output = false;
bool _use_telem_forwarder = false;
Telem_Forwarder_Client *_client = NULL;
char **_paths = NULL;
uint8_t _pathcount;
Format_Reader *reader;
MAVLink_Writer *writer;
Analyze::output_style_option output_style = Analyze::OUTPUT_JSON;
long _argc;
char **_argv;
const char * output_style_string = NULL;
const char * _model_string = NULL;
const char * _frame_string = NULL;
const char * forced_format_string = NULL;
AnalyzerVehicle::Base *_vehicle = NULL;
void create_vehicle_from_commandline_arguments();
const char *program_name();
void usage();
void instantiate_message_handlers();
void run_live_analysis();
void run_df(const char *_pathname);
void do_idle_callbacks();
void pack_select_fds(fd_set &fds_read, fd_set &fds_write, fd_set &fds_err, uint8_t &nfds);
void handle_select_fds(fd_set &fds_read, fd_set &fds_write, fd_set &fds_err, uint8_t &nfds);
int xopen(const char *filepath, uint8_t mode);
void prep_for_df();
void prep_for_log();
void prep_for_tlog();
void cleanup_after_df();
void cleanup_after_log();
void cleanup_after_tlog();
void show_version_information();
bool _show_version_information = false;
void list_analyzers();
bool _do_list_analyzers = false;
void expand_names_to_run();
std::vector<std::string> _analyzer_names_to_run;
enum log_format_t {
log_format_none = 19,
log_format_tlog,
log_format_log, // text dump of dflog
log_format_df,
};
log_format_t _force_format = log_format_none;
log_format_t force_format() { return _force_format; }
static const uint32_t _writer_buflen = 65536;
uint8_t _writer_buf[_writer_buflen] = { }; // FIXME constant
uint32_t _writer_buf_start = 0;
uint32_t _writer_buf_stop = 0;
};
#endif