Skip to content

Commit

Permalink
Merge pull request mavlink-router#422 from mavlink-router/syslog
Browse files Browse the repository at this point in the history
Add TRACE log level and syslog output option
  • Loading branch information
lucasdemarchi authored Aug 21, 2024
2 parents 6789b72 + 9b14f7e commit c20337b
Show file tree
Hide file tree
Showing 8 changed files with 111 additions and 37 deletions.
2 changes: 1 addition & 1 deletion examples/config.sample
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
#ReportStats = false

# Logging verbosity (stderr)
# Valid values: <error>, <warning>, <info> or <debug>
# Valid values: <error>, <warning>, <info>, <debug> or <trace>
# Default: <info>
#DebugLogLevel = info

Expand Down
2 changes: 1 addition & 1 deletion mavlink-router.service.in
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ Description=MAVLink Router

[Service]
Type=simple
ExecStart=@BINDIR@/mavlink-routerd
ExecStart=@BINDIR@/mavlink-routerd --syslog
Restart=on-failure

[Install]
Expand Down
79 changes: 66 additions & 13 deletions src/common/log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <stdio.h>
#include <string.h>
#include <sys/uio.h>
#include <syslog.h>
#include <unistd.h>

#define COLOR_RED "\033[31m"
Expand All @@ -34,6 +35,7 @@
Log::Level Log::_max_level = Level::INFO;
int Log::_target_fd = -1;
bool Log::_show_colors;
Log::Backend Log::_backend = Log::Backend::STDERR;

const char *Log::_get_color(Level level)
{
Expand All @@ -52,29 +54,46 @@ const char *Log::_get_color(Level level)
return COLOR_WHITE;
case Level::DEBUG:
return COLOR_LIGHTBLUE;
case Level::TRACE:
break;
}

return nullptr;
}

int Log::open()
int Log::open(Backend backend)
{
assert_or_return(_target_fd < 0, -1);

/* for now, only logging is supported only to stderr */
_target_fd = STDERR_FILENO;
_backend = backend;

if (isatty(_target_fd)) {
_show_colors = true;
switch (backend) {
case Backend::STDERR:
_target_fd = STDERR_FILENO;

if (isatty(_target_fd))
_show_colors = true;

break;
case Backend::SYSLOG:
openlog(nullptr, LOG_CONS, LOG_USER);
break;
}

return 0;
}

int Log::close()
{
/* see _target_fd on open() */
fflush(stderr);
switch (_backend) {
case Backend::STDERR:
/* see _target_fd on open() */
fflush(stderr);
break;
case Backend::SYSLOG:
closelog();
break;
}

return 0;
}
Expand All @@ -84,18 +103,14 @@ void Log::set_max_level(Level level)
_max_level = level;
}

void Log::logv(Level level, const char *format, va_list ap)
void Log::logv_to_fd(int fd, Log::Level level, const char *format, va_list ap)
{
struct iovec iovec[6] = {};
const char *color;
int n = 0;
char buffer[LINE_MAX];
int save_errno;

if (_max_level < level) {
return;
}

/* so %m works as expected */
save_errno = errno;

Expand All @@ -120,7 +135,26 @@ void Log::logv(Level level, const char *format, va_list ap)

IOVEC_SET_STRING(iovec[n++], "\n");

(void)writev(_target_fd, iovec, n);
(void)writev(fd, iovec, n);
}

void Log::logv(Level level, const char *format, va_list ap)
{
if (_max_level < level) {
return;
}

switch (_backend) {
case Backend::STDERR:
logv_to_fd(_target_fd, level, format, ap);
break;
case Backend::SYSLOG:
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wformat-nonliteral"
vsyslog(syslog_log_level(level), format, ap);
#pragma GCC diagnostic pop
break;
}
}

void Log::log(Level level, const char *format, ...)
Expand All @@ -131,3 +165,22 @@ void Log::log(Level level, const char *format, ...)
logv(level, format, ap);
va_end(ap);
}

int Log::syslog_log_level(Log::Level level)
{
switch (level) {
case Level::ERROR:
return LOG_ERR;
case Level::WARNING:
return LOG_WARNING;
case Level::NOTICE:
return LOG_NOTICE;
case Level::INFO:
return LOG_INFO;
case Level::DEBUG:
return LOG_DEBUG;
case Level::TRACE:
return LOG_DEBUG;
}
return LOG_DEBUG;
}
13 changes: 12 additions & 1 deletion src/common/log.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,15 @@ class Log {
NOTICE,
INFO,
DEBUG,
TRACE,
};

static int open();
enum class Backend {
STDERR,
SYSLOG,
};

static int open(Backend backend);
static int close();

