forked from dronekit/dronekit-la
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathanalyzer.cpp
130 lines (115 loc) · 3.88 KB
/
analyzer.cpp
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
#include "analyzer.h"
void Analyzer_Result::to_json_add_array(Json::Value &root,
std::string name,
std::vector<std::string> array) const
{
if (array.size() == 0) {
return;
}
Json::Value json_array(Json::arrayValue);
for (std::vector<std::string>::const_iterator it = array.begin();
it != array.end(); it++) {
json_array.append((*it));
}
root[name] = json_array;
}
void Analyzer_Result::to_json(Json::Value &root) const
{
root["status"] = status_as_string();
root["severity-score"] = severity_score();
if (!pure_output()) {
root["evilness"] = root["severity-score"];
root["evilness-is-deprecated"] = "Use severity-score";
}
const std::string *my_reason = reason();
if (my_reason != NULL) {
root["reason"] = *my_reason;
}
std::vector<std::string> some_series;
for (std::vector<const Data_Source*>::const_iterator it = _sources.begin();
it != _sources.end();
it++) {
std::vector<std::string> source_series = (*it)->series();
some_series.insert(some_series.end(), source_series.begin(), source_series.end());
}
to_json_add_array(root, "series", some_series);
to_json_add_array(root, "evidence", _evidence);
}
void Analyzer_Result_Period::to_json(Json::Value &root) const
{
Analyzer_Result::to_json(root);
root["timestamp_start"] = (Json::UInt64)_T_start;
root["timestamp_stop"] = (Json::UInt64)_T_stop;
root["duration"] = (_T_stop - _T_start) / 1000000.0f;
root["duration-units"] = "seconds";
}
void Analyzer_Result_Event::to_json(Json::Value &root) const
{
Analyzer_Result::to_json(root);
root["timestamp"] = (Json::UInt64)_T;
}
uint32_t Analyzer::severity_score() const {
uint32_t ret = 0; // remove _evilness here?
std::vector<Analyzer_Result*> my_results = results();
for (std::vector<Analyzer_Result*>::const_iterator it = my_results.begin();
it != my_results.end();
it++) {
ret += (*it)->severity_score();
}
return ret;
}
void Analyzer::results_json_results(Json::Value &root) const
{
std::vector<Analyzer_Result*> my_results = results();
for (std::vector<Analyzer_Result*>::const_iterator it = my_results.begin();
it != my_results.end();
it++) {
Json::Value result(Json::objectValue);
(*it)->to_json(result);
if (result["series"].type() == Json::nullValue) {
::fprintf(stderr, "No series in (%s)\n", name().c_str());
// that appears to autovivify :-/
result["series"] = Json::Value(Json::arrayValue);
}
if (result["reason"].type() == Json::nullValue) {
::fprintf(stderr, "No reason in (%s)\n", name().c_str());
}
if (result["severity-score"].type() == Json::nullValue) {
::fprintf(stderr, "No severity-score in (%s)\n", name().c_str());
}
root.append(result);
}
}
analyzer_status Analyzer::status() const
{
analyzer_status ret = analyzer_status_ok;
std::vector<Analyzer_Result*> my_results = results();
for (std::vector<Analyzer_Result*>::const_iterator it = my_results.begin();
it != my_results.end();
it++) {
switch((*it)->status()) {
case analyzer_status_fail:
ret = analyzer_status_fail;
break;
case analyzer_status_warn:
if (ret == analyzer_status_ok) {
ret = analyzer_status_warn;
}
break;
case analyzer_status_ok:
break;
}
}
return ret;
}
const char *_status_as_string(analyzer_status status) {
switch(status) {
case analyzer_status_fail:
return "FAIL";
case analyzer_status_warn:
return "WARN";
case analyzer_status_ok:
return "PASS";
}
return "STRANGE";
}