Arduplane autonomous aerobatics

roger on all that, andy. i was just wondering what would happen in the current mode.

Currently, if the model is stable and ‘mushes’, it will hold full up elevator trying to achieve a demanded pitch rate until the script times out - then will (may) hopefully recover to continue the mission. If the model stalls and happens to then hit a positive deck angle (unlikely), it may think the loop is finished, and continue on the mission. But more than likely things are going to end badly unless you change to manual mode… Once the plane stalls, there is no recovery except manual mode…

The possibility to control flight maneuvers via LUA Script fascinates me among other things because of the various possibilities. Thanks to @tridge , @andyp and the others who helped make this brilliant idea a reality.
After the yaw rate controller for the ACRO mode was implemented and Tridge presented the Lua script, it was also time for me to dare with a real airplane.
The aircraft used is a Durafly Avios Grand Tundra, as it is both good-natured and sufficiently (knife-edge) aerobatic. The STOL characteristics are impressive by the way.


With the YAW Rate Controller alone, barrel rolls became real rolls in Acro Mode. The FC installed so far was a Pixhawk 1 (2MB), unfortunately does not have enough RAM to run the script. Therefore I installed a Matek F765 (V1) last week, which has power in abundance. Before the test flight I had only run the autotune (for all 3 axes). Out of curiosity, I didn’t feel like carefully setting the TECS parameters. To be safe, I set the waypoints to 110 meters altitude and only parameterized a 360° roll. What can I say, it works ! For sure I will still adjust the TECS parameters and throttle parameters and get closer to the settingst. Thanks to the developers.

Rolf

5 Likes

Hi Rolf
That’s awesome! We are working on a better aerobatic implementation… it will take some time, but exciting things to come!
Andrew

In the meantime I have extended the demonstration flight and condensed it a bit:
https://vimeo.com/726520355
(For the rolling circle, note that the input parameters arg1/2 mean the rotation rate at which the circle is flown through (arg1) and the roll rate (arg2), respectively, and not the circle radius or number of rolls.)

1 Like

Slightly off topic, so I’ll keep this to a single post, but lest us Rover guys get left out…

I looked at the scripted aerobatics code for a loop, modified it for lateral nav, and put this quick little test together. For ease of triggering in SITL, I just poll for a switch to LOITER mode and then it does a counterclockwise circle before switching back to the previous mode. I could just as easily implement with NAV_SCRIPT_TIME but wanted an easy way to trigger on demand.

I think this guided mode capability can be leveraged for things like custom obstacle avoidance or complex path planning where straight line nav falls short. Thanks to all here who helped pioneer the bindings and examples!

local RUN_INTERVAL_MS   =  100
local ROVER_MODE_GUIDED =   15
local ROVER_MODE_LOITER =    5

local circle_angle = 0
local circle_angle_increment = 1    -- increment the target angle by 1 deg every 0.1 sec (i.e. 10deg/sec)
local circle_speed = 1              -- velocity is always 1m/s
local last_mode = vehicle:get_mode()

function do_circle()
    local mode = vehicle:get_mode()

    if mode == ROVER_MODE_LOITER then
        circle_angle = 0
        vehicle:set_mode(ROVER_MODE_GUIDED)
    end

    if mode ~= ROVER_MODE_GUIDED then
        if mode ~= ROVER_MODE_LOITER then
            last_mode = mode
        end
        return do_circle, RUN_INTERVAL_MS
    end

    -- calculate velocity vector
    circle_angle = circle_angle + circle_angle_increment
    if (circle_angle >= 360) then
        vehicle:set_mode(last_mode)
        return do_circle, RUN_INTERVAL_MS
    end
    local target_vel = Vector3f()
    target_vel:x(math.sin(math.rad(circle_angle)) * circle_speed)
    target_vel:y(math.cos(math.rad(circle_angle)) * circle_speed)
    target_vel:z(0)

    -- send velocity request
    if not (vehicle:set_target_velocity_NED(target_vel)) then
        gcs:send_text(0, "failed to execute velocity command")
    end
    return do_circle, RUN_INTERVAL_MS
end

return do_circle()
6 Likes

we’ve made a lot more progress, and can now put entire aerobatic schedules on a switch or in a mission
demo here:

