Skip to content

Commit

Permalink
AP_Scripting: use seconds_since_boot() in scripts
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Jun 9, 2023
1 parent 1feeb45 commit d314ef2
Show file tree
Hide file tree
Showing 16 changed files with 27 additions and 27 deletions.
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()
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
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

0 comments on commit d314ef2

Please sign in to comment.