mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Scripting:Updates to schedules and sports_aero messages
This commit is contained in:
parent
7db1048f91
commit
3a4d33c776
@ -791,7 +791,7 @@ end
|
||||
name[1] = "Roll(s)"
|
||||
name[2] = "Loop(s)/Turnaround"
|
||||
name[3] = "Rolling Circle"
|
||||
name[4] = "Knife-Edge"
|
||||
name[4] = "Straight Hold"
|
||||
name[5] = "Pause"
|
||||
name[6] = "Knife Edge Circle"
|
||||
name[7] = "4pt Roll"
|
||||
@ -817,7 +817,7 @@ function check_trick()
|
||||
return 0
|
||||
end
|
||||
if action == 1 and selection ~= last_trick_selection then
|
||||
gcs:send_text(5, string.format("%s selected", name[id]))
|
||||
gcs:send_text(5, string.format("Trick %u selected (%s)", id, name[id]))
|
||||
last_trick_action_state = action
|
||||
last_trick_selection = selection
|
||||
return 0
|
||||
@ -836,7 +836,7 @@ function check_trick()
|
||||
end
|
||||
local id = TRICKS[selection].id:get()
|
||||
if action == 1 then
|
||||
gcs:send_text(5, string.format("%s selected ", name[id]))
|
||||
gcs:send_text(5, string.format("Trick %u selected (%s)", id, name[id]))
|
||||
return 0
|
||||
end
|
||||
-- action changed to execute
|
||||
|
@ -60,33 +60,32 @@ align_box 1
|
||||
message: HalfReverseCubanEight
|
||||
half_reverse_cuban_eight 25
|
||||
|
||||
message: ScaleFigureEight
|
||||
align_center
|
||||
message: ScaleFigureEight
|
||||
scale_figure_eight -40 -45
|
||||
|
||||
message: Immelmann
|
||||
align_box 1
|
||||
message: Immelmann
|
||||
immelmann_turn 30
|
||||
|
||||
message: StraightAlign
|
||||
message: Roll
|
||||
align_center
|
||||
message: Roll
|
||||
straight_roll 80 2
|
||||
|
||||
message: Split-S
|
||||
align_box 1
|
||||
message: Split-S
|
||||
split_s 30
|
||||
|
||||
message: RollingCircle
|
||||
align_center
|
||||
message: RollingCircle
|
||||
rolling_circle -75 1
|
||||
|
||||
message: HumptyBump
|
||||
align_box 1
|
||||
message: HumptyBump
|
||||
humpty_bump 20 60
|
||||
|
||||
message: HalfCubanEight
|
||||
align_box 1
|
||||
message: HalfCubanEight
|
||||
half_cuban_eight 25
|
||||
|
||||
align_center
|
||||
|
@ -13,57 +13,54 @@
|
||||
name: Sport_Plane_AirShow
|
||||
|
||||
message: Upline45
|
||||
upline_45 10 20
|
||||
upline_45 10 30
|
||||
|
||||
message: SplitS
|
||||
align_box 1
|
||||
split_s 10
|
||||
message: SplitS
|
||||
split_s 15
|
||||
|
||||
message: 4pt Roll
|
||||
align_center
|
||||
message: 4pt Roll
|
||||
multi_point_roll 100 4 .5 0
|
||||
|
||||
message: HalfReverseCubanEight
|
||||
align_box 1
|
||||
message: HalfReverseCubanEight
|
||||
half_reverse_cuban_eight 10
|
||||
|
||||
message: Knife Edge
|
||||
align_center
|
||||
message: Knife Edge
|
||||
straight_flight 150 90
|
||||
|
||||
message: HalfReverseCubanEight
|
||||
align_box 1
|
||||
message: HalfReverseCubanEight
|
||||
half_reverse_cuban_eight 10
|
||||
|
||||
message: Slow Roll
|
||||
align_center
|
||||
message: Slow Roll
|
||||
straight_roll 200 2
|
||||
|
||||
message: HalfReverseCubanEight
|
||||
align_box 1
|
||||
message: HalfReverseCubanEight
|
||||
half_reverse_cuban_eight 10
|
||||
|
||||
align_center
|
||||
message: Rolling Circle
|
||||
align_center
|
||||
rolling_circle 50 6
|
||||
rolling_circle 80 6
|
||||
|
||||
message: HalfReverseCubanEight
|
||||
align_box 1
|
||||
message: HalfReverseCubanEight
|
||||
half_reverse_cuban_eight 10
|
||||
|
||||
message: Figure Eight
|
||||
align_center
|
||||
figure_eight -30 45
|
||||
message: Inverted Figure Eight
|
||||
figure_eight -80 135
|
||||
|
||||
message: ClimbingCircle
|
||||
climbing_circle 20 20 -45
|
||||
|
||||
messge: SplitS
|
||||
align_box 1
|
||||
message: SplitS
|
||||
split_s 10
|
||||
|
||||
message: InvertedFlight
|
||||
align_center
|
||||
message: InvertedFlight
|
||||
straight_flight 200 180
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user