David Dewey's Posts (4)

Sort by

 

After a few months of hard work, SplineNav 0.3 is now ready to fly! This SplineNav release started with the goal of simply reducing the yaw jitter issues of SplineNav 0.2, but in the end it turned into a major rewrite of the code.

 

New Features:

 

  • Smoother Yaw: Updates x and y spline derivative calculations faster, in a separate loop, for a more precise yaw control. Uses a fast approximation of the atan2 function to compute the yaw angle from the spline derivative.
  • Features yaw rate smoothing for much smoother video, avoiding the small yaw "jerk" at each waypoint.
  • Allows manual override of yaw control, then takes back auto control of yaw if the pilot centers the stick when yaw is directed approximately in the direction of the spline curve.
  • Now enters SplineNav mode smoothly, without an initial jerk.
  • Uses it's own flight mode, so unlike SplineNav 0.2 it doesn't override your Circle mode. To use SplineNav 0.3, set one of your FLTMODE parameters to 14 in the Full Parameter List.

 

SplineNav Waypoints

 

We collected the waypoints for this video while flying FPV, and flipping the channel 8 switch at each point to record. Then we loaded the waypoints into Mission Planner, and made some small adjustments:

waypoints.png
Waypoints recorded during FPV flight and adjusted in Mission Planner


The GPS track indicates it hit all the waypoints quite precisely, on each lap for a total of 3 laps (72 waypoints in total):

splinenav_track.png
GPS track from dataflash log shows SplineNav hitting each waypoint precisely over 3 complete laps


The waypoints had a range of altitudes set, from 7 to 35 meters. Here is the flight profile from the autopilot logs, imported into Google Earth:

GPS_profile.png
GPS flight profile from dataflash logs after 3 complete laps

 

Hardware Used:


Airframe: 3D Robotics Quad, with some modifications.

Autopilot
: 3DR APM 2.6, with external compass/GPS module

Motors
: T-Motor MT2216 KV800

Props
: APC 11x4.7

Gimbal
: WIND-1 two-axis brushless

Camera
: GoPro Hero 3 Silver

Telemetry
: 3DR 433 MHz

R/C
: FlySky TH9X(ER9X FW) + 2.4GHz FrSky DJT module + V8R7-II rx

FPV
: ImmersionRC 5.8GHz 600mA + FatShark Predator + SecurityCamera2000 CMQ1993X
Also: These mods for longer range FPV.

SplineNav 0.3 Firmware Installation:

 

  1. First make sure your quad copter is flying well with ArduCopter version 3.0.1, since SplineNav 0.3 is based on this firmware version.
  2. Go to https://github.com/mavbot/SplineNav, and click the "Download ZIP" link.
  3. In the special Ardupilot version of Arduino, go to File -> Preferences and set your sketch directory to the path of the "SplineNav-SplineNav-0.3" directory from the extracted zip archive.
  4. Restart Arduino, then choose File -> Sketchbook -> ArduCopter from the menu.
  5. From the ArduPilot menu, make sure your HAL Board is set correctly.
  6. Connect your copter's APM via USB, and from Arduino's Tools menu make sure the serial port is set correctly.
  7. Click the Upload arrow button and wait for the code to compile and upload to your APM.
  8. Set one of your FLTMODE parameters to 14 in Mission Planner's Full Parameter List, set your waypoints (either with Mission Planner or with the channel 7 or 8 switch), then go fly!

Note: If you have any special requirements, such as a frame or orientation other than quad X, remember to make those adjustments in the code before compiling. Or if you'd rather not compile yourself, please contact us to get a hex file you can upload directly via Mission Planner.

 

Parameters

 

Here are the speed and acceleration parameters we used for this video (set in Mission Planner):

WPNAV_SPEED: 1350 cm/s
This should make SplineNav go about 49 km/h on straight segments.

WPNAV_SPEED_UP: 1000 cm/s

WPNAV_SPEED_DN: 650 cm/s

WPNAV_LOIT_SPEED: 1500 cm/s
Should be set higher than WPNAV_SPEED.

WPNAV_ACCEL: 180 cm/s/s
Nice low value for a smooth steady start.

Also, the following parameters are #defines in the splinenav.h source code, and can be changed at compile time:

SPLINE_TENSION: 1.6
Higher tension splines curve more tightly at waypoints, but straighter in between waypoints. A tension value of 2 makes it a Catmull-Rom spline. We found that slightly lower tensions tend to give nice loose curves for smooth aerial video.

SPLINE_CURVE_ACCEL_MULTIPLE: 2.0
This allows for twice the max curve acceleration as set in the WPNAV_ACCEL parameter. Added this parameter to allow for smooth slow starts without making tight curves overly sluggish.

SPLINE_JERK: 200.0 cm/s/s/s
Jerk is the maximum rate that SplineNav increases or decreases acceleration as it flies the curve.

SPLINE_LOOP: true
This makes SplineNav loop the waypoints forever until you exit out into another mode.

Read more…


