AP_NavEKF2: use union to alias array and struct access to states

This avoids creating two pointers of different types to the same memory.

Having two pointers to the same memory can lead to the compiler
optimising code such that a write to one pointer is rearranged to be
either before or after a read from the other pointer depending on which
is deemed faster - not a good outcome.
This commit is contained in:
Peter Barker 2018-10-01 09:42:28 +10:00 committed by Peter Barker
parent fb3b976aa2
commit 3a79ae4eca
2 changed files with 6 additions and 4 deletions

View File

@ -21,8 +21,6 @@ extern const AP_HAL::HAL& hal;
// constructor
NavEKF2_core::NavEKF2_core(void) :
stateStruct(*reinterpret_cast<struct state_elements *>(&statesArray)),
_perf_UpdateFilter(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_UpdateFilter")),
_perf_CovariancePrediction(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_CovariancePrediction")),
_perf_FuseVelPosNED(hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, "EK2_FuseVelPosNED")),

View File

@ -383,7 +383,6 @@ private:
// the states are available in two forms, either as a Vector31, or
// broken down as individual elements. Both are equivalent (same
// memory)
Vector28 statesArray;
struct state_elements {
Vector3f angErr; // 0..2
Vector3f velocity; // 3..5
@ -395,7 +394,12 @@ private:
Vector3f body_magfield; // 19..21
Vector2f wind_vel; // 22..23
Quaternion quat; // 24..27
} &stateStruct;
};
union {
Vector28 statesArray;
struct state_elements stateStruct;
};
struct output_elements {
Quaternion quat; // 0..3