-
Notifications
You must be signed in to change notification settings - Fork 30
/
analyze.h
92 lines (63 loc) · 2.45 KB
/
analyze.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
#ifndef ANALYZE_H
#define ANALYZE_H
#include "mavlink_message_handler.h"
#include "analyzer.h"
#include "analyzervehicle_copter.h"
#include "analyzer_util.h"
#include "analyzer/analyzer_altitude_estimate_divergence.h"
#include "analyzer/analyzer_ever_flew.h"
#include "analyzer/analyzer_position_estimate_divergence.h"
#include "analyzer/analyzer_velocity_estimate_divergence.h"
#include "data_sources.h"
class Analyze {
public:
Analyze(AnalyzerVehicle::Base *&vehicle) :
vehicle(vehicle)
{
start_time = now();
}
void instantiate_analyzers(INIReader *config);
void end_of_log(uint32_t packet_count, uint64_t bytes_dropped = 0);
enum output_style_option {
OUTPUT_JSON = 17,
OUTPUT_PLAINTEXT,
OUTPUT_HTML,
OUTPUT_BRIEF,
};
void set_output_style(output_style_option option) { _output_style = option;}
output_style_option output_style() { return _output_style; }
void evaluate_all();
void add_data_source(std::string type, const std::string data_source) {
_data_sources.add_series(type, data_source);
}
std::vector<Analyzer *> analyzers() { return _analyzers; }
void set_analyzer_names_to_run(const std::vector<std::string> run_these);
void set_pure_output(bool value) {
_pure_output = value;
}
bool pure_output() const {
return _pure_output;
}
protected:
private:
uint64_t start_time;
bool _pure_output = false;
AnalyzerVehicle::Base *&vehicle;
output_style_option _output_style = OUTPUT_JSON;
std::vector<Analyzer*> _analyzers;
bool _use_names_to_run = false;
std::map<std::string,bool> _names_to_run;
void configure_message_handler(INIReader *config,
MAVLink_Message_Handler *handler,
const char *handler_name);
void configure_analyzer(INIReader *config, Analyzer *handler, bool run_default=true);
void results_json_add_statistics(Json::Value &root);
void results_json(Json::Value &root);
void output_plaintext(Json::Value &root);
Data_Sources _data_sources;
Analyzer_Altitude_Estimate_Divergence *analyzer_altitude_estimate_divergence = NULL;
Analyzer_Ever_Flew *analyzer_ever_flew = NULL;
Analyzer_Position_Estimate_Divergence *analyzer_position_estimate_divergence = NULL;
Analyzer_Velocity_Estimate_Divergence * analyzer_velocity_estimate_divergence = NULL;
};
#endif