From 1b10008e38abecb25416c246019aad6aefa2a067 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 14 Jun 2023 12:39:46 -0400 Subject: [PATCH] AP_Math: use message with static assertion --- libraries/AP_Math/AP_Math.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index a333cac5cb..e784486e92 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -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.