Skip to content
Snippets Groups Projects
Commit 1a8703ec authored by Mark Charlebois's avatar Mark Charlebois
Browse files

Improved logging with both compile and runtime level filtering


The device level debug will have to be removed and the debugging
can be based on this new logging structure which can tell where
an error (or debug output) occured whch the current implmentation
cannot.

The one limitation is the new macros cannot take a char* for the
format parameter. It must be an actual string literal because it
is concatenated with other strings.

Signed-off-by: default avatarMark Charlebois <charlebm@gmail.com>
parent f56990a9
No related branches found
No related tags found
No related merge requests found
......@@ -85,11 +85,10 @@ Device::log(const char *fmt, ...)
PX4_INFO("[%s] ", _name);
va_start(ap, fmt);
PX4_INFO( fmt, ap );
//vprintf(fmt, ap);
vprintf(fmt, ap);
va_end(ap);
//printf("\n");
//fflush(stdout);
printf("\n");
fflush(stdout);
}
void
......@@ -98,14 +97,12 @@ Device::debug(const char *fmt, ...)
va_list ap;
if (_debug_enabled) {
PX4_INFO("<%s> ", _name);
//printf("<%s> ", _name);
printf("<%s> ", _name);
va_start(ap, fmt);
//vprintf(fmt, ap);
PX4_INFO(fmt, ap);
vprintf(fmt, ap);
va_end(ap);
//printf("\n");
//fflush(stdout);
printf("\n");
fflush(stdout);
}
}
......
......@@ -269,14 +269,15 @@ arming_state_transition(struct vehicle_status_s *status, ///< current vehicle s
}
if (ret == TRANSITION_DENIED) {
const char * str = "INVAL: %s - %s";
#define WARNSTR "INVAL: %s - %s"
/* only print to console here by default as this is too technical to be useful during operation */
warnx(str, state_names[status->arming_state], state_names[new_arming_state]);
warnx(WARNSTR, state_names[status->arming_state], state_names[new_arming_state]);
/* print to MAVLink if we didn't provide any feedback yet */
if (!feedback_provided) {
mavlink_log_critical(mavlink_fd, str, state_names[status->arming_state], state_names[new_arming_state]);
mavlink_log_critical(mavlink_fd, WARNSTR, state_names[status->arming_state], state_names[new_arming_state]);
}
#undef WARNSTR
}
return ret;
......
......@@ -2,5 +2,6 @@
# Common OS porting APIs
#
SRCS = px4_getopt.c
SRCS = px4_getopt.c \
px4_log.c
#include <px4_log.h>
__EXPORT unsigned int __px4_log_level_current = PX4_LOG_LEVEL_AT_RUN_TIME;
__EXPORT const char *__px4_log_level_str[_PX4_LOG_LEVEL_DEBUG+1] = { "INFO", "PANIC", "ERROR", "WARN", "DEBUG" };
......@@ -32,92 +32,136 @@
****************************************************************************/
/**
* @file px4_log.h
* Platform dependant logging/debug
* @file px4_log_os_impl.h
* Platform dependant logging/debug implementation
*/
#pragma once
#define __px4_log_omit(level, ...) { }
#define __px4_log(level, ...) { \
printf("%-5s ", level);\
printf(__VA_ARGS__);\
printf("\n");\
}
#define __px4_log_verbose(level, ...) { \
printf("%-5s ", level);\
printf(__VA_ARGS__);\
printf(" (file %s line %d)\n", __FILE__, __LINE__);\
}
#if defined(__PX4_QURT)
#define __STDC_FORMAT_MACROS
#include <inttypes.h>
#include <stdint.h>
#include <sys/cdefs.h>
#include <stdio.h>
#define FARF printf
#define __FARF_omit(level, ...) { }
#define __FARF_log(level, ...) { \
FARF("%-5s ", level);\
FARF(__VA_ARGS__);\
FARF("\n");\
}
#define __FARF_log_verbose(level, ...) { \
FARF("%-5s ", level);\
FARF(__VA_ARGS__);\
FARF(" (file %s line %d)\n", __FILE__, __LINE__);\
}
#define PX4_DEBUG(...) __FARF_omit("DEBUG", __VA_ARGS__)
#define PX4_INFO(...) __FARF_log("INFO", __VA_ARGS__)
#define PX4_WARN(...) __FARF_log_verbose("WARN", __VA_ARGS__)
#define PX4_ERR(...) __FARF_log_verbose("ERROR", __VA_ARGS__)
#elif defined(__PX4_LINUX)
#include <stdio.h>
#include <pthread.h>
#define __px4_log_threads(level, ...) { \
printf("%-5s %ld ", level, pthread_self());\
printf(__VA_ARGS__);\
printf(" (file %s line %d)\n", __FILE__, __LINE__);\
}
__BEGIN_DECLS
__EXPORT extern uint64_t hrt_absolute_time(void);
//__EXPORT extern unsigned long pthread_self();
#define PX4_DEBUG(...) __px4_log_omit("DEBUG", __VA_ARGS__)
#define PX4_INFO(...) __px4_log("INFO", __VA_ARGS__)
#define PX4_WARN(...) __px4_log_verbose("WARN", __VA_ARGS__)
#define PX4_ERR(...) __px4_log_verbose("ERROR", __VA_ARGS__)
#define _PX4_LOG_LEVEL_ALWAYS 0
#define _PX4_LOG_LEVEL_PANIC 1
#define _PX4_LOG_LEVEL_ERROR 2
#define _PX4_LOG_LEVEL_WARN 3
#define _PX4_LOG_LEVEL_DEBUG 4
#elif defined(__PX4_DARWIN)
#include <stdio.h>
#include <pthread.h>
extern const char *__px4_log_level_str[5];
extern unsigned int __px4_log_level_current;
#define PX4_LOG_LEVEL_AT_RUN_TIME _PX4_LOG_LEVEL_WARN
#define __px4_log_threads(level, ...) { \
printf("%-5s %ld ", level, pthread_self());\
printf(__VA_ARGS__);\
printf(" (file %s line %d)\n", __FILE__, __LINE__);\
}
#define _PX4_LOG_LEVEL_STR(level) __px4_log_level_str[level];
/****************************************************************************
* Implementation of log section formatting based on printf
****************************************************************************/
#if defined(__PX4_ROS)
#define __px4__log_startline(level) if (level <= __px4_log_level_current) ROS_WARN(
#else
#define __px4__log_startline(level) if (level <= __px4_log_level_current) printf(
#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 "%ld "
#define __px4__log_thread_arg ,pthread_self()
#define __px4__log_file_and_line_fmt " (file %s line %d)"
#define __px4__log_file_and_line_arg , __FILE__, __LINE__
#define __px4__log_end_fmt "\n"
#define __px4__log_endline )
#define PX4_DEBUG(...) __px4_log_omit("DEBUG", __VA_ARGS__)
#define PX4_INFO(...) __px4_log("INFO", __VA_ARGS__)
#define PX4_WARN(...) __px4_log_verbose("WARN", __VA_ARGS__)
#define PX4_ERR(...) __px4_log_verbose("ERROR", __VA_ARGS__)
/****************************************************************************
* Output format macros
* Use these to implement the code level macros below
****************************************************************************/
#define __px4_log_omit(level, FMT, ...) { }
#define __px4_log(level, FMT, ...) \
__px4__log_startline(level)\
__px4__log_level_fmt \
FMT\
__px4__log_end_fmt \
__px4__log_level_arg(level), ##__VA_ARGS__\
__px4__log_endline
#define __px4_log_timestamp(level, FMT, ...) \
__px4__log_startline(level)\
__px4__log_timestamp_fmt\
__px4__log_level_fmt\
FMT\
__px4__log_end_fmt\
__px4__log_timestamp_arg\
__px4__log_level_arg(level), ##__VA_ARGS__\
__px4__log_endline
#define __px4_log_file_and_line(level, FMT, ...) \
__px4__log_startline(level)\
__px4__log_timestamp_fmt\
__px4__log_level_fmt\
FMT\
__px4__log_file_and_line_fmt\
__px4__log_end_fmt\
__px4__log_timestamp_arg\
__px4__log_level_arg(level), ##__VA_ARGS__\
__px4__log_file_and_line_arg\
__px4__log_endline
#define __px4_log_timestamp_file_and_line(level, FMT, ...) \
__px4__log_startline(level)\
__px4__log_timestamp_fmt\
__px4__log_level_fmt\
FMT\
__px4__log_file_and_line_fmt\
__px4__log_end_fmt\
__px4__log_timestamp_arg\
__px4__log_level_arg(level) , ##__VA_ARGS__\
__px4__log_file_and_line_arg\
__px4__log_endline
#define __px4_log_thread_file_and_line(level, FMT, ...) \
__px4__log_startline(level)\
__px4__log_thread_fmt\
__px4__log_level_fmt\
FMT\
__px4__log_file_and_line_fmt\
__px4__log_end_fmt\
__px4__log_thread_arg\
__px4__log_level_arg(level) , ##__VA_ARGS__\
__px4__log_file_and_line_arg\
__px4__log_endline
#elif defined(__PX4_ROS)
#define PX4_DBG(...)
#define PX4_INFO(...) ROS_WARN(__VA_ARGS__)
#define PX4_WARN(...) ROS_WARN(__VA_ARGS__)
#define PX4_ERR(...) ROS_WARN(__VA_ARGS__)
/****************************************************************************
* Code level macros
* These are the log APIs that should be used by the code
****************************************************************************/
#define PX4_LOG(FMT, ...) __px4_log(_PX4_LOG_LEVEL_ALWAYS, FMT, __VA_ARGS__)
#elif defined(__PX4_NUTTX)
#include <systemlib/err.h>
#if defined(DEBUG_BUILD)
#define PX4_DBG(...)
#define PX4_INFO(...) warnx(__VA_ARGS__)
#define PX4_WARN(...) warnx(__VA_ARGS__)
#define PX4_ERR(...) warnx(__VA_ARGS__)
#define PX4_PANIC(FMT, ...) __px4_log_timestamp_file_and_line(_PX4_LOG_LEVEL_PANIC, FMT, ##__VA_ARGS__)
#define PX4_ERR(FMT, ...) __px4_log_timestamp_file_and_line(_PX4_LOG_LEVEL_ERROR, FMT, ##__VA_ARGS__)
#define PX4_WARN(FMT, ...) __px4_log_timestamp_file_and_line(_PX4_LOG_LEVEL_WARN, FMT, ##__VA_ARGS__)
#define PX4_DEBUG(FMT, ...) __px4_log_timestamp(_PX4_LOG_LEVEL_DEBUG, FMT, __VA_ARGS__)
#else
#error "Target platform unknown"
#define PX4_PANIC(FMT, ...) __px4_log_file_and_line(_PX4_LOG_LEVEL_PANIC, FMT, ##__VA_ARGS__)
#define PX4_ERR(FMT, ...) __px4_log_file_and_line(_PX4_LOG_LEVEL_ERROR, FMT, ##__VA_ARGS__)
#define PX4_WARN(FMT, ...) __px4_log_file_and_line(_PX4_LOG_LEVEL_WARN, FMT, ##__VA_ARGS__)
#define PX4_INFO(FMT, ...) __px4_log(_PX4_LOG_LEVEL_WARN, FMT, ##__VA_ARGS__)
#define PX4_DEBUG(FMT, ...) __px4_log_omit(_PX4_LOG_LEVEL_DEBUG, FMT, ##__VA_ARGS__)
#endif
__END_DECLS
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment