AP_NavEKF2 in ArduPilot Master - Intrepid Testers Sought

1,453 views
Skip to first unread message

Paul Riseborough

unread,
Oct 21, 2015, 7:11:52 AM10/21/15
to drones-discuss
Now that the new EKF has been pulled ArduPilot master and can be activated via user parameters I thought it was time to start a new thread to share test results, provide instructions on how to run it, etc. Because it can be run in parallel but not used by the control loops I am hoping that some of you will be able to test it and post your findings and logs to this thread. It has been flown on Copter and Plane, but has had limited performance tuning.

Tomorrow I'll share some flight test results to get the ball rolling.

Regards,

Paul

Q) What is the 'New EKF' ?

It is a 24 state extended Kalman filter in the AP_NavEKF2 library that can estimate the following

Attitude (Quaternions)
Velocity (North,East,Down)
Position (North,East,Down)
Gyro bias offsets (X,Y,Z)
Gyro scale factors (X,Y,Z)
Z accel bias
Earth magnetic field (North,East,Down)
Body magnetic field (X,Y,Z)
Wind Velocity (North,East)

Q) How is it different to the legacy EKF in AP_NavEKF ?

It can estimate gyro scale factors which can  improve accuracy during high rate manoeuvres
It can simultaneously estimate both  gyro offsets and orientation on startup whilst moving and doesn't rely on the DCM algorithm for its initial orientation. This makes it ideal for flying from moving platforms when the gyro has not been calibrated.
It is able to recover faster from bad sensor data
It uses slightly less processing power but uses slightly more RAM as it has to buffer more data
It provides a smoother output with none of the 'stepping' associated with fusion of measurements.
It copes better with time delayed measurements

Q) How does it achieve this ?

Instead of trying to estimate the quaternion orientation directly, it estimates an error rotation vector and applies the correction to the quaternion from the inertial navigation equations. This is better when there are large angle errors due to issues associated with linearising quaternions across large angle changes. See "Rotation Vector in Attitude Estimation", Mark E. Pittelkau, Journal of Guidance, Control, and Dynamics, 2003” for details on this approach.

The new EKF runs on a delayed time horizon so that when measurements are fused, they are done so using the state vector and covariance matrix from the same point in time. The legacy EKF uses a simpler method where delayed measurements are fused using stored states and with the covariance matrix from the current time which reduces accuracy.

The delayed filter states are then predicted forward into the current time horizon using a complementary filter that removes the time delay and also filters out noise from the fusion processing. This approach was inspired by the output predictor work done by Ali Khosravian from ANU. "Recursive Attitude Estimation in the Presence of Multi-rate and Multi-delay Vector Measurements,” A Khosravian, J Trumpf, R Mahony, T Hamel - American Control Conference, vol.-, 2015. This is computationally much cheaper than winding the states forward using buffered IMU data at each update, but slightly less accurate.

Further optimisation of mathematics to reduce the number of calculations required.

Q) How do I use it ?

1) Build ArduPilot master or download the latest executable for your platform from the build server: http://firmware.diydrones.com
2) Disable terrain by setting TERRAIN_ENABLE = 0  as we don't have enough memory for two EKF's and the terrain function
3) Enable the new EKF by setting EK2_ENABLE = 1
4) Restart the flight computer

The new EKF will now be running in parallel and logging to NKF1, NKF2, etc but it will not be used by the control loops until you set  AHRS_EKF_TYPE = 2.

5) Once you have inspected the logs and are satisfied it is producing  roll,pitch,yaw velocity and position outputs that are consistent with the legacy EKF, you can fly with it in the control loops by setting AHRS_EKF_TYPE = 2. If you want the control loops to use the old EKF, set AHRS_EKF_TYPE  1.

Q What effect will this have on processor loading

Running both EKF's simultaneously on a Pixhawk flying an IRIS+ resulted in a negligible number of frame over-runs. The legacy EKF can be turned off by setting EKF_ENABLE = 0 if you wish to free up processing time for data logging. I was compiling using GCC 4.9.

Plot these log messages to plot to compare the outputs that are used by the flight control loops. 

Roll (deg): EKF1.Roll and NKF1.Roll
Pitch (deg): EKF1.Pitch and NKF1.Pitch
Yaw (deg): EKF1.Yaw and NKF1.Yaw
NE Velocity (m/s): EKF1.VN,VE and NKF1.VN,VE
Down Position (m): EKF1.PD, NKF1.PD

 A more in-depth look at the filter performance can be had by comparing the innovations for the legacy and new EKF (difference between the filters predicted and measured values for the different sensors)

GPS position innovations (m): EKF3.IPN,IPE and NKF3.IPN,IPE
GPS velocity innovations (m/s): EKF3.IVN,IVE and NKF3.IVN,IVE
Barometer innovations (m): EKF3.IPD and NKF3.IPD
Magnetometer innovations: EKF3.IMX,IMY,IMZ and NKF3.IMX,IMY,IMZ

The smaller the innovations and the less biased (closer to zero mean), the better the filter is performing

IMU error estimates can be viewed by plotting these log messages.

Z accel bias: EKF2.AZ1bias EKF2.AZ2bias NKF2.AZbias (New EKF does not estimate separate bias values for each IMU)
Gyro bias (deg/s): EKF1.GX,GY,GZ and NKF1.GX,GY,GZ
Gyro scale factors: NKF2.GSX NKF2.GSY NKF2.GSZ (Legacy EKF does not estimate scale factors)

Other things to note:

The new EKF starts using GPS when checks pass rather than waiting for the vehicle motors to arm.

The parameters for the new EKF are labelled EK2_* and where the suffix text is the same, they have the same definition as the old EKF parameters, e.g. EK2_ALT_NOISE has the same definition for EKF2 as EKF_ALT_NOISE does for the legacy EKF.

Please be careful - this is new code with limited testing so if you are going to fly with AHRS_EKF_TYPE = 2 make sure you have stabilise mode available if flying a copter or manual mode available for planes.

Robert Lefebvre

unread,
Oct 21, 2015, 8:35:02 AM10/21/15
to drones-discuss
Thanks for this post Paul, it makes the situation much more clear.

I have a few questions:

"The legacy EKF can be turned off by setting EKF_ENABLE = 0 if you wish to free up processing time for data logging. I was compiling using GCC 4.9."

This statement seems to suggest that with both EKF's running, there's a problem using data logging?

"Please be careful - this is new code with limited testing so if you are going to fly with AHRS_EKF_TYPE = 2 make sure you have stabilise mode available if flying a copter or manual mode available for planes."

Using Stabilize mode for Copter won't help if the attitude goes off on EKF2, correct?  You're suggesting this for if the navigation solution goes off?  Perhaps Acro could be used to rescue the copter if the attitude goes off?

Rob

--
You received this message because you are subscribed to the Google Groups "drones-discuss" group.
To unsubscribe from this group and stop receiving emails from it, send an email to drones-discus...@googlegroups.com.
For more options, visit https://groups.google.com/d/optout.

Andy Little

unread,
Oct 21, 2015, 1:23:31 PM10/21/15
to drones-discuss
 This sounds fantastic. It is certainly a coola feature to be able to swap  IMU algorithms. 

regards
Andy 
Message has been deleted

Paul Riseborough

unread,
Oct 21, 2015, 4:43:41 PM10/21/15
to drones-discuss
Rob,

Answers below.

Regards,

Paul

On Wednesday, October 21, 2015 at 11:35:02 PM UTC+11, robert.lefebvre wrote:
Thanks for this post Paul, it makes the situation much more clear.

I have a few questions:

"The legacy EKF can be turned off by setting EKF_ENABLE = 0 if you wish to free up processing time for data logging. I was compiling using GCC 4.9."

