Browse Source

Merge pull request #2406 from mcharleb/logging-v3

Improved logging with both compile and runtime level filtering
sbg
Lorenz Meier 10 years ago
parent
commit
509ec90b76
  1. 17
      src/drivers/device/device_posix.cpp
  2. 7
      src/modules/commander/state_machine_helper.cpp
  3. 3
      src/platforms/common/module.mk
  4. 5
      src/platforms/common/px4_log.c
  5. 315
      src/platforms/px4_log.h
  6. 6
      unittests/CMakeLists.txt

17
src/drivers/device/device_posix.cpp

@ -85,11 +85,10 @@ Device::log(const char *fmt, ...) @@ -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, ...) @@ -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);
}
}

7
src/modules/commander/state_machine_helper.cpp

@ -268,14 +268,15 @@ arming_state_transition(struct vehicle_status_s *status, ///< current vehicle s @@ -268,14 +268,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;

3
src/platforms/common/module.mk

@ -2,5 +2,6 @@ @@ -2,5 +2,6 @@
# Common OS porting APIs
#
SRCS = px4_getopt.c
SRCS = px4_getopt.c \
px4_log.c

5
src/platforms/common/px4_log.c

@ -0,0 +1,5 @@ @@ -0,0 +1,5 @@
#include <px4_log.h>
__EXPORT 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" };

315
src/platforms/px4_log.h

@ -33,91 +33,276 @@ @@ -33,91 +33,276 @@
/**
* @file px4_log.h
* Platform dependant logging/debug
* Platform dependant logging/debug implementation
*/
#pragma once
#define __px4_log_omit(level, ...) { }
#if defined(__PX4_ROS)
#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)
#include <ros/console.h>
#define PX4_PANIC(...) ROS_WARN(__VA_ARGS__)
#define PX4_ERR(...) ROS_WARN(__VA_ARGS__)
#define PX4_WARN(...) ROS_WARN(__VA_ARGS__)
#define PX4_INFO(...) ROS_WARN(__VA_ARGS__)
#define PX4_DEBUG(...)
#else
#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__);\
__BEGIN_DECLS
__EXPORT extern uint64_t hrt_absolute_time(void);
// Used to silence unused variable warning
static inline void do_nothing(int level, ...)
{
(void)level;
}
#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__)
#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_LINUX)
#include <stdio.h>
#include <pthread.h>
__EXPORT extern const char *__px4_log_level_str[5];
__EXPORT extern int __px4_log_level_current;
#define __px4_log_threads(level, ...) { \
printf("%-5s %ld ", level, pthread_self());\
printf(__VA_ARGS__);\
printf(" (file %s line %d)\n", __FILE__, __LINE__);\
}
// __px4_log_level_current will be initialized to PX4_LOG_LEVEL_AT_RUN_TIME
#define PX4_LOG_LEVEL_AT_RUN_TIME _PX4_LOG_LEVEL_WARN
#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__)
/****************************************************************************
* Implementation of log section formatting based on printf
*
* To write to a specific stream for each message type, open the streams and
* set __px4__log_startline to something like:
* if (level <= __px4_log_level_current) printf(_px4_fd[level],
*
* Additional behavior can be added using "{\" for __px4__log_startline and
* "}" for __px4__log_endline and any other required setup or teardown steps
****************************************************************************/
#define __px4__log_startline(level) if (level <= __px4_log_level_current) printf(
#elif defined(__PX4_DARWIN)
#include <stdio.h>
#include <pthread.h>
#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 ,pthread_self()
#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_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 )
#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
****************************************************************************/
#elif defined(__PX4_ROS)
/****************************************************************************
* __px4_log_omit:
* Compile out the message
****************************************************************************/
#define __px4_log_omit(level, FMT, ...) do_nothing(level, ##__VA_ARGS__)
#define PX4_DBG(...)
#define PX4_INFO(...) ROS_WARN(__VA_ARGS__)
#define PX4_WARN(...) ROS_WARN(__VA_ARGS__)
#define PX4_ERR(...) ROS_WARN(__VA_ARGS__)
/****************************************************************************
* __px4_log:
* Convert a message in the form:
* PX4_WARN("val is %d", val);
* to
* printf("%-5s val is %d\n", __px4_log_level_str[3], val);
****************************************************************************/
#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
#elif defined(__PX4_NUTTX)
#include <systemlib/err.h>
/****************************************************************************
* __px4_log_timestamp:
* Convert a message in the form:
* PX4_WARN("val is %d", val);
* to
* printf("%-5s %10lu val is %d\n", __px4_log_level_str[3],
* hrt_absolute_time(), val);
****************************************************************************/
#define __px4_log_timestamp(level, FMT, ...) \
__px4__log_startline(level)\
__px4__log_level_fmt\
__px4__log_timestamp_fmt\
FMT\
__px4__log_end_fmt\
__px4__log_level_arg(level)\
__px4__log_timestamp_arg\
, ##__VA_ARGS__\
__px4__log_endline
#define PX4_DBG(...)
#define PX4_INFO(...) warnx(__VA_ARGS__)
#define PX4_WARN(...) warnx(__VA_ARGS__)
#define PX4_ERR(...) warnx(__VA_ARGS__)
/****************************************************************************
* __px4_log_timestamp_thread:
* Convert a message in the form:
* PX4_WARN("val is %d", val);
* to
* printf("%-5s %10lu %#X val is %d\n", __px4_log_level_str[3],
* hrt_absolute_time(), pthread_self(), val);
****************************************************************************/
#define __px4_log_timestamp_thread(level, FMT, ...) \
__px4__log_startline(level)\
__px4__log_level_fmt\
__px4__log_timestamp_fmt\
__px4__log_thread_fmt\
FMT\
__px4__log_end_fmt\
__px4__log_level_arg(level)\
__px4__log_timestamp_arg\
__px4__log_thread_arg\
, ##__VA_ARGS__\
__px4__log_endline
#else
/****************************************************************************
* __px4_log_file_and_line:
* Convert a message in the form:
* PX4_WARN("val is %d", val);
* to
* printf("%-5s val is %d (file %s line %u)\n",
* __px4_log_level_str[3], val, __FILE__, __LINE__);
****************************************************************************/
#define __px4_log_file_and_line(level, FMT, ...) \
__px4__log_startline(level)\
__px4__log_level_fmt\
__px4__log_timestamp_fmt\
FMT\
__px4__log_file_and_line_fmt\
__px4__log_end_fmt\
__px4__log_level_arg(level)\
__px4__log_timestamp_arg\
, ##__VA_ARGS__\
__px4__log_file_and_line_arg\
__px4__log_endline
#error "Target platform unknown"
/****************************************************************************
* __px4_log_timestamp_file_and_line:
* Convert a message in the form:
* PX4_WARN("val is %d", val);
* to
* printf("%-5s %-10lu val is %d (file %s line %u)\n",
* __px4_log_level_str[3], hrt_absolute_time(),
* val, __FILE__, __LINE__);
****************************************************************************/
#define __px4_log_timestamp_file_and_line(level, FMT, ...) \
__px4__log_startline(level)\
__px4__log_level_fmt\
__px4__log_timestamp_fmt\
FMT\
__px4__log_file_and_line_fmt\
__px4__log_end_fmt\
__px4__log_level_arg(level)\
__px4__log_timestamp_arg\
, ##__VA_ARGS__\
__px4__log_file_and_line_arg\
__px4__log_endline
/****************************************************************************
* __px4_log_thread_file_and_line:
* Convert a message in the form:
* PX4_WARN("val is %d", val);
* to
* printf("%-5s %#X val is %d (file %s line %u)\n",
* __px4_log_level_str[3], pthread_self(),
* val, __FILE__, __LINE__);
****************************************************************************/
#define __px4_log_thread_file_and_line(level, FMT, ...) \
__px4__log_startline(level)\
__px4__log_level_fmt\
__px4__log_thread_fmt\
FMT\
__px4__log_file_and_line_fmt\
__px4__log_end_fmt\
__px4__log_level_arg(level)\
__px4__log_thread_arg\
, ##__VA_ARGS__\
__px4__log_file_and_line_arg\
__px4__log_endline
/****************************************************************************
* __px4_log_timestamp_thread_file_and_line:
* Convert a message in the form:
* PX4_WARN("val is %d", val);
* to
* printf("%-5s %-10lu %#X val is %d (file %s line %u)\n",
* __px4_log_level_str[3], hrt_absolute_time(),
* pthread_self(), val, __FILE__, __LINE__);
****************************************************************************/
#define __px4_log_timestamp_thread_file_and_line(level, FMT, ...) \
__px4__log_startline(level)\
__px4__log_level_fmt\
__px4__log_timestamp_fmt\
__px4__log_thread_fmt\
FMT\
__px4__log_file_and_line_fmt\
__px4__log_end_fmt\
__px4__log_level_arg(level)\
__px4__log_timestamp_arg\
__px4__log_thread_arg\
, ##__VA_ARGS__\
__px4__log_file_and_line_arg\
__px4__log_endline
/****************************************************************************
* Code level macros
* These are the log APIs that should be used by the code
****************************************************************************/
/****************************************************************************
* 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__)
#if defined(TRACE_BUILD)
/****************************************************************************
* Extremely Verbose settings for a Trace build
****************************************************************************/
#define PX4_PANIC(FMT, ...) __px4_log_timestamp_thread_file_and_line(_PX4_LOG_LEVEL_PANIC, FMT, ##__VA_ARGS__)
#define PX4_ERR(FMT, ...) __px4_log_timestamp_thread_file_and_line(_PX4_LOG_LEVEL_ERROR, FMT, ##__VA_ARGS__)
#define PX4_WARN(FMT, ...) __px4_log_timestamp_thread_file_and_line(_PX4_LOG_LEVEL_WARN, FMT, ##__VA_ARGS__)
#define PX4_DEBUG(FMT, ...) __px4_log_timestamp_thread(_PX4_LOG_LEVEL_DEBUG, FMT, __VA_ARGS__)
#elif defined(DEBUG_BUILD)
/****************************************************************************
* Verbose settings for a Debug build
****************************************************************************/
#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__)
#elif defined(RELEASE_BUILD)
/****************************************************************************
* Non-verbose settings for a Release build to minimize strings in build
****************************************************************************/
#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_omit(_PX4_LOG_LEVEL_WARN, FMT, ##__VA_ARGS__)
#define PX4_DEBUG(FMT, ...) __px4_log_omit(_PX4_LOG_LEVEL_DEBUG, FMT, ##__VA_ARGS__)
#else
/****************************************************************************
* Medium verbose settings for a default build
****************************************************************************/
#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_DEBUG(FMT, ...) __px4_log_omit(_PX4_LOG_LEVEL_DEBUG, FMT, ##__VA_ARGS__)
#endif
__END_DECLS
#endif