static Level get_max_level() _pure_ { return _max_level; }
Expand All @@ -43,13 +49,18 @@ class Log {
static void log(Level level, const char *format, ...) _printf_format_(2, 3);

protected:
static void logv_to_fd(int fd, Level level, const char *format, va_list ap);
static const char *_get_color(Level level);

static int syslog_log_level(Level level);

static int _target_fd;
static Level _max_level;
static bool _show_colors;
static Backend _backend;
};

#define log_trace(...) Log::log(Log::Level::TRACE, __VA_ARGS__)
#define log_debug(...) Log::log(Log::Level::DEBUG, __VA_ARGS__)
#define log_info(...) Log::log(Log::Level::INFO, __VA_ARGS__)
#define log_notice(...) Log::log(Log::Level::NOTICE, __VA_ARGS__)
Expand Down
24 changes: 12 additions & 12 deletions src/endpoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -231,11 +231,11 @@ int Endpoint::handle_read()
// check incoming message filters
if (!allowed_by_dedup(&buf)) {
if (Log::get_max_level() >= Log::Level::DEBUG) {
log_debug("Message %u discarded by de-duplication", buf.curr.msg_id);
log_trace("Message %u discarded by de-duplication", buf.curr.msg_id);
}
} else if (!allowed_by_incoming_filters(&buf)) {
if (Log::get_max_level() >= Log::Level::DEBUG) {
log_debug("Message %u to %d/%d from %u/%u discarded by incoming filters",
log_trace("Message %u to %d/%d from %u/%u discarded by incoming filters",
buf.curr.msg_id,
buf.curr.target_sysid,
buf.curr.target_compid,
Expand Down Expand Up @@ -292,7 +292,7 @@ int Endpoint::read_msg(struct buffer *pbuf)
return r;
}

log_debug("> %s [%d]%s: Got %zd bytes", _type.c_str(), fd, _name.c_str(), r);
log_trace("> %s [%d]%s: Got %zd bytes", _type.c_str(), fd, _name.c_str(), r);
rx_buf.len += r;
}

Expand Down Expand Up @@ -411,7 +411,7 @@ int Endpoint::read_msg(struct buffer *pbuf)
target_compid = -1;

if (msg_entry == nullptr) {
log_debug("%s [%d]%s: No message entry for %u", _type.c_str(), fd, _name.c_str(), msg_id);
log_trace("%s [%d]%s: No message entry for %u", _type.c_str(), fd, _name.c_str(), msg_id);
} else {
if (msg_entry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM) {
// if target_system is 0, it may have been trimmed out on mavlink2
Expand Down Expand Up @@ -502,18 +502,18 @@ bool Endpoint::has_sys_comp_id(unsigned sys_comp_id) const

Endpoint::AcceptState Endpoint::accept_msg(const struct buffer *pbuf) const
{
if (Log::get_max_level() >= Log::Level::DEBUG) {
log_debug("Endpoint [%d]%s: got message %u to %d/%d from %u/%u",
if (Log::get_max_level() >= Log::Level::TRACE) {
log_trace("Endpoint [%d]%s: got message %u to %d/%d from %u/%u",
fd,
_name.c_str(),
pbuf->curr.msg_id,
pbuf->curr.target_sysid,
pbuf->curr.target_compid,
pbuf->curr.src_sysid,
pbuf->curr.src_compid);
log_debug("\tKnown components:");
log_trace("\tKnown components:");
for (const auto &id : _sys_comp_ids) {
log_debug("\t\t%u/%u", (id >> 8), id & 0xff);
log_trace("\t\t%u/%u", (id >> 8), id & 0xff);
}
}

Expand Down Expand Up @@ -1024,7 +1024,7 @@ int UartEndpoint::write_msg(const struct buffer *pbuf)
pbuf->len);
}

log_debug("UART [%d]%s: Wrote %zd bytes", fd, _name.c_str(), r);
log_trace("UART [%d]%s: Wrote %zd bytes", fd, _name.c_str(), r);

return r;
}
Expand Down Expand Up @@ -1350,7 +1350,7 @@ int UdpEndpoint::write_msg(const struct buffer *pbuf)
}

if (!sock_connected) {
log_debug("UDP %s: No one ever connected to us. No one to write for", _name.c_str());
log_trace("UDP %s: No one ever connected to us. No one to write for", _name.c_str());
return 0;
}

Expand All @@ -1374,7 +1374,7 @@ int UdpEndpoint::write_msg(const struct buffer *pbuf)
pbuf->len);
}

log_debug("UDP [%d]%s: Wrote %zd bytes", fd, _name.c_str(), r);
log_trace("UDP [%d]%s: Wrote %zd bytes", fd, _name.c_str(), r);

return r;
}
Expand Down Expand Up @@ -1733,7 +1733,7 @@ int TcpEndpoint::write_msg(const struct buffer *pbuf)
pbuf->len);
}

log_debug("TCP [%d]%s: Wrote %zd bytes", fd, _name.c_str(), r);
log_trace("TCP [%d]%s: Wrote %zd bytes", fd, _name.c_str(), r);

