mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Common: add macro to ignore unused result
In some cases we want to call functions annotated with warn_unused_result but we know it's safe to ignore the return value. Prefixing with (void) used to work, but it doesn't do anymore on all versions of gcc and clang. See: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=66425 This solution is a mix of the solutions provided in the above bug report and the one provided by Gustavo Sousa at https://github.com/ArduPilot/ardupilot/pull/4277#issuecomment-224957375
This commit is contained in:
parent
d3ed17f047
commit
8a58c06adb
@ -64,6 +64,27 @@ char (&_ARRAY_SIZE_HELPER(T (&_arr)[0]))[0];
|
||||
|
||||
#define ARRAY_SIZE(_arr) sizeof(_ARRAY_SIZE_HELPER(_arr))
|
||||
|
||||
/*
|
||||
* See UNUSED_RESULT. The difference is that it receives @uniq_ as the name to
|
||||
* be used for its internal variable.
|
||||
*
|
||||
* @uniq_: a unique name to use for variable name
|
||||
* @expr_: the expression to be evaluated
|
||||
*/
|
||||
#define _UNUSED_RESULT(uniq_, expr_) \
|
||||
do { \
|
||||
decltype(expr_) uniq_ __attribute__((unused)); \
|
||||
uniq_ = expr_; \
|
||||
} while (0)
|
||||
|
||||
/*
|
||||
* Allow to call a function annotated with warn_unused_result attribute
|
||||
* without getting a warning, because sometimes this is what we want to do.
|
||||
*
|
||||
* @expr_: the expression to be evaluated
|
||||
*/
|
||||
#define UNUSED_RESULT(expr_) _UNUSED_RESULT(__unique_name_##__COUNTER__, expr_)
|
||||
|
||||
// @}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user