From ea44da1e8dc9443665d7c71758b4007406115aaa Mon Sep 17 00:00:00 2001 From: Rolf-G Date: Sun, 26 Jun 2022 14:00:09 +0200 Subject: [PATCH] AP_Scripting: examples: Aerobatics: Corrects arg1/arg2 Corrects bad description of arg1 and arg2 for rolling circle in plane_aerobatics.lua See https://github.com/ArduPilot/ardupilot/issues/21022 --- .../examples/Aerobatics/Missions/plane_aerobatics.lua | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Scripting/examples/Aerobatics/Missions/plane_aerobatics.lua b/libraries/AP_Scripting/examples/Aerobatics/Missions/plane_aerobatics.lua index 5ef1524ba3..e5a8b2232c 100644 --- a/libraries/AP_Scripting/examples/Aerobatics/Missions/plane_aerobatics.lua +++ b/libraries/AP_Scripting/examples/Aerobatics/Missions/plane_aerobatics.lua @@ -1,7 +1,7 @@ --[[ perform simple aerobatic manoeuvres in AUTO mode cmd = 1: axial rolls, arg1 = roll rate dps, arg2 = number of rolls cmd = 2: loops or 180deg return, arg1 = pitch rate dps, arg2 = number of loops, if zero do a 1/2 cuban8-like return -cmd = 3: rolling circle, arg1 = radius, arg2 = number of rolls +cmd = 3: rolling circle, arg1 = earth frame yaw rate, dps, arg2 = roll rate, dps cmd = 4: knife edge at any angle, arg1 = roll angle to hold, arg2 = duration cmd = 5: pause, holding heading and alt to allow stabilization after a move, arg1 = duration in seconds ]]-- @@ -342,7 +342,7 @@ local rolling_circle_yaw = 0 local rolling_circle_last_ms = 0 function do_rolling_circle(arg1, arg2) - -- constant roll rate circle roll, arg1 radius of circle, positive to right, neg to left, arg2 is number of rolls to do + -- constant roll rate circle roll, arg1 = earth frame yaw rate, dps, positive to right, neg to left, arg2 = roll rate, dps if not running then running = true rolling_circle_stage = 0