diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 38a547282f..d47b45d89f 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -361,7 +361,7 @@ int commander_main(int argc, char *argv[]) if (!strcmp(argv[1], "check")) { int mavlink_fd_local = open(MAVLINK_LOG_DEVICE, 0); - int checkres __attribute__ ((unused)) = prearm_check(&status, mavlink_fd_local); + int checkres = prearm_check(&status, mavlink_fd_local); close(mavlink_fd_local); warnx("FINAL RESULT: %s", (checkres == 0) ? "OK" : "FAILED"); return 0; diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 67e45154cb..270804075e 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -1936,8 +1936,8 @@ void sdlog2_status() } else { float kibibytes = log_bytes_written / 1024.0f; - float mebibytes __attribute__ ((unused)) = kibibytes / 1024.0f; - float seconds __attribute__ ((unused)) = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f; + float mebibytes = kibibytes / 1024.0f; + float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f; warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped); mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs", log_msgs_written, log_msgs_skipped); diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 484092c747..0be31046b1 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -706,7 +706,7 @@ Sensors::parameters_update() warnx("WARNING WARNING WARNING\n\nRC CALIBRATION NOT SANE!\n\n"); } - const char *paramerr __attribute__ ((unused)) = "FAIL PARM LOAD"; + const char *paramerr = "FAIL PARM LOAD"; /* channel mapping */ if (param_get(_parameter_handles.rc_map_roll, &(_parameters.rc_map_roll)) != OK) { diff --git a/src/platforms/px4_log.h b/src/platforms/px4_log.h index 05278131c8..327df7abe1 100644 --- a/src/platforms/px4_log.h +++ b/src/platforms/px4_log.h @@ -58,6 +58,12 @@ __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_LOG_LEVEL_ALWAYS 0 #define _PX4_LOG_LEVEL_PANIC 1 #define _PX4_LOG_LEVEL_ERROR 2 @@ -103,7 +109,7 @@ __EXPORT extern int __px4_log_level_current; * __px4_log_omit: * Compile out the message ****************************************************************************/ -#define __px4_log_omit(level, FMT, ...) { } +#define __px4_log_omit(level, FMT, ...) do_nothing(level, ##__VA_ARGS__) /**************************************************************************** * __px4_log: