flighttrack5_c.jpg
Figure 1: Mission Planner waypoints and telemetry track after 3 spline circuits


I wanted my ArduCopter to fly smooth continuous curves between waypoints for some nicer aerial video, so I coded up this SplineNav class. Each spline segment is a cubic polynomial curve defined in 3D space, with 1st and 2nd derivatives continuous wherever two segments meet at a waypoint. This gives a nice smooth transition between curve segments during flight (Figure 1). It also saves time and battery, since abrupt speed and direction changes are avoided.

3D_track.jpg
Figure 2: Autopilot logged track after 3 spline circuits


The SplineNav class, like CIRCLE mode, calls the loiter controller, which is what allows it to precisely control position along the curve using GPS and inertial navigation (thanks to the brand new ArduCopter 3.0 firmware). Unlike CIRCLE mode, in SplineNav the autopilot takes full control of setting altitude as well, so it can fly complex 3D curves. However, it also references your WPNAV_SPEED, WPNAV_SPEED_DN, and WPNAV_SPEED_UP parameter settings to avoid flying too fast, or climbing or descending too quickly.

For this video I wanted a slightly more wild ride, so I increased my WPNAV_SPEED_DN to 250 cm/s, and WPNAV_SPEED_UP to 350 cm/s. I left WPNAV_SPEED at 500 cm/s for now, but will try increasing it later. Figure 2 shows the 3D track in Google Earth. If you reduce these UP/DN speed parameters you will get the same 3D track for these waypoints, but at the steep up and down locations SplineNav will reduce its travel speed along the 3D curve.

 

Video

I shot this SplineNav demonstration video with my ArduPhantom. The GoPro is mounted on a Hummer 2-axis brushless gimbal designed for DJI Phantom.

Source Code

Here's the source code for developers and brave testers to test and suggest fixes and improvements. There's a .PDE file and an .H file, both of which go in your ArduCopter 3.0 sketch folder:

SplineNav.h
SplineNav.pde

Follow the directions in the SplineNav Readme to make the ArduCopter 3.0 code call SplineNav. Then compile with the special ArduPilot version of the Arduino IDE, and upload to your copter. Set your waypoints with Mission Planner, or with the channel 7 switch, and go test out SplineNav.

 

Warnings

Make sure your loiter is rock solid before you test, because SplineNav relies on the loiter controller. Also, the first time you test a new set of waypoints, you should probably keep WPNAV_SPEED low, perhaps just 200 cm/s or so. That way you'll have enough time to take over control in case the spline curve intersects any solid objects!
E-mail me when people leave their comments –

You need to be a member of diydrones to add comments!

Join diydrones

Comments

  • Moderator

    Waiting for the right weather is part of the puzzle for all of this. A chap I have had the honour of meeting and flying with is the European AP champion IMHO , he does not fly with autopilots and frames the shots by eye, looking at his homebuilt fixed wing aircraft and thinking its right. He will sit under a tree for hours waiting for the clouds and light. If you know your craft is only good for 15 knot winds then don't fly above that. At the end of the day you have not invested in an EC 135 and a million dollar cineflex gimble so something has to give.

    You can tell by photos submitted all over the place who knows what they are doing and who thinks there work is good enough.

  • Thanks Gary, yes, and I'm really looking forward to doing some more interesting videos with the SplineNav feature. Most of my past videos were via FPV, but it's oftentimes hard for me to control it smoothly enough and make it go where I want it at the same time, so with FPV I usually have to fly a segment over and over to get it right. With SplineNav I can just set the waypoints I want with channel 7, make some adjustments in mission planner, and get almost the exact track I want without a lot of repeat attempts. Also, once I have the track set up and ready, then I can wait until the right time or day when weather/lighting conditions are just right to fly the final video shoot.

  • Hi Leonard, thanks for the explanation, I think I understand the potential issue now. If people are running SplineNav into a headwind or at too high of a requested ground speed, etc, then the copter could trail behind the target position (either horizontally, or in altitude). So I need to add a check that the target position isn't getting too far ahead of copter position, and reduce the target speed if it is. I will consider possible solutions and see what I can come up with.

  • David, you have just seriously increased the value and versatility of the APM platform, especially for video and photographic applications.

    Great video too, it really shows what you accomplished.

    It is fantastic that the APM still had room for it, I, can't wait to see what you will do with a PX4.

    Great job.

  • Developer

    Great work David! The problem arises when one of those parameters exceeds what the copter is capable of.

    For example I was running my copter at 15m/s at ACV but it is only just capable of this 17m/s I think (at sea level). So any head wind means the copter can't achieve the requested ground speed and can loos altitude trying. this was a problem with the previous version and there were a number of "fast landings" in ACV2012 because of this.

    We should chat on skype sometime. Randy and I are both excited to include your code in 3.1.

  • awesome, I totally wanted to do this too, thankyou !!  I hope this gets integrated into the official builds soon!

  • Developer

    This looks stunning. way to go!

    Jason

  • Hi Leonard. Currently my code looks at what the climb rate, decent rate, velocity, and acceleration will be, and adjusts target velocity accordingly if any of them would otherwise exceed the parameters.

    I'm running this on APM 2.5, not PX4. I was careful to try and make the code efficient in memory and execution, and the APM seems to have enough power to run it just fine.

  • Developer

    MATE, we were talking about this and how the loiter controller is set up to do this. Well done!

    I have not looked through your code yet but the thing that took us some time to get right is the trade off between horizontal speed and height. With the auto controller we aren't using the feed forward, that means the point we define is a distance in front of the copter (the leash). This lets us stop the point abruptly with enough distance for the copter to decelerate. We use the leash length in the horizontal and the vertical to slow the copter down if it begins to loose altitude because it is fighting into a head wind or is simply asked to go too fast (like at ACV).

    Have you considered this already in your implementation (somehow I won't be surprised if you have)?

    Finally, were you using a PX4 or and APM for this. When we were discussing this we were thinking that spline navigation will probably be a PX4 only thing.

  • Yes, the acceleration limiting is already implemented, as it's necessary in case the user chooses waypoints that result in tight curves. See lines 68 to 75 of SplineNav.pde.

This reply was deleted.