Skip to content

Commit 2058352

Browse files
committed
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.
1 parent 650f79e commit 2058352

File tree

1 file changed

+14
-7
lines changed

1 file changed

+14
-7
lines changed

libraries/AP_Param/AP_Param.h

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include <string.h>
2424
#include <stdint.h>
2525
#include <cmath>
26+
#include <type_traits>
2627

2728
#include <AP_HAL/AP_HAL.h>
2829
#include <AP_HAL/utility/RingBuffer.h>
@@ -121,13 +122,19 @@
121122
#define AP_PARAM_FRAME_HELI (1<<5)
122123
#define AP_PARAM_FRAME_BLIMP (1<<6)
123124

124-
// a variant of offsetof() to work around C++ restrictions.
125-
// this can only be used when the offset of a variable in a object
126-
// is constant and known at compile time
127-
#define AP_VAROFFSET(type, element) (((ptrdiff_t)(&((const type *)1)->element))-1)
128-
129-
// find the type of a variable given the class and element
130-
#define AP_CLASSTYPE(clazz, element) ((uint8_t)(((const clazz *) 1)->element.vtype))
125+
// use __builtin_offsetof which is more or less defined by Clang and GCC to work
126+
// on non-standard-layout C++ classes, and works in constexpr. as that isn't
127+
// standard-compliant, it raises "-Winvalid-offsetof" which we globally disable.
128+
// https://github.com/llvm/llvm-project/blob/5fa5ffeb6cb5bc9aa414c02513e44b8405f0e7cc/libcxx/include/__type_traits/datasizeof.h#L51
129+
// the first comma operator operand makes the compiler see element as used by
130+
// conjuring a class instance and passing element to an unevaluating function.
131+
#define AP_VAROFFSET(clazz, element) ((void)sizeof(std::declval<clazz>().element), (ptrdiff_t)__builtin_offsetof(clazz, element))
132+
133+
// get the internal type of an AP_Param variable given an arbitrary class and an
134+
// element on it. convert the element, which must be of type AP_Param or a
135+
// subclass, into a non-reference type. then get AP_Param's vtype member, which
136+
// is static const but varies depending on the subclass. works in constexpr!
137+
#define AP_CLASSTYPE(clazz, element) ((uint8_t)(std::remove_reference<decltype(clazz::element)>::type::vtype))
131138

132139
// declare a group var_info line
133140
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags) { name, AP_VAROFFSET(clazz, element), {def_value : def}, flags, idx, AP_CLASSTYPE(clazz, element)}

0 commit comments

Comments
 (0)