mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-06 11:06:42 +08:00
AP_Param: work around Clang -ftrapping-math issue
In Clang (independent of OS or architecture), if three factors are true about a static variable initialization (const or not): * `-ftrapping-math` is turned on * a double literal needs to be rounded and doesn't exactly equal a float * the initialization involves something which isn't constexpr then Clang will decline to do constant initialization, unlike GCC, or Clang if any one of these factors is not true. Constant initialization is where the object is initialized as part of the memory image and is ready to go when the program is loaded. Instead, Clang will generate code at runtime to do the initialization. This is fine in a vacuum, but it makes lots more variables suddenly vulnerable to the static initialization order fiasco. In particular, many of the `AP_Param::Info` tables for the parameter system meet all the factors. The use for these tables, `AP_Param::setup_object_defaults`, is part of constructors of objects which are usually constructed in a different file than the table. Due to the new runtime initialization, there is no longer a guarantee that the table has meaningful data at the time of that setup call. This causes many parameter defaults to not be loaded and the system generally crashes and burns. This PR addresses the issue by fixing the non-constexpr casts in `AP_VAROFFSET` and `AP_CLASSTYPE` to use things permissible in constexpr. The compiler then constant initializes these tables again, parameters get their defaults, and everybody is happy. This is probably easier than fixing all the double literals to be floats. This fix could be "locked in" and be made to cause a compiler error in case of a problem by declaring all tables `constexpr`, but that is a lot of effort. Examination of the binary symbol tables shows that all `var_info` tables are correctly constant initialized now.
This commit is contained in:
committed by
Andrew Tridgell
parent
8c3b38655a
commit
d70cefdb90
@@ -23,6 +23,7 @@
|
||||
#include <string.h>
|
||||
#include <stdint.h>
|
||||
#include <cmath>
|
||||
#include <type_traits>
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/utility/RingBuffer.h>
|
||||
@@ -121,13 +122,19 @@
|
||||
#define AP_PARAM_FRAME_HELI (1<<5)
|
||||
#define AP_PARAM_FRAME_BLIMP (1<<6)
|
||||
|
||||
// a variant of offsetof() to work around C++ restrictions.
|
||||
// this can only be used when the offset of a variable in a object
|
||||
// is constant and known at compile time
|
||||
#define AP_VAROFFSET(type, element) (((ptrdiff_t)(&((const type *)1)->element))-1)
|
||||
// use __builtin_offsetof which is more or less defined by Clang and GCC to work
|
||||
// on non-standard-layout C++ classes, and works in constexpr. as that isn't
|
||||
// standard-compliant, it raises "-Winvalid-offsetof" which we globally disable.
|
||||
// https://github.com/llvm/llvm-project/blob/5fa5ffeb6cb5bc9aa414c02513e44b8405f0e7cc/libcxx/include/__type_traits/datasizeof.h#L51
|
||||
// the first comma operator operand makes the compiler see element as used by
|
||||
// conjuring a class instance and passing element to an unevaluating function.
|
||||
#define AP_VAROFFSET(clazz, element) ((void)sizeof(std::declval<clazz>().element), (ptrdiff_t)__builtin_offsetof(clazz, element))
|
||||
|
||||
// find the type of a variable given the class and element
|
||||
#define AP_CLASSTYPE(clazz, element) ((uint8_t)(((const clazz *) 1)->element.vtype))
|
||||
// get the internal type of an AP_Param variable given an arbitrary class and an
|
||||
// element on it. convert the element, which must be of type AP_Param or a
|
||||
// subclass, into a non-reference type. then get AP_Param's vtype member, which
|
||||
// is static const but varies depending on the subclass. works in constexpr!
|
||||
#define AP_CLASSTYPE(clazz, element) ((uint8_t)(std::remove_reference<decltype(clazz::element)>::type::vtype))
|
||||
|
||||
// declare a group var_info line
|
||||
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags) { name, AP_VAROFFSET(clazz, element), {def_value : def}, flags, idx, AP_CLASSTYPE(clazz, element)}
|
||||
|
||||
Reference in New Issue
Block a user