mirror of https://github.com/ArduPilot/ardupilot
AP_Common: add ASSERT_STORAGE_SIZE macro
saves havin gto name the dummy variable yourself
This commit is contained in:
parent
9de1b6164b
commit
5488ca6403
|
@ -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
|
||||
///
|
||||
|
|
|
@ -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
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue