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

scripts: update navlight script to support Rover 4.2 through 4.5 #11

Merged
merged 1 commit into from
Apr 6, 2024
Merged
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
12 changes: 7 additions & 5 deletions scripts/ardupilot/ArduRover/4.x/navlight.lua
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
-- This scripts is used to control Blue Robotics`s NavLight on the Blue Boat

local RELAY_NUM = 0
local LIGHT_PIN = 18
gpio:pinMode(LIGHT_PIN, 1)

local MODES = {
"MANU",
Expand Down Expand Up @@ -107,7 +108,7 @@ function update() -- this is the loop which periodically runs

if interval == 0 then -- Special case, light always on
if not is_light_on_tm then
relay:on(RELAY_NUM)
gpio:write(LIGHT_PIN,1)
is_light_on_tm = true
end
return update, 50 -- reschedules
Expand All @@ -121,11 +122,12 @@ function update() -- this is the loop which periodically runs

-- Check if it's time to toggle the light
if blink_counter < times and now - last_blink >= (is_light_on_tm and high or low) then
gpio:toggle(LIGHT_PIN)
is_light_on_tm = not is_light_on_tm
if is_light_on_tm then
relay:on(RELAY_NUM)
gpio:write(LIGHT_PIN, 1)
else
relay:off(RELAY_NUM)
gpio:write(LIGHT_PIN, 0)
end
last_blink = now
if not is_light_on_tm then -- Increment the counter when the light turns off
Expand All @@ -135,7 +137,7 @@ function update() -- this is the loop which periodically runs

-- Turn off the light at the end of the cycle
if blink_counter >= times and is_light_on_tm then
relay:off(RELAY_NUM)
gpio:write(LIGHT_PIN, 0)
is_light_on_tm = false
end

Expand Down
Loading