I've now finished coding up SplineNav version 0.2. It's almost a complete rewrite from version 0.1. Besides flying smoother and using processor resources more efficiently, it now restricts maximum speed to prevent lag. For example, if you're flying fast into a strong headwind, then altitude may get low due to insufficient downward thrust, and position may also start lagging target, resulting in corner cutting. SplineNav now tracks this, and continuously and smoothly adjusts target speed to allow the copter to keep up without major altitude loss. So it's now completely safe to crank up the speed settings and fly SplineNav really fast.

 

SplineNav Waypoints

I collected the waypoints for this video while flying FPV, and flipping the channel 8 switch at each point I wanted to record. Then I loaded the waypoints into Mission Planner, and made some small adjustments (Figure 1). I also checked them by flying SplineNav at low speed first, and watching via FPV how close it got to the trees.

map.jpg
Figure 1: Waypoints recorded during FPV flight and adjusted in Mission Planner


After the low speed check I felt comfortable to fly it at max speed, although it was still very nerve racking, because it was zipping by a few meters from those weeping willow trees at about 60 km/h. I'm not sure I could have reacted in time to prevent my copter going to the bottom of the pond had a GPS error caused it to brush the willow branches and careen out of control!

 

Flight Log Track

After the flight, I loaded the log data into Google Earth and exported a KML file to overlay on the map, using Mission Planner's handy KML Overlay feature (Figure 2).

map_track.jpg
Figure 2: Purple track is GPS recorded track during SplineNav flight


As you can see, the GPS track indicates it hit all the waypoints very precisely, expect it slightly missed waypoint 8, which I attribute to the copter having just flown right next to a large building which could have caused GPS signal reflections.

The waypoints had a range of altitudes set, for a more interesting flight. Here is the flight profile from the data logs, imported into Google Earth:

altitude_profile.jpg
Altitude profile generated in Google Earth from flight log data

Hardware Used

Airframe: ArduPhantom (DJI Phantom case, stock motors, ESC, and battery)
Autopilot: 3DR APM 2.5
Gimbal: Hummer 2-axis brushless gimbal for DJI Phantom and GoPro 3
Camera: GoPro Hero 3 Silver
GPS: 3DR ublox LEA-6H
Telemetry: 3DR 433 MHz
R/C: FlySky TH9X(ER9X FW) + 2.4GHz FrSky DJT module + V8R7-II rx
FPV: ImmersionRC 5.8GHz 600mA + FatShark Predator goggles

 

Software

This test was done using the excellent new ArduCopter 3.0.1 release code, that I then modified to include and call the SplineNav code.

The latest SplineNav code, already integrated into my own branch of ArduCopter 3.0.1, is available here: https://github.com/mavbot/SplineNav

 

SplineNav 0.2 Firmware Installation

Warning: Only install SplineNav if your copter is already working well with ArduCopter Version 3.0.1, and if you're experienced enough to test fly it safely.

1. Download the code with this link: https://github.com/mavbot/SplineNav/archive/SplineNav-0.2.zip and extract the zip file.

2. In the special Ardupilot version of Arduino, go to File -> Preferences and set your sketch directory to the path of the "SplineNav-SplineNav-0.2" directory from the extracted zip archive.

3. Restart Arduino, and choose File -> Sketchbook -> ArduCopter from the menu.

4. From the ArduPilot menu, make sure your HAL Board is set correctly.

5. Connect your copter's APM via USB, and from the Tools menu make sure the serial port is set correctly.

6. Click the Upload arrow button and wait for the code to compile and upload to your APM.

7. Set your waypoints (either with Mission planner or with the channel 7 or 8 switch), then go fly!

Note: Since there is not yet any SPLINENAV mode in Mission Planner, SplineNav for now just commandeers CIRCLE mode. So switch to CIRCLE mode on your transmitter when you're ready to fly your waypoints with SplineNav.

 

Parameters

Here are the speed and acceleration parameters I used for this video (set in Mission Planner):

WPNAV_SPEED: 2000 cm/s
My copter can't fly 2000 cm/s, but SplineNav correctly kept the speed adjusted to what my copter can actually handle, and according to the GPS data it reached a maximum velocity of 1760 cm/s (63 km/hour).

WPNAV_SPEED_UP: 350 cm/s
WPNAV_SPEED_DN: 450 cm/s
WPNAV_LOIT_SPEED: 2500 cm/s
WPNAV_ACCEL: 500 cm/s/s

Also, the following parameters are #defines in the splinenav.h source code, but hopefully they will eventually become configurable parameters:

SPLINE_TENSION: 1.4
Higher tension splines curve more tightly at waypoints, but straighter in between waypoints. A tension value of 2 makes it a Catmull-Rom spline. I found that slightly lower tensions tend to give nice loose curves for smooth aerial video.

SPLINE_JERK: 500.0 cm/s/s/s
Jerk is the maximum rate that SplineNav increases or decreases acceleration as it flies the curve.

SPLINE_LOOP: true
This makes SplineNav loop the waypoints forever until you exit out into another mode.


