mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Scripting: fixed derry turn in aerobatics
This commit is contained in:
parent
6edfe7368e
commit
d5a0421bbb
@ -41,7 +41,6 @@ the ground track.
|
||||
| 18 | Downline-45 | radius | height loss | | | No |
|
||||
| 19 | Stall Turn(experimental) | radius | height | direction | | Yes |
|
||||
| 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 |
|
||||
| 25 | Laydown Humpty | radius | height | | | Yes |
|
||||
| 25 | Barrel Roll | radius | length | num spirals | | No |
|
||||
|
@ -90,10 +90,14 @@ function split_s(r, arg2, arg3, arg4)
|
||||
})
|
||||
end
|
||||
|
||||
function derry_turn(radius, bank_angle, arg3, arg4)
|
||||
function derry_turn(radius, bank_angle, roll_dist, arg4)
|
||||
local direction = sgn(radius)
|
||||
local abs_bank = math.abs(bank_angle)
|
||||
local bank2 = 360.0 - abs_bank*2
|
||||
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) },
|
||||
{ path_horizontal_arc(radius, 90), roll_angle_entry(direction*abs_bank) },
|
||||
{ path_straight(roll_dist), roll_angle(bank2) },
|
||||
{ path_horizontal_arc(-radius, 90), roll_angle_exit(direction*abs_bank) },
|
||||
})
|
||||
end
|
||||
|
||||
@ -155,7 +159,7 @@ half_climbing_circle 65 0 50
|
||||
|
||||
align_center
|
||||
message: DerryTurn
|
||||
derry_turn 140 60
|
||||
derry_turn 140 60 30
|
||||
|
||||
straight_roll 80 0
|
||||
half_climbing_circle -140 0 -50
|
||||
|
@ -309,7 +309,7 @@ end
|
||||
|
||||
local speed_PI = speed_controller(SPD_P, SPD_I, THR_PIT_FF, 100.0, 0.0, 100.0)
|
||||
|
||||
local function sgn(x)
|
||||
function sgn(x)
|
||||
local eps = 0.000001
|
||||
if (x > eps) then
|
||||
return 1.0
|
||||
@ -2199,7 +2199,6 @@ command_table[17]= PathFunction(upline_45, "Upline-45")
|
||||
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[23]= PathFunction(half_climbing_circle, "Half Climbing Circle")
|
||||
command_table[25]= PathFunction(laydown_humpty, "Laydown Humpty")
|
||||
command_table[26]= PathFunction(barrel_roll, "Barrel Roll")
|
||||
|
Loading…
Reference in New Issue
Block a user