Showing posts with label complementary filter. Show all posts
Showing posts with label complementary filter. Show all posts

Tuesday, September 18, 2012

Fun with the Complementary Filter / MultiWii

I first started using a complementary filter, not even knowing what it was called at the time, on the DIY Segway project six years ago. It's a convenient way to combine measurements from an accelerometer and an angular rate sensor (gyro) into a better angle estimate than either could provide on its own. The single-axis case (like on a self-balancing vehicle or robot) is very simple, especially if the balancing platform stays close to horizontal where the small angle approximation can be used to linearize the accelerometer measurement. This is the case I wrote up in the Balance Filter white paper.


Since then, I've used the 1DOF small-angle complementary filter on a bunch of projects, including Segstick, Mini-Segstick (which was really just Segstick in disguise), and some quadrotors.

Wait, but quadrotors are not constrained to a single axis of rotation. They have the ability to pitch, roll, and yaw, as well as translate in 3D. A full representation of orientation in 3D is itself a difficult concept to grasp. I've mostly avoided the complexity by working only with small pitch and roll angles, using a separate rate-only controller for yaw. On 4pcb, the pitch and roll complementary filters are completely independent, and take up only four lines of code in total.

Recently, I found a similar implementation of independent pitch/roll complementary filters in the firmware for the KK2.0 flight controller. It was written in a different form than the one I've used on my projects, which got me thinking about equivalent forms. There are now at least three different implementations I've seen that are functionally identical. Anyway, the complementary filter-based angle estimate was disabled in the KK2.0 firmware as of v1.2, and I wondered why that was since it seemed to fly well in my testing. My question was answered by KK himself:
It treats the Roll and Pitch axis separately. It keeps track of the absolute angle by integrating the output from the gyro on that axis, and corrects the angle with a small part of the angle from the accelerometer on that axis when it is within a certain range (+- 10 degrees or something like that).

This angle is then fed into the control PI loop resulting in roll/pitch angles controlled by the stick. 
Unfortunately it was not that easy. It works very well as long as no yaw is commanded when the craft is not level, as seen in the video earlier in the thread. If yaw is applied when not level, both roll and pitch angles change, but roll/pitch gyros does not sense this rotation, resulting in wrong angles. Try for your self with a airplane model in your hand.
So, the scenario of concern is when then the normal vector of the quadrotor isn't vertical. Then, rotating about that normal axis (yaw) will cause the pitch and roll angles to change in a way that isn't measurable by the X and Y rate gyros. This animation shows yaw with and without the normal axis vertical. The accelerometers will still pick up the changing pitch and roll angles, but they are low-pass filtered in the complementary filter so they will only update slowly. Rapid yaw while not horizontal could result in bad angle estimates, and consequently a loss of control.

Tangent Alert:

Now is about the time I would normally expect someone to suggest using a Kalman filter. I would argue that the choice between a Kalman filter and a complementary filter lies on a completely different axis (of decision making...) than the choice of 3D angle representation. For example, you could have a complementary filter acting on quaternions, which would solve the above problem by having a complete set of 3D kinematic equations. Conversely, you can have a Kalman filter operating independently on each single axis.

Until recently, I hadn't seen a good, well-explained example of a Kalman filter applied to a single axis. Most sites refer to it as more of a buzzword, hand-waiving the explanation and using copy-pasted code from another project. However, this post lives up to its title by completely developing a simple and easy to implement Kalman filter for a single rotational axis. It uses a method I only recently began to appreciate where the rate sensor signal is treated as an input, rather than a measurement. The state equations are thus purely kinematic; no information is required about the plant dynamics. The states are the angle and the rate sensor bias. The output is the accelerometer-measured angle, either from a linearized approximation or an arctan operation.

One interesting thing I learned about the Kalman filters in 2.KalmanFilters is that in the bone-stock Kalman filter with known, constant process and measurement noise variance (Q and R), it's possible to pre-compute the time-dependent covariance matrix (and hence the Kalman gains) before you even take your first measurement. This is definitely true in the above-mentioned post: P[i][j], S, K[0], and K[1] don't depend on states or measurements. If the filter is stable, the gains should converge after some amount of time. If they do, the remaining state observer looks like this:

