mirror of https://github.com/ArduPilot/ardupilot
AP_Math: use message with static assertion
This commit is contained in:
parent
d9869290ee
commit
1b10008e38
|
@ -531,7 +531,7 @@ int32_t double_to_int32(const double v)
|
|||
int32_t float_to_int32_le(const float& value)
|
||||
{
|
||||
int32_t out;
|
||||
static_assert(sizeof(value) == sizeof(out));
|
||||
static_assert(sizeof(value) == sizeof(out), "mismatched sizes");
|
||||
|
||||
// Use memcpy because it's the most portable.
|
||||
// It might not be the fastest way on all hardware.
|
||||
|
@ -543,7 +543,7 @@ int32_t float_to_int32_le(const float& value)
|
|||
float int32_to_float_le(const uint32_t& value)
|
||||
{
|
||||
float out;
|
||||
static_assert(sizeof(value) == sizeof(out));
|
||||
static_assert(sizeof(value) == sizeof(out), "mismatched sizes");
|
||||
|
||||
// Use memcpy because it's the most portable.
|
||||
// It might not be the fastest way on all hardware.
|
||||
|
@ -555,7 +555,7 @@ float int32_to_float_le(const uint32_t& value)
|
|||
double uint64_to_double_le(const uint64_t& value)
|
||||
{
|
||||
double out;
|
||||
static_assert(sizeof(value) == sizeof(out));
|
||||
static_assert(sizeof(value) == sizeof(out), "mismatched sizes");
|
||||
|
||||
// Use memcpy because it's the most portable.
|
||||
// It might not be the fastest way on all hardware.
|
||||
|
|
Loading…
Reference in New Issue