6
unittests/CMakeLists.txt

@ -75,6 +75,7 @@ endfunction() @@ -75,6 +75,7 @@ endfunction()
add_library( px4_platform
# ${PX_SRC}/platforms/common/px4_getopt.c
${PX_SRC}/platforms/common/px4_log.c
${PX_SRC}/platforms/posix/px4_layer/px4_posix_impl.cpp
${PX_SRC}/platforms/posix/px4_layer/px4_posix_tasks.cpp
${PX_SRC}/platforms/posix/px4_layer/work_lock.c
@ -130,22 +131,27 @@ add_gtest(mixer_test) @@ -130,22 +131,27 @@ add_gtest(mixer_test)
# conversion_test
add_executable(conversion_test conversion_test.cpp ${PX_SRC}/systemcmds/tests/test_conv.cpp)
target_link_libraries( conversion_test px4_platform )
add_gtest(conversion_test)
# sbus2_test
add_executable(sbus2_test sbus2_test.cpp hrt.cpp)
target_link_libraries( sbus2_test px4_platform )
add_gtest(sbus2_test)
# st24_test
add_executable(st24_test st24_test.cpp hrt.cpp ${PX_SRC}/lib/rc/st24.c)
target_link_libraries( st24_test px4_platform )
add_gtest(st24_test)
# sumd_test
add_executable(sumd_test sumd_test.cpp hrt.cpp ${PX_SRC}/lib/rc/sumd.c)
target_link_libraries( sumd_test px4_platform )
add_gtest(sumd_test)
# sf0x_test
add_executable(sf0x_test sf0x_test.cpp ${PX_SRC}/drivers/sf0x/sf0x_parser.cpp)
target_link_libraries( sf0x_test px4_platform )
add_gtest(sf0x_test)
# param_test

Loading…
Cancel
Save