rate = newRate - bias;
angle += dt * rate;
y = newAngle - angle;
angle += K[0] * y;
bias += K[1] * y;


This simple algorithm is very similar to Implementation #3 of the complementary filter from my previous post, the method that is in the KK2.0 firmware. It's based on feedback of the error between the angle prediction using the rate sensor alone and the angle measurement using the accelerometer. In this case, K[0] sets the time constant of the complementary filter. This implementation has a nice addition, though: a bias estimator that can track an unknown and variable gyro bias over time. The rate at which the bias estimate is updated based on the output error is set by K[1].

End of tangent.

I finally understand how a single-axis Kalman filter might work, but it won't solve the problem at hand, which is cross-axis coupling between yaw rate and pitch/roll angle on the quadrotor. I'm not quite ready for a full 3D angle representation, though. I'm a fan of inexpensive hardware like the KK2.0 or my recently-acquired HobbyKing MultiWii clone, both of which are under $30 and have a full 6DOF inertial sensor set (plus more, in the case of the MultiWii clone). However, they use 8-bit fixed-point processors that would struggle to do the math required for a full 3D angle estimation algorithm.

Actually...that's not really true. As far as I can tell from reading the source code, MultiWii now implements an angle estimation algorithm that covers any possible orientation and would have no trouble handling the yaw-while-not-horizontal scenario. It's based on a complementary filter and uses an interesting representation that (I think) would not have problems with gimbal lock. (Pitch and roll are always uniquely defined based on the orientation of the gravity vector with respect to the frame. Heading is treated separately.) Interestingly, the problem of yaw while not level is addressed in the second page of this development thread.

I guess the real reason why I want to implement a simple complementary filter is because I will always prefer a piece of code that I developed from start to finish, even if it's inferior to something that already exists. I like understanding how all the pieces work, including their limitations. So, I'd rather make a small improvement to my existing angle estimation code that solves the problem of yaw rate coupling. With that in mind, I erased my MultiWii and started from scratch...

// integrate pitch rate into pitch angle
int_pitch = angle_pitch + gyro_pitch * DT;
// integrate component of yaw rate into pitch angle
int_pitch += angle_roll * INV_RAD * gyro_yaw * DT;
// filter with error feedback from pitch accelerometer
error_pitch = accel_pitch - int_pitch;
angle_pitch = int_pitch + AA * error_pitch;

// integrate roll rate into roll angle
int_roll = angle_roll + gyro_roll * DT;
// integrate component of yaw rate into roll angle
int_roll -= angle_pitch * INV_RAD * gyro_yaw * DT;
// filter with error feedback from roll accelerometer
error_roll = accel_roll - int_roll;
angle_roll = int_roll + AA * error_roll;

This Implementation #3 again, but with an extra term to include a component of yaw rate in the integration from the previous angle to the gyro-only new angle estimate. The component of yaw rate integrated into pitch is proportional to the roll angle. The component of yaw rate integrated into roll is proportional to the (negative) pitch angle. This linear approximation should hold for small angles (less than 30º) to within 5%. It should provide reasonable performance at the cost of two extra lines of code with some multiplies (still no trig).

To test it, I made a MultiWii-on-a-stick that I could spin around in a cordless drill...



Since it obviously couldn't be USB-tethered, this required an on-board battery and an XBee radio connected to the TX pin of the ATmega328. (It's broken out for use with an external serial LCD module.) This way, I could power it, tilt to some angle, and yaw like crazy while collecting data wirelessly.


First, I did a test with the yaw terms turned off, making the two complementary filters independent again. This is what I have running on 4pcb, but 4pcb is so twitchy anyway I wouldn't have noticed any quirks with yaw-while-not-horizontal. As expected, at a constant angle of about 30º to horizontal, yawing causes the pitch and roll angles to do strange things:


