From 5488ca6403f1cbd40de691cf25beaa065db2717f Mon Sep 17 00:00:00 2001
From: Peter Barker <pbarker@barker.dropbear.id.au>
Date: Thu, 14 Dec 2023 10:20:16 +1100
Subject: [PATCH] AP_Common: add ASSERT_STORAGE_SIZE macro

saves havin gto name the dummy variable yourself
---
 libraries/AP_Common/AP_Common.h  | 5 +++++
 libraries/AP_Common/Location.cpp | 7 +++----
 2 files changed, 8 insertions(+), 4 deletions(-)

diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h
index 5949ca14cf..65a5648ad6 100644
--- a/libraries/AP_Common/AP_Common.h
+++ b/libraries/AP_Common/AP_Common.h
@@ -142,6 +142,11 @@ template<typename s, size_t t> struct assert_storage_size {
     _assert_storage_size<s, sizeof(s), t> _member;
 };
 
+#define ASSERT_STORAGE_SIZE_JOIN( name, line ) ASSERT_STORAGE_SIZE_DO_JOIN( name, line )
+#define ASSERT_STORAGE_SIZE_DO_JOIN( name, line )  name ## line
+#define ASSERT_STORAGE_SIZE(structure, size) \
+    do { assert_storage_size<structure, size> ASSERT_STORAGE_SIZE_JOIN(assert_storage_sizex, __LINE__); (void)ASSERT_STORAGE_SIZE_JOIN(assert_storage_sizex, __LINE__); } while(false)
+
 ////////////////////////////////////////////////////////////////////////////////
 /// @name	Conversions
 ///
diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp
index f466e99db2..e1a1ec578c 100644
--- a/libraries/AP_Common/Location.cpp
+++ b/libraries/AP_Common/Location.cpp
@@ -27,6 +27,9 @@ void Location::zero(void)
 // Construct location using position (NEU) from ekf_origin for the given altitude frame
 Location::Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, AltFrame frame)
 {
+    // make sure we know what size the Location object is:
+    ASSERT_STORAGE_SIZE(Location, 16);
+
     zero();
     lat = latitude;
     lng = longitude;
@@ -381,10 +384,6 @@ bool Location::sanitize(const Location &defaultLoc)
     return has_changed;
 }
 
-// make sure we know what size the Location object is:
-assert_storage_size<Location, 16> _assert_storage_size_Location;
-
-
 // return bearing in radians from location to loc2, return is 0 to 2*Pi
 ftype Location::get_bearing(const Location &loc2) const
 {