mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-07 09:13:32 +08:00
err/px4_log: switch everything to static function
Instead of having separate log functions for NuttX and POSIX, this now switches everything to px4_log.h and PX4_INFO/WARN/ERR/DEBUG. Also, the call mostly used is now a static inline function instead of a macro which lead to a big increase in flash size for STM32.
This commit is contained in:
@@ -60,6 +60,8 @@ extern int lib_lowvprintf(const char *fmt, va_list ap);
|
||||
# warning Cannot output without one of CONFIG_NFILE_STREAMS or CONFIG_ARCH_LOWPUTC
|
||||
#endif
|
||||
|
||||
// XXX not used anymore
|
||||
#if 0
|
||||
const char *
|
||||
getprogname(void)
|
||||
{
|
||||
@@ -201,3 +203,4 @@ vwarnx(const char *fmt, va_list args)
|
||||
{
|
||||
warnerr_core(NOCODE, fmt, args);
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -67,23 +67,33 @@
|
||||
|
||||
#include <px4_log.h>
|
||||
#include <stdarg.h>
|
||||
#include <errno.h>
|
||||
#include "visibility.h"
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
__EXPORT const char *getprogname(void);
|
||||
|
||||
#ifdef __PX4_POSIX
|
||||
|
||||
#include <errno.h>
|
||||
#include <px4_tasks.h>
|
||||
#define err(eval, ...) do { PX4_ERR(__VA_ARGS__); PX4_ERR("Task exited with errno=%i\n", errno); \
|
||||
px4_task_exit(eval); } while(0)
|
||||
#define errx(eval, ...) do { PX4_ERR(__VA_ARGS__); px4_task_exit(eval); } while(0)
|
||||
#define warn(...) PX4_WARN(__VA_ARGS__)
|
||||
#define warnx(...) PX4_WARN(__VA_ARGS__)
|
||||
|
||||
#else
|
||||
#define err(eval, ...) do { \
|
||||
PX4_ERR(__VA_ARGS__); \
|
||||
PX4_ERR("Task exited with errno=%i\n", errno); \
|
||||
px4_task_exit(eval); } \
|
||||
while(0)
|
||||
|
||||
#define errx(eval, ...) do { \
|
||||
PX4_ERR(__VA_ARGS__); \
|
||||
px4_task_exit(eval); \
|
||||
} while(0)
|
||||
|
||||
#define warn(...) PX4_WARN(__VA_ARGS__)
|
||||
#define warnx(...) PX4_WARN(__VA_ARGS__)
|
||||
|
||||
// XXX not used anymore
|
||||
#if 0
|
||||
__EXPORT void err(int eval, const char *fmt, ...) __attribute__((noreturn, format(printf, 2, 3)));
|
||||
__EXPORT void verr(int eval, const char *fmt, va_list) __attribute__((noreturn, format(printf, 2, 0)));
|
||||
__EXPORT void errc(int eval, int code, const char *fmt, ...) __attribute__((noreturn, format(printf, 3, 4)));
|
||||
|
||||
+49
-8
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2015 Mark Charlebois. All rights reserved.
|
||||
* Copyright (C) 2015-2016 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -50,6 +50,7 @@ static inline void do_nothing(int level, ...)
|
||||
(void)level;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* __px4_log_omit:
|
||||
* Compile out the message
|
||||
@@ -150,17 +151,23 @@ __END_DECLS
|
||||
#define __px4__log_printcond(cond, ...) if (cond) printf(__VA_ARGS__)
|
||||
#define __px4__log_printline(level, ...) if (level <= __px4_log_level_current) printf(__VA_ARGS__)
|
||||
|
||||
|
||||
#ifndef MODULE_NAME
|
||||
#define MODULE_NAME "Unknown"
|
||||
#endif
|
||||
|
||||
#define __px4__log_timestamp_fmt "%-10" PRIu64 " "
|
||||
#define __px4__log_timestamp_arg ,hrt_absolute_time()
|
||||
#define __px4__log_level_fmt "%-5s "
|
||||
#define __px4__log_level_arg(level) ,__px4_log_level_str[level]
|
||||
#define __px4__log_thread_fmt "%#X "
|
||||
#define __px4__log_thread_arg ,(unsigned int)pthread_self()
|
||||
#define __px4__log_modulename_fmt "%-10s "
|
||||
#define __px4__log_modulename_arg ,"[" MODULE_NAME "]"
|
||||
|
||||
#define __px4__log_file_and_line_fmt " (file %s line %u)"
|
||||
#define __px4__log_file_and_line_arg , __FILE__, __LINE__
|
||||
#define __px4__log_end_fmt "\n"
|
||||
#define __px4__log_endline )
|
||||
|
||||
/****************************************************************************
|
||||
* Output format macros
|
||||
@@ -199,6 +206,40 @@ __END_DECLS
|
||||
__px4__log_level_arg(level), ##__VA_ARGS__\
|
||||
)
|
||||
|
||||
/****************************************************************************
|
||||
* __px4_log_modulename:
|
||||
* Convert a message in the form:
|
||||
* PX4_WARN("val is %d", val);
|
||||
* to
|
||||
* printf("%-5s [%-10s] val is %d\n", __px4_log_level_str[3],
|
||||
* MODULENAME, val);
|
||||
****************************************************************************/
|
||||
|
||||
/* It turns out the macro below uses a lot more flash space than a static
|
||||
* inline function. */
|
||||
#if 0
|
||||
#define __px4_log_modulename(level, FMT, ...) \
|
||||
__px4__log_printline(level,\
|
||||
__px4__log_level_fmt\
|
||||
__px4__log_modulename_fmt\
|
||||
FMT\
|
||||
__px4__log_end_fmt\
|
||||
__px4__log_level_arg(level)\
|
||||
__px4__log_modulename_arg\
|
||||
, ##__VA_ARGS__\
|
||||
)
|
||||
#endif
|
||||
|
||||
static inline void __px4_log_modulename(int level, const char *fmt, ...)
|
||||
{
|
||||
if (level <= __px4_log_level_current) {
|
||||
printf(__px4__log_level_fmt __px4__log_level_arg(level));
|
||||
printf(__px4__log_modulename_fmt __px4__log_modulename_arg);
|
||||
printf(fmt);
|
||||
printf("\n");
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* __px4_log_timestamp:
|
||||
* Convert a message in the form:
|
||||
@@ -338,7 +379,7 @@ __END_DECLS
|
||||
* Messages that should never be filtered or compiled out
|
||||
****************************************************************************/
|
||||
#define PX4_LOG(FMT, ...) __px4_log(_PX4_LOG_LEVEL_ALWAYS, FMT, ##__VA_ARGS__)
|
||||
#define PX4_INFO(FMT, ...) __px4_log(_PX4_LOG_LEVEL_ALWAYS, FMT, ##__VA_ARGS__)
|
||||
#define PX4_INFO(FMT, ...) __px4_log_modulename(_PX4_LOG_LEVEL_ALWAYS, FMT, ##__VA_ARGS__)
|
||||
|
||||
#if defined(TRACE_BUILD)
|
||||
/****************************************************************************
|
||||
@@ -362,8 +403,8 @@ __END_DECLS
|
||||
/****************************************************************************
|
||||
* Non-verbose settings for a Release build to minimize strings in build
|
||||
****************************************************************************/
|
||||
#define PX4_PANIC(FMT, ...) __px4_log(_PX4_LOG_LEVEL_PANIC, FMT, ##__VA_ARGS__)
|
||||
#define PX4_ERR(FMT, ...) __px4_log(_PX4_LOG_LEVEL_ERROR, FMT, ##__VA_ARGS__)
|
||||
#define PX4_PANIC(FMT, ...) __px4_log_modulename(_PX4_LOG_LEVEL_PANIC, FMT, ##__VA_ARGS__)
|
||||
#define PX4_ERR(FMT, ...) __px4_log_modulename(_PX4_LOG_LEVEL_ERROR, FMT, ##__VA_ARGS__)
|
||||
#define PX4_WARN(FMT, ...) __px4_log_omit(_PX4_LOG_LEVEL_WARN, FMT, ##__VA_ARGS__)
|
||||
#define PX4_DEBUG(FMT, ...) __px4_log_omit(_PX4_LOG_LEVEL_DEBUG, FMT, ##__VA_ARGS__)
|
||||
|
||||
@@ -371,9 +412,9 @@ __END_DECLS
|
||||
/****************************************************************************
|
||||
* Medium verbose settings for a default build
|
||||
****************************************************************************/
|
||||
#define PX4_PANIC(FMT, ...) __px4_log(_PX4_LOG_LEVEL_PANIC, FMT, ##__VA_ARGS__)
|
||||
#define PX4_ERR(FMT, ...) __px4_log(_PX4_LOG_LEVEL_ERROR, FMT, ##__VA_ARGS__)
|
||||
#define PX4_WARN(FMT, ...) __px4_log(_PX4_LOG_LEVEL_WARN, FMT, ##__VA_ARGS__)
|
||||
#define PX4_PANIC(FMT, ...) __px4_log_modulename(_PX4_LOG_LEVEL_PANIC, FMT, ##__VA_ARGS__)
|
||||
#define PX4_ERR(FMT, ...) __px4_log_modulename(_PX4_LOG_LEVEL_ERROR, FMT, ##__VA_ARGS__)
|
||||
#define PX4_WARN(FMT, ...) __px4_log_modulename(_PX4_LOG_LEVEL_WARN, FMT, ##__VA_ARGS__)
|
||||
#define PX4_DEBUG(FMT, ...) __px4_log_omit(_PX4_LOG_LEVEL_DEBUG, FMT, ##__VA_ARGS__)
|
||||
|
||||
#endif
|
||||
|
||||
Reference in New Issue
Block a user