This statement seems to suggest that with both EKF's running, there's a problem using data logging?
No problems with standard 50Hz data logging, but my Pixhawk and SD card  combinations struggled to log dual IMU's at 400Hz whilst running both EKF's so the data log regularly missed IMU samples. Changing data logging options had no effect on frame over-runs that I could see. 

"Please be careful - this is new code with limited testing so if you are going to fly with AHRS_EKF_TYPE = 2 make sure you have stabilise mode available if flying a copter or manual mode available for planes."

Using Stabilize mode for Copter won't help if the attitude goes off on EKF2, correct?  You're suggesting this for if the navigation solution goes off?  Perhaps Acro could be used to rescue the copter if the attitude goes off?
Yes, Acro could be used to counteract a slow drift in attitude, but you would need to have set it up without attitude limits and I think it still uses the attitude solution to lock the attitude when sticks are released. I think having direct control over throttle  is the important bit. I did my early testing at low altitude over grass so the option was always there to do a throttle cut.

Paul Riseborough

unread,
Oct 21, 2015, 4:48:42 PM10/21/15
to drones-discuss
Tridge did the work enabling the code to run dual algorithms.

I should also acknowledge Sid Purohit for his initial work splitting the new EKF into separate files to make it more maintainable.

Robert Lefebvre

unread,
Oct 21, 2015, 6:46:33 PM10/21/15
to drones-discuss
Acro uses the AHRS heading even while the sticks are displaced.  It's slewing the heading around.  So yes, if the EKF blows up, it can be bad.  As long as the EKF isn't spinning, if it's just a static offset, it should be flyable.  But if the EKF solution were spinning, or just zero or static, Acro would be totally unflyable.  

You should consider using the Motor Interlock or Estop functionality.  It would allow you to instantly stop the motors from any mode.

Tridge and I have talked about bringing back a pure manual flight mode that just uses native gyro readings for cases where the EKF blows up.  It might not be a normal mode that users would have.

On 21 October 2015 at 16:38, Paul Riseborough <pa...@3drobotics.com> wrote:
Rob,

Answers below


On Wednesday, October 21, 2015 at 11:35:02 PM UTC+11, robert.lefebvre wrote:
Thanks for this post Paul, it makes the situation much more clear.

I have a few questions:

"The legacy EKF can be turned off by setting EKF_ENABLE = 0 if you wish to free up processing time for data logging. I was compiling using GCC 4.9."

This statement seems to suggest that with both EKF's running, there's a problem using data logging?
 
No problems with standard 50Hz data logging, but my Pixhawk and SD card  combinations struggled to log dual IMU's at 400Hz whilst running both EKF's so the data log regularly missed IMU samples.
Changing data logging options had no effect on timing bitter that I could see.

"Please be careful - this is new code with limited testing so if you are going to fly with AHRS_EKF_TYPE = 2 make sure you have stabilise mode available if flying a copter or manual mode available for planes."

Using Stabilize mode for Copter won't help if the attitude goes off on EKF2, correct?  You're suggesting this for if the navigation solution goes off?  Perhaps Acro could be used to rescue the copter if the attitude goes off?
Yes, Acro could be used, but you would need to have set it up without attitude limits and I think it still uses the attitude solution to lock the attitude when sticks are released. The biggest benefit with stabilise (or macro) for this type of testing is the control over throttle. I did my early testing at low altitude over grass so the option was always there to do a throttle cut.

Paul Riseborough

unread,
Oct 21, 2015, 7:53:07 PM10/21/15
to drones-discuss
Here's a flight log from an IRIS+ flying ArduCopter Master with:

TERRAIN_ENABLE=0
EKF_ENABLE = 1
EK2_ENABLE = 1
AHRS_EKF_TYPE = 2


All EKF and EK2 parameters were at the default values with the exception of EK2_MAG_CAL = 4 which forces the magnetometer learning in the new EKF to start running as soon as the EKF starts using GPS. The default is EK2_MAG_CAL = 3 which delays magnetometer learning until it is airborne.

