Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Scripting: use double precision when on hardware with double support #24001

Open
wants to merge 6 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 0 additions & 5 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -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',
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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()
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why not just correct this to do the time wrapping correctly with the uint32 case? It's a simple replacement, and more accurate.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

using uint32 is both slow and less accurate. The seconds_since_boot() is microsecond accurate, and cheaper

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Don't you lose all the accuracy immediately when you don't have double precision support available though?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

23 bit mantissa does not leave a lot of space on single precision float, I'd actually expect this to be significantly worse then before in accuracy on any 32bit board....

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the point is to get 64 bit float on any board running a non-trivial script

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As discussed on the dev call - isn't it really time to recognize that it's not really worthwhile supporting scripting on these low end boards?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the point is to get 64 bit float on any board running a non-trivial script

I kind of get it, but at the same time I think there's a lot of value on say more lightly loaded Periph's (on M4's) to not forcing everything down this path. And it seems odd to chase the precision here when the core controls aren't at this resolution.

I do support a time wrapper utility if needed, but I'd almost prefer to see that just be us provide a library with get delta functions and the like. My big objection is I just don't want to force M4's to use double precision in scripting, as it hamstrings some of the AP_Periph style uses, and if we encourage the default path to be "rely upon high precision" that makes things harder to do. (I think at that point we also need a binding of "does this board have double support")

if not running then
running = true
height_PI.reset()
Expand Down Expand Up @@ -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()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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()
Expand Down
10 changes: 5 additions & 5 deletions libraries/AP_Scripting/applets/RockBlock.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -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

Expand All @@ -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
Expand Down Expand Up @@ -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()
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/applets/VTOL-quicktune.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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" }
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/applets/plane_package_place.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/drivers/EFI_HFE.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/drivers/EFI_Halo6000.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/drivers/EFI_SkyPower.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/examples/EFI_tester.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_Scripting/examples/MAVLinkHL.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Scripting/examples/OOP_example.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/examples/gen_control.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/examples/opendog_demo.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/examples/protected_call.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/examples/servo_scan.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/examples/servo_slew.lua
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_Scripting/lua/src/lgc.c
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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;
Expand Down
Loading