The complementary filter was set to a time constant of 0.99s, so even a modest yaw rate of 65º/s was enough to cause major offset problems due to the accelerometer lag. At higher rates (570º/s), it's hopeless. The filter barely has time to react before a complete rotation is finished, so it barely registers a change in orientation at all. Here's what it looks like in phase space:


If all were working as it should, the initial -30º roll angle would trace out a circle of 30º radius (yes, the radius is now measured in degrees) as it transforms into pitch angle, then back to roll, etc. Clearly, all is not working as it should. At the higher yaw rate, the "circle" becomes a blob off in one corner.

With the extra integration terms from the yaw rate turned on , the result is much better:




Now it seems to have no trouble with yawing at any rate right up to the gyro limit of 2000º/s. The initial angle traces out a nice circle in phase space as the yaw rate shifts it back and forth between pitch and roll. There's a little bit of skew, but it could very likely be from my hack spinny board mount.

So that fixes the yaw problem. I can already think of other minor tweaks to make that wouldn't cost any trig or matrix math. But I think this was the biggest of them. Now that I've taken care of reading in sensors and estimating angles, I think I should have no trouble finishing up my ultra-simple MultiWii control software. My goal is to have a working flight controller in less than 500 lines of (Arduino) code. (The sensor reading and angle filtering code is only 150 lines, 4pcb's entire flight controller is 495 lines.)  

It will only work for "small angles", but with +/-30º of pitch and roll range (45º in a pinch), it should handle the non-acrobatic flying that I do. Maybe when I get myself an STM32F3Discovery board I will do a full 3D flight controller with real math. In the mean time, I'll also attempt to implement the yaw decoupling terms on the KK2.0, but that will be a bit harder since it's all written in assembly.

Friday, August 31, 2012

KK2.0 Testing / Talon Cam Returns

After finding the makings of a complementary filter in the KK2.0 flight controller firmware and enabling it on the Talon Quad, I've been flying it for several days to test out the fast angle control. I've heard from a number of other people who have tried it with mixed results. Several people got it working, confirming that the self-leveling is faster and doesn't overshoot like crazy. But since it has, in at least two cases, lead to crashes, I'll just reiterate the warning that the modified firmware should be considered experimental and tested at ones own risk!

One thing that's 100% certain is that the self-level is set up for small angles. Do not expect it to recover from any position at any time. Do not try to fly acrobatically with self-level on. For one, the accelerometer component is mixed in only for angles that are less than a certain deviation from the horizontal. There's some confusion about what the maximum angle for which accelerometers are factored in is - I would guess based on my reading of the code that it's 26º.

Since the raw accelerometer inputs are treated linearly, the small angle approximation would allow less than 5% deviation from the true angle up to 30º and less than 10% deviation up to 45º. I might try increasing the maximum value for accelerometer merging up to the higher limit of 45º, just to give it more workspace for aggressive flying. Past 45º, the linearizations really start to break down and it would be wise to switch to a gyro-only estimate and hope for the best. (This is assuming that trig operations or other methods of handling large angles are out of the question on an 8-bit microcontroller.)

That's not the only problem, though. As KK himself points out in the now-226-page RCGroups thread, the simple controller based on two complementary filters begins to lose its fast attitude estimate when you combine a yaw command with either a pitch or a roll command:
Unfortunately it was not that easy. It works very well as long as no yaw is commanded when the craft is not level, as seen in the video earlier in the thread. If yaw is applied when not level, both roll and pitch angles change, but roll/pitch gyros does not sense this rotation, resulting in wrong angles. Try for your self with a airplane model in your hand.
That, plus a more direct warning:
In short: only yaw when level. 
Mathematically it makes sense. If you do happen to yaw while within the 26º (?) envelope, the accelerometer readings can still help the angles recover over time. But the fast gyro update is lost. If you yaw while outside the 26º envelope, all bets are off. Since my flying is decidedly conservative, it's possible that the problem had just never come up. So, more aggressive flying is called for.


I felt comfortable enough to put the GoPro back on. It's basically indestructible anyway, and it's a good way of registering the angle of the quad. You can see that I attempted, mostly successfully, some long moderately banked turns. This seems like the most likely scenario where a yaw + roll input would occur and where the sensors have enough time to stray from correct values. While in the turns, I had no trouble maintaining attitude. Coming out of the turns and returning to level flight was a bit trickier (I had one unintentional landing resulting in no damage), but not at all impossible.

Granted, I never really got past 30º in the banked turns. It could start to fail more catastrophically at steeper angles. But the ironic thing is that, until now, I've never felt comfortable enough with the performance of the self-leveling to even attempt these maneuvers. I can also fly nose-in and at larger height with much more confidence thanks to the faster and more stable angle control.

I can think of ways to handle the yaw + roll and yaw + pitch inputs at small angles (45º or less), and they only require math that the ATmega324PA should be able to handle. Maybe I will dig into the assembly more and try to implement something. But, 4pcb has lived this long with nothing but independent pitch/roll complementary filters. (Not that it's the most smooth-flying thing in the world...) Some day I'd like to make my own flight controller from scratch, maybe with a bit more fancy math on a 32-bit processor. But right now this is working very well for me.

Sunday, August 26, 2012

KK2.0 Firmware Mod: Unleash the Complementary Filter

The KK2.0 is HobbyKing's ultra-cheap ($30) multirotor flight controller, which I bought a few of for testing some time ago. Unlike its predecessor, the KK2.0 has a full 6DOF IMU with an InvenSense 3-axis gyro and an Analog Devices three-axis accelerometer.

That means it should be fully-capable of doing angle control (a.k.a. attitude control, self-leveling), where the joystick axes correspond to a commanded pitch and roll angle, and center-stick returns the multirotor to level. This is in contrast to rate control, where the joystick axes correspond to a commanded pitch and roll rate, and center-stick holds the current angle (but does not return the quadrotor to level).

Rate control is good for doing tricks and flips, but angle control is better in most other cases when you want to stay within say +/-30º of horizontal. If you get disoriented, you can go to center-stick and know that the quadrotor will return to level and not go rocketing off into the distance. It's also more well-suited to camera platforms, since it helps maintain a level horizon.

The KK2.0 has a "self-leveling" feature that I was very eager to try, but I was a little disappointed in the performance. It was sluggish, and increasing the gains to make it return to level faster would lead to pendulum-like behavior, especially in the wind. It would eventually return to level, but not before overshooting back and forth a couple times.

Skimming through the 200+ page RCGroups thread for the KK2.0, which is frequently updated by the designer of the KK board, it seems that in the initial firmwares (v1.0, v1.1, and v1.2), self-leveling is implemented using only the accelerometer angle estimate. From the tuning guide,
Q: Why is Autolevel so slow?
A: The autolevel is based only on the ACC. It takes some time before the ACC registers tilt due to the horizontal acceleration of the craft when tilting. It needs some speed to get air resistance and a force on the ACC. Therefore the autolevel works best on draggy crafts. Later I will try to implement a AHRS algorithm, which uses both ACC and gyros to get a immediate tilt angle.
This all sounds very familiar. I have explored the specific problem of creating an angle estimate using both accelerometers and gyros at length on many projects, using a technique known as a complementary filter. I used it on all the self-balancing things I've built or helped build, as well as two quadrotors: 4pcb and the original Edgerton Center copter.

Tangent: Two complementary filter implementations in simple code.

I won't go into the theoretical details here, since they are well-explained in several of the links above, but I will put forward the typical code snippet I use to implement the complementary filter on a single axis of the accelerometer/gyro data. It takes as its input the gyro rate (gyro_rate) and the accelerometer angle (acc_angle), pre-converted into compatible units (deg and deg/s, or rad and rad/s, for example). The accelerometer angle can be calculated with an arctan function or by linearization for small angles.

// Complementary Filter Implementation #1:
filtered_angle = (A)*(filtered_angle+gyro_rate*dt); 
filtered_angle += (1-A)*acc_angle;

The previous angle estimate is incremented by the small angle predicted by multiplying the rate by the loop time (dt). This gyro-only angle estimate is high-pass filtered. The accelerometer-only estimate is low-pass filtered and the two estimates are added to created the new filtered angle estimate (filtered_angle). The time constant of the high-pass and low-pass filters (they are the same) is:

tau = A / (1-A) * dt;

and it depends on the loop time. Larger time constant trusts the gyro for longer and filters the accelerometer more. Making this time constant long enough to overcome the time required for buildup of aerodynamic drag mentioned in tuning FAQ is the key. However, if the gyro rate has a lot of bias, a time constant that is too large can lead to offset in the angle estimate.

Interestingly, the complementary filter can also be formulated as follows:

// Complementary Filter Implementation #2:
filtered_gyro = A*filtered_gyro + (1-A)*gyro_rate;
filtered_acc = A*filtered_acc + (1-A)*acc_angle;
filtered_angle = tau*filtered_gyro + filtered_acc;

Unwrapping the math to show that this is equivalent to Implementation #1 above is a little tricky, but it definitely works out. The nice thing about Implementation #2 is that it's just two low-pass filters, a multiply, and an add. It could be done entirely in analog hardware if one so desired.

Ok but what does this have to do with the KK2.0?

Well, while browsing through the open-source KK2.0 firmware v1.2 (the latest at the time of writing) I stumbled onto a curious section of code. Now, it's entirely written in assembly, and it's been a long time since I programmed in assembly, so it took me some time to interpret it. It's in imu.asm in a section labeled "Calculate Tilt Angle" and another section labeled "Correct tilt angle". If I'm reading it correctly, it behaves roughly like this:

// Complementary Filter Implementation #3:
filtered_angle = filtered_angle + gyro_rate*dt;
error_angle = acc_angle - filtered_angle;
filtered_angle = filtered_angle + (1-A)*error_angle;

And I label it as Implementation #3 because in fact, if you rearrange the math, you get exactly the same thing as the other two. This version is formulated more as an error feedback approach, which is intuitive.

The strange thing about this complementary filter isn't that it's written in a different way...it's that it's entirely commented out! The complementary-filtered angle estimate (I call it filtered_angle, the firmware uses GyroAnglePitch and GyroAngleRoll) is never used. Instead, the self-leveling angle estimate is straight from the accelerometer (what I call acc_angle, and the firmware calls AccAnglePitch and AccAngleRoll).

Maybe it's a planned future upgrade and needs more testing. In any case I decided to turn it on and see what happens. I uncommented the "Calculate Tilt Angle" and "Correct tilt angle" sections in imu.asm. Two other lines also needed to be changed:

b16sub Error, AccAngleRoll, RxRoll ;calculate error

becomes

b16sub Error, GyroAngleRoll, RxRoll ;calculate error

and

b16sub Error, AccAnglePitch, RxPitch ;calculate error

becomes

b16sub Error, GyroAnglePitch, RxPitch ;calculate error

And that's it. Here is the modified firmware I used. No other changes were made to the project. If you want to stare at the code or rebuild the project yourself, you'll need AVR Studio. Otherwise, KK2_1V2_modS.hex is the file to be flashed. Note: Use at your own risk! Most likely, this is a future upgrade that may not be fully ready yet!

I wasn't really expecting this to work so easily, but on the fist test flight after loading the new firmware, I was able to increase the self-level gain  a bit and get very nice angle control:



The stick response is very fast. Going back to center gives very fast return to level, with no overshoot and no pendulum effect. It now flies as well or better than other (way more expensive) flight controllers I've tried. I'm sure that by tuning the complementary filter time constant, the self-level P gain and the inner rate loop PI gains, I could get it to be even better.

So now my $30 flight controller looks like an incredibly good deal.