some docs here:
https://github.com/ArduPilot/ardupilot/tree/master/libraries/AP_Scripting/examples/Aerobatics/Trajectory

2 Likes

I flew the same schedule on a Flex Innovations Yak55 today:

Overall it did well, but didn’t maintain height in the rolling circle


i’m going to see if I can improve knifeedge height hold to get the rolling circle right

7 Likes

Incredible and absolutely ingenious.
A thousand thanks to Tridge and all those involved. Even the non-trajectory version seemed to be a miracle of technology for some of my pilot friends at the airfield. One of them suspected during the rolling circle, when I held the transmitter aside, that he had become a Candid Camera victim and the actual pilot was hidden behind a bush.

Now I want to exchange the old aerobatic script in my tundra against this new one. The parameters of most maneuvers are clear to me. I want to take the radii from the logfiles of the previous flights.

But two understanding questions I have before planning a mission:

What is the difference between maneuver 15 = Immelman Turn and 6 = Immelmann (FastRoll) . I guess the roll at no.15 is flown slower ?

No.19, Stall turn. I suppose it is the maneuver also called Hammerhead Turn. “Radius” and “Height” make sense as to what it means. But what does the parameter 3 " direction" mean in this context.

Does an airspeed sensor make sense or not ?

Rolf

Hi Rolf

The trajectory stuff really is amazing!!

#15 - the exit roll rate is based on the manouver radius - the bigger the radius, the slower the roll rate - so scales for different aircraft. #6 always does a fast roll regardless of set radius…

The stall turn is experimental - we are still working on how to achieve a stall turn, snap roll and spin. Also still working on a barrel roll. I would suggest not using the stall turn at the moment. This stuff is ‘bleeding edge’ :slight_smile:

Test in SITL and enjoy! More pre-made schedules to come!
Andrew (with huge thanks to Tridge, Matthew Hampsey, Paul Riseborough and Henry Wurzburg)

1 Like

That’s an interesting idea. I have been thinking about the crossover with Object Avoidance too. Not sure what to do with it thought. Would it mean having to move OA into Lua out off c++? Interesting idea perhaps but also a lot of work …
Alternatively - might there be some way for OA (in c++) to trigger Lua script navigation?

It doesn’t mean OA has to move strictly to Lua. A script could work in conjunction with existing OA.

I already have a prototype script that neatly circumvents geofences, which avoids some of the less desirable effects of the existing path planning algorithms (specifically, existing BR and Dijkstra end up skipping more of the preplanned path than is desirable when mowing with a Rover).

I’m not comfortable releasing that script to the masses just yet, as it takes very direct control that could result in bad behavior, and I’d like to mitigate the associated risk(s) a bit better before submitting it as an example or for use at large.

Which plotter is this for planned vs actual trajectory? Looks quite handy.

Maybe we can do something together on this. I’m working on trying to bring OA into Plane - and right away I have similar challenges. I’ve seen exactly what you are talking about with the path planning just skipping part of the pre-planned path - I think it just decides it can get to the end of the mission quicker by just not hitting some of the waypoints, definitely not desirable.
I have been looking at using some of the obstacle avoidance code instead, but still figuring out how the whole thing works.

1 Like

it’s in libraries/AP_Scripting/examples/Aerobatics/Trajectory/view_path.py
I plan to incorporate it into MAVExplorer, and extend for GPS, POS, XKF1 etc

1 Like

barrell roll has been added now. Here is the new trick72.txt sequence with a 2 spiral barrell roll:


4 Likes

an intro video on how to get started with aerobatics:

5 Likes

Hi all i setting up plane for ( Arduplane autonomous aerobatics) can i add ESP32 Development Board WiFi+Bluetooth Dual Core Module WiFi just to upload missions or adjust prams when sitting on the ground or will it play up with the Rc radio link ? and it will do mav link to frsky Sport yaapu Telemetry as well it nice not hove to add a 900mhz telemetry radio as well

I would say it is OK, plenty of people use the ESP32. Just keep the radios and antennas separated as much as practical.

they must be using 900 mhz i place it 300 mm away as soon as i power it the RC link drops off
and if i power on first the radio will not lock to the receiver then i took it out put on the bench power it on
and still plays up with the rc link