return r;
}
Expand Down
19 changes: 14 additions & 5 deletions src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,12 +50,13 @@ static const struct option long_options[] = {{"endpoints", required_argument, nu
{"log", required_argument, nullptr, 'l'},
{"telemetry-log", no_argument, nullptr, 'T'},
{"debug-log-level", required_argument, nullptr, 'g'},
{"syslog", no_argument, NULL, 'y'},
{"verbose", no_argument, nullptr, 'v'},
{"version", no_argument, nullptr, 'V'},
{"sniffer-sysid", required_argument, nullptr, 's'},
{}};

static const char *short_options = "he:rt:c:d:l:p:g:vV:s:T:";
static const char *short_options = "he:rt:c:d:l:p:g:vV:s:T:y";

static void help(FILE *fp)
{
Expand Down Expand Up @@ -86,6 +87,7 @@ static void help(FILE *fp)
" -v --verbose Verbose. Same as --debug-log-level=debug\n"
" -V --version Show version\n"
" -s --sniffer-sysid Sysid that all messages are sent to.\n"
" -y --syslog Use syslog output instead of stderr\n"
" -h --help Print this message\n",
program_invocation_short_name);
}
Expand Down Expand Up @@ -137,6 +139,9 @@ static Log::Level log_level_from_str(const char *str)
if (strcaseeq(str, "debug")) {
return Log::Level::DEBUG;
}
if (strcaseeq(str, "trace")) {
return Log::Level::TRACE;
}

throw std::invalid_argument("log_level_from_str: unkown string value");
}
Expand All @@ -160,6 +165,10 @@ static bool pre_parse_argv(int argc, char *argv[], Configuration &config)
config.conf_dir = optarg;
break;
}
case 'y': {
config.log_backend = Log::Backend::SYSLOG;
break;
}
case 'V':
printf(PACKAGE " version %s\n", BUILD_VERSION);
return false;
Expand Down Expand Up @@ -296,6 +305,7 @@ static int parse_argv(int argc, char *argv[], Configuration &config)
}
case 'c':
case 'd':
case 'y':
case 'V':
break; // These options were parsed on pre_parse_argv
case '?':
Expand Down Expand Up @@ -595,14 +605,13 @@ int main(int argc, char *argv[])
int retcode;
Configuration config{};

Log::open();
log_info(PACKAGE " version %s", BUILD_VERSION);

if (!pre_parse_argv(argc, argv, config)) {
Log::close();
return 0;
}

Log::open(config.log_backend);
log_info(PACKAGE " version %s", BUILD_VERSION);

// Build remaining config from config files and CLI parameters
if (parse_conf_files(config) < 0) {
goto close_log;
Expand Down
6 changes: 3 additions & 3 deletions src/mainloop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,7 +164,7 @@ void Mainloop::route_msg(struct buffer *buf)

switch (acceptState) {
case Endpoint::AcceptState::Accepted:
log_debug("Endpoint [%d] accepted message %u to %d/%d from %u/%u",
log_trace("Endpoint [%d] accepted message %u to %d/%d from %u/%u",
e->fd,
buf->curr.msg_id,
buf->curr.target_sysid,
Expand All @@ -177,7 +177,7 @@ void Mainloop::route_msg(struct buffer *buf)
unknown = false;
break;
case Endpoint::AcceptState::Filtered:
log_debug("Endpoint [%d] filtered out message %u to %d/%d from %u/%u",
log_trace("Endpoint [%d] filtered out message %u to %d/%d from %u/%u",
e->fd,
buf->curr.msg_id,
buf->curr.target_sysid,
Expand All @@ -195,7 +195,7 @@ void Mainloop::route_msg(struct buffer *buf)

if (unknown) {
_errors_aggregate.msg_to_unknown++;
log_debug("Message %u to unknown sysid/compid: %d/%d",
log_trace("Message %u to unknown sysid/compid: %d/%d",
buf->curr.msg_id,
buf->curr.target_sysid,
buf->curr.target_compid);
Expand Down
3 changes: 2 additions & 1 deletion src/mainloop.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,8 @@ struct Configuration {
unsigned long tcp_port{5760}; ///< conf "TcpServerPort" or CLI "tcp-port"
bool report_msg_statistics{false}; ///< conf "ReportStats" or CLI "report_msg_statistics"
Log::Level debug_log_level{Log::Level::INFO}; ///< conf "DebugLogLevel" or CLI "debug-log-level"
unsigned long dedup_period_ms; ///< conf "DeduplicationPeriod"
Log::Backend log_backend{Log::Backend::STDERR}; ///< CLI "syslog"
unsigned long dedup_period_ms; ///< conf "DeduplicationPeriod"

LogOptions log_config; ///< logging is in General config section, but internally an endpoint
std::vector<UartEndpointConfig> uart_configs;
Expand Down

0 comments on commit c20337b

Please sign in to comment.