Here are some innovation plots showing the difference between the filters prediction and the measurement.

GPS position innovations

GPS velocity innovations

Barometer innovations


X magnetometer innovations

Y magnetometer innovations


Z magnetometer innovations


The smaller and less biased innovations indicate that the new EKF is probably providing a more accurate solution, however we are talking about small differences other than at the end of flight when the coper is picked up and carried which is when the legacy EKF develops about a metre of position innovation. Here are some difference plots.


Position difference

Velocity difference


Roll and pitch difference








 

Philip Rowse

unread,
Oct 21, 2015, 8:36:54 PM10/21/15
to drones-...@googlegroups.com
Awesome!

Andrew Tridgell

unread,
Oct 21, 2015, 11:38:17 PM10/21/15
to Robert Lefebvre, drones-discuss
> Tridge and I have talked about bringing back a pure manual flight mode that
> just uses native gyro readings for cases where the EKF blows up. It might
> not be a normal mode that users would have.

I would love to see this!

Josh Welsh

unread,
Oct 22, 2015, 1:26:24 AM10/22/15
to drones-...@googlegroups.com
+1

Paul Riseborough

unread,
Oct 22, 2015, 3:16:43 AM10/22/15
to drones-discuss
I have been PM'd with a question about where the derivation can be found.  The Matlab script file that was used to generate the auto-code fragments in the EKF can be found here:


Links to this have been placed in the relevant function header documentation.

Julien BERAUD

unread,
Oct 22, 2015, 5:35:32 AM10/22/15
to drones-discuss
Hi Paul,

I have tried EKF2 on the bebop and have some issues. I fly without a gps or an optical flow and the roll/pitch attitude doesn't look correct.
when I move the drone in different positions and come back to the original flat one(either flying or on the floor), the roll/pitch sometimes indicates an angle.
I noticed while flying that the bebop didn't go back to a flat position.

This doesn't happen with EKF1

Julien

john...@gmail.com

unread,
Oct 22, 2015, 8:02:53 AM10/22/15
to drones-discuss
Yes please. For me the whole point of having a manual mode, is a fallback where you can take control and fly using the absolute minimum of sensors (gyros only) needed for human control. A bypass for whatever the flight controller wants to do. Kinda like the e-stop but for flight control.

Robert Lefebvre

unread,
Oct 22, 2015, 8:15:40 AM10/22/15
to drones-discuss
Ok, lots of interest in this.

What should the mode be called?  Originally I was going to call it Acro-Pure, but I think it really should be a totally different name, not to be confused as Acro.  Rescue Mode?  I think some people would think it's a go-to mode when they lose control (or orientation), and it's really not helpful if you can't fly Acro.  How about Direct Control Mode? (probably can't use 2 words for a mode, so DC Mode for short)?

This shouldn't be hard to do.  It's actually just reverting to the Acro mode I had made for 3.1 I think it was.  It does integrate rate errors and feed back the error through the PID.  But it doesn't use AHRS at all.  Directly reads the gyros.

Rob

john...@gmail.com

unread,
Oct 22, 2015, 8:29:29 AM10/22/15
to drones-discuss
Direct mode is fine and descriptive. Or if not already (wrongly) used, what it actually is. Manual mode. That's what most other controllers call it.

john...@gmail.com

unread,
Oct 22, 2015, 8:41:35 AM10/22/15
to drones-discuss
On second thought, since the mode implies that the users knows what he or she wants. What about Gyro mode? No way of confusing the meaning then.

Robert Lefebvre

unread,
Oct 22, 2015, 10:02:48 AM10/22/15
to drones-discuss
That makes sense.  It's very simple and conveys what is really happening.  FPV racers would love it too.  I've heard that some FPV racing classes will mandate flying with pure rate control.  Not sure if our current Acro mode would satisfy the rules, not sure how they're written.  Acro is pure rate based inputs, but it uses AHRS to augment the attitude hold performance.

