3 changed files with 118 additions and 0 deletions
@ -0,0 +1,59 @@
@@ -0,0 +1,59 @@
|
||||
-- Example of loading a mission from the SD card using Scripting |
||||
-- Would be trivial to select a mission based on scripting params or RC switch |
||||
|
||||
local function read_mission(file_name) |
||||
|
||||
-- Open file |
||||
file = assert(io.open(file_name), 'Could open :' .. file_name) |
||||
|
||||
-- check header |
||||
assert(string.find(file:read('l'),'QGC WPL 110') == 1, file_name .. ': incorrect format') |
||||
|
||||
-- clear any existing mission |
||||
assert(mission:clear(), 'Could not clear current mission') |
||||
|
||||
-- read each line and write to mission |
||||
local item = mavlink_mission_item_int_t() |
||||
local index = 0 |
||||
while true do |
||||
|
||||
local data = {} |
||||
for i = 1, 12 do |
||||
data[i] = file:read('n') |
||||
if data[i] == nil then |
||||
if i == 1 then |
||||
gcs:send_text(6, 'loaded mission: ' .. file_name) |
||||
return -- got to the end of the file |
||||
else |
||||
mission:clear() -- clear part loaded mission |
||||
error('failed to read file') |
||||
end |
||||
end |
||||
end |
||||
|
||||
item:seq(data[1]) |
||||
item:frame(data[3]) |
||||
item:command(data[4]) |
||||
item:param1(data[5]) |
||||
item:param2(data[6]) |
||||
item:param3(data[7]) |
||||
item:param4(data[8]) |
||||
item:x(data[9]*10^7) |
||||
item:y(data[10]*10^7) |
||||
item:z(data[11]) |
||||
|
||||
if not mission:set_item(index,item) then |
||||
mission:clear() -- clear part loaded mission |
||||
error(string.format('failed to set mission item %i',index)) |
||||
end |
||||
index = index + 1 |
||||
end |
||||
|
||||
end |
||||
|
||||
function update() |
||||
read_mission('Tools/autotest/Generic_Missions/CMAC-bigloop.txt') |
||||
return |
||||
end |
||||
|
||||
return update, 5000 |
@ -0,0 +1,58 @@
@@ -0,0 +1,58 @@
|
||||
-- Example of saving the current mission to a file on the SD card on arming |
||||
|
||||
local function save_to_SD() |
||||
|
||||
-- check if there is a mission to save |
||||
local num_wp = mission:num_commands() |
||||
if num_wp <= 1 then |
||||
return |
||||
end |
||||
|
||||
local index = 0 |
||||
local file_name |
||||
-- search for a index without a file |
||||
while true do |
||||
file_name = string.format('%i.waypoints',index) |
||||
local file = io.open(file_name) |
||||
local first_line = file:read(1) -- try and read the first character |
||||
io.close(file) |
||||
if first_line == nil then |
||||
break |
||||
end |
||||
index = index + 1 |
||||
end |
||||
|
||||
-- create new file |
||||
file = assert(io.open(file_name, 'w'), 'Could not make file :' .. file_name) |
||||
|
||||
-- header |
||||
file:write('QGC WPL 110\n') |
||||
|
||||
-- read each item and write to file |
||||
for i = 0, num_wp - 1 do |
||||
local item = mission:get_item(i) |
||||
file:write(string.format('%i\t0\t%i\t%i\t%0.8f\t%.8f\t%.8f\t%.8f\t%.8f\t%.8f\t%.6f\t1\n',item:seq(),item:frame(),item:command(),item:param1(),item:param2(),item:param3(),item:param4(),item:x()*10^-7,item:y()*10^-7,item:z())) |
||||
end |
||||
|
||||
file:close() |
||||
|
||||
gcs:send_text(6,'saved mission to: ' .. file_name) |
||||
|
||||
end |
||||
|
||||
function idle_disarmed() |
||||
if arming:is_armed() then |
||||
save_to_SD() |
||||
return idle_armed, 1000 |
||||
end |
||||
return idle_disarmed, 1000 |
||||
end |
||||
|
||||
function idle_armed() |
||||
if not arming:is_armed() then |
||||
return idle_disarmed, 1000 |
||||
end |
||||
return idle_armed, 1000 |
||||
end |
||||
|
||||
return idle_disarmed, 1000 |
Loading…
Reference in new issue