Skip to content

Commit

Permalink
AP_Scripting: fix easy lua check issues in examples
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 committed Oct 25, 2023
1 parent 62af92e commit 0706edb
Show file tree
Hide file tree
Showing 12 changed files with 13 additions and 33 deletions.
3 changes: 1 addition & 2 deletions libraries/AP_Scripting/applets/Hexsoon LEDs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,11 @@ LEDs should now work!, if not try swapping AUX 5 and 6, either by physically swa
To get colours to match either change the ordering in "local led_map =" below or swap headers round on the LED distribution board
If using 6 les add two extra colours to "local led_map =" e.g: "local led_map = {red, red, red, green, green, green}"
--]]
-- luacheck: only 0

-- helper colours, red, green, blue values from 0 to 255
local red = {255, 0, 0}
local green = {0, 255, 0}
local blue = {0, 0, 255}
-- local blue = {0, 0, 255}

-- led map giving the colour for the LEDs plugged in
local led_map = {red, red, green, green}
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/examples/Serial_Dump.lua
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
-- this script reads data from a serial port and dumps it to a file
-- luacheck: only 0

local file_name = 'raw serial dump.txt'
local file_name_plain = 'serial dump.txt'
Expand All @@ -11,6 +10,7 @@ local port = assert(serial:find_serial(0),"Could not find Scripting Serial Port"

-- make a file
local file = assert(io.open(file_name, "w"),"Could not create file " .. file_name)
file:close()
file = assert(io.open(file_name_plain, "w"),"Could not create file " .. file_name)
file:close()

Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_Scripting/examples/aux_cached.lua
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
--[[
example for getting cached aux function value
--]]
-- luacheck: only 0


local RATE_HZ = 10
Expand All @@ -11,7 +10,6 @@ local MAV_SEVERITY_INFO = 6

local AUX_FUNCTION_NUM = 302

local last_func_val = nil
local last_aux_pos = nil

function update()
Expand Down
3 changes: 1 addition & 2 deletions libraries/AP_Scripting/examples/copy_userdata.lua
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
--[[
An example of using the copy() method on userdata
--]]
-- luacheck: only 0


local loc1 = Location()
Expand All @@ -24,5 +23,5 @@ local v2 = v1:copy()
v2:x(v2:x()+100)
v2:y(v2:y()+300)

local diff = v2 - v1
diff = v2 - v1
gcs:send_text(0,string.format("vdiff=(%.2f,%.2f)", diff:x(), diff:y()))
13 changes: 4 additions & 9 deletions libraries/AP_Scripting/examples/opendog_demo.lua
Original file line number Diff line number Diff line change
@@ -1,14 +1,9 @@
-- demo of waving paw of opendog
-- luacheck: only 0

local flipflop = true

pwm = { 1500, 1500, 2000,
1500, 1500, 1000,
1500, 1500, 1500,
1500, 1500, 1500 }

local angle = 0.0
local pwm = { 1500, 1500, 2000,
1500, 1500, 1000,
1500, 1500, 1500,
1500, 1500, 1500 }

function update()
local t = 0.001 * millis():tofloat()
Expand Down
5 changes: 3 additions & 2 deletions libraries/AP_Scripting/examples/param_get_set_test.lua
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
-- This script is a test of param set and get
-- luacheck: only 0

local count = 0

Expand All @@ -21,7 +20,9 @@ local user_param = Parameter('SCR_USER1')
-- this will error out for a bad parameter
-- Parameter('FAKE_PARAM')
local success, err = pcall(Parameter,'FAKE_PARAM')
gcs:send_text(0, "Lua Caught Error: " .. err)
if not success then
gcs:send_text(0, "Lua Caught Error: " .. err)
end
-- this allows this example to catch the otherwise fatal error
-- not recommend if error is possible/expected, use separate construction and init

Expand Down
3 changes: 1 addition & 2 deletions libraries/AP_Scripting/examples/rangefinder_test.lua
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
-- This script checks RangeFinder
-- luacheck: only 0

local rotation_downward = 25
local rotation_forward = 0
Expand All @@ -8,7 +7,7 @@ function update()
local sensor_count = rangefinder:num_sensors()
gcs:send_text(0, string.format("%d rangefinder sensors found.", sensor_count))

for i = 0, rangefinder:num_sensors() do
for _ = 0, rangefinder:num_sensors() do
if rangefinder:has_data_orient(rotation_downward) then
info(rotation_downward)
elseif rangefinder:has_data_orient(rotation_forward) then
Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_Scripting/examples/rover-SaveTurns.lua
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@ of a vehicle. Use this script AT YOUR OWN RISK.
LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html
------------------------------------------------------------------------------]]
-- luacheck: only 0

local SCRIPT_NAME = 'SaveTurns'

Expand All @@ -33,7 +32,6 @@ local WAYPOINT = 16 -- waypoint command
local MAV_SEVERITY_WARNING = 4
local MAV_SEVERITY_INFO = 6
local MSG_NORMAL = 1
local MSG_DEBUG = 2

local RC_CHAN = rc:find_channel_for_option(RC_OPTION)
local last_wp = Location()
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_Scripting/examples/set-target-location.lua
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
-- a) switches to Guided mode
-- b) sets the target location to be 10m above home
-- c) switches the vehicle to land once it is within a couple of meters of home
-- luacheck: only 0

local wp_radius = 2
local target_alt_above_home = 10
Expand Down
7 changes: 2 additions & 5 deletions libraries/AP_Scripting/examples/set_target_posvel_circle.lua
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
-- 2) switch to GUIDED mode
-- 3) the vehilce will follow a circle in clockwise direction with increasing speed until ramp_up_time_s time has passed.
-- 4) switch out of and into the GUIDED mode any time to restart the trajectory from the start.
-- luacheck: only 0

-- Edit these variables
local rad_xy_m = 10.0 -- circle radius in xy plane in m
Expand All @@ -26,7 +25,7 @@ gcs:send_text(0,"Script started")
gcs:send_text(0,"Trajectory period: " .. tostring(2 * math.rad(180) / omega_radps))

function circle()
local cur_freq = 0
local cur_freq
-- increase target speed lineary with time until ramp_up_time_s is reached
if time <= ramp_up_time_s then
cur_freq = omega_radps*(time/ramp_up_time_s)^2
Expand Down Expand Up @@ -57,9 +56,7 @@ function update()
if arming:is_armed() and vehicle:get_mode() == copter_guided_mode_num and -test_start_location:z()>=5 then

-- calculate current position and velocity for circle trajectory
local target_pos = Vector3f()
local target_vel = Vector3f()
target_pos, target_vel = circle()
local target_pos, target_vel = circle()

-- advance the time
time = time + sampling_time_s
Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_Scripting/examples/terrain_warning.lua
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
-- height above terrain warning script
-- luacheck: only 0

-- min altitude above terrain, script will warn if lower than this
local terrain_min_alt = 20
Expand All @@ -15,7 +14,6 @@ local warn_ms = 10000


local height_threshold_passed = false
local last_warn = 0
function update()

if not arming:is_armed() then
Expand Down
3 changes: 0 additions & 3 deletions libraries/AP_Scripting/examples/wp_test.lua
Original file line number Diff line number Diff line change
@@ -1,12 +1,9 @@
-- Example script for accessing waypoint info
-- luacheck: only 0

local wp_index
local wp_distance
local wp_bearing
local wp_error
local wp_max_distance = 0
local last_log_ms = millis()


function on_wp_change(index, distance)
Expand Down

0 comments on commit 0706edb

Please sign in to comment.