Scripted Aerobatics¶
Note
this capability is in ArduPlane 4.2 and higher. It is rapidly evolving. Its suggested that users uses load the current “Latest” firmware and refer to its matching doucmentation ( Scripted Aerobatics ) for best perfoemance.
ArduPilot has the capability of executing aerobatics from a LUA script. Either via AUTO mode mission items, or via scripts executed in many normal plane flight modes, usually controlled via a transmitter switch and selection RC channels.
Note
this requires a vehicle capable of aerobatic flight, properly tuned pitch,roll, and yaw rate controllers, and the pilot should be capable of safely taking over control (by switch or mode change) the vehicle while in an unusual attitude, if the need arises. The ACRO_x_RATE
parameters limit the maximum commanded rate for each axis, as in ACRO mode.
Tricks on a Switch¶
In addition to allowing LUA scripts to take over the vehicles rate controllers during AUTO missions as described above, they can also take control in normal modes like CRUISE or FBWA. This requires that the script:
Enable the feature with a specific call “vehicle:nav_scripting_enable(..)” which returns a boolean indicating success or failure.
Call the “vehicle:set_target_throttle_rpy(….)” function regularly (at least every 50ms) to set the roll/pitch/yaw rates and throttle percentage. Failure to do so, will disable the control overide and return control to the original flight mode. Changing flight modes also disables script control.
This allows the implementation of “Tricks on a Switch” where an activation switch driving an RC channel is used to enable an aerobatics trick script, which is selected by another RC channel. An example system is given here.
This consists of a small control script to read the RC channels for trick selection and activation, and individual trick maneuver scripts for up to 10 different tricks. This allows the exchange of tricks between users, with, at most, the change in a text editor of a given trick’s ID number to fit into the new user’s list of trick scripts loaded on his SD card.
In order to create new tricks, a user needs to have some LUA script creation knowledge, but the task is simplified since they can use existing tricks as templates for the creation of new tricks.
As above, using SITL, especially in conjunction with RealFlight and a RealFlight model like the AddictionX, makes development and debugging much easier without risking a real vehicle.
Below is an introductory video to “Trick on a Switch”:
Here is a video on showing the development of a new trick for Tricks on a Switch:
Setup Instructions for Example Tricks on a Switch Scripts¶
Make sure you have Autotuned your plane and that its capable of doing aerobatics in ACRO mode well (Bixlers and flying wings only can do rolls and loops, generally….no yaw authority…ie should be able to knife edge for full capability). This includes Autotuning the new YAW rate controller. Enable YAW_RATE_ENABLE and set ACRO_YAW_RATE appropriately (90deg/s is a good start). When you Autotune, not only do pitch and roll, but also yaw by exercising the rudder, like pitch and roll.
Enable scripting, on an autopilot that is capable (F7 or H7) with SCR_ENABLE =1 and SCR_HEAP_SIZE = 200000 (which will allow four trick scripts + AUTO mission scripting in the future).
Copy the https://github.com/ArduPilot/ardupilot/tree/master/libraries/AP_Scripting/examples/Aerobatics/Via_Switch scripts into your SD card APM/scripts directory. Use the RAW view and copy to files on the SD card using the same names.
Assign an RC channel to
RCx_OPTION
= 300 for the trick activation switch (low=disable,mid=show trick number selected, high= do it) and one for 301 which is trick selection. You can use a three position for 0/5/10 trick id selection setup toRCx_OPTION
= 301. 0 is disable, 5 is the knife edge, 10 is the loop/immelman example using the above scripts.Upon boot you should see messages that show the trick 5(knife-edge) and 10(loop/immelman) are loaded. Setting the activation switch to mid position will identify the trick number selected by the selection channel on the ground station or TX, if running Yaapu telemetry.
In the Ground Control Station’s parameter lists, you should see a set of “AERO” params….the
AERO_TRICK_RAT
sets the loop pitch rate, try 90deg/s,AERO_RPT_COUNT
sets the number of loops or if 0, an immelman.AERO_TRICK_ANG
set the knife-edge trick angle 0 to 180 or -180 deg that will be executed as long as you have the activation switch high. Using the GCS or Yaapu GCS or CRSF parameter editor, you can change these in air to vary the trick characteristics, if you wishYou can bail out of the trick by putting activation switch low, change modes, or set selector to 0
Remember: ALTITUDE IS YOUR FRIEND! dont attempt your first one below 200feet! and FPV is a good way to try it out first, if you have trouble with seeing the vehicle at that altitude.
Tuning for Aerobatics¶
Normal ArduPilot Autotune provides a safe, stable PID tune for most vehicles. As such, its not optimized for precision aerobatics which require a tight tune. See below: