mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_Scripting: removed P23 schedules from main lua
now moved to Schedules directory
This commit is contained in:
parent
136538e69b
commit
c5840e512b
@ -1529,474 +1529,6 @@ function procedure_turn(radius, bank_angle, step_out, arg4)
|
|||||||
})
|
})
|
||||||
end
|
end
|
||||||
|
|
||||||
function derry_turn(radius, bank_angle, arg3, arg4)
|
|
||||||
return make_paths("derry_turn", {
|
|
||||||
{ path_horizontal_arc(radius, 90), roll_angle_entry_exit(bank_angle) },
|
|
||||||
{ path_horizontal_arc(-radius, 90), roll_angle_entry_exit(-bank_angle) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_1(radius, height, width, arg4) -- top hat
|
|
||||||
return make_paths("p23_1", {
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)), roll_sequence({{2,0}, {2, 90}, {1, 0}, {2, 90}, {2, 0}}) },
|
|
||||||
{ path_vertical_arc(-radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight((width-2*radius)), roll_sequence({{1,0}, {1, 180}, {1, 0}}) },
|
|
||||||
{ path_vertical_arc(-radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)), roll_sequence({{2,0}, {2, 90}, {1, 0}, {2, 90}, {2, 0}}) },
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_2(radius, height, arg3, arg4) -- half square
|
|
||||||
return make_paths("p23_2", {
|
|
||||||
{ path_vertical_arc(-radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(180) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 90), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_3(radius, height, arg3, arg4) -- humpty
|
|
||||||
return make_paths("p23_3", {
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/8), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)*6/8), roll_angle(360) },
|
|
||||||
{ path_straight((height-2*radius)/8), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(radius, 180), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(180) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_4(radius, height, arg3, arg4) -- on corner
|
|
||||||
local l = ((height - (2 * radius)) * math.sin(math.rad(45)))
|
|
||||||
return make_paths("p23_4", {
|
|
||||||
{ path_vertical_arc(-radius, 45), roll_angle(0) },
|
|
||||||
{ path_straight(l/3), roll_angle(0) },
|
|
||||||
{ path_straight(l/3), roll_angle(180) },
|
|
||||||
{ path_straight(l/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight(l/3), roll_angle(0) },
|
|
||||||
{ path_straight(l/3), roll_angle(180) },
|
|
||||||
{ path_straight(l/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 45), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_5(radius, height_gain, arg3, arg4) -- 45 up - should be 1 1/2 snaps....
|
|
||||||
--local l = (height_gain - 2*radius*(1.0-math.cos(math.rad(45))))/math.sin(math.rad(45))
|
|
||||||
local l = (height_gain - (2 * radius) + (2 * radius * math.cos(math.rad(45)))) / math.cos(math.rad(45))
|
|
||||||
return make_paths("p23_5", {
|
|
||||||
{ path_vertical_arc(-radius, 45), roll_angle(0) },
|
|
||||||
{ path_straight(l/3), roll_angle(0) },
|
|
||||||
{ path_straight(l/3), roll_angle(540) },
|
|
||||||
{ path_straight(l/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(radius, 45), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_6(radius, height_gain, arg3, arg4) -- 3 sided
|
|
||||||
local l = (height_gain - 2*radius) / ((2*math.sin(math.rad(45))) + 1)
|
|
||||||
return make_paths("p23_6", {
|
|
||||||
{ path_vertical_arc(-radius, 45), roll_angle(0) },
|
|
||||||
{ path_straight(l), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 45), roll_angle(0) },
|
|
||||||
{ path_straight(l), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 45), roll_angle(0) },
|
|
||||||
{ path_straight(l), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 45), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_7(length, arg2, arg3, arg4) -- roll combination
|
|
||||||
return make_paths("p23_7", {
|
|
||||||
{ path_straight(length*5/22), roll_angle(180) },
|
|
||||||
{ path_straight(length*1/22), roll_angle(0) },
|
|
||||||
{ path_straight(length*5/22), roll_angle(180) },
|
|
||||||
{ path_straight(length*5/22), roll_angle(-180) },
|
|
||||||
{ path_straight(length*1/22), roll_angle(0) },
|
|
||||||
{ path_straight(length*5/22), roll_angle(-180) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_8(radius, height, arg3, arg4) -- immelmann
|
|
||||||
return make_paths("p23_8", {
|
|
||||||
{ path_vertical_arc(-radius, 180), roll_angle(0) },
|
|
||||||
{ path_straight(radius/2), roll_angle(180) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_9(radius, height, num_turns, arg4) -- spin (currently a vert down 1/2 roll)
|
|
||||||
return make_paths("p23_9", {
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight(height-2*radius), roll_angle(180) },
|
|
||||||
{ path_vertical_arc(-radius, 90), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_10(radius, height, arg3, arg4) -- humpty
|
|
||||||
return make_paths("p23_10", {
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(180) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 180), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(180) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 90), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_11(radius, height, arg3, arg4) -- laydown loop
|
|
||||||
local rabs = math.abs(radius)
|
|
||||||
local vert_length = height - (2 * rabs)
|
|
||||||
local angle_length = ((2 * rabs) - (2 * (rabs - (rabs * (math.cos(math.rad(45))))))) / math.sin(math.rad(45))
|
|
||||||
return make_paths("p23_11", {
|
|
||||||
{ path_vertical_arc(-radius, 45), roll_angle(0) },
|
|
||||||
{ path_straight(angle_length*2/6), roll_angle(0) },
|
|
||||||
{ path_straight(angle_length*1/6), roll_angle(180) },
|
|
||||||
{ path_straight(angle_length*1/6), roll_angle(-180) },
|
|
||||||
{ path_straight(angle_length*2/6), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(radius, 315), roll_angle(0) },
|
|
||||||
{ path_straight(vert_length*2/9), roll_angle(0) },
|
|
||||||
{ path_straight(vert_length*2/9), roll_angle(90) },
|
|
||||||
{ path_straight(vert_length*1/9), roll_angle(0) },
|
|
||||||
{ path_straight(vert_length*2/9), roll_angle(90) },
|
|
||||||
{ path_straight(vert_length*2/9), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_12(radius, height, arg3, arg4) -- 1/2 square
|
|
||||||
return make_paths("p23_12", {
|
|
||||||
{ path_vertical_arc(-radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(180) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 90), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_13(radius, height, arg3, arg4) -- stall turn
|
|
||||||
return make_paths("p23_13", {
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(90) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(90) },
|
|
||||||
{ path_straight((height-2*radius)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 90), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_13a(radius, height, arg3, arg4) -- stall turn PLACE HOLDER
|
|
||||||
assert(height >= 2*radius)
|
|
||||||
local rabs = math.abs(radius)
|
|
||||||
return make_paths("P23_13a", {
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*rabs)/3), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*rabs)/3), roll_angle(90), roll_ref=90 },
|
|
||||||
{ path_straight((height-2*rabs)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 180), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*rabs)/3), roll_angle(0) },
|
|
||||||
{ path_straight((height-2*rabs)/3), roll_angle(90), roll_ref=-90 },
|
|
||||||
{ path_straight((height-2*rabs)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0), roll_ref=180 },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
|
|
||||||
function p23_14(r, h, arg3, arg4) -- fighter turn
|
|
||||||
assert(h >= 2*r)
|
|
||||||
local rabs = math.abs(r)
|
|
||||||
local angle_length = (h - ((0.2929 * rabs)) / (math.sin(math.rad(45)))) - rabs
|
|
||||||
return make_paths("fighter_turn", {
|
|
||||||
{ path_vertical_arc(r, 45), roll_angle(0) },
|
|
||||||
{ path_straight((angle_length)/3), roll_angle(0) },
|
|
||||||
{ path_straight((angle_length)/3), roll_angle(-90), roll_ref=90 },
|
|
||||||
{ path_straight((angle_length)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(r, 180), roll_angle(0) },
|
|
||||||
{ path_straight((angle_length)/3), roll_angle(0) },
|
|
||||||
{ path_straight((angle_length)/3), roll_angle(90), roll_ref=-90 },
|
|
||||||
{ path_straight((angle_length)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-r, 45), roll_angle(0), roll_ref=180 },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_15(radius, height, arg3, arg4) -- triangle
|
|
||||||
local h1 = radius * math.sin(math.rad(45))
|
|
||||||
local h2 = (2 * radius) - (radius * math.cos(math.rad(45)))
|
|
||||||
local h3 = height - (2 * radius)
|
|
||||||
local side = h3 / math.cos(math.rad(45))
|
|
||||||
--local base = (h3 + (2 * (radius - radius * math.cos(math.rad(45))))) - (2 * radius)
|
|
||||||
local base = (2 * (h3 + radius)) - 2 * radius
|
|
||||||
return make_paths("p23_15", {
|
|
||||||
{ path_straight(base * 1/5), roll_angle(180) },
|
|
||||||
{ path_straight(base * 2/5), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(radius, 135) , roll_angle(0) },
|
|
||||||
{ path_straight(side*2/9), roll_angle(0) },
|
|
||||||
{ path_straight(side*2/9), roll_angle(90) },
|
|
||||||
{ path_straight(side*1/9), roll_angle(0) },
|
|
||||||
{ path_straight(side*2/9), roll_angle(90) },
|
|
||||||
{ path_straight(side*2/9), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight(side*2/9), roll_angle(0) },
|
|
||||||
{ path_straight(side*2/9), roll_angle(90) },
|
|
||||||
{ path_straight(side*1/9), roll_angle(0) },
|
|
||||||
{ path_straight(side*2/9), roll_angle(90) },
|
|
||||||
{ path_straight(side*2/9), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(radius, 135), roll_angle(0) },
|
|
||||||
{ path_straight(base * 2/5), roll_angle(0) },
|
|
||||||
{ path_straight(base * 1/5), roll_angle(180) },
|
|
||||||
{ path_straight(base * 2/5), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_16(radius, height, arg3, arg4) -- sharks tooth
|
|
||||||
local angle_length = (height - 2 * (radius - (radius * math.cos(math.rad(45))))) / math.cos(math.rad(45))
|
|
||||||
local vert_length = height - (2 * radius)
|
|
||||||
return make_paths("p23_16", {
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
|
||||||
{ path_straight((vert_length)/3), roll_angle(0) },
|
|
||||||
{ path_straight((vert_length)/3), roll_angle(180) },
|
|
||||||
{ path_straight((vert_length)/3), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(radius, 135), roll_angle(0) },
|
|
||||||
{ path_straight(angle_length*2/9), roll_angle(0) },
|
|
||||||
{ path_straight(angle_length*2/9), roll_angle(90) },
|
|
||||||
{ path_straight(angle_length*1/9), roll_angle(0) },
|
|
||||||
{ path_straight(angle_length*2/9), roll_angle(90) },
|
|
||||||
{ path_straight(angle_length*2/9), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(-radius, 45), roll_angle(0), roll_ref=180 },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function p23_17(radius, arg2, arg3, arg4) -- loop
|
|
||||||
return make_paths("p23_17", {
|
|
||||||
{ path_vertical_arc(radius, 135), roll_angle(0) },
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(180) },
|
|
||||||
{ path_vertical_arc(radius, 135), roll_angle(0), roll_ref=180 },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function half_roll(arg1, arg2, arg3, arg4) -- half roll for testing inverted manouvers
|
|
||||||
return make_paths("half_roll", {
|
|
||||||
{ path_straight(40), roll_angle(180) },
|
|
||||||
{ path_straight(10), roll_angle(0) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function fai_f3a_box_l_r()
|
|
||||||
return path_composer("f3a_box_l_r", { -- positioned for a flight line 150m out. Flight line 520m total length.
|
|
||||||
-- Script start point is ON CENTER, with the model heading DOWNWIND!
|
|
||||||
{ straight_roll, { 150, 0 } },
|
|
||||||
{ half_reverse_cuban_eight, { 95 } },
|
|
||||||
{ straight_align, { 0, 0 } },
|
|
||||||
{ vertical_aerobatic_box, { 540, 190, 45, 0 }, message="Starting Box Demo"},
|
|
||||||
{ vertical_aerobatic_box, { 540, 190, 45, 0 } },
|
|
||||||
{ vertical_aerobatic_box, { 540, 190, 45, 0 } },
|
|
||||||
{ vertical_aerobatic_box, { 540, 190, 45, 0 } },
|
|
||||||
{ straight_roll, { 50, 0 } }
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function funny_loop(radius, arg2, arg3, arg4)
|
|
||||||
return make_paths("funny_loop", {
|
|
||||||
{ path_horizontal_arc(radius, 90), roll_angle(180) },
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0), set_orient=qorient(0,90,90)},
|
|
||||||
{ path_horizontal_arc(radius, 180), roll_angle(360), set_orient=qorient(0,-90,-90) },
|
|
||||||
{ path_vertical_arc(radius, 90), roll_angle(0), set_orient=qorient(0,0,-90) },
|
|
||||||
{ path_horizontal_arc(radius, 90), roll_angle(-180) },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
--[[
|
|
||||||
NZ clubman schedule
|
|
||||||
--]]
|
|
||||||
function nz_clubman() -- positioned for a flight line 100m out
|
|
||||||
-- Script start point is ON CENTER, with the model heading DOWNWIND!
|
|
||||||
return path_composer("nz_clubman_l_r", {
|
|
||||||
--[[
|
|
||||||
{ straight_roll, { 20, 0 } },
|
|
||||||
{ procedure_turn, { 20, 45, 60 } },
|
|
||||||
{ straight_roll, { 150, 0 } },
|
|
||||||
{ half_reverse_cuban_eight, { 40 } },
|
|
||||||
{ straight_roll, { 150, 0 } },
|
|
||||||
--]]
|
|
||||||
{ straight_roll, { 150, 0 } },
|
|
||||||
{ half_reverse_cuban_eight, { 90 } },
|
|
||||||
{ straight_align, { 0, 0 } },
|
|
||||||
{ cuban_eight, { 90 }, message="Cuban Eight"},
|
|
||||||
{ straight_align, { -100, 0 } },
|
|
||||||
{ half_reverse_cuban_eight, { 90 } },
|
|
||||||
{ straight_align, { 40, 0 } },
|
|
||||||
{ half_reverse_cuban_eight, { 90 }, message="Half Rev Cuban"},
|
|
||||||
{ straight_align, { -180, 0 } },
|
|
||||||
{ half_reverse_cuban_eight, { 90 } },
|
|
||||||
{ straight_align, { -120, 0 } },
|
|
||||||
{ multi_point_roll, { 240, 2, 0.5 }, message="Two Point Roll"},
|
|
||||||
{ straight_align, { 150, 0 } },
|
|
||||||
{ half_reverse_cuban_eight, { 90 } },
|
|
||||||
{ straight_align, { 106, 0 } },
|
|
||||||
{ upline_45, { 40, 180 }, message="45 Upline"},
|
|
||||||
{ straight_align, { -180, 0 } }, -- missing the stall turn
|
|
||||||
{ split_s, { 90, 90 } },
|
|
||||||
{ straight_align, { -120, 0 } },
|
|
||||||
{ straight_roll, { 240, 1 }, message="Slow Roll"},
|
|
||||||
{ straight_align, { 150, 0 } },
|
|
||||||
{ half_cuban_eight, { 90 } },
|
|
||||||
{ straight_align, { 0, 0 } },
|
|
||||||
{ loop, { 90, 0, 2 }, message="Two Loops"},
|
|
||||||
{ straight_align, { -180, 0 } },
|
|
||||||
{ immelmann_turn, { 90, 90 } },
|
|
||||||
{ straight_align, { -106, 0 } },
|
|
||||||
{ downline_45, { 40, 180 }, message="45 Downline"},
|
|
||||||
{ straight_align, { 150, 0 } },
|
|
||||||
{ half_cuban_eight, { 90 } },
|
|
||||||
{ straight_roll, { 100, 0 } },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
--[[
|
|
||||||
F3A p23, preliminary schedule 2023
|
|
||||||
--]]
|
|
||||||
function f3a_p23_l_r()
|
|
||||||
return path_composer("f3a_p23_l_r", { -- positioned for a flight line 150m out. Flight line 520m total length.
|
|
||||||
-- Script start point is ON CENTER, with the model heading DOWNWIND!
|
|
||||||
{ straight_roll, { 160, 0 } },
|
|
||||||
{ half_reverse_cuban_eight, { 80 } },
|
|
||||||
{ straight_align, { 140, 0 } },
|
|
||||||
{ p23_1, { 40, 200, 200 }, message="Top Hat"},
|
|
||||||
{ straight_align, { -220, 0 } },
|
|
||||||
{ p23_2, { 40, 200 }, message="Half Square Loop"},
|
|
||||||
{ straight_align, { 0, 0 } },
|
|
||||||
{ p23_3, { 40, 200 }, message="Humpty"},
|
|
||||||
{ straight_align, { 160, 0 } },
|
|
||||||
{ p23_4, { 40, 200 }, message="Half Square on Corner"},
|
|
||||||
{ straight_align, { 116, 0 } },
|
|
||||||
{ p23_5, { 40, 200 }, message="45 Up"}, -- snap roll
|
|
||||||
{ straight_align, { -185, 0 } },
|
|
||||||
{ p23_6, { 40, 200 }, message="Half Eight Sided Loop"},
|
|
||||||
{ straight_align, { -100, 0 } },
|
|
||||||
{ p23_7, { 200 }, message="Roll Combination"},
|
|
||||||
{ straight_align, { 160, 0 } },
|
|
||||||
{ p23_8, { 100 }, message="Immelmann Turn"},
|
|
||||||
{ straight_align, { 40, 0 } },
|
|
||||||
{ p23_9, { 40, 200 }, message="Should be a Spin"}, -- spin
|
|
||||||
{ straight_align, { -140, 0 } },
|
|
||||||
{ p23_10, { 40, 200 }, message="Humpty"},
|
|
||||||
{ straight_align, { -91, 0 } },
|
|
||||||
{ p23_11, { 50, 200 }, message="Laydown Loop"},
|
|
||||||
{ straight_align, { 220, 0 } },
|
|
||||||
{ p23_12, { 40, 200 }, message="Half Square Loop"},
|
|
||||||
{ straight_align, { 40, 0 } },
|
|
||||||
{ p23_13a, { 40, 200 }, message="Stall Turn"}, -- stall turn
|
|
||||||
{ straight_roll, { 100, 0 } },
|
|
||||||
{ p23_14, { 40, 180 }, message="Fighter Turn"},
|
|
||||||
{ straight_align, { -24, 0 } },
|
|
||||||
{ p23_15, { 40, 200 }, message="Triangle"},
|
|
||||||
{ straight_align, { 220, 0 } },
|
|
||||||
{ p23_16, { 40, 160 }, message="Sharks Tooth"},
|
|
||||||
{ straight_align, { 0, 0 } },
|
|
||||||
{ p23_17, { 100 }, message="Loop"},
|
|
||||||
{ straight_roll, { 100, 0 } },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
--[[
|
|
||||||
F4C Scale Schedule Example
|
|
||||||
--]]
|
|
||||||
|
|
||||||
function f4c_example_l_r() -- positioned for a flight line nominally 150m out (some manouvers start 30m out)
|
|
||||||
-- Script start point is ON CENTER @ 150m, with the model heading DOWNWIND ie flying Right to Left!
|
|
||||||
return path_composer("f4c_example", {
|
|
||||||
{ straight_roll, { 320, 0 } },
|
|
||||||
{ half_climbing_circle, { -70, 0, -60 } }, -- come in close for the first two manouvers
|
|
||||||
--{ straight_roll, { 10, 0 } },
|
|
||||||
{ straight_align, { 280, 0 } },
|
|
||||||
{ scale_figure_eight, { -140, -30 }, message="Scale Figure Eight"},
|
|
||||||
{ straight_roll, { 80, 0 } },
|
|
||||||
{ immelmann_turn, { 90 } },
|
|
||||||
{ straight_align, { 0, 0 } },
|
|
||||||
--{ straight_roll, { 340, 0 } },
|
|
||||||
{ climbing_circle, { 140, -205, 30 }, message="Descending 360"},
|
|
||||||
{ straight_roll, { 40, 0 } },
|
|
||||||
{ upline_20, { 80, 25 } }, -- Climb up 25m to base height
|
|
||||||
{ straight_roll, { 50, 0 } },
|
|
||||||
{ half_climbing_circle, { 70, 0, 60 } }, -- Go back out to 150m
|
|
||||||
{ straight_align, { 0, 0 } },
|
|
||||||
{ loop, { 90, 0, 1 }, message="Loop"},
|
|
||||||
{ straight_align, { -50, 0 } },
|
|
||||||
{ half_reverse_cuban_eight, { 90 } },
|
|
||||||
{ straight_align, { 0, 0 } },
|
|
||||||
{ immelmann_turn, { 90 }, message="Immelmann Turn"},
|
|
||||||
{ straight_align, { -140, 0 } },
|
|
||||||
{ split_s, { 90 } },
|
|
||||||
{ straight_align, { 0, 0 } },
|
|
||||||
{ half_cuban_eight, { 90 }, message="Half Cuban Eight"},
|
|
||||||
{ straight_align, { -180, 0 } },
|
|
||||||
{ half_climbing_circle, { 70, 0, 60 } },
|
|
||||||
--{ straight_roll, { 115, 0 } },
|
|
||||||
{ straight_align, { -90, 0 } },
|
|
||||||
{ derry_turn, { 90, 60 }, message="Derry Turn"},
|
|
||||||
{ straight_roll, { 200, 0 } },
|
|
||||||
{ half_climbing_circle, { -90, 0, -60 } },
|
|
||||||
{ straight_align, { 0, 0 } },
|
|
||||||
{ climbing_circle, { -140, 0, -30 }, message="Gear Demo"},
|
|
||||||
{ straight_roll, { 250, 0 } },
|
|
||||||
{ half_climbing_circle, { -100, 0, -60 } },
|
|
||||||
{ straight_align, { -185, 0 } },
|
|
||||||
{ barrel_roll, { 90, 240, 1 }, message="Barrel Roll"},
|
|
||||||
{ straight_roll, { 60, 0 } },
|
|
||||||
{ half_reverse_cuban_eight, { 90 }},
|
|
||||||
{ straight_roll, { 60, 0 } },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
--[[
|
|
||||||
simple air show
|
|
||||||
--]]
|
|
||||||
|
|
||||||
function air_show1()
|
|
||||||
return path_composer("AirShow", {
|
|
||||||
{ loop, { 25, 0, 1 }, message="Loop"},
|
|
||||||
{ straight_align, { 80, 0 } },
|
|
||||||
{ half_reverse_cuban_eight, { 25 }, message="HalfReverseCubanEight" },
|
|
||||||
{ straight_align, { 80 } },
|
|
||||||
{ scale_figure_eight, { -40, -45 }, message="ScaleFigureEight" },
|
|
||||||
{ immelmann_turn, { 30 }, message="Immelmann" },
|
|
||||||
{ straight_align, { -40, 0 } },
|
|
||||||
{ straight_roll, { 80, 2 }, message="Roll" },
|
|
||||||
{ straight_align, { 120, 0 } },
|
|
||||||
{ split_s, { 30 }, message="Split-S"},
|
|
||||||
{ straight_align, { 0 } },
|
|
||||||
{ rolling_circle, { -50, 3}, message="RollingCircle" },
|
|
||||||
{ straight_align, { -50, 0 } },
|
|
||||||
{ humpty_bump, { 20, 60 }, message="HumptyBump" },
|
|
||||||
{ straight_align, { 80, 0 } },
|
|
||||||
{ half_cuban_eight, { 25 }, message="HalfCubanEight" },
|
|
||||||
{ straight_align, { 75, 0 } },
|
|
||||||
{ upline_45, { 30, 50 }, message="Upline45", },
|
|
||||||
{ downline_45, { 30, 50 }, message="Downline45" },
|
|
||||||
{ half_reverse_cuban_eight, { 25 }, message="HalfReverseCubanEight" },
|
|
||||||
{ straight_align, { 0 } },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
function air_show3()
|
|
||||||
return path_composer("AirShow3", {
|
|
||||||
{ air_show1, {}, message="AirShowPt1" },
|
|
||||||
{ air_show1, {}, message="AirShowPt2" },
|
|
||||||
{ air_show1, {}, message="AirShowPt3" },
|
|
||||||
})
|
|
||||||
end
|
|
||||||
|
|
||||||
---------------------------------------------------
|
---------------------------------------------------
|
||||||
|
|
||||||
--[[
|
--[[
|
||||||
@ -2591,24 +2123,13 @@ command_table[18]= PathFunction(downline_45, "Downline-45")
|
|||||||
command_table[19]= PathFunction(stall_turn, "Stall Turn")
|
command_table[19]= PathFunction(stall_turn, "Stall Turn")
|
||||||
command_table[20]= PathFunction(procedure_turn, "Procedure Turn")
|
command_table[20]= PathFunction(procedure_turn, "Procedure Turn")
|
||||||
command_table[21]= PathFunction(derry_turn, "Derry Turn")
|
command_table[21]= PathFunction(derry_turn, "Derry Turn")
|
||||||
-- 22 was Two Point Roll - use multi point roll instead
|
|
||||||
command_table[23]= PathFunction(half_climbing_circle, "Half Climbing Circle")
|
command_table[23]= PathFunction(half_climbing_circle, "Half Climbing Circle")
|
||||||
-- 24 was crossbox-humpty
|
|
||||||
command_table[25]= PathFunction(laydown_humpty, "Laydown Humpty")
|
command_table[25]= PathFunction(laydown_humpty, "Laydown Humpty")
|
||||||
command_table[26]= PathFunction(barrel_roll, "Barrel Roll")
|
command_table[26]= PathFunction(barrel_roll, "Barrel Roll")
|
||||||
command_table[27]= PathFunction(straight_flight, "Straight Hold")
|
command_table[27]= PathFunction(straight_flight, "Straight Hold")
|
||||||
command_table[28]= PathFunction(partial_circle, "Partial Circle")
|
command_table[28]= PathFunction(partial_circle, "Partial Circle")
|
||||||
-- 29 was Four Point Roll - use multi point roll instead
|
|
||||||
-- 30 was Eight Point Roll - use multi point roll instead
|
|
||||||
command_table[31]= PathFunction(multi_point_roll, "Multi Point Roll")
|
command_table[31]= PathFunction(multi_point_roll, "Multi Point Roll")
|
||||||
command_table[32]= PathFunction(side_step, "Side Step")
|
command_table[32]= PathFunction(side_step, "Side Step")
|
||||||
command_table[201] = PathFunction(nz_clubman, "NZ Clubman")
|
|
||||||
command_table[202] = PathFunction(f3a_p23_l_r, "FAI F3A P23 L to R")
|
|
||||||
command_table[203] = PathFunction(f4c_example_l_r, "FAI F4C Example L to R")
|
|
||||||
command_table[204] = PathFunction(air_show1, "AirShow")
|
|
||||||
command_table[205] = PathFunction(fai_f3a_box_l_r, "FAI F3A Aerobatic Box Demonstration")
|
|
||||||
command_table[206] = PathFunction(air_show3, "AirShow3")
|
|
||||||
|
|
||||||
|
|
||||||
--[[
|
--[[
|
||||||
a table of function available in loadable tricks
|
a table of function available in loadable tricks
|
||||||
@ -2633,7 +2154,6 @@ load_table["upline_45"] = upline_45
|
|||||||
load_table["downline_45"] = downline_45
|
load_table["downline_45"] = downline_45
|
||||||
load_table["stall_turn"] = stall_turn
|
load_table["stall_turn"] = stall_turn
|
||||||
load_table["procedure_turn"] = procedure_turn
|
load_table["procedure_turn"] = procedure_turn
|
||||||
load_table["derry_turn"] = derry_turn
|
|
||||||
load_table["two_point_roll"] = two_point_roll
|
load_table["two_point_roll"] = two_point_roll
|
||||||
load_table["half_climbing_circle"] = half_climbing_circle
|
load_table["half_climbing_circle"] = half_climbing_circle
|
||||||
load_table["laydown_humpty"] = laydown_humpty
|
load_table["laydown_humpty"] = laydown_humpty
|
||||||
@ -2644,14 +2164,6 @@ load_table["straight_hold"] = straight_hold
|
|||||||
load_table["partial_circle"] = partial_circle
|
load_table["partial_circle"] = partial_circle
|
||||||
load_table["multi_point_roll"] = multi_point_roll
|
load_table["multi_point_roll"] = multi_point_roll
|
||||||
load_table["side_step"] = side_step
|
load_table["side_step"] = side_step
|
||||||
load_table["p23_1a"] = p23_1a
|
|
||||||
load_table["p23_1"] = p23_1
|
|
||||||
load_table["p23_13a"] = p23_13a
|
|
||||||
load_table["p23_14"] = p23_14
|
|
||||||
load_table["p23_15"] = p23_15
|
|
||||||
load_table["p23_16"] = p23_16
|
|
||||||
load_table["p23_17"] = p23_17
|
|
||||||
load_table["funny_loop"] = funny_loop
|
|
||||||
load_table["align_box"] = align_box
|
load_table["align_box"] = align_box
|
||||||
load_table["align_center"] = align_center
|
load_table["align_center"] = align_center
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user