AP_Scripting: added schedules

this adds F3A, F4C and the NZ ClubMan schedules as txt files
This commit is contained in:
andypnz 2022-11-28 07:16:47 +11:00 committed by Andrew Tridgell
parent 2863f3954b
commit 136538e69b
7 changed files with 1916 additions and 0 deletions

View File

@ -0,0 +1,398 @@
# trajectory tracking aerobatic control
# See README.md for usage
# Written by Matthew Hampsey, Andy Palmer and Andrew Tridgell, with controller
# assistance from Paul Riseborough, testing by Henry Wurzburg
# To use this schedule put the file on your microSD in the root directory
# (not the APM directory) with name trick93.txt The schedule can then be
# used in auto missions or in TRIKn_ID commands for tricks on a switch
# This schedule is set up to be flown Left to Right. The schedule starts downwind - so
# the mission should be set up with WP's lined up on the flight line (150m out from the
# pilot), and the mission should be triggered when the plane gets to the center marker
# heading RIGHT to LEFT. Schedule direction is reversed with aerom_scale = -1 (and
# remember to reverse the mission WP's as well). Note the required height is greater
# than 400 feet - so only fly at an airfield where there is a 1500 foot clearance
# This is an example of a F3A F23 schedule. Some manouvers are flown over the center
# line of the runway. Please understand the behaviour by flying in SITL before flying this
# schedule with a real aircraft! Your aircraft requires adequate performance to complete
# the schedule
name: F3AF23
function half_reverse_cuban_eight(r, arg2, arg3, arg4)
local rabs = math.abs(r)
return make_paths("half_reverse_cuban_eight", {
{ path_vertical_arc(r, 45), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(180) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_vertical_arc(-r, 225), roll_angle(0) },
})
end
function f23_1(radius, arg2, arg3, arg4) -- loop
return make_paths("f23_1", {
{ path_straight(radius/2), roll_angle(0) },
{ path_straight(radius/2), roll_angle(-270) },
{ path_straight(radius/2), roll_angle(0) },
{ path_vertical_arc(radius, 360), roll_angle(360) },
{ path_straight(radius/2), roll_angle(0) },
{ path_straight(radius/2), roll_angle(-270) },
{ path_straight(radius/2), roll_angle(0), roll_ref=180 },
})
end
function f23_2(radius, height, arg3, arg4) -- stall turn -- Currently a humpty!
return make_paths("f23_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, 180), roll_angle(0) },
{ path_straight((height-2*radius)), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0) },
})
end
function f23_3(length, arg2, arg3, arg4) -- eight point roll
return make_paths("f23_3", {
{ path_straight(length/16), roll_angle(45) },
{ path_straight(length/16), roll_angle(0) },
{ path_straight(length/16), roll_angle(45) },
{ path_straight(length/16), roll_angle(0) },
{ path_straight(length/16), roll_angle(45) },
{ path_straight(length/16), roll_angle(0) },
{ path_straight(length/16), roll_angle(45) },
{ path_straight(length/16), roll_angle(0) },
{ path_straight(length/16), roll_angle(45) },
{ path_straight(length/16), roll_angle(0) },
{ path_straight(length/16), roll_angle(45) },
{ path_straight(length/16), roll_angle(0) },
{ path_straight(length/16), roll_angle(45) },
{ path_straight(length/16), roll_angle(0) },
{ path_straight(length/16), roll_angle(45) },
{ path_straight(length/16), roll_angle(0) },
})
end
function f23_4(radius, height, arg3, arg4) -- sharks tooth
local l = (height - (2 * radius))
local angle_l = l * 1.9 -- WRONG
return make_paths("f23_4", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l * 2/9), roll_angle(0) },
{ path_straight(l * 1/9), roll_angle(-90) },
{ path_straight(l * 1/9), roll_angle(0) },
{ path_straight(l * 1/9), roll_angle(-90) },
{ path_straight(l * 1/9), roll_angle(0) },
{ path_straight(l * 1/9), roll_angle(-90) },
{ path_straight(l * 2/9), roll_angle(0) },
{ path_vertical_arc(radius, 135), roll_angle(0) },
{ path_straight(angle_l/3), roll_angle(0) },
{ path_straight(angle_l/3), roll_angle(270) },
{ path_straight(angle_l/3), roll_angle(0) },
{ path_vertical_arc(-radius, 45), roll_angle(0), roll_ref=180 },
})
end
function f23_5(radius, height_gain, arg3, arg4) -- square loop on corner
local l = ((height_gain - (2 * radius)) * math.sin(math.rad(45))) -- CHECK
return make_paths("f23_5", {
{ path_vertical_arc(radius, 45), roll_angle(0) },
{ path_straight(l/3), roll_angle(0) },
{ path_straight(l/3), roll_angle(90) },
{ 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, 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, 90), roll_angle(0) },
{ path_straight(l/3), roll_angle(0) },
{ path_straight(l/3), roll_angle(90) },
{ path_straight(l/3), roll_angle(0) },
{ path_vertical_arc(radius, 45), roll_angle(0) , roll_ref=180 },
})
end
function f23_6(radius, height_gain, arg3, arg4) -- humpty bump
local l = (height_gain - 2*radius)
return make_paths("f23_6", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(2 * l/7), roll_angle(0) },
{ path_straight(l/7), roll_angle(180) },
{ path_straight(l/7), roll_angle(0) },
{ path_straight(l/7), roll_angle(180) },
{ path_straight(2 * l/7), roll_angle(0) },
{ path_vertical_arc(-radius, 180), roll_angle(360) },
{ path_straight(l/3), roll_angle(0) },
{ path_straight(l/3), roll_angle(360) }, -- should be a snap roll
{ path_straight(l/3), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0) , roll_ref=180 },
})
end
function f23_7(radius, arg2, arg3, arg4) -- horizontal eight
return make_paths("f23_7", {
{ path_vertical_arc(radius, 270), roll_angle(270) },
{ path_vertical_arc(-radius, 360), roll_angle(360) },
{ path_vertical_arc(radius, 90), roll_angle(90) },
})
end
function f23_8(radius, height, arg3, arg4) -- tear drop
local l = (height - 2*radius)
local angle_l = l * 0.74 -- WRONG
return make_paths("f23_8", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l/6), roll_angle(0) },
{ path_straight(4 * l/6), roll_angle(360) },
{ path_straight(l/6), roll_angle(0) },
{ path_vertical_arc(radius, 225), roll_angle(0) },
{ path_straight(2 * angle_l/7), roll_angle(0) },
{ path_straight(angle_l/7), roll_angle(90) },
{ path_straight(angle_l/7), roll_angle(0) },
{ path_straight(angle_l/7), roll_angle(90) },
{ path_straight(2 * angle_l/7), roll_angle(0) },
{ path_vertical_arc(-radius, 135), roll_angle(0) },
})
end
function f23_9(radius, height, arg3, arg4) -- 45 up
local l = (height - (2 * radius) + (2 * radius * math.cos(math.rad(45)))) / math.cos(math.rad(45))
return make_paths("f23_9", {
{ path_straight(radius/3), roll_angle(90) },
{ path_straight(radius/3), roll_angle(0) },
{ path_vertical_arc(radius, 45), roll_angle(0) },
{ path_straight(l/3), roll_angle(0) },
{ path_straight(l/6), roll_angle(180) },
{ path_straight(l/6), roll_angle(-180) },
{ path_straight(l/3), roll_angle(0) },
{ path_vertical_arc(-radius, 45), roll_angle(0) },
{ path_straight(radius/3), roll_angle(0) },
{ path_straight(radius/3), roll_angle(90) , roll_ref=180 },
})
end
function f23_10(radius, height, arg3, arg4) -- figure z
local l = height - (2 * radius)
-- local angle_l = (l + (2 * radius * math.cos(math.rad(45)))) / math.cos(math.rad(45)) -- WRONG
local angle_l = l * 1.1
return make_paths("f23_10", {
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_straight(l/4), roll_angle(0) },
{ path_straight(l/4), roll_angle(180) },
{ path_straight(l/4), roll_angle(-180) },
{ path_straight(l/4), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_straight(2 * l/7), roll_angle(0) },
{ path_straight(l/7), roll_angle(90) },
{ path_straight(l/7), roll_angle(0) },
{ path_straight(l/7), roll_angle(90) },
{ path_straight(2 * l/7), roll_angle(0) },
{ path_vertical_arc(-radius, 135), roll_angle(0) },
{ path_straight(angle_l/6), roll_angle(0) },
{ path_straight(angle_l/3), roll_angle(360) },
{ path_straight(angle_l/6), roll_angle(0) },
{ path_vertical_arc(radius, 135), roll_angle(0) },
})
end
function f23_11(radius, height, arg3, arg4) -- heart
local rabs = math.abs(radius)
local l = height * 1.15 -- WRONG
return make_paths("f23_11", {
{ path_vertical_arc(-radius, 45), roll_angle(0) },
{ path_straight(l * 2/9), roll_angle(0) },
{ path_straight(l * 1/9), roll_angle(-90) },
{ path_straight(l * 1/9), roll_angle(0) },
{ path_straight(l * 1/9), roll_angle(-90) },
{ path_straight(l * 1/9), roll_angle(0) },
{ path_straight(l * 1/9), roll_angle(-90), roll_ref=90 },
{ path_straight(l * 2/9), roll_angle(0) },
{ path_vertical_arc(radius, 180), roll_angle(0) },
{ path_straight(l * 1/3), roll_angle(0) },
{ path_straight(l * 1/3), roll_angle(180) , roll_ref=-90 },
{ path_straight(l * 1/3), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l * 1/3), roll_angle(0) },
{ path_straight(l * 1/3), roll_angle(180) , roll_ref=90 },
{ path_straight(l * 1/3), roll_angle(0) },
{ path_vertical_arc(-radius, 180), roll_angle(0) },
{ path_straight(l * 2/9), roll_angle(0) },
{ path_straight(l * 1/9), roll_angle(90) },
{ path_straight(l * 1/9), roll_angle(0) },
{ path_straight(l * 1/9), roll_angle(90) },
{ path_straight(l * 1/9), roll_angle(0) },
{ path_straight(l * 1/9), roll_angle(90), roll_ref=-90 },
{ path_straight(l * 2/9), roll_angle(0) },
{ path_vertical_arc(-radius, 45), roll_angle(0) },
})
end
function f23_12(radius, height, arg3, arg4) -- reverse top hat
return make_paths("f23_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) },
{ path_straight(radius/2), 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(180) },
{ path_straight((height-2*radius)/3), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(0) , roll_ref=180 },
})
end
function f23_13(radius, height, arg3, arg4) -- spin place holder
local l = height - (2 * radius)
return make_paths("f23_13", {
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_straight(2 * l/7), roll_angle(0) },
{ path_straight(l/7), roll_angle(180) },
{ path_straight(l/7), roll_angle(0) },
{ path_straight(l/7), roll_angle(-180) },
{ path_straight(2 * l/7), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(0) },
})
end
function f23_14(r, arg2, arg3, arg4) -- half cuban eight - needs a snap on the way down
local rabs = math.abs(r)
return make_paths("f23_14", {
--{ path_straight((2*rabs*math.sqrt(2))/4), roll_angle(0) },
{ path_straight((2*rabs*math.sqrt(2))/4), roll_angle(180) },
{ path_straight((2*rabs*math.sqrt(2))/4), roll_angle(-180) },
{ path_straight((2*rabs*math.sqrt(2))/4), roll_angle(0) },
{ path_vertical_arc(r, 225), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(180) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_vertical_arc(-r, 45), roll_angle(0) },
})
end
function f23_15(radius, arg2, arg3, arg4) -- rolling circle
return make_paths("f23_15", {
{ path_horizontal_arc(radius, 180), roll_angle(-180), thr_boost=true },
{ path_horizontal_arc(radius, 180), roll_angle(180), thr_boost=true },
})
end
function f23_16(radius, height, arg3, arg4) -- half square loop
local l = height - (2 * radius)
return make_paths("f23_16", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l/4), roll_angle(0) },
{ path_straight(l/4), roll_angle(180) },
{ path_straight(l/4), roll_angle(-180) },
{ path_straight(l/4), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(0) , roll_ref=180},
})
end
function f23_17(radius, arg2, arg3, arg4) -- down loop
return make_paths("f23_17", {
{ path_vertical_arc(-radius, 90), roll_angle(180) },
{ path_vertical_arc(-radius, 90), roll_angle(0) }, -- needs a snap in here
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(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
straight_roll 80 0
half_reverse_cuban_eight 70
align_center
message: Loop
f23_1 90
align_box 1
message: StallTurn
f23_2 40 200
align_center
message: RollCombination
f23_3 200
align_box 1
message: KnifeEdgeSharksTooth
f23_4 30 190
align_center
message: SquareLooponCorner
f23_5 40 200
align_box 1
message: Humpty
f23_6 40 200
align_center
message: HorizontalEight
f23_7 100
align_box 1
message: TearDrop
f23_8 40 200
align_center
message: 45Up
f23_9 40 200
align_box 1
message: FigureZ
f23_10 40 200
align_center
message: Heart
f23_11 40 200
align_box 1
message: ReverseTopHat
f23_12 40 200
align_center
message: Spin
f23_13 40 200
align_box 1
message: HalfCuban
f23_14 70
align_center
message: RollingCircle
f23_15 100
align_box 1
message: HalfSquareLoop
f23_16 40 200
align_center
message: DownLoop
f23_17 100
straight_roll 50 0
half_roll 0
straight_roll 50 0

View File

@ -0,0 +1,361 @@
# trajectory tracking aerobatic control
# See README.md for usage
# Written by Matthew Hampsey, Andy Palmer and Andrew Tridgell, with controller
# assistance from Paul Riseborough, testing by Henry Wurzburg
# To use this schedule put the file on your microSD in the root directory
# (not the APM directory) with name trick95.txt The schedule can then be
# used in auto missions or in TRIKn_ID commands for tricks on a switch
# This schedule is set up to be flown Left to Right. The schedule starts downwind - so
# the mission should be set up with WP's lined up on the flight line (150m out from the
# pilot), and the mission should be triggered when the plane gets to the center marker
# heading RIGHT to LEFT. Schedule direction is reversed with aerom_scale = -1 (and
# remember to reverse the mission WP's as well). Note the required height is greater
# than 400 feet - so only fly at an airfield where there is a 1500 foot clearance
# This is an example of a F3A F25 schedule. Some manouvers are flown over the center
# line of the runway. Please understand the behaviour by flying in SITL before flying this
# schedule with a real aircraft! Your aircraft requires adequate performance to complete
# the schedule
name: F3AF25
function half_reverse_cuban_eight(r, arg2, arg3, arg4)
local rabs = math.abs(r)
return make_paths("half_reverse_cuban_eight", {
{ path_vertical_arc(r, 45), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(180) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_vertical_arc(-r, 225), roll_angle(0) },
})
end
function f25_1(radius, height, width, arg4) -- square loop on corner
local l = ((height - (2 * radius)) * math.sin(math.rad(45))) -- CHECK
return make_paths("f25_1", {
{ path_vertical_arc(radius, 45), roll_angle(90) },
{ path_straight(l), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(180) },
{ path_straight(l), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(-180) },
{ path_straight(l), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(180) },
{ path_straight(l), roll_angle(0) },
{ path_vertical_arc(radius, 45), roll_angle(-90) , roll_ref=180 },
})
end
function f25_2(radius, height, arg3, arg4) -- figure p
local l = (height - (2 * radius))
return make_paths("f25_2", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l/20), roll_angle(0) },
{ path_straight(l* 6/10), roll_angle(360) },
{ path_straight(l* 3/10), roll_angle(-180) },
{ path_straight(l/20), roll_angle(0) },
{ path_vertical_arc(-radius, 270), roll_angle(0) },
})
end
function f25_3(length, arg2, arg3, arg4) -- roll combination
return make_paths("f25_3", {
{ path_straight(length/13), roll_angle(90) },
{ path_straight(length/13), roll_angle(0) },
{ path_straight(length/13), roll_angle(90) },
{ path_straight(length/13), roll_angle(-90) },
{ path_straight(length/13), roll_angle(0) },
{ path_straight(length/13), roll_angle(-90) },
{ path_straight(length/13), roll_angle(0) },
{ path_straight(length/13), roll_angle(-90) },
{ path_straight(length/13), roll_angle(0) },
{ path_straight(length/13), roll_angle(-90) },
{ path_straight(length/13), roll_angle(90) },
{ path_straight(length/13), roll_angle(0) },
{ path_straight(length/13), roll_angle(90) },
})
end
function f25_4(radius, arg2, arg3, arg4) -- half loop
return make_paths("f25_4", {
{ path_vertical_arc(radius, 180), roll_angle(180) },
})
end
function f25_5(radius, height, arg3, arg4) -- reverse humpty
local l = height - (2 * radius)
return make_paths("f25_5", {
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_straight(l/8), roll_angle(0) },
{ path_straight(l*6/8), roll_angle(180) },
{ path_straight(l/8), roll_angle(0) },
{ path_vertical_arc(radius, 180), roll_angle(180) },
{ path_straight(l/8), roll_angle(0) },
{ path_straight(l*6/8), roll_angle(180) }, -- 540
{ path_straight(l/8), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0) , roll_ref=180 },
})
end
function f25_6(radius, height, arg3, arg4) -- spin
local l = (height - (2 * radius))
return make_paths("f25_6", {
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_straight(l/5), roll_angle(0) },
{ path_straight(l/5), roll_angle(360) },
{ path_straight(l/5), roll_angle(0) },
{ path_straight(l/5), roll_angle(180) },
{ path_straight(l/5), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0) },
})
end
function f25_7(radius, arg2, arg3, arg4) -- rolling circle
return make_paths("f25_7", {
{ path_horizontal_arc(radius, 90), roll_angle(180), thr_boost=true },
{ path_horizontal_arc(radius, 180), roll_angle(-180), thr_boost=true },
{ path_horizontal_arc(radius, 90), roll_angle(180), thr_boost=true },
{ path_straight(1), roll_angle(0), roll_ref=180 },
})
end
function f25_8(radius, height, arg3, arg4) -- sharks tooth
local l = height - (2 * radius) -- WRONG
local angle_l = l * 1.9
return make_paths("f25_8", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l * 1/6), roll_angle(0) },
{ path_straight(l * 4/6), roll_angle(360) },
{ path_straight(l * 1/6), roll_angle(0) },
{ path_vertical_arc(radius, 135), roll_angle(0) },
{ path_straight(angle_l/4), roll_angle(0) },
{ path_straight(angle_l/4), roll_angle(180) },
{ path_straight(angle_l/4), roll_angle(-180) },
{ path_straight(angle_l/4), roll_angle(0) },
{ path_vertical_arc(-radius, 45), roll_angle(0), roll_ref=180 },
})
end
function f25_9(radius, height, arg3, arg4) -- vertical square eight
local l = (height - (4 * radius)) / 2
return make_paths("f25_9", {
{ 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, 90), roll_angle(0) },
{ path_straight(l/3), roll_angle(0) },
{ path_straight(l/3), roll_angle(360) },
{ 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(-90) },
{ 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(360) },
{ 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(-90) },
{ 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(360) },
{ 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, 90), roll_angle(0), roll_ref=180 },
})
end
function f25_10(radius, height, arg3, arg4) -- humpty
local l = height - (2 * radius)
return make_paths("f25_10", {
{ 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, 180), roll_angle(0) },
{ path_straight(l/8), roll_angle(0) },
{ path_straight(l * 6/8), roll_angle(540) },
{ path_straight(l/8), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0), roll_ref=180 },
})
end
function f25_11(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("f25_11", {
{ path_straight(base / 2), roll_angle(0) },
{ path_vertical_arc(radius, 135) , roll_angle(-90) },
{ path_straight(side/3), roll_angle(0) },
{ path_straight(side/3), roll_angle(180) },
{ path_straight(side/3), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(180) },
{ path_straight(side/3), roll_angle(0) },
{ path_straight(side/3), roll_angle(180) },
{ path_straight(side/3), roll_angle(0) },
{ path_vertical_arc(radius, 135), roll_angle(-90) },
})
end
function f25_12(radius, height, arg3, arg4) -- half eight sided loop
local l = (height - 2*radius) / ((2*math.sin(math.rad(45))) + 1)
return make_paths("f25_12", {
{ path_vertical_arc(radius, 45), roll_angle(0) },
{ path_straight(l/3), roll_angle(0) },
{ path_straight(l/3), roll_angle(-90) },
{ path_straight(l/3), 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/3), roll_angle(0) },
{ path_straight(l/3), roll_angle(90) },
{ path_straight(l/3), roll_angle(0) },
{ path_vertical_arc(radius, 45), roll_angle(0) , roll_ref=180 },
})
end
function f25_13(radius, height, arg3, arg4) -- 45 down
local l = (height - (2 * radius) + (2 * radius * math.cos(math.rad(45)))) / math.cos(math.rad(45))
return make_paths("f25_13", {
{ path_vertical_arc(-radius, 45), roll_angle(0) },
{ path_straight(l/3), roll_angle(0) },
{ path_straight(l/6), roll_angle(90) },
{ path_straight(l/6), roll_angle(-90) },
{ path_straight(l/3), roll_angle(0) },
{ path_vertical_arc(radius, 45), roll_angle(0) },
})
end
function f25_14(radius, height, arg3, arg4) -- half square
local l = height - (2 * radius)
return make_paths("f25_14", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l/4), roll_angle(0) },
{ path_straight(l/4), roll_angle(360) },
{ path_straight(l/4), roll_angle(-180) },
{ path_straight(l/4), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(0) },
})
end
function f25_15(radius, arg2, arg3, arg4) -- down loop
return make_paths("f25_15", {
{ path_vertical_arc(-radius, 90), roll_angle(-90) },
{ path_vertical_arc(-radius, 90), roll_angle(0) }, -- needs a snap in here
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(90) },
})
end
function f25_16(radius, arg2, arg3, arg4) -- half loop
return make_paths("f25_16", {
{ path_straight(radius/2), roll_angle(90) },
{ path_vertical_arc(-radius, 180), roll_angle(0) },
{ path_straight(radius/2), roll_angle(90) },
})
end
function f25_17(radius, height, arg3, arg4) -- stall turn
local l = height - 2 * radius
return make_paths("f25_17", {
{ path_straight(radius/2), roll_angle(180) },
{ path_straight(radius/2), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l), roll_angle(0) },
{ path_vertical_arc(radius, 180), roll_angle(0) },
{ path_straight(l/3), roll_angle(0) },
{ path_straight(l/3), roll_angle(360) },
{ path_straight(l/3), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(radius/2), roll_angle(0) },
{ path_straight(radius/2), roll_angle(180) },
})
end
straight_roll 80
half_reverse_cuban_eight 60
align_center
message: LooponCorner
f25_1 50 200
align_box 1
message: FigureP
f25_2 70 200
align_center
message: RollCombination
thr_boost: true
f25_3 200
align_box 1
message: HalfLoop
f25_4 70
align_center
message: InvertedHumpty
f25_5 40 200
align_box 1
message: Spin
f25_6 40 200
align_center
message: RollingCircle
f25_7 100
align_box 1
message: SharksTooth
f25_8 30 190
align_center
message: VerticalSquareEight
f25_9 40 200
align_box 1
message: Humpty
f25_10 40 200
align_center
message: Triangle
f25_11 40 200
align_box 1
message: HalfEightSidedLoop
f25_12 40 200
align_center
message: 45Down
f25_13 40 200
align_box 1
message: HalfSquareLoop
f25_14 40 200
align_center
message: DownLoop
f25_15 100
align_box 1
message: HalfLoop
f25_16 100
align_center
message: Stall Turn
f25_17 40 200
straight_roll 100

View File

@ -0,0 +1,385 @@
# trajectory tracking aerobatic control
# See README.md for usage
# Written by Matthew Hampsey, Andy Palmer and Andrew Tridgell, with controller
# assistance from Paul Riseborough, testing by Henry Wurzburg
# To use this schedule put the file on your microSD in the root directory
# (not the APM directory) with name trick92.txt The schedule can then be
# used in auto missions or in TRIKn_ID commands for tricks on a switch
# This schedule is set up to be flown Left to Right. The schedule starts downwind - so
# the mission should be set up with WP's lined up on the flight line (150m out from the
# pilot), and the mission should be triggered when the plane gets to the center marker
# heading RIGHT to LEFT. Schedule direction is reversed with aerom_scale = -1 (and
# remember to reverse the mission WP's as well). Note the required height is greater
# than 400 feet - so only fly at an airfield where there is a 1500 foot clearance
# This is an example of a F3A P23 schedule. Some manouvers are flown over the center
# line of the runway. Please understand the behaviour by flying in SITL before flying this
# schedule with a real aircraft! Your aircraft requires adequate performance to complete
# the schedule
name: F3AP23
function half_reverse_cuban_eight(r, arg2, arg3, arg4)
local rabs = math.abs(r)
return make_paths("half_reverse_cuban_eight", {
{ path_vertical_arc(r, 45), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(180) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_vertical_arc(-r, 225), roll_angle(0) },
})
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)*2/9), roll_angle(0) },
{ path_straight((height-2*radius)*2/9), roll_angle(90) },
{ path_straight((height-2*radius)/9), roll_angle(0) },
{ path_straight((height-2*radius)*2/9), roll_angle(90) },
{ path_straight((height-2*radius)*2/9), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_straight((width-2*radius)/3), roll_angle(0) },
{ path_straight((width-2*radius)/3), roll_angle(180) },
{ path_straight((width-2*radius)/3), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_straight((height-2*radius)*2/9), roll_angle(0) },
{ path_straight((height-2*radius)*2/9), roll_angle(90) },
{ path_straight((height-2*radius)/9), roll_angle(0) },
{ path_straight((height-2*radius)*2/9), roll_angle(90) },
{ path_straight((height-2*radius)*2/9), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(0) },
})
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)
local l = height- (2*radius)
return make_paths("p23_9", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l/4), roll_angle(0) },
{ path_straight(l/2), roll_angle(180) },
{ path_straight(l/4), roll_angle(0) },
{ 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
straight_roll 160 0
half_reverse_cuban_eight 80
align_center
message: TopHat
p23_1 40 200 200
align_box 1
message: HalfSquareLoop
p23_2 40 200
align_center
message: Humpty
p23_3 40 200
align_box 1
message: HalfSquareonCorner
p23_4 40 200
align_center
message: 45Up
p23_5 40 200
align_box 1
message: HalfEightSidedLoop
p23_6 40 200
align_center
message: RollCombination
thr_boost: true
p23_7 200
align_box 1
message: ImmelmannTurn
p23_8 100
align_center
message: ShouldbeaSpin
p23_9 40 200
align_box 1
message: Humpty
p23_10 40 200
straight_align -91
message: LaydownLoop
p23_11 50 200
align_box 1
message: HalfSquareLoop
p23_12 40 200
align_center
message: StallTurn
p23_13a 40 200
align_box 1
message: FighterTurn
p23_14 40 180
align_center
message: Triangle
p23_15 40 200
align_box 1
message: SharksTooth
p23_16 40 160
align_center
message: Loop
p23_17 100
straight_roll 100 0

View File

@ -0,0 +1,376 @@
# trajectory tracking aerobatic control
# See README.md for usage
# Written by Matthew Hampsey, Andy Palmer and Andrew Tridgell, with controller
# assistance from Paul Riseborough, testing by Henry Wurzburg
# To use this schedule put the file on your microSD in the root directory
# (not the APM directory) with name trick94.txt The schedule can then be
# used in auto missions or in TRIKn_ID commands for tricks on a switch
# This schedule is set up to be flown Left to Right. The schedule starts downwind - so
# the mission should be set up with WP's lined up on the flight line (150m out from the
# pilot), and the mission should be triggered when the plane gets to the center marker
# heading RIGHT to LEFT. Schedule direction is reversed with aerom_scale = -1 (and
# remember to reverse the mission WP's as well). Note the required height is greater
# than 400 feet - so only fly at an airfield where there is a 1500 foot clearance
# This is an example of a F3A P25 schedule. Some manouvers are flown over the center
# line of the runway. Please understand the behaviour by flying in SITL before flying this
# schedule with a real aircraft! Your aircraft requires adequate performance to complete
# the schedule
name: F3AP25
function p25_half_loop(radius, arg2, arg3, arg4) -- half roll for testing inverted manouvers
return make_paths("half_loop", {
{ path_vertical_arc(radius, 180), roll_angle(0) , roll_ref=180 },
})
end
function p25_1(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("p25_1", {
{ path_vertical_arc(-radius, 45), 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 /3), roll_angle(0) },
{ path_straight(base /3), roll_angle(180) },
{ path_straight(base /3), 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, 45), roll_angle(0) , roll_ref=180},
})
end
function p25_2(radius, height, arg3, arg4) -- half square
return make_paths("p25_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 p25_3(radius, height, arg3, arg4) -- sq on corner
local l = ((height - (2 * radius)) * math.sin(math.rad(45))) -- CHECK
return make_paths("p25_3", {
{ 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, 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, 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 p25_4(radius, height, arg3, arg4) -- figure p
local l = (height - (2 * radius))
return make_paths("p23_4", {
{ 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, 270), roll_angle(0) },
})
end
function p25_5(length, arg2, arg3, arg4) -- roll combination
return make_paths("p25_5", {
{ path_straight(length/9), roll_angle(90) },
{ path_straight(length/9), roll_angle(0) },
{ path_straight(length/9), roll_angle(90) },
{ path_straight(length/9), roll_angle(0) },
{ path_straight(length/9), roll_angle(90) },
{ path_straight(length/9), roll_angle(-90) },
{ path_straight(length/9), roll_angle(0) },
{ path_straight(length/9), roll_angle(-90) },
{ path_straight(length/9), roll_angle(0) },
{ path_straight(length/9), roll_angle(-90) },
})
end
function p25_6(radius, height, arg3, arg4) -- stall turn
local l = height - 2 * radius
return make_paths("p25_6", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l-60), roll_angle(0) },
{ path_vertical_arc(radius, 180), roll_angle(0) },
{ path_straight(l/3), roll_angle(0) },
{ path_straight(l/3), roll_angle(360) },
{ path_straight(l/3), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0) , roll_ref=180},
})
end
function p25_7(radius, length, arg3, arg4) -- double immelmann
local l = length - (2 * radius)
return make_paths("p25_7", {
{ path_straight(l/4), roll_angle(0) },
{ path_straight(l/4), roll_angle(180) },
{ path_vertical_arc(radius, 180), roll_angle(0) },
{ path_straight(l/4), roll_angle(-90) },
{ path_straight(l/2), roll_angle(0) },
{ path_straight(l/4), roll_angle(-90) },
{ path_vertical_arc(radius, 180), roll_angle(0) },
{ path_straight(l/4), roll_angle(180) , roll_ref=180},
})
end
function p25_8(radius, height, arg3, arg4) -- humpty
local l = height - (2 * radius)
return make_paths("p25_8", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l/4), roll_angle(0) },
{ path_straight(l/4), roll_angle(180) },
{ path_straight(l/4), roll_angle(-180) },
{ path_straight(l/4), roll_angle(0) },
{ path_vertical_arc(-radius, 180), 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) },
})
end
function p25_9(radius, arg2, arg3, arg4) -- loop
return make_paths("p25_9", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(90) },
{ path_vertical_arc(radius, 90), roll_angle(-90) },
{ path_vertical_arc(radius, 90), roll_angle(0) },
})
end
function p25_10(radius, height, arg3, arg4) -- half square on corner
local l = ((height - (2 * radius)) * math.sin(math.rad(45)))
return make_paths("p23_10", {
{ 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) , roll_ref=180},
})
end
function p25_11(radius, height, arg3, arg4) -- double p
local l = (height - (2 * radius))
return make_paths("p25_11", {
{ 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, 270), roll_angle(0) },
{ path_straight(radius * 2/3), roll_angle(0) },
{ path_straight(radius * 2/3), roll_angle(180) },
{ path_straight(radius * 2/3), roll_angle(0) },
{ path_vertical_arc(radius, 270), 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) , roll_ref=180},
})
end
function p25_12(radius, height, arg3, arg4) -- inverted tear drop
local l = (height - (2 * radius))
local angle_l = l * 1.4
return make_paths("p25_12", {
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_straight(l/5), roll_angle(0) },
{ path_straight(l/5), roll_angle(90) },
{ path_straight(l/5), roll_angle(0) },
{ path_straight(l/5), roll_angle(90) },
{ path_straight(l/5), roll_angle(0) },
{ path_vertical_arc(radius, 225), roll_angle(0) },
{ path_straight(angle_l/3), roll_angle(0) },
{ path_straight(angle_l/3), roll_angle(180) },
{ path_straight(angle_l/3), roll_angle(0) },
{ path_vertical_arc(radius, 45), roll_angle(0) , roll_ref=180},
})
end
function p25_13(radius, height, arg3, arg4) -- spin
local l = (height - (2 * radius))
return make_paths("p25_13", {
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_straight(l/5), roll_angle(0) },
{ path_straight(l/5), roll_angle(360) },
{ path_straight(l/5), roll_angle(0) },
{ path_straight(l/5), roll_angle(180) },
{ path_straight(l/5), roll_angle(0) },
{ path_vertical_arc(radius, 90), roll_angle(0) , roll_ref=180},
})
end
function p25_14(radius, height, arg3, arg4) -- top hat
local l = (height - (2 * radius))
return make_paths("p25_14", {
{ path_vertical_arc(radius, 90), roll_angle(0) },
{ path_straight(l/5), roll_angle(0) },
{ path_straight(l/5), roll_angle(90) },
{ path_straight(l/5), roll_angle(0) },
{ path_straight(l/5), roll_angle(90) },
{ path_straight(l/5), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_straight(radius/2), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0) },
{ path_straight(l), roll_angle(0) },
{ path_vertical_arc(-radius, 90), roll_angle(0)},
})
end
function p25_15(radius, height, arg3, arg4) -- figure z
--local l = (height - (2 * radius) + (2 * radius * math.cos(math.rad(45)))) / math.cos(math.rad(45))
local l = (height - (2 * radius)) * 0.72
return make_paths("p25_15", {
{ path_straight((height - (2 *radius))/20), roll_angle(0) },
{ path_vertical_arc(radius, 135), 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, 135), roll_angle(0), roll_ref=180},
})
end
function p25_16(radius, height, arg3, arg4) -- commet
-- NEEDS RADIUS + HEIGHT LOSS included.....
local l = (height - (2 * radius)) * 1.36
return make_paths("p25_16", {
{ path_vertical_arc(-radius, 45), roll_angle(0) },
{ path_straight(l/5), roll_angle(0) },
{ path_straight(l/5), roll_angle(90) },
{ path_straight(l/5), roll_angle(0) },
{ path_straight(l/5), roll_angle(90) },
{ path_straight(l/5), roll_angle(0) },
{ path_vertical_arc(radius, 270), roll_angle(0) },
{ path_straight(l/3), roll_angle(0) },
{ path_straight(l/3), roll_angle(360) },
{ path_straight(l/3), roll_angle(0) },
{ path_vertical_arc(-radius, 45), roll_angle(0) },
})
end
function p25_17(height, arg2, arg3, arg4) -- dunny pipe
local radius = height / 4
return make_paths("p25_17", {
{ path_vertical_arc(radius, 135), roll_angle(0) },
{ path_vertical_arc(radius, 45), roll_angle(90) },
{ path_vertical_arc(-radius, 135), roll_angle(0) },
{ path_vertical_arc(-radius, 45), roll_angle(90), 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
straight_roll 160 0
p25_half_loop 100
align_center
message: Triangle
p25_1 40 200
align_box 1
message: HalfSquareDown
p25_2 40 200
align_center
message: SquareonCorner
p25_3 40 200
align_box 1
message: FigureP
p25_4 70 200
align_center
message: RollCombination
thr_boost: true
p25_5 200
align_box 1
message: StallTurn
p25_6 40 200
align_center
message: Immelmann
p25_7 100 300
align_box 1
message: Humpty
p25_8 40 200
align_center
message: Loop
p25_9 100
align_box 1
message: HalfSquareonCorner
p25_10 40 200
align_center
message: DoubleP
p25_11 50 200
align_box 1
message: InvertedTearDrop
p25_12 40 200
align_center
message: Spin
p25_13 40 200
align_box 1
message: TopHat
p25_14 40 200
align_center
message: FigureZ
p25_15 40 200
align_box 1
message: Commet
p25_16 40 200
align_center
message: DunnyPipe
p25_17 200
straight_roll 50 0
half_roll 0
straight_roll 50 0

View File

@ -0,0 +1,178 @@
# trajectory tracking aerobatic control
# See README.md for usage
# Written by Matthew Hampsey, Andy Palmer and Andrew Tridgell, with controller
# assistance from Paul Riseborough, testing by Henry Wurzburg
# To use this schedule put the file on your microSD in the root directory
# (not the APM directory) with name trick91.txt The schedule can then be
# used in auto missions or in TRIKn_ID commands for tricks on a switch
# This schedule is set up to be flown Left to Right. The schedule starts downwind - so
# the mission should be set up with WP's lined up on the flight line (150m out from the
# pilot), and the mission should be triggered when the plane gets to the center marker
# heading RIGHT to LEFT. Schedule direction is reversed with aerom_scale = -1 (and
# remember to reverse the mission WP's as well). Note the required height is greater
# than 400 feet - so only fly at an airfield where there is a 1500 foot clearance
# This is an example of a F4C Scale schedule. Some manouvers are flown over the center
# line of the runway. Please understand the behaviour by flying in SITL before flying this
# schedule with a real aircraft! Your aircraft requires adequate performance to complete
# the schedule
name: F4CScaleExampleSchedule
function half_climbing_circle(radius, height, bank_angle, arg4)
return make_paths("half_climbing_circle", {
{ path_horizontal_arc(radius, 180, height), roll_angle_entry_exit(bank_angle) },
})
end
function scale_figure_eight(r, bank_angle, arg3, arg4)
local rabs = math.abs(r)
return make_paths("scale_figure_eight", {
{ path_straight(rabs), roll_angle(0) },
{ path_horizontal_arc(r, 90), roll_angle_entry_exit(bank_angle) },
{ path_horizontal_arc(-r, 360), roll_angle_entry_exit(-bank_angle) },
{ path_horizontal_arc(r, 270), roll_angle_entry_exit(bank_angle) },
{ path_straight(3*rabs), roll_angle(0) },
})
end
function immelmann_turn(r, arg2, arg3, arg4)
local rabs = math.abs(r)
return make_paths("immelmann_turn", {
{ path_vertical_arc(r, 180), roll_angle(0) },
{ path_straight(rabs/2), roll_angle(180) },
})
end
function climbing_circle(radius, height, bank_angle, arg4)
return make_paths("climbing_circle", {
{ path_horizontal_arc(radius, 360, height), roll_angle_entry_exit(bank_angle) },
})
end
function upline_20(r, height_gain, arg3, arg4)
local h = (height_gain - 2*r*(1.0-math.cos(math.rad(20))))/math.sin(math.rad(20))
assert(h >= 0)
return make_paths("upline_45", {
{ path_vertical_arc(r, 20), roll_angle(0) },
{ path_straight(h), roll_angle(0) },
{ path_vertical_arc(-r, 20), roll_angle(0) },
})
end
function loop(radius, bank_angle, num_loops, arg4)
if not num_loops or num_loops <= 0 then
num_loops = 1
end
return make_paths("loop", {
{ path_vertical_arc(radius, 360*num_loops), roll_angle_entry_exit(bank_angle) },
})
end
function half_reverse_cuban_eight(r, arg2, arg3, arg4)
local rabs = math.abs(r)
return make_paths("half_reverse_cuban_eight", {
{ path_vertical_arc(r, 45), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(180) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_vertical_arc(-r, 225), roll_angle(0) },
})
end
function split_s(r, arg2, arg3, arg4)
local rabs = math.abs(r)
return make_paths("split_s", {
{ path_straight(rabs/2), roll_angle(180) },
{ path_vertical_arc(-r, 180), roll_angle(0) },
})
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 barrel_roll(radius, length, num_spirals, arg4)
local gamma_deg = math.deg(math.atan((length/num_spirals)/(2*math.pi*radius)))
local speed = target_groundspeed()
local bank = math.deg(math.atan((speed*speed) / (radius * GRAVITY_MSS)))
local radius2 = radius/(1.0 - math.cos(math.rad(90-gamma_deg)))
return make_paths("barrel_roll", {
{ path_horizontal_arc(-radius2, 90-gamma_deg, 0), roll_angle_entry_exit(-bank) },
{ path_cylinder(radius, length, num_spirals), roll_angle(0) },
{ path_horizontal_arc(radius2, 90-gamma_deg, 0), roll_angle_entry_exit(bank) },
})
end
straight_roll 20 0
side_step 15 70
straight_roll 200
half_climbing_circle -65 0 -50
straight_roll 10 0
align_center
message: ScaleFigureEight
scale_figure_eight -140 -35
straight_roll 20 0
immelmann_turn 90
align_center
message: Descending360
climbing_circle 180 -225 40
straight_roll 40 0
upline_20 100 45
straight_roll 20 0
half_climbing_circle 65 0 50
align_center
message: Loop
loop 80 0 1
straight_align -40
half_reverse_cuban_eight 80
align_center
message: ImmelmannTurn
immelmann_turn 80
straight_align -140
split_s 80
align_center
message: HalfCubanEight
half_cuban_eight 80
straight_align -180
half_climbing_circle 65 0 50
align_center
message: DerryTurn
derry_turn 140 60
straight_roll 80 0
half_climbing_circle -140 0 -50
align_center
message: GearDemo
climbing_circle -140 0 -40
straight_roll 290 0
half_climbing_circle -105 0 -45
align_center
message: BarrelRoll
barrel_roll 80 260 1
straight_roll 5 0
half_cuban_eight 80
straight_roll 60 0

View File

@ -0,0 +1,183 @@
# trajectory tracking aerobatic control
# See README.md for usage
# Written by Matthew Hampsey, Andy Palmer and Andrew Tridgell, with controller
# assistance from Paul Riseborough, testing by Henry Wurzburg
# To use this schedule put the file on your microSD in the root directory
# (not the APM directory) with name trick90.txt The schedule can then be
# used in auto missions or in TRIKn_ID commands for tricks on a switch
# This schedule is set up to be flown Left to Right. The schedule starts downwind - so
# the mission should be set up with WP's lined up on the flight line (150m out from the
# pilot), and the mission should be triggered when the plane gets to the center marker
# heading RIGHT to LEFT. Schedule direction is reversed with aerom_scale = -1 (and
# remember to reverse the mission WP's as well). Note the required height is greater
# than 400 feet - so only fly at an airfield where there is a 1500 foot clearance
# This is the New Zealand Clubman Aerobatics schedule. Please understand the behaviour
# by flying in SITL before flying this schedule with a real aircraft! Your aircraft
# requires adequate performance to complete the schedule
name: NZClubmanSchedule
function half_reverse_cuban_eight(r, arg2, arg3, arg4)
local rabs = math.abs(r)
return make_paths("half_reverse_cuban_eight", {
{ path_vertical_arc(r, 45), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(180) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_vertical_arc(-r, 225), roll_angle(0) },
})
end
function cuban_eight(r, arg2, arg3, arg4)
local rabs = math.abs(r)
return make_paths("cuban_eight", {
--{ path_straight(rabs*math.sqrt(2)), roll_angle(0) },
{ path_vertical_arc(r, 225), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(180) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_vertical_arc(-r, 270), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(180) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_vertical_arc(r, 45), roll_angle(0) },
})
end
function multi_point_roll(length, N, hold_frac, num_points)
if hold_frac <= 0 then
hold_frac = 0.2
end
if num_points <= 0 then
num_points = N
end
--[[
construct a roll sequence to use over the full length
--]]
local seq = {}
local roll_frac = 1.0 - hold_frac
for i = 1, num_points do
seq[#seq+1] = { roll_frac, 360 / N }
if i < num_points then
seq[#seq+1] = { hold_frac, 0 }
end
end
return make_paths("multi_point_roll", {{ path_straight(length), roll_sequence(seq) }})
end
function upline_45(r, height_gain, arg3, arg4)
--local h = (height_gain - 2*r*(1.0-math.cos(math.rad(45))))/math.sin(math.rad(45))
local h = (height_gain - (2 * r) + (2 * r * math.cos(math.rad(45)))) / math.cos(math.rad(45))
assert(h >= 0)
return make_paths("upline_45", {
{ path_vertical_arc(r, 45), roll_angle(0) },
{ path_straight(h), roll_angle(0) },
{ path_vertical_arc(-r, 45), roll_angle(0) },
})
end
function split_s(r, arg2, arg3, arg4)
local rabs = math.abs(r)
return make_paths("split_s", {
{ path_straight(rabs/2), roll_angle(180) },
{ path_vertical_arc(-r, 180), roll_angle(0) },
})
end
function half_cuban_eight(r, arg2, arg3, arg4)
local rabs = math.abs(r)
return make_paths("half_cuban_eight", {
{ path_straight(2*rabs*math.sqrt(2)), roll_angle(0) },
{ path_vertical_arc(r, 225), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_straight(2*rabs/3), roll_angle(180) },
{ path_straight(2*rabs/3), roll_angle(0) },
{ path_vertical_arc(-r, 45), roll_angle(0) },
})
end
function loop(radius, bank_angle, num_loops, arg4)
if not num_loops or num_loops <= 0 then
num_loops = 1
end
return make_paths("loop", {
{ path_vertical_arc(radius, 360*num_loops), roll_angle_entry_exit(bank_angle) },
})
end
function immelmann_turn(r, arg2, arg3, arg4)
local rabs = math.abs(r)
return make_paths("immelmann_turn", {
{ path_vertical_arc(r, 180), roll_angle(0) },
{ path_straight(rabs/2), roll_angle(180) },
})
end
function downline_45(r, height_loss, arg3, arg4)
local h = (height_loss - 2*r*(1.0-math.cos(math.rad(45))))/math.sin(math.rad(45))
assert(h >= 0)
return make_paths("downline_45", {
{ path_vertical_arc(-r, 45), roll_angle(0) },
{ path_straight(h), roll_angle(0) },
{ path_vertical_arc(r, 45), roll_angle(0) },
})
end
straight_roll 100 0
half_reverse_cuban_eight 80
align_center
message: CubanEight
cuban_eight 80
straight_align -130
half_reverse_cuban_eight 80
straight_align 40
message: HalfReverseCuban
half_reverse_cuban_eight 80
straight_align -180
half_reverse_cuban_eight 80
align_center
message: TwoPointRoll
thr_boost: true
multi_point_roll 240 2 0.8 2
straight_align 150
half_reverse_cuban_eight 80
align_center
message: 45DegreeUpline
upline_45 40 180
straight_align -200
split_s 90 90
align_center
message: SlowRoll
thr_boost: true
straight_roll 240 1
straight_align 130
half_cuban_eight 80
align_center
message: TwoLoops
loop 80 0 2
straight_align -210
immelmann_turn 90 90
align_center
message: 45DegreeDownline
downline_45 40 180
straight_align 150
half_cuban_eight 80
straight_roll 100

View File

@ -0,0 +1,35 @@
# Scripted Aerobatics Schedules
This directory contains full aerobatic schedules for the ArduPilot
fixed wing scripted aerobatics system. If you develop your own
schedules please contribute to the project by submitting them for
inclusion in this directory.
## Usage
To use one of these schedules in SITL copy it (or use a symbolic link)
to a file called trickNN.txt in your scripts/ directory (the same
directory that plane_aerobatics.lua goes in). The NN is the trick
number used in the AUTO mission or with tricks on a switch in the
TRIKn_ID parameter.
For example, if you wanted to fly the NewZealand Clubman schedule you
could copy NZClubMan.txt to trick94.txt in your scripts
directory. Then you could set TRIK3_ID to 94 to make this schedule be
trick 3. Or you could put 94 in the NAV_SCRIPT_TIME auto-mission
command.
## Scaling
Some of these schedules are quite large and you may need to shrink
them for your model or flying field. You can use the AEROM_PATH_SCALE
parameter to adjust the size. For example, setting AEROM_PATH_SCALE to
0.5 will halve the size of the schedule. This impacts all tricks and
schedules.
You can also mirror the schedule by setting AEROM_PATH_SCALE to a
negative value. This is good if the schedule is designed to be flown
right-to-left and you want to fly it left-to-right due to the wind
direction. If you set AEROM_PATH_SCALE to -0.5 then it would do a
half-scale mirrored schedule.