Anyway, I really like that idea.

On 22 October 2015 at 08:41, <john...@gmail.com> wrote:
On second thought, since the mode implies that the users knows what he or she wants. What about Gyro mode? No way of confusing the meaning then.

--

Josh Welsh

unread,
Oct 22, 2015, 12:43:15 PM10/22/15
to drones-...@googlegroups.com

I would call it “Rate” to fall in line with what the other Gyro-based flight modes are doing in quadcopter land out there.

 

I am in favor of this for sure, but have had conversations with Leonard on it and think we should get his input as well.

 

From: drones-...@googlegroups.com [mailto:drones-...@googlegroups.com] On Behalf Of Robert Lefebvre
Sent: Thursday, October 22, 2015 7:03 AM
To: drones-discuss <drones-...@googlegroups.com>
Subject: Re: [drones-discuss] AP_NavEKF2 in ArduPilot Master - Intrepid Testers Sought

 

That makes sense.  It's very simple and conveys what is really happening.  FPV racers would love it too.  I've heard that some FPV racing classes will mandate flying with pure rate control.  Not sure if our current Acro mode would satisfy the rules, not sure how they're written.  Acro is pure rate based inputs, but it uses AHRS to augment the attitude hold performance.

Robert Lefebvre

unread,
Oct 22, 2015, 2:27:58 PM10/22/15
to drones-discuss
I'm not sure that Rate would distinguish it enough from Acro, which is already a rate controller.  It should be very clear that this is a simple controller, and not a replacement or alternative for Acro.  Any input from Leonard welcome.  But my old Acro mode worked pretty well and gets us what we really want here.  This isn't about performance or feel.  It's about having a dead-nuts simple controller to rescue a copter with a blown up AHRS.  Tridge has had this happen a number of times which is why he's now flying flybarred helis with an external tail gyro, using an Acro mode that does a straight input-output pass-through.  He's hesitant to try flybarless again because of his experiences with it.  This is a step towards remedying that. 

john...@gmail.com

unread,
Oct 22, 2015, 3:44:54 PM10/22/15
to drones-discuss
Robert, so in helicopter gyro terms. Will it be a rate or head hold system? A pure rate is simpler, but harder to fly. Head hold needs a time based accumulator but is much easier to fly.

Leonard Hall

unread,
Oct 22, 2015, 5:40:26 PM10/22/15
to drones-discuss
This isn't the right place to have this discussion so I will keep it brief.

As we go to quertonion control I should be able to remove the absolute attitude input into the rate controller and effectively integrate rate error. This will simplify the controller maths as well hopefully. All this will mean that steps in the roll and pitch angles won't change acro (EKF switching caused this to happen to Rob once which is why he is so hot on it), however I don't think it justifies a new mode anyway.

The other thing worth mentioning is the current acro is what Rob wants with an additional ACRO_TYPE parameter and an addition to a single IF statement.

Now I would suggest that ad-hoc discussions about unrelated mode concepts be moved out of one of the most important threads currently on drones discuss.

Andrew Tridgell

unread,
Oct 22, 2015, 6:02:01 PM10/22/15
to Robert Lefebvre, drones-discuss
Hi Rob,

I asked Randy about this yesterday and he is happy to support
AHRS-independent ACRO. He suggested it may be best to keep it in ACRO
and adding a parameter selecting if you want this simpler ACRO or
not. He wasn't totally opposed to a new mode instead, just thought a
parameter would be easier.

Also note that it won't make ACRO completely independent of AHRS, as it
will still depend on the gyro bias esimation (and scaling estimation for
EKF2). Those are limited to a reasonably narrow range though, so worst
case the heli would tend to have a bit of a tendency to lean, like it
was badly trimmed.

Regarding Johns question on accumulation, I think a simple accumulator
would be fine, and would probably make it work better if the RATE tuning
is a bit off. I think the accumulators should be variables inside the
logic for the ACRO handling to keep the behaviour as independent of
other systems as possible.