Read more…
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!
Read more…

ufo.jpg
Figure 1: ArduPhantom Night Flying

 

The DJI Phantom has some nice air frame features: A sturdy plastic injection molded polycarbonate enclosure that keeps out light rain and resists hard impacts very well; Nice motors with simple, easy to use prop-mounts that are very unlikely to come loose in flight or get bent or broken in a crash; and very light-weight ESCs that have super bright LEDs on them for easy visual orientation at great distance, and superb night flying (Figure 1).

I also wanted a very small, lightweight, and extremely rugged FPV platform that I could carry in my backpack when I go hiking. The DJI Phantom air frame seems perfect for this, as the propellers are extremely easy and fast to remove, and once removed the rest of the aircraft can be stuffed in my backpack as is, and is sturdy enough to not worry about it being damaged during the trip.

But, since I'm a fan of ArduPilot, and like to be able to perform complex auto missions and make modifications to the code, I decided to build a DJI Phantom air frame with an APM flight controller. The result was very successful, and I encourage you to do the same, following the instructions below.  


Materials


For this build, you will need the following parts. Fortunately, the DJI replacement parts needed can all be purchased quite cheaply. My budget for this entire project was about $600.
 

1x DJI Phantom replacement case kit

1x DJI Phantom replacement screw kit

1x DJI Phantom connectors kit

2x DJI Phantom ESCs (green)

2x DJI Phantom ESCs (red)

4x DJI Phantom motors

2x DJI Phantom props (set of 1 CCW and 1 CW)

1x DJI Phantom landing gear

1x APM 2.5

1x 3DR Power Module

1x 3DR GPS module


Power System Wiring


First you'll need to mount the ESCs and motors in the case, and wire up the ESCs to the output side of the power module. When mounting the ESCs, be sure the green ones are at the front end of the aircraft (the battery door end), and the red ESCs in back. If you put the red ESCs in front instead, then the signal leads won't reach, because they are of different lengths.

There is not much space inside the case for a lot of wiring and connectors, so I just cut off the XT60 connector from the output side of the APM power module, and soldered the connection directly, insulating with heat shrink of course. If you plan to use an internal battery, make sure the wiring doesn't cross over the central area where the battery goes, because it will snag on the battery when you take it in or out, and it's already a fairly tight fit for the battery as is.


Also, be sure to keep all the wiring as low in the bottom of the case as possible, so the magnetic fields from high-current wires will not interfere with the autopilot's magnetometer (Figure 2).
esc_motors_power_module.jpg
Figure 2: Power Module and Power System Wiring


Mounting APM, GPS, and RC Receiver


At first I velcro mounted the autopilot, GPS, and receiver to a thin wood plate which I screwed on to the four screw bosses protruding from the case bottom. This held it high enough above the power wiring below to avoid magnetic interference. However, I found that this piece of wood was basically a sounding board for vibration. Even adding foam between it and the autopilot wasn't enough to reduce the vibration to a reasonable level to get good accelerometer readings (Figure 3).
APM_receiver_GPS.jpg
Figure 3: How NOT to mount your APM


Later I found that a soft plastic cottage cheese lid made of Low-Density Polyethylene (LDPE) is a great way to mount the APM, since the soft flexible material helps to dampen vibrations (Figure 4).
APM_receiver_GPS_plastic_lid.jpg
Figure 4: APM mounted on LDPE food lid greatly reduces vibration

Once you get the case on you won't want to remove those 16 screws every time you need to upload the latest version of ArduCopter, or download a flight log. So you should probably make a short USB cable that permanently connects to the APM, as shown connected in figures 3 and 4 above.


LED Connection


You won't be able to see the status of the armed and GPS lock LEDs once the APM is enclosed in the case, so you'll want to connect a couple external LEDs that you can view through the tail light port on the Phantom case. Connect one LED to A4 and one to A6 (you can also connect a buzzer to A5 if you want). Signal goes to the + side of the LED, and ground to the - side. Remember to include resistors in series with each LED to drop the voltage to the proper level for the LEDs you are using (Figure 5).
indicator_leds.jpg
Figure 5: Armed and GPS fix LEDs visible through tailight port

 You'll also need to go into Mission Planner and change the LED_MODE to 11 (the default is 9 for some reason).


Final Assembly


You can now put the top of the case on (attached with the twelve M2.5x5 and four M2.0x8 screws from your screw pack). Once you calibrate and configure everything in Mission Planner then you should be ready to bolt on the props and go fly (Figure 6)DJI phantom
ready_to_fly.jpg
Figure 6: Ready to Fly


Flight Testing


I added a GoPro, a 5.8 GHz video transmitter, and a 3DR telemetry module for some FPV flying during a Sunday hike in the mountains. Here's the results of the first test:


It flies very nicely, even in auto modes. The main issue is shakiness and vibration of the recorded video. Hopefully I can reduce that with some tuning, better camera mounting, and perhaps stiffer props.
Read more…