AP_Scripting: re-work multi-point roll using roll_sequence

This commit is contained in:
Paul Riseborough 2022-11-20 09:34:52 +11:00 committed by Andrew Tridgell
parent 486787937a
commit e09ae7bc43
2 changed files with 34 additions and 26 deletions

View File

@ -42,15 +42,12 @@ the ground track.
| 19 | Stall Turn | radius | height | direction | | Yes |
| 20 | Procedure Turn | radius | bank angle | step-out | | Yes |
| 21 | Derry Turn | radius | bank angle | | | No |
| 22 | Two Point Roll | length | | | | 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 |
| 29 | Four Point Roll | length | | | | No |
| 30 | Eight Point Roll | length | | | | No |
| 31 | Multi Point Roll | length | num points | | | No |
| 31 | Multi Point Roll | length | num points | hold frac | | No |
Note: In the script you will find other (specialised) manouvers which do not appear in the
'command table'. These tend to be specialised manouvers which may expect an inverted entry or

View File

@ -1220,28 +1220,39 @@ function vertical_aerobatic_box(total_length, total_width, r, bank_angle)
})
end
function multi_point_roll(length, N, arg3, arg4)
local paths = {}
local len_roll = length * (N-1) / (N*4-1)
local len_hold = length / (N*4-1)
local ang = 360 / N
for i = 1, N do
paths[#paths+1] = { path_straight(len_roll), roll_angle(ang) }
paths[#paths+1] = { path_straight(len_hold), roll_angle(0) }
--[[
a multi-point roll
- length = total length of straight flight
- N = number of points of roll for full 360
- hold_frac = proportion of each segment to hold attitude, will use 0.2 if 0
- num_points = number of points of the N point roll to do, will use N if 0
Note that num_points can be greater than N, for example do 6 points
of a 4 point roll, resulting in inverted flight
--]]
function multi_point_roll(length, N, hold_frac, num_points)
if hold_frac <= 0 then
hold_frac = 0.2
end
return make_paths("multi_point_roll", paths)
end
function two_point_roll(length, arg2, arg3, arg4)
return multi_point_roll(length, 2)
end
function four_point_roll(length, arg2, arg3, arg4)
return multi_point_roll(length, 4)
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 eight_point_roll(length, arg2, arg3, arg4)
return multi_point_roll(length, 8)
return multi_point_roll(length, 8, 0.5)
end
function procedure_turn(radius, bank_angle, step_out, arg4)
@ -1556,7 +1567,7 @@ function nz_clubman() -- positioned for a flight l
{ straight_align, { -180, 0 } },
{ half_reverse_cuban_eight, { 90 } },
{ straight_align, { -120, 0 } },
{ two_point_roll, { 240 }, message="Two Point Roll"},
{ multi_point_roll, { 240, 2, 0.5 }, message="Two Point Roll"},
{ straight_align, { 150, 0 } },
{ half_reverse_cuban_eight, { 90 } },
{ straight_align, { 106, 0 } },
@ -2360,15 +2371,15 @@ command_table[18]= PathFunction(downline_45, "Downline-45")
command_table[19]= PathFunction(stall_turn, "Stall Turn")
command_table[20]= PathFunction(procedure_turn, "Procedure Turn")
command_table[21]= PathFunction(derry_turn, "Derry Turn")
command_table[22]= PathFunction(two_point_roll, "Two Point Roll")
-- 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")
command_table[25]= PathFunction(laydown_humpty, "Laydown Humpty")
command_table[26]= PathFunction(barrel_roll, "Barrel Roll")
command_table[27]= PathFunction(straight_flight, "Straight Hold")
command_table[28]= PathFunction(partial_circle, "Partial Circle")
command_table[29]= PathFunction(four_point_roll, "Four Point Roll")
command_table[30]= PathFunction(eight_point_roll, "Eight Point Roll")
-- 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[32]= PathFunction(side_step, "Side Step")
command_table[200] = PathFunction(test_all_paths, "Test Suite")