mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: Added side_step maneuver
This commit is contained in:
parent
3fd212063c
commit
97bcc11f68
|
@ -1045,6 +1045,20 @@ function barrel_roll(radius, length, num_spirals, arg4)
|
|||
})
|
||||
end
|
||||
|
||||
function side_step(displacement, length, arg3, arg4)
|
||||
local speed = target_groundspeed()
|
||||
local radius = (displacement*displacement + length*length)/(4*displacement)
|
||||
local angle = math.deg(2*math.atan(displacement, length))
|
||||
local sign = sgn(displacement)
|
||||
local bank = math.deg(math.atan((speed*speed) / (radius * GRAVITY_MSS)))
|
||||
displacement = math.abs(displacement)
|
||||
|
||||
return make_paths("side_step",{
|
||||
{path_horizontal_arc(sign*radius, angle, 0), roll_angle_entry_exit(sign*bank)},
|
||||
{path_horizontal_arc(-sign*radius, angle, 0) , roll_angle_entry_exit(-sign*bank)},
|
||||
})
|
||||
end
|
||||
|
||||
function straight_flight(length, bank_angle, arg3, arg4)
|
||||
return make_paths("straight_flight", {
|
||||
{ path_straight(length), roll_angle_entry_exit(bank_angle) },
|
||||
|
@ -2312,12 +2326,13 @@ command_table[22]= PathFunction(two_point_roll, "Two Point Roll")
|
|||
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[26]= PathFunction(barrel_roll, "Barrel Roll")
|
||||
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[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")
|
||||
command_table[201] = PathFunction(nz_clubman, "NZ Clubman")
|
||||
command_table[202] = PathFunction(f3a_p23_l_r, "FAI F3A P23 L to R")
|
||||
|
@ -2361,6 +2376,7 @@ load_table["barrel_roll"] = barrel_roll
|
|||
load_table["straight_hold"] = straight_hold
|
||||
load_table["partial_circle"] = partial_circle
|
||||
load_table["multi_point_roll"] = multi_point_roll
|
||||
load_table["side_step"] = side_step
|
||||
load_table["p23_1a"] = p23_1a
|
||||
load_table["p23_1"] = p23_1
|
||||
load_table["p23_13a"] = p23_13a
|
||||
|
|
Loading…
Reference in New Issue