mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: examples: update examples for fixed io.open behaviour
This commit is contained in:
parent
b13632cc94
commit
81d4804d53
|
@ -14,6 +14,9 @@ local file_name
|
||||||
while true do
|
while true do
|
||||||
file_name = string.format('Particle %i.csv',index)
|
file_name = string.format('Particle %i.csv',index)
|
||||||
local file = io.open(file_name)
|
local file = io.open(file_name)
|
||||||
|
if file == nil then
|
||||||
|
break
|
||||||
|
end
|
||||||
local first_line = file:read(1) -- try and read the first character
|
local first_line = file:read(1) -- try and read the first character
|
||||||
io.close(file)
|
io.close(file)
|
||||||
if first_line == nil then
|
if first_line == nil then
|
||||||
|
|
|
@ -14,6 +14,9 @@ local function save_to_SD()
|
||||||
while true do
|
while true do
|
||||||
file_name = string.format('%i.waypoints',index)
|
file_name = string.format('%i.waypoints',index)
|
||||||
local file = io.open(file_name)
|
local file = io.open(file_name)
|
||||||
|
if file == nil then
|
||||||
|
break
|
||||||
|
end
|
||||||
local first_line = file:read(1) -- try and read the first character
|
local first_line = file:read(1) -- try and read the first character
|
||||||
io.close(file)
|
io.close(file)
|
||||||
if first_line == nil then
|
if first_line == nil then
|
||||||
|
|
Loading…
Reference in New Issue