Cheers, Tridge

Paul Riseborough

unread,
Oct 22, 2015, 8:50:51 PM10/22/15
to drones-discuss
OK, i haven't yet tuned it for non-GPS operation so thanks for the feedback.

Paul Riseborough

unread,
Oct 22, 2015, 11:21:22 PM10/22/15
to drones-discuss
Julien,

I did some testing today with non-GPS operation and have pushed a patch as part of a larger PR that gave reasonable matches between GPS and non-GPS aided roll and pitch angles during moderate manoeuvring outdoor operation. If the BeeBop is able to log the IMU data at 400Hz without dropouts, then i would be happy to run your log through replay and compare the two filter solutions


Regards,

-Paul


On Thursday, October 22, 2015 at 8:35:32 PM UTC+11, Julien BERAUD wrote:

Julien BERAUD

unread,
Oct 23, 2015, 3:52:31 AM10/23/15
to drones-discuss
Thanks Paul,

I will try that today.

Julien

Pepe Pérez Español

unread,
Oct 23, 2015, 9:41:43 AM10/23/15
to drones-...@googlegroups.com, Paul Riseborough
That's interesting, but is there any place where the dynamic models and
assumptions are written ?

I've been looking into the code with interest, but it is almost impossible to
verify/contribute without knowing the dynamic model, observability matrices,
and so on.

Greetings

Paul Riseborough

unread,
Oct 23, 2015, 5:52:15 PM10/23/15
to drones-discuss, pa...@3drobotics.com, alejand...@yahoo.es
The plant equations and observation equations are defined in the derivation script file I provided the link to. All of the supporting scripts required to generate the auto-code fragments are in the same repo:


-Paul

Aleksandr Buyval

unread,
Nov 1, 2015, 10:32:25 AM11/1/15
to drones-discuss
Hi Paul,

I have done some experiments with new EKF in SITL mode. I am not sure that these experiments will be helpful for you. But I am concerned about some data which I got.

First of all, I need to explain how I were doing experiments. I have used 'ALT_HOLD' mode and external ROS node to control the virtual copter. This node uses the position of visual marker to hover above marker as on the following video. Also this node uses  the orientaion data from ArduCopter to compensate a tilt during of position calculation of visual marker.

In addition, I have used 'EK2_GPS_TYPE=3' for all experiments.

In the first and the second experiments I have used AHRS_EKF_TYPE = 1. I have got stable flights in these experiments, however I have noticed some stranges in logs.
First strange is that NKF1.PN and NKF1.PE don't start from zero. Each times they starts from differents points.
For instance, in the second expiriment NKF1.PN starts from 8.5.

Note, that in the first experiment initial values of NKF1.PN and NKF1.PE were close to zero.

In spite of this, NKF1.PN and NKF1.PE looks more correct. I have compared the NKF1.PN and NKF1.PE data from the first experiment with ground truth odometry data which I got from ROS/Gazebo environment and NKF1 data are more close to the ground truth odometry. In fact, the simulated copter moves around start position, but as you can see on images above EKF.PN drifts into minus values. 


In the third experiment I have used AHRS_EKF_TYPE = 2. As I understood, in this case, the new EKF is used to control. However, I have not got stable flight in this mode. As I mentioned early, I used the ROS node to control the copter. This node uses the orientation data for own algorithm. I have compared the EKF1.Roll and NKF1.Roll (EKF1.Pitch and NKF1.Pitch) and have found that they are significantly different. And I think that EKF are more correct than NKF, because I could get a stable flight with EKF orientation data and could not with NKF data.

You can see the comparision of EKF1.Roll and NKF1.Roll for first experiment below:


You can see the comparision of EKF1.Pitch and NKF1.Pitch for first experiment below:


Maybe these stranges are specific only for SITL mode. I am going to make some experiments with real copter and new EKF in couple weeks, however I would like to get stable flight in SITL mode before.


PS. I have attached log files for all mentioned experiments.


Best Regards,

Alex






 




среда, 21 октября 2015 г., 14:11:52 UTC+3 пользователь Paul Riseborough написал:
Third experiment.BIN
Second experiment.BIN
First experiment.BIN

Paul Riseborough

unread,
Nov 10, 2015, 3:14:19 AM11/10/15
to drones-discuss
Alex,

I am not familiar with ROS and my testing has been restricted to flight testing on a quad and testing on ArduCopter SITL with good results for both EKF and EKF2. For SITL testing I am using these specific parameters.


For flying my own quad I have set ARMING_CHECK to -42 to avoid the need to lift the quad to clear the range finder check and to ignore the GPS checks

Can you please post a log with pre-arm logging turned on - maybe that will help me to see something, but as you are using a different simulation environment it is difficult to comment on where the error could be.

-Paul

Aleksandr Buyval

unread,
Nov 14, 2015, 6:23:16 AM11/14/15
to drones-discuss
Paul,

I have pulled all last commits from master branch and have turned on the pre-arm checking with compass skipping. 
It looks that the issue with initial values of NKF1.PN and NKF1.PE disappeared. Now they starts close to zero. Also I should say, that NKF1.PN and NKF1.PE values looks more correctly than EKF1.PN and EKF1.PE

However, I have got the issue with NKF1.Roll and NKF1.Pitch values. You can see comparison of EKF1.Pitch (red line), NKF1.Pitch (green line) and Pitch angle from simulation (blue line) on picture below:


As you can see, EKF1.Pitch values look more correctly. Also if I use new EKF to control, the drone will unstable.


I understand that my simulation environment could produce some causes of such results and you will be not able reproduce it on your side. Maybe you give advice which variables should I compare additional to understand this issue.  


Best Regards,

Alex



вторник, 10 ноября 2015 г., 11:14:19 UTC+3 пользователь Paul Riseborough написал:
328.BIN
SITL_598.param

Tobias Witting

unread,
Jan 9, 2016, 3:53:48 PM1/9/16
to drones-discuss
Hi all,
I would like to test the new EKF2 on my 250 quad. I can compile master and upload to my pixhawk and AUAV-X2 boards. Both boards boot fine after the flasing. However MissionPlanner can only connect to the AUAV-X2. The connection to Pixhawk times out. I also tried Qgroundcontrol and APMplanner.
Any hints why pixhawk is not letting me connect via mission planner appreciated.
Cheers,
Tobi

Tom Pittenger

unread,
Jan 9, 2016, 5:02:55 PM1/9/16
to drones-discuss

Via USB? If by serial radio check your baud rate. Default is 57600.

Paul Riseborough

unread,
Jan 26, 2016, 7:00:16 AM1/26/16
to drones-discuss
I will see if there is anything in the log that stands out

Paul Riseborough

unread,
Jan 26, 2016, 8:25:30 PM1/26/16
to drones-discuss
There is a lot of timing error in the data which is evident in magnetometer innovations. How is your simulation synchronised to the autopilot code?


On Saturday, November 14, 2015 at 10:23:16 PM UTC+11, Aleksandr Buyval wrote:

Przemek Lekston

unread,
Feb 23, 2016, 11:00:55 PM2/23/16
to drones-discuss
Hi all,

Could you point me to the new code logic on GPS glitch detection and handling? This commit: 74da4d8e57cf9eac3cc24116314e4aed515c7672 removes the logic integrated into the EKF indicating that it this feature will be now served by the main control loops, but I was unable to find the new corresponding fuctions.

The GPS glitches are among the worst causes of odd APM attitude behaviour I know: I had witnessed a few situations of short time outages during tight turns (both in AUTO and CRUISE modes) when it caused a Attitude indication error of ~20deg or more resulting in excessively tight turns still on EKF1. The outages were most likely related to GPS antenna rejecting some satellites during banking, but let's just consider we have a GPS receiver failure or operate in strong multipath environment - how to make sure that the inertial measurements should be trusted more in this scenario?

Regards,
Przemek

Paul Riseborough

unread,
Feb 27, 2016, 6:13:27 PM2/27/16
to drones-discuss
Przemek ,

Which estimator (DCM, EKF or EKF2) were you using when you experienced the attitude errors?

The EKF2 handles glitches via innovation consistency checks, whose strictness can be adjusted via the EK2_POS_GATE and EK2_VEL_GATE parameters. If a glitch and sudden change in GPs measurements cause them to fail innovation checks, then the uncertainty in position grow until the checks pass. 

To protect against bad IMU data or other non-GPs errors causing indefinite rejection and loss of navigation, if the radial position uncertainty exceeds the value set by the EK2_GLITCH_RAD parameter, then the position and velocity will be reset to the GPS measurements. The innovation consistency checks and reset logic can be found here:

Przemek Lekston

unread,
Mar 1, 2016, 8:45:16 PM3/1/16
to drones-...@googlegroups.com
Paul,

Thank you for the links that you have provided and for the explanation - I am still getting myself familiar with the EKF2 implementation.

In the mean time, I was able to recreate the attitude stability errors I was referring under poor GPS reception conditions. Basically, what I did was to leave the airplane (with all of its APM sensors fully calibrated) on top of a table in under the roof of the top floor of out office. The uBlox receiver is really remarkable in acquiring 3D fixes in such situation, although no surprise here precision is really low - typically I see a lot of GPS glitches with position jumping by 10-20m.

Below I'm enlisting links to the data log and some graphs for a quick overview.

DataLog, Telemetry Log and APM parameter excerpt can be found here:
https://www.dropbox.com/sh/gar373cnwf18c8r/AACl-b0S-BGdz8ONaeBJfanHa?dl=0

While the graphs are here:
Velocity Innovation and Variance
http://tinypic.com/r/2cshy7t/9
Gyro Bias:
http://tinypic.com/r/2hd6sk5/9
Raw Gyro:
http://tinypic.com/r/imo3u8/9

When reviewing the Telemetry Log, GPS fix was acquired at about 50%, around 80% I briefly moved the airplane myself to check Attitude Indicator response, while the attitude started experiencing minor disturbances at about 82%. Around 88% the disturbances become very aggressive and unsafe (even though the airplane was standing completely still since my very short test at 80%).

I know that my test conditions might be seen as exceedingly demanding, but in real life this can happen even (or especially) with high quality receivers. My experience is that even with a ~700USD Ashtech MB100 (now owned by Trimble) fitted with a high grade antenna with multipath rejection, one can see tremendous glitches in position as the antenna is banked by say 30deg. My guess is that high precision GPS's apply a broad scope of corrections and occasionally some of those corrections seemed to be applied the wrong way, but the ideal case would be that the impact of such GPS glitches on the overall stability of attitude determination is very limited at least for airplanes, where DCM complementary filter provides some sort of additional reference. Would it help if we had (for fixed-wing only) a fallback from EKF2 to DCM (just as it was provided for EKF1)?

If there is anything I can do with respect to testing of analysing this sort of instability I will be more than happy to do so. Currently, I'm spending my large part of my free time (and some of my office hours) on analysing options for robust attitude reference for larger drones furnished with the APM/PX4 (like the feasibility of feeding VN100 as an additional AHRS used by the APM in parallel).

Regards,
Przemek Lekston

--
You received this message because you are subscribed to a topic in the Google Groups "drones-discuss" group.
To unsubscribe from this topic, visit https://groups.google.com/d/topic/drones-discuss/inMOZBjmANY/unsubscribe.
To unsubscribe from this group and all its topics, send an email to drones-discus...@googlegroups.com.
Reply all
Reply to author
Forward
0 new messages