mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
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:
parent
fb3b976aa2
commit
3a79ae4eca
@ -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")),
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user