mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Scripting: use the new lua load() functionality in the airshow
This commit is contained in:
parent
65746de112
commit
ce88ddef07
@ -43,7 +43,6 @@ the ground track.
|
||||
| 20 | Procedure Turn | radius | bank angle | step-out | | Yes |
|
||||
| 21 | Derry Turn | radius | bank angle | | | No |
|
||||
| 23 | Half Climbing Circle | radius | height | bank angle | | Yes |
|
||||
| 24 | Crossbox Humpty | radius | height | | | Yes |
|
||||
| 25 | Laydown Humpty | radius | height | | | Yes |
|
||||
| 25 | Barrel Roll | radius | length | num spirals | | No |
|
||||
| 26 | Straight Hold | length | bank angle | | | No |
|
||||
|
@ -1157,22 +1157,6 @@ function humpty_bump(r, h, arg3, arg4)
|
||||
})
|
||||
end
|
||||
|
||||
function crossbox_humpty(r, h, arg3, arg4)
|
||||
assert(h >= 2*r)
|
||||
local rabs = math.abs(r)
|
||||
return make_paths("crossbox_humpty", {
|
||||
{ path_vertical_arc(r, 90), roll_angle(0) },
|
||||
{ path_straight((h-2*rabs)/3), roll_angle(0) },
|
||||
{ path_straight((h-2*rabs)/3), roll_angle(90), roll_ref=90 },
|
||||
{ path_straight((h-2*rabs)/3), roll_angle(0) },
|
||||
{ path_vertical_arc(-r, 180), roll_angle(0) },
|
||||
{ path_straight((h-2*rabs)/3), roll_angle(0) },
|
||||
{ path_straight((h-2*rabs)/3), roll_angle(90), roll_ref=-90 },
|
||||
{ path_straight((h-2*rabs)/3), roll_angle(0) },
|
||||
{ path_vertical_arc(r, 90), roll_angle(0), roll_ref=180 },
|
||||
})
|
||||
end
|
||||
|
||||
function laydown_humpty(r, h, arg3, arg4)
|
||||
assert(h >= 2*r)
|
||||
local rabs = math.abs(r)
|
||||
@ -2609,7 +2593,7 @@ command_table[20]= PathFunction(procedure_turn, "Procedure 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[24]= PathFunction(crossbox_humpty, "Crossbox Humpty")
|
||||
-- 24 was crossbox-humpty
|
||||
command_table[25]= PathFunction(laydown_humpty, "Laydown Humpty")
|
||||
command_table[26]= PathFunction(barrel_roll, "Barrel Roll")
|
||||
command_table[27]= PathFunction(straight_flight, "Straight Hold")
|
||||
@ -2652,7 +2636,6 @@ load_table["procedure_turn"] = procedure_turn
|
||||
load_table["derry_turn"] = derry_turn
|
||||
load_table["two_point_roll"] = two_point_roll
|
||||
load_table["half_climbing_circle"] = half_climbing_circle
|
||||
load_table["crossbox_humpty"] = crossbox_humpty
|
||||
load_table["laydown_humpty"] = laydown_humpty
|
||||
load_table["straight_align"] = straight_align
|
||||
load_table["figure_eight"] = figure_eight
|
||||
|
@ -7,6 +7,51 @@
|
||||
# you can use name: to give your sequence a name
|
||||
name: SuperAirShow
|
||||
|
||||
# you can add new path functions, following the same syntax
|
||||
# as in the main plane_aerobatics.lua
|
||||
function triangular_loop(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("triangular_loop", {
|
||||
{ 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
|
||||
|
||||
# a cross-box tophat, used to get us back on track after the barrell roll
|
||||
function crossbox_tophat(radius, height, width, arg4) -- top hat
|
||||
local w = width - 2*radius
|
||||
return make_paths('crossbox_tophat', {
|
||||
{ path_vertical_arc(radius, 90), roll_angle(0) },
|
||||
{ path_straight((height-2*radius)), roll_sequence({{1,0}, {1, 90}, {1, 0}}), set_orient=qorient(0,90,90) },
|
||||
{ path_vertical_arc(-radius, 90), roll_angle(0), set_orient=qorient(180,0,90) },
|
||||
{ path_straight(w), roll_angle(0) },
|
||||
{ path_vertical_arc(radius, 90), roll_angle(0), set_orient=qorient(0,-90,90) },
|
||||
{ path_straight((height-2*radius)), roll_sequence({{1,0}, {1, -90}, {1, 0}}), set_orient=qorient(0,-90,180) },
|
||||
{ path_vertical_arc(radius, 90), roll_angle(0), set_orient=qorient(0,0,180) },
|
||||
})
|
||||
end
|
||||
|
||||
# you can add messages to display on the GCS/OSD while flying
|
||||
message: Loop
|
||||
loop 25 0 1
|
||||
@ -48,9 +93,10 @@ align_center
|
||||
message: BarrelRoll
|
||||
barrel_roll 30 100 2
|
||||
|
||||
message: ProcedureTurn
|
||||
align_box 1
|
||||
procedure_turn 30 45 30
|
||||
message: CrossBoxTopHat
|
||||
crossbox_tophat 20 60 60
|
||||
|
||||
# get back to the start point
|
||||
straight_align 0
|
||||
align_center
|
||||
message: TriangularLoop
|
||||
triangular_loop 20 60
|
||||
|
Loading…
Reference in New Issue
Block a user