diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 17a62218b3c8ea..5e0d8236301f99 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -47,11 +47,6 @@ def srcpath(path): env.SRCROOT = srcpath('') self.configure_env(cfg, env) - # Setup scripting: - env.DEFINES.update( - LUA_32BITS = 1, - ) - env.AP_LIBRARIES += [ 'AP_Scripting', 'AP_Scripting/lua/src', diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/RateBased/sport_aerobatics.lua b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/RateBased/sport_aerobatics.lua index 9991fb3b3e4be9..b11775abd288d7 100644 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/RateBased/sport_aerobatics.lua +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/RateBased/sport_aerobatics.lua @@ -174,7 +174,7 @@ local function PI_controller(kP,kI,iMax) -- update the controller. function self.update(target, current) - local now = millis():tofloat() * 0.001 + local now = seconds_since_boot() if not _last_t then _last_t = now end @@ -460,7 +460,7 @@ end local knife_edge_ms = 0 function do_knife_edge(arg1,arg2) -- arg1 is angle +/-180, duration is arg2 - local now = millis():tofloat() * 0.001 + local now = seconds_since_boot() if not running then running = true height_PI.reset() @@ -498,7 +498,7 @@ end -- fly level for a time..allows full altitude recovery after trick function do_pause(arg1,arg2) -- arg1 is time of pause in sec, arg2 is unused - local now = millis():tofloat() * 0.001 + local now = seconds_since_boot() if not running then running = true height_PI.reset() diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua index 0ea2a38faef4ca..77e330c3863f16 100644 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua @@ -280,7 +280,7 @@ local function PI_controller(kP,kI,iMax,min,max) -- update the controller. function self.update(target, current) - local now = millis():tofloat() * 0.001 + local now = seconds_since_boot() if not _last_t then _last_t = now end @@ -1386,7 +1386,7 @@ function rudder_over(_direction, _min_speed) local ahrs_quat = ahrs:get_quaternion() local ahrs_pos = ahrs:get_relative_position_NED_origin() local ahrs_gyro = ahrs:get_gyro() - local now = millis():tofloat() * 0.001 + local now = seconds_since_boot() local pitch_threshold = 60.0 if target_q == nil then @@ -1815,7 +1815,7 @@ end path_var.count = 0 function do_path() - local now = millis():tofloat() * 0.001 + local now = seconds_since_boot() local ahrs_pos_NED = ahrs:get_relative_position_NED_origin() local ahrs_pos = ahrs:get_position() local ahrs_gyro = ahrs:get_gyro() diff --git a/libraries/AP_Scripting/applets/RockBlock.lua b/libraries/AP_Scripting/applets/RockBlock.lua index be1cb8cadc3180..0781f3cf8b3a48 100644 --- a/libraries/AP_Scripting/applets/RockBlock.lua +++ b/libraries/AP_Scripting/applets/RockBlock.lua @@ -386,7 +386,7 @@ local function RockblockModem() local self = { is_transmitting = false, first_sucessful_mailbox_check = false, - time_last_tx = millis():tofloat() * 0.001, + time_last_tx = seconds_since_boot(), last_modem_status_check = 0, modem_detected = false, in_read_cycle = false, @@ -601,9 +601,9 @@ local function RockblockModem() function self.checkmodem() --- send detect command to modem every 10 sec if not detected - if (millis():tofloat() * 0.001) - self.last_modem_status_check > 10 then + if seconds_since_boot() - self.last_modem_status_check > 10 then table.insert(_modem_to_send, _AT_query) - self.last_modem_status_check = millis():tofloat() * 0.001 + self.last_modem_status_check = seconds_since_boot() end end @@ -630,7 +630,7 @@ local function RockblockModem() table.insert(_modem_to_send, pkt) table.insert(_modem_to_send, highByte .. lowByte .. "\r") - self.time_last_tx = millis():tofloat() * 0.001 + self.time_last_tx = seconds_since_boot() if RCK_ENABLE:get() == 1 then table.insert(_modem_to_send, _AT_mailbox_check) self.is_transmitting = true @@ -714,7 +714,7 @@ function HLSatcom() -- send HL2 packet every 30 sec, if not aleady in a mailbox check if rockblock.modem_detected and gcs:get_high_latency_status() and - (millis():tofloat() * 0.001) - rockblock.time_last_tx > RCK_PERIOD:get() and not rockblock.is_transmitting then + seconds_since_boot() - rockblock.time_last_tx > RCK_PERIOD:get() and not rockblock.is_transmitting then -- update HL2 packet hl2.timestamp = millis():tofloat() diff --git a/libraries/AP_Scripting/applets/VTOL-quicktune.lua b/libraries/AP_Scripting/applets/VTOL-quicktune.lua index 900bb03fec0316..8a70b00800a666 100644 --- a/libraries/AP_Scripting/applets/VTOL-quicktune.lua +++ b/libraries/AP_Scripting/applets/VTOL-quicktune.lua @@ -186,7 +186,7 @@ end -- get time in seconds since boot function get_time() - return millis():tofloat() * 0.001 + return seconds_since_boot() end local axis_names = { "RLL", "PIT", "YAW" } diff --git a/libraries/AP_Scripting/applets/plane_package_place.lua b/libraries/AP_Scripting/applets/plane_package_place.lua index 242435fc7f34b6..a0910e698107fe 100644 --- a/libraries/AP_Scripting/applets/plane_package_place.lua +++ b/libraries/AP_Scripting/applets/plane_package_place.lua @@ -57,7 +57,7 @@ SRV_Channels:set_output_scaled(PKG_RELEASE_FUNC:get(), 0) -- get time in seconds function get_time() - return millis():tofloat() * 0.001 + return seconds_since_boot() end -- reset state diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index b54b9ca54c2332..12e8857c75c7c3 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -36,6 +36,10 @@ function millis() end ---@return uint32_t_ud -- microseconds function micros() end +-- system time in seconds +---@return number -- seconds +function seconds_since_boot() end + -- receive mission command from running mission ---@return uint32_t_ud|nil -- command start time milliseconds ---@return integer|nil -- command param 1 diff --git a/libraries/AP_Scripting/drivers/EFI_HFE.lua b/libraries/AP_Scripting/drivers/EFI_HFE.lua index 08a28724142317..26be2d19661444 100644 --- a/libraries/AP_Scripting/drivers/EFI_HFE.lua +++ b/libraries/AP_Scripting/drivers/EFI_HFE.lua @@ -34,7 +34,7 @@ function bind_add_param(name, idx, default_value) end function get_time_sec() - return millis():tofloat() * 0.001 + return seconds_since_boot() end -- Type conversion functions diff --git a/libraries/AP_Scripting/drivers/EFI_Halo6000.lua b/libraries/AP_Scripting/drivers/EFI_Halo6000.lua index dc6cd075b1f454..d70826c66269a2 100644 --- a/libraries/AP_Scripting/drivers/EFI_Halo6000.lua +++ b/libraries/AP_Scripting/drivers/EFI_Halo6000.lua @@ -31,7 +31,7 @@ function bind_add_param(name, idx, default_value) end function get_time_sec() - return millis():tofloat() * 0.001 + return seconds_since_boot() end -- Type conversion functions diff --git a/libraries/AP_Scripting/drivers/EFI_SkyPower.lua b/libraries/AP_Scripting/drivers/EFI_SkyPower.lua index ba75519a99b6b5..677606c438d504 100644 --- a/libraries/AP_Scripting/drivers/EFI_SkyPower.lua +++ b/libraries/AP_Scripting/drivers/EFI_SkyPower.lua @@ -44,7 +44,7 @@ function bind_add_param(name, idx, default_value) end function get_time_sec() - return millis():tofloat() * 0.001 + return seconds_since_boot() end -- Type conversion functions diff --git a/libraries/AP_Scripting/examples/EFI_tester.lua b/libraries/AP_Scripting/examples/EFI_tester.lua index 0bb2719d85e336..e1e6b469960b3a 100644 --- a/libraries/AP_Scripting/examples/EFI_tester.lua +++ b/libraries/AP_Scripting/examples/EFI_tester.lua @@ -31,7 +31,7 @@ local EFISIM_TYPE = bind_add_param('TYPE', 1, 0) local EFISIM_RATE_HZ = bind_add_param('RATE_HZ', 2, 100) function get_time_sec() - return millis():tofloat() * 0.001 + return seconds_since_boot() end local FRM_100 = uint32_t(0x80000100) diff --git a/libraries/AP_Scripting/examples/MAVLinkHL.lua b/libraries/AP_Scripting/examples/MAVLinkHL.lua index 032f80f774a86e..49ad0dc807e192 100644 --- a/libraries/AP_Scripting/examples/MAVLinkHL.lua +++ b/libraries/AP_Scripting/examples/MAVLinkHL.lua @@ -27,7 +27,7 @@ end port:begin(19200) port:set_flow_control(0) -local time_last_tx = millis():tofloat() * 0.001 +local time_last_tx = seconds_since_boot() -- enable high latency mode from here, instead of having to enable from GCS gcs:enable_high_latency_connections(true) @@ -369,7 +369,7 @@ function HLSatcom() end -- send HL2 packet every 5 sec - if gcs:get_high_latency_status() and (millis():tofloat() * 0.001) - + if gcs:get_high_latency_status() and seconds_since_boot() - time_last_tx > 5 then -- update HL2 packet @@ -454,7 +454,7 @@ function HLSatcom() for idx = 1, #newpkt do port:write(newpkt:byte(idx)) end - time_last_tx = millis():tofloat() * 0.001 + time_last_tx = seconds_since_boot() end diff --git a/libraries/AP_Scripting/examples/OOP_example.lua b/libraries/AP_Scripting/examples/OOP_example.lua index d555cb4a0278e7..3b91533ccf58ed 100644 --- a/libraries/AP_Scripting/examples/OOP_example.lua +++ b/libraries/AP_Scripting/examples/OOP_example.lua @@ -34,7 +34,7 @@ local function PIFF(kFF,kP,kI,iMax) -- update the controller. function self.update(target, current) - local now = millis():tofloat() * 0.001 + local now = seconds_since_boot() if not _last_t then _last_t = now end @@ -90,7 +90,7 @@ function PIFF2.new(kFF,kP,kI,iMax) end function PIFF2.update(self, target, current) - local now = millis():tofloat() * 0.001 + local now = seconds_since_boot() if not self.last_t then self.last_t = now end diff --git a/libraries/AP_Scripting/examples/gen_control.lua b/libraries/AP_Scripting/examples/gen_control.lua index 018c6ce23f8c4e..33fbf64d4f7506 100644 --- a/libraries/AP_Scripting/examples/gen_control.lua +++ b/libraries/AP_Scripting/examples/gen_control.lua @@ -101,7 +101,7 @@ local function PI_controller(kP,kI,iMax,min,max) -- update the controller. function self.update(target, current) - local now = millis():tofloat() * 0.001 + local now = seconds_since_boot() if not _last_t then _last_t = now end diff --git a/libraries/AP_Scripting/examples/opendog_demo.lua b/libraries/AP_Scripting/examples/opendog_demo.lua index d518b95c6e0e15..fc93592b46b0b4 100644 --- a/libraries/AP_Scripting/examples/opendog_demo.lua +++ b/libraries/AP_Scripting/examples/opendog_demo.lua @@ -11,7 +11,7 @@ pwm = { 1500, 1500, 2000, local angle = 0.0 function update() - local t = 0.001 * millis():tofloat() + local t = seconds_since_boot() local angle = math.sin(t) * 0.5 pwm[6] = math.floor(1500.0 + angle*500.0) for i = 1, 12 do diff --git a/libraries/AP_Scripting/examples/protected_call.lua b/libraries/AP_Scripting/examples/protected_call.lua index 7446092c5f4e2c..1e29cbeaa46191 100644 --- a/libraries/AP_Scripting/examples/protected_call.lua +++ b/libraries/AP_Scripting/examples/protected_call.lua @@ -6,7 +6,7 @@ -- example main loop function function update() - local t = 0.001 * millis():tofloat() + local t = seconds_since_boot() gcs:send_text(0, string.format("TICK %.1fs", t)) if math.floor(t) % 10 == 0 then -- deliberately make a bad call to cause a fault, asking for the 6th GPS status diff --git a/libraries/AP_Scripting/examples/servo_scan.lua b/libraries/AP_Scripting/examples/servo_scan.lua index 0e02d8b1d91ccd..e0cb58a801eb58 100644 --- a/libraries/AP_Scripting/examples/servo_scan.lua +++ b/libraries/AP_Scripting/examples/servo_scan.lua @@ -4,7 +4,7 @@ local SERVO_FUNCTION = 94 local PERIOD = 0.5 function update() -- this is the loop which periodically runs - local t = 0.001 * millis():tofloat() + local t = seconds_since_boot() local pi = 3.1415 local output = math.sin(pi * t * PERIOD * 2.0) local pwm = math.floor(1500 + 500 * output) diff --git a/libraries/AP_Scripting/examples/servo_slew.lua b/libraries/AP_Scripting/examples/servo_slew.lua index 36d0f103bd788a..ab6d513614142a 100644 --- a/libraries/AP_Scripting/examples/servo_slew.lua +++ b/libraries/AP_Scripting/examples/servo_slew.lua @@ -29,7 +29,7 @@ function update() local chan = STEST_CHAN:get() local freq = STEST_FREQ:get() if chan > 0 and freq > 0 then - local t = 0.001 * millis():tofloat() + local t = seconds_since_boot() local pi = 3.1415 local output = math.sin(pi * t * freq * 2.0) * STEST_PCT:get() * 0.01 local pwm_min = STEST_PWM_MIN:get() diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index de148309913a34..6551ef69bc56d7 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -698,6 +698,7 @@ singleton i2c manual get_device lua_get_i2c_device 4 global manual millis lua_millis 0 global manual micros lua_micros 0 +global manual seconds_since_boot lua_seconds_since_boot 0 global manual mission_receive lua_mission_receive 0 userdata uint32_t creation lua_new_uint32_t 1 diff --git a/libraries/AP_Scripting/lua/src/lgc.c b/libraries/AP_Scripting/lua/src/lgc.c index db4df82922e08b..fb1bcb69e65790 100644 --- a/libraries/AP_Scripting/lua/src/lgc.c +++ b/libraries/AP_Scripting/lua/src/lgc.c @@ -128,6 +128,13 @@ static void removeentry (Node *n) { setdeadvalue(wgkey(n)); /* unused and unmarked key; remove it */ } +/* + the GC code assumed pointer alignment is at least as large as + lua_Number. The memory allocator does align to at least 8 bytes, but + the compiler doesn't know this so need to suppress cast-align warnings + */ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wcast-align" /* ** tells whether a key or value can be cleared from a weak @@ -526,6 +533,7 @@ static lu_mem traverseLclosure (global_State *g, LClosure *cl) { return sizeLclosure(cl->nupvalues); } +#pragma GCC diagnostic pop static lu_mem traversethread (global_State *g, lua_State *th) { StkId o = th->stack; diff --git a/libraries/AP_Scripting/lua/src/lobject.h b/libraries/AP_Scripting/lua/src/lobject.h index 24088614027ff5..6b5f25a9d35419 100644 --- a/libraries/AP_Scripting/lua/src/lobject.h +++ b/libraries/AP_Scripting/lua/src/lobject.h @@ -69,7 +69,7 @@ /* ** Common type for all collectable objects */ -typedef struct GCObject GCObject; +typedef struct GCObject GCObject ALIGNED_NUMBER; /* @@ -84,7 +84,7 @@ typedef struct GCObject GCObject; */ struct GCObject { CommonHeader; -}; +} ALIGNED_NUMBER; @@ -104,15 +104,15 @@ typedef union Value { lua_CFunction f; /* light C functions */ lua_Integer i; /* integer numbers */ lua_Number n; /* float numbers */ -} Value; +} Value ALIGNED_NUMBER; #define TValuefields Value value_; int tt_ typedef struct lua_TValue { - TValuefields; -} TValue; + TValuefields; +} TValue ALIGNED_NUMBER; @@ -309,7 +309,7 @@ typedef struct TString { size_t lnglen; /* length for long strings */ struct TString *hnext; /* linked list for hash table */ } u; -} TString; +} TString ALIGNED_NUMBER; /* @@ -318,7 +318,7 @@ typedef struct TString { typedef union UTString { L_Umaxalign dummy; /* ensures maximum alignment for strings */ TString tsv; -} UTString; +} UTString ALIGNED_NUMBER; /* @@ -349,7 +349,7 @@ typedef struct Udata { struct Table *metatable; size_t len; /* number of bytes */ union Value user_; /* user value */ -} Udata; +} Udata ALIGNED_NUMBER; /* @@ -358,7 +358,7 @@ typedef struct Udata { typedef union UUdata { L_Umaxalign dummy; /* ensures maximum alignment for 'local' udata */ Udata uv; -} UUdata; +} UUdata ALIGNED_NUMBER; /* @@ -387,7 +387,7 @@ typedef struct Upvaldesc { TString *name; /* upvalue name (for debug information) */ lu_byte instack; /* whether it is in stack (register) */ lu_byte idx; /* index of upvalue (in stack or in outer function's list) */ -} Upvaldesc; +} Upvaldesc ALIGNED_NUMBER; /* @@ -398,7 +398,7 @@ typedef struct LocVar { TString *varname; int startpc; /* first point where variable is active */ int endpc; /* first point where variable is dead */ -} LocVar; +} LocVar ALIGNED_NUMBER; /* @@ -426,7 +426,7 @@ typedef struct Proto { struct LClosure *cache; /* last-created closure with this prototype */ TString *source; /* used for debug information */ GCObject *gclist; -} Proto; +} Proto ALIGNED_NUMBER; @@ -441,26 +441,26 @@ typedef struct UpVal UpVal; */ #define ClosureHeader \ - CommonHeader; lu_byte nupvalues; GCObject *gclist + CommonHeader; lu_byte nupvalues; GCObject *gclist ALIGNED_NUMBER typedef struct CClosure { ClosureHeader; lua_CFunction f; TValue upvalue[1]; /* list of upvalues */ -} CClosure; +} CClosure ALIGNED_NUMBER; typedef struct LClosure { ClosureHeader; struct Proto *p; UpVal *upvals[1]; /* list of upvalues */ -} LClosure; +} LClosure ALIGNED_NUMBER; typedef union Closure { CClosure c; LClosure l; -} Closure; +} Closure ALIGNED_NUMBER; #define isLfunction(o) ttisLclosure(o) @@ -478,7 +478,7 @@ typedef union TKey { int next; /* for chaining (offset for next node) */ } nk; TValue tvk; -} TKey; +} TKey ALIGNED_NUMBER; /* copy a value into a key without messing up field 'next' */ @@ -491,7 +491,7 @@ typedef union TKey { typedef struct Node { TValue i_val; TKey i_key; -} Node; +} Node ALIGNED_NUMBER; typedef struct Table { @@ -504,7 +504,7 @@ typedef struct Table { Node *lastfree; /* any free position is before this position */ struct Table *metatable; GCObject *gclist; -} Table; +} Table ALIGNED_NUMBER; diff --git a/libraries/AP_Scripting/lua/src/lstate.h b/libraries/AP_Scripting/lua/src/lstate.h index 56b374100007de..d1673c4dd7186c 100644 --- a/libraries/AP_Scripting/lua/src/lstate.h +++ b/libraries/AP_Scripting/lua/src/lstate.h @@ -77,7 +77,7 @@ typedef struct stringtable { TString **hash; int nuse; /* number of elements */ int size; -} stringtable; +} stringtable ALIGNED_NUMBER; /* @@ -107,7 +107,7 @@ typedef struct CallInfo { ptrdiff_t extra; short nresults; /* expected number of results from this function */ unsigned short callstatus; -} CallInfo; +} CallInfo ALIGNED_NUMBER; /* @@ -169,7 +169,7 @@ typedef struct global_State { TString *tmname[TM_N]; /* array with tag-method names */ struct Table *mt[LUA_NUMTAGS]; /* metatables for basic types */ TString *strcache[STRCACHE_N][STRCACHE_M]; /* cache for strings in API */ -} global_State; +} global_State ALIGNED_NUMBER; /* @@ -199,7 +199,7 @@ struct lua_State { unsigned short nCcalls; /* number of nested C calls */ l_signalT hookmask; lu_byte allowhook; -}; +} ALIGNED_NUMBER; #define G(L) (L->l_G) @@ -216,7 +216,7 @@ union GCUnion { struct Table h; struct Proto p; struct lua_State th; /* thread */ -}; +} ALIGNED_NUMBER; #define cast_u(o) cast(union GCUnion *, (o)) diff --git a/libraries/AP_Scripting/lua/src/luaconf.h b/libraries/AP_Scripting/lua/src/luaconf.h index f148e1d48ff0a7..f328ce1875839a 100644 --- a/libraries/AP_Scripting/lua/src/luaconf.h +++ b/libraries/AP_Scripting/lua/src/luaconf.h @@ -19,6 +19,20 @@ #endif #include +// use 32 bit number and integer types if we don't have hardware double supportx +#if !HAL_HAVE_HARDWARE_DOUBLE +#define LUA_32BITS 1 +#define ALIGNED_NUMBER +#else +// ChibiOS does not define LLONG_MAX +#ifndef LLONG_MAX +#define LLONG_MAX 9223372036854775807LL +#define LLONG_MIN (-LLONG_MAX - 1) +#endif +#pragma GCC diagnostic error "-Wframe-larger-than=3000" +#define ALIGNED_NUMBER __attribute__((aligned(8))) +#endif // HAL_HAVE_HARDWARE_DOUBLE + /* ** =================================================================== ** Search for "@@" to find all configurable definitions. diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index d27cd3c5648cae..fb4613c8f12241 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -43,6 +43,13 @@ int lua_micros(lua_State *L) { return 1; } +// seconds_since_boot +int lua_seconds_since_boot(lua_State *L) { + binding_argcheck(L, 0); + lua_pushnumber(L, AP_HAL::micros64()*1.0e-6); + return 1; +} + int lua_mavlink_init(lua_State *L) { binding_argcheck(L, 2); WITH_SEMAPHORE(AP::scripting()->mavlink_data.sem); diff --git a/libraries/AP_Scripting/lua_bindings.h b/libraries/AP_Scripting/lua_bindings.h index 2b9f6f34c5e39d..841d6bbd97bf62 100644 --- a/libraries/AP_Scripting/lua_bindings.h +++ b/libraries/AP_Scripting/lua_bindings.h @@ -4,6 +4,7 @@ int lua_millis(lua_State *L); int lua_micros(lua_State *L); +int lua_seconds_since_boot(lua_State *L); int lua_mission_receive(lua_State *L); int AP_Logger_Write(lua_State *L); int lua_get_i2c_device(lua_State *L); diff --git a/libraries/AP_Scripting/lua_boxed_numerics.cpp b/libraries/AP_Scripting/lua_boxed_numerics.cpp index fe2304df978ef5..19da0e931c7fe1 100644 --- a/libraries/AP_Scripting/lua_boxed_numerics.cpp +++ b/libraries/AP_Scripting/lua_boxed_numerics.cpp @@ -17,10 +17,7 @@ uint32_t coerce_to_uint32_t(lua_State *L, int arg) { } } { // integer - - // if this assert fails, you will need to add an upper bounds - // check that ensures the value isn't greater then UINT32_MAX - static_assert(sizeof(lua_Number) == sizeof(uint32_t), "32 bit integers are only supported"); + static_assert(sizeof(lua_Number) == sizeof(lua_Integer), "sizes of lua_Number and lua_Integer must match"); int success; const lua_Integer v = lua_tointegerx(L, arg, &success);