mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: add uint64 userdata
This commit is contained in:
parent
574b9939a5
commit
1c26c241f1
|
@ -44,6 +44,44 @@ function uint32_t_ud:tofloat() end
|
|||
---@return integer
|
||||
function uint32_t_ud:toint() end
|
||||
|
||||
---@class (exact) uint64_t_ud
|
||||
---@operator add(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud
|
||||
---@operator sub(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud
|
||||
---@operator mul(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud
|
||||
---@operator div(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud
|
||||
---@operator mod(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud
|
||||
---@operator band(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud
|
||||
---@operator bor(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud
|
||||
---@operator shl(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud
|
||||
---@operator shr(uint64_t_ud|uint32_t_ud|integer|number): uint64_t_ud
|
||||
local uint64_t_ud = {}
|
||||
|
||||
-- create uint64_t_ud with optional value
|
||||
-- Note that lua ints are 32 bits and lua floats will loose resolution at large values
|
||||
---@param value? uint64_t_ud|uint32_t_ud|integer|number
|
||||
---@return uint64_t_ud
|
||||
function uint64_t(value) end
|
||||
|
||||
-- create uint64_t_ud from a low and high half
|
||||
-- value = (high << 32) | low
|
||||
---@param high uint32_t_ud|integer|number
|
||||
---@param low uint32_t_ud|integer|number
|
||||
---@return uint64_t_ud
|
||||
function uint64_t(high, low) end
|
||||
|
||||
-- Convert to number, will loose resolution at large values
|
||||
---@return number
|
||||
function uint64_t_ud:tofloat() end
|
||||
|
||||
-- Convert to integer, nil if too large to be represented by native int32
|
||||
---@return integer|nil
|
||||
function uint64_t_ud:toint() end
|
||||
|
||||
-- Split into high and low half's, returning each as a uint32_t_ud
|
||||
---@return uint32_t_ud -- high (value >> 32)
|
||||
---@return uint32_t_ud -- low (value & 0xFFFFFFFF)
|
||||
function uint64_t_ud:split() end
|
||||
|
||||
-- system time in milliseconds
|
||||
---@return uint32_t_ud -- milliseconds
|
||||
function millis() end
|
||||
|
|
|
@ -875,6 +875,27 @@ userdata uint32_t manual_operator __tostring uint32_t___tostring
|
|||
userdata uint32_t manual toint uint32_t_toint 0 1
|
||||
userdata uint32_t manual tofloat uint32_t_tofloat 0 1
|
||||
|
||||
userdata uint64_t creation lua_new_uint64_t 2
|
||||
userdata uint64_t operator_getter coerce_to_uint64_t
|
||||
userdata uint64_t operator +
|
||||
userdata uint64_t operator -
|
||||
userdata uint64_t operator *
|
||||
userdata uint64_t operator /
|
||||
userdata uint64_t operator %
|
||||
userdata uint64_t operator &
|
||||
userdata uint64_t operator |
|
||||
userdata uint64_t operator ^
|
||||
userdata uint64_t operator <<
|
||||
userdata uint64_t operator >>
|
||||
userdata uint64_t operator ==
|
||||
userdata uint64_t operator <
|
||||
userdata uint64_t operator <=
|
||||
userdata uint64_t operator ~
|
||||
userdata uint64_t manual_operator __tostring uint64_t___tostring
|
||||
userdata uint64_t manual toint uint64_t_toint 0 1
|
||||
userdata uint64_t manual tofloat uint64_t_tofloat 0 1
|
||||
userdata uint64_t manual split uint64_t_split 0 2
|
||||
|
||||
global manual dirlist lua_dirlist 1 2
|
||||
global manual remove lua_removefile 1 3
|
||||
global manual print lua_print 1 0
|
||||
|
|
|
@ -381,9 +381,8 @@ int AP_Logger_Write(lua_State *L) {
|
|||
switch(fmt_cat[index]) {
|
||||
// logger variable types not available to scripting
|
||||
// 'd': double
|
||||
// 'Q': uint64_t
|
||||
// 'q': int64_t
|
||||
// 'a': arrays
|
||||
// 'a': int16_t[32]
|
||||
case 'b': { // int8_t
|
||||
int isnum;
|
||||
const lua_Integer tmp1 = lua_tointegerx(L, arg_index, &isnum);
|
||||
|
@ -496,6 +495,18 @@ int AP_Logger_Write(lua_State *L) {
|
|||
offset += sizeof(uint32_t);
|
||||
break;
|
||||
}
|
||||
case 'Q': { // uint64_t
|
||||
void * ud = luaL_testudata(L, arg_index, "uint64_t");
|
||||
if (ud == nullptr) {
|
||||
luaM_free(L, buffer);
|
||||
luaL_argerror(L, arg_index, "argument out of range");
|
||||
// no return
|
||||
}
|
||||
uint64_t tmp = *static_cast<uint64_t *>(ud);
|
||||
memcpy(&buffer[offset], &tmp, sizeof(uint64_t));
|
||||
offset += sizeof(uint64_t);
|
||||
break;
|
||||
}
|
||||
case 'N': { // char[16]
|
||||
charlen = 16;
|
||||
break;
|
||||
|
|
|
@ -39,6 +39,39 @@ uint32_t coerce_to_uint32_t(lua_State *L, int arg) {
|
|||
return luaL_argerror(L, arg, "Unable to coerce to uint32_t");
|
||||
}
|
||||
|
||||
uint64_t coerce_to_uint64_t(lua_State *L, int arg) {
|
||||
{ // uint64_t userdata
|
||||
const uint64_t * ud = static_cast<uint64_t *>(luaL_testudata(L, arg, "uint64_t"));
|
||||
if (ud != nullptr) {
|
||||
return *ud;
|
||||
}
|
||||
}
|
||||
{ // integer
|
||||
int success;
|
||||
const lua_Integer v = lua_tointegerx(L, arg, &success);
|
||||
|
||||
// Lua int maps to int32. However, because of the size difference negatives numbers wont come out correctly as they do for uint32
|
||||
if (success && v >= 0) {
|
||||
return static_cast<uint64_t>(v);
|
||||
}
|
||||
}
|
||||
{ // uint32_t userdata
|
||||
const uint32_t * ud = static_cast<uint32_t *>(luaL_testudata(L, arg, "uint32_t"));
|
||||
if (ud != nullptr) {
|
||||
return static_cast<uint64_t>(*ud);
|
||||
}
|
||||
}
|
||||
{ // float
|
||||
int success;
|
||||
const lua_Number v = lua_tonumberx(L, arg, &success);
|
||||
if (success && (v >= 0) && (v <= float(UINT64_MAX))) {
|
||||
return static_cast<uint64_t>(v);
|
||||
}
|
||||
}
|
||||
// failure
|
||||
return luaL_argerror(L, arg, "Unable to coerce to uint64_t");
|
||||
}
|
||||
|
||||
// the exposed constructor to lua calls to create a uint32_t
|
||||
int lua_new_uint32_t(lua_State *L) {
|
||||
const int args = lua_gettop(L);
|
||||
|
@ -51,11 +84,56 @@ int lua_new_uint32_t(lua_State *L) {
|
|||
return 1;
|
||||
}
|
||||
|
||||
// the exposed constructor to lua calls to create a uint64_t
|
||||
int lua_new_uint64_t(lua_State *L) {
|
||||
const int args = lua_gettop(L);
|
||||
if (args > 2) {
|
||||
return luaL_argerror(L, args, "too many arguments");
|
||||
}
|
||||
|
||||
uint64_t value = 0;
|
||||
switch (args) {
|
||||
case 0:
|
||||
default:
|
||||
// No arguments, init to 0
|
||||
break;
|
||||
case 1:
|
||||
// Single argument
|
||||
value = coerce_to_uint64_t(L, 1);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
// Two uint32 giving high and low half
|
||||
const uint64_t high = coerce_to_uint32_t(L, 1);
|
||||
const uint64_t low = coerce_to_uint32_t(L, 2);
|
||||
value = (high << 32) | low;
|
||||
break;
|
||||
}
|
||||
|
||||
new_uint64_t(L);
|
||||
*check_uint64_t(L, -1) = value;
|
||||
return 1;
|
||||
}
|
||||
|
||||
int uint32_t_toint(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
|
||||
const uint32_t v = *check_uint32_t(L, 1);
|
||||
|
||||
lua_pushinteger(L, static_cast<lua_Integer>(v));
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int uint64_t_toint(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
|
||||
const uint64_t v = *check_uint64_t(L, 1);
|
||||
|
||||
if (v > INT32_MAX) {
|
||||
// uint64_t too large to convert to int return nill rather than giving error
|
||||
return 0;
|
||||
}
|
||||
|
||||
lua_pushinteger(L, static_cast<lua_Integer>(v));
|
||||
|
||||
|
@ -67,6 +145,15 @@ int uint32_t_tofloat(lua_State *L) {
|
|||
|
||||
const uint32_t v = *check_uint32_t(L, 1);
|
||||
|
||||
lua_pushnumber(L, static_cast<lua_Number>(v));
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int uint64_t_tofloat(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
|
||||
const uint64_t v = *check_uint64_t(L, 1);
|
||||
|
||||
lua_pushnumber(L, static_cast<lua_Number>(v));
|
||||
|
||||
|
@ -79,11 +166,41 @@ int uint32_t___tostring(lua_State *L) {
|
|||
const uint32_t v = *check_uint32_t(L, 1);
|
||||
|
||||
char buf[32];
|
||||
hal.util->snprintf(buf, ARRAY_SIZE(buf), "%u", (unsigned)v);
|
||||
hal.util->snprintf(buf, ARRAY_SIZE(buf), "%lu", (unsigned long)v);
|
||||
|
||||
lua_pushstring(L, buf);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
int uint64_t___tostring(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
|
||||
const uint64_t v = *check_uint64_t(L, 1);
|
||||
|
||||
char buf[32];
|
||||
hal.util->snprintf(buf, ARRAY_SIZE(buf), "%llu", (unsigned long long)v);
|
||||
|
||||
lua_pushstring(L, buf);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
// Split uint64 into a high and low uint32
|
||||
int uint64_t_split(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
|
||||
const uint64_t v = *check_uint64_t(L, 1);
|
||||
|
||||
// high
|
||||
new_uint32_t(L);
|
||||
*check_uint32_t(L, -1) = v >> 32;
|
||||
|
||||
// low
|
||||
new_uint32_t(L);
|
||||
*check_uint32_t(L, -1) = v & 0xFFFFFFFF;
|
||||
|
||||
return 2;
|
||||
}
|
||||
|
||||
#endif // AP_SCRIPTING_ENABLED
|
||||
|
|
|
@ -8,3 +8,12 @@ int lua_new_uint32_t(lua_State *L);
|
|||
int uint32_t___tostring(lua_State *L);
|
||||
int uint32_t_toint(lua_State *L);
|
||||
int uint32_t_tofloat(lua_State *L);
|
||||
|
||||
int lua_new_uint64_t(lua_State *L);
|
||||
uint64_t coerce_to_uint64_t(lua_State *L, int arg);
|
||||
|
||||
int uint64_t___tostring(lua_State *L);
|
||||
int uint64_t_toint(lua_State *L);
|
||||
int uint64_t_tofloat(lua_State *L);
|
||||
int uint64_t_split(lua_State *L);
|
||||
|
||||
|
|
|
@ -35,6 +35,34 @@ function test_offset(ofs_e, ofs_n)
|
|||
return true
|
||||
end
|
||||
|
||||
function test_uint64()
|
||||
local pass = true
|
||||
|
||||
local zero = uint64_t()
|
||||
local max = uint64_t(-1, -1)
|
||||
|
||||
pass = pass and (zero - 1) == max
|
||||
pass = pass and ~max == zero
|
||||
pass = pass and max > zero
|
||||
pass = pass and (((zero + 1) + 1.1) + uint32_t(1)) == uint64_t(0, 3)
|
||||
pass = pass and tostring(zero) == "0"
|
||||
pass = pass and (uint64_t(15) & uint64_t(130)) == uint32_t(2)
|
||||
pass = pass and (uint64_t(1) | uint64_t(2)) == uint64_t(3)
|
||||
pass = pass and (uint64_t(1) << 1) == uint64_t(2)
|
||||
pass = pass and (uint64_t(16) >> 1) == uint64_t(8)
|
||||
pass = pass and type(zero:tofloat()) == "number"
|
||||
pass = pass and zero:tofloat() == 0
|
||||
|
||||
local high, low
|
||||
high, low = zero:split()
|
||||
pass = pass and high == uint32_t(0) and low == uint32_t(0)
|
||||
|
||||
high, low = max:split()
|
||||
pass = pass and high == uint32_t(-1) and low == uint32_t(-1)
|
||||
|
||||
return pass
|
||||
end
|
||||
|
||||
function update()
|
||||
local all_tests_passed = true
|
||||
local require_test_local = require('test/nested')
|
||||
|
@ -53,6 +81,7 @@ function update()
|
|||
end
|
||||
-- each test should run then and it's result with the previous ones
|
||||
all_tests_passed = test_offset(500, 200) and all_tests_passed
|
||||
all_tests_passed = test_uint64() and all_tests_passed
|
||||
|
||||
if all_tests_passed then
|
||||
gcs:send_text(3, "Internal tests passed")
|
||||
|
|
Loading…
Reference in New Issue