forked from mavlink-router/mavlink-router
-
Notifications
You must be signed in to change notification settings - Fork 0
/
logendpoint.cpp
208 lines (173 loc) · 5.22 KB
/
logendpoint.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
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
/*
* This file is part of the MAVLink Router project
*
* Copyright (C) 2017 Intel Corporation. All rights reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "logendpoint.h"
#include <dirent.h>
#include <fcntl.h>
#include <limits.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/stat.h>
#include <sys/types.h>
#include <time.h>
#include <unistd.h>
#include <memory>
#include "log.h"
#include "mainloop.h"
#include "util.h"
#define ALIVE_TIMEOUT 5
#define MAX_RETRIES 10
void LogEndpoint::_send_msg(const mavlink_message_t *msg, int target_sysid)
{
uint8_t data[MAVLINK_MAX_PACKET_LEN];
struct buffer buffer {
0, data
};
buffer.len = mavlink_msg_to_send_buffer(data, msg);
Mainloop::get_instance().route_msg(&buffer, target_sysid, msg->sysid);
_stat.read.total++;
_stat.read.handled++;
_stat.read.handled_bytes += buffer.len;
}
uint32_t LogEndpoint::_get_prefix(DIR *dir)
{
struct dirent *ent;
uint32_t u, prefix = 0;
while ((ent = readdir(dir)) != nullptr) {
if (sscanf(ent->d_name, "%u-", &u) == 1) {
if (u >= prefix && u < UINT32_MAX) {
prefix = ++u;
}
}
}
return prefix;
}
DIR *LogEndpoint::_open_or_create_dir(const char *name)
{
int r;
DIR *dir = opendir(name);
// If failed because dir doesn't exist, try to create it
if (!dir && errno == ENOENT) {
r = mkdir_p(name, strlen(name), 0755);
if (r < 0) {
errno = -r;
return NULL;
}
dir = opendir(name);
}
return dir;
}
int LogEndpoint::_get_file(const char *extension, char *filename, size_t filename_size)
{
time_t t = time(NULL);
struct tm *timeinfo = localtime(&t);
uint32_t i;
int j, r;
DIR *dir;
dir = _open_or_create_dir(_logs_dir);
if (!dir) {
log_error("Could not open log dir (%m)");
return -1;
}
// Close dir when leaving function.
std::shared_ptr<void> defer(dir, [](DIR *p) { closedir(p); });
i = _get_prefix(dir);
for (j = 0; j <= MAX_RETRIES; j++) {
r = snprintf(filename, filename_size, "%05u-%i-%02i-%02i_%02i-%02i-%02i.%s", i + j,
timeinfo->tm_year + 1900, timeinfo->tm_mon + 1, timeinfo->tm_mday,
timeinfo->tm_hour, timeinfo->tm_min, timeinfo->tm_sec, extension);
if (r < 1 || (size_t)r >= filename_size) {
log_error("Error formatting Log file name: (%m)");
return -1;
}
r = openat(dirfd(dir), filename, O_WRONLY | O_CLOEXEC | O_CREAT | O_NONBLOCK | O_EXCL,
0644);
if (r < 0) {
if (errno != EEXIST) {
log_error("Unable to open Log file(%s): (%m)", filename);
return -1;
}
continue;
}
return r;
}
log_error("Unable to create a Log file without override another file.");
return -EEXIST;
}
void LogEndpoint::stop()
{
Mainloop &mainloop = Mainloop::get_instance();
if (_logging_start_timeout) {
mainloop.del_timeout(_logging_start_timeout);
_logging_start_timeout = nullptr;
}
if (_alive_check_timeout) {
mainloop.del_timeout(_alive_check_timeout);
_alive_check_timeout = nullptr;
}
fsync(_file);
close(_file);
_file = -1;
_system_id = 0;
}
bool LogEndpoint::start()
{
char filename[PATH_MAX];
if (_file != -1) {
log_warning("Log already started");
return false;
}
_file = _get_file(_get_logfile_extension(), filename, sizeof(filename));
if (_file < 0) {
_file = -1;
return false;
}
_logging_start_timeout = Mainloop::get_instance().add_timeout(
MSEC_PER_SEC, std::bind(&LogEndpoint::_start_timeout, this), this);
if (!_logging_start_timeout) {
log_error("Unable to add timeout");
goto timeout_error;
}
log_info("Logging target system_id=%u on %s", _target_system_id, filename);
return true;
timeout_error:
close(_file);
_file = -1;
return false;
}
bool LogEndpoint::_alive_timeout()
{
if (_timeout_write_total == _stat.write.total) {
log_warning("No Log messages received in %u seconds restarting Log...", ALIVE_TIMEOUT);
stop();
start();
}
_timeout_write_total = _stat.write.total;
return true;
}
void LogEndpoint::_remove_start_timeout()
{
Mainloop::get_instance().del_timeout(_logging_start_timeout);
_logging_start_timeout = nullptr;
}
bool LogEndpoint::_start_alive_timeout()
{
_alive_check_timeout = Mainloop::get_instance().add_timeout(
MSEC_PER_SEC * ALIVE_TIMEOUT, std::bind(&LogEndpoint::_alive_timeout, this), this);
return !!_alive_check_timeout;
}