AP_Scripting: Add four and eight point rolls to plane aerobatics script

Signed-off-by: Paul Riseborough <gncsolns@gmail.com>
This commit is contained in:
Paul Riseborough 2022-11-13 18:07:50 +11:00 committed by Andrew Tridgell
parent 79db2fe4da
commit 2b1098c2b8
2 changed files with 36 additions and 0 deletions

View File

@ -48,6 +48,8 @@ the ground track.
| 25 | Laydown Humpty | radius | height | | | Yes | | 25 | Laydown Humpty | radius | height | | | Yes |
| 25 | Barrel Roll | radius | length | num spirals | | No | | 25 | Barrel Roll | radius | length | num spirals | | No |
| 26 | Straight Hold | length | bank angle | | | No | | 26 | Straight Hold | length | bank angle | | | No |
| 29 | Four Point Roll | length | | | | No |
| 30 | Eight Point Roll | length | | | | No |
Note: In the script you will find other (specialised) manouvers which do not appear in the 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 'command table'. These tend to be specialised manouvers which may expect an inverted entry or

View File

@ -1163,6 +1163,38 @@ function two_point_roll(length, arg2, arg3, arg4)
}) })
end end
function four_point_roll(length, arg2, arg3, arg4)
return make_paths("four_point_roll", {
{ path_straight((length*3)/15), roll_angle(90) },
{ path_straight(length/15), roll_angle(0) },
{ path_straight((length*3)/15), roll_angle(90) },
{ path_straight(length/15), roll_angle(0) },
{ path_straight((length*3)/15), roll_angle(90) },
{ path_straight(length/15), roll_angle(0) },
{ path_straight((length*3)/15), roll_angle(90) },
})
end
function eight_point_roll(length, arg2, arg3, arg4)
return make_paths("eight_point_roll", {
{ path_straight((length*4)/39), roll_angle(45) },
{ path_straight(length/39), roll_angle(0) },
{ path_straight((length*4)/39), roll_angle(45) },
{ path_straight(length/39), roll_angle(0) },
{ path_straight((length*4)/39), roll_angle(45) },
{ path_straight(length/39), roll_angle(0) },
{ path_straight((length*4)/39), roll_angle(45) },
{ path_straight(length/39), roll_angle(0) },
{ path_straight((length*4)/39), roll_angle(45) },
{ path_straight(length/39), roll_angle(0) },
{ path_straight((length*4)/39), roll_angle(45) },
{ path_straight(length/39), roll_angle(0) },
{ path_straight((length*4)/39), roll_angle(45) },
{ path_straight(length/39), roll_angle(0) },
{ path_straight((length*4)/39), roll_angle(45) },
})
end
function procedure_turn(radius, bank_angle, step_out, arg4) function procedure_turn(radius, bank_angle, step_out, arg4)
local rabs = math.abs(radius) local rabs = math.abs(radius)
return make_paths("procedure_turn", { return make_paths("procedure_turn", {
@ -2263,6 +2295,8 @@ 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")
command_table[29]= PathFunction(four_point_roll, "Four Point Roll")
command_table[30]= PathFunction(eight_point_roll, "Eight Point Roll")
command_table[200] = PathFunction(test_all_paths, "Test Suite") command_table[200] = PathFunction(test_all_paths, "Test Suite")
command_table[201] = PathFunction(nz_clubman, "NZ Clubman") command_table[201] = PathFunction(nz_clubman, "NZ Clubman")
command_table[202] = PathFunction(f3a_p23_l_r, "FAI F3A P23 L to R") command_table[202] = PathFunction(f3a_p23_l_r, "FAI F3A P23 L to R")