mirror of https://github.com/ArduPilot/ardupilot
AP_Common: Add type-punning alternative
Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
parent
35ebc25172
commit
d40b02fbbd
|
@ -101,3 +101,39 @@ int16_t char_to_hex(char a)
|
|||
else
|
||||
return a - '0';
|
||||
}
|
||||
|
||||
int32_t to_int32(const float value)
|
||||
{
|
||||
int32_t out;
|
||||
static_assert(sizeof(value) == sizeof(out));
|
||||
|
||||
// Use memcpy because it's the most portable.
|
||||
// It might not be the fastest way on all hardware.
|
||||
// At least it's defined behavior in both c and c++.
|
||||
memcpy(&out, &value, sizeof(out));
|
||||
return out;
|
||||
}
|
||||
|
||||
float to_float(const uint32_t value)
|
||||
{
|
||||
float out;
|
||||
static_assert(sizeof(value) == sizeof(out));
|
||||
|
||||
// Use memcpy because it's the most portable.
|
||||
// It might not be the fastest way on all hardware.
|
||||
// At least it's defined behavior in both c and c++.
|
||||
memcpy(&out, &value, sizeof(out));
|
||||
return out;
|
||||
}
|
||||
|
||||
double to_double(const uint64_t value)
|
||||
{
|
||||
double out;
|
||||
static_assert(sizeof(value) == sizeof(out));
|
||||
|
||||
// Use memcpy because it's the most portable.
|
||||
// It might not be the fastest way on all hardware.
|
||||
// At least it's defined behavior in both c and c++.
|
||||
memcpy(&out, &value, sizeof(out));
|
||||
return out;
|
||||
}
|
||||
|
|
|
@ -178,3 +178,19 @@ template <typename T> void BIT_CLEAR (T& value, uint8_t bitnumber) noexcept {
|
|||
static_assert(std::is_integral<T>::value, "Integral required.");
|
||||
((value) &= ~((T)(1U) << (bitnumber)));
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
Convert from float to int32_t without breaking Wstrict-aliasing due to type punning
|
||||
*/
|
||||
int32_t to_int32(const float value) WARN_IF_UNUSED;
|
||||
|
||||
/*
|
||||
Convert from uint32_t to float without breaking Wstrict-aliasing due to type punning
|
||||
*/
|
||||
float to_float(const uint32_t value) WARN_IF_UNUSED;
|
||||
|
||||
/*
|
||||
Convert from uint64_t to double without breaking Wstrict-aliasing due to type punning
|
||||
*/
|
||||
double to_double(const uint64_t value) WARN_IF_UNUSED;
|
||||
|
|
Loading…
Reference in New Issue