An IMU failure in flight

437 views
Skip to first unread message

Randy Mackay

unread,
Sep 25, 2014, 12:24:31 AM9/25/14
to drones-...@googlegroups.com

 

     Craig passed me a log today from the RTF testing guys who apparently had a Pixhawk’s IMU1 go bad in flight while flying AC3.2-Iris (basically AC3.2-rc9).  It happened while the vehicle was in RTL and it led to a fence breach (which did nothing because it was already in RTL) and they attempted to re-take control in Stabilize but for some reason it looks like it crashed into a building.   It’s not clear to me whether that’s because the attitude solution went bad (position estimates from inertial nav obviously went bad) or if the pilot became disoriented and didn’t have time to recover.

 

     IMU failures are pretty rare, the last one we saw was from about a month ago (Artem’s log is also attached).  The two situations are quite different though:

·         Craig’s goes bad during the flight (26seconds, line 6726) while Artem’s was bad for the entire flight (we’ve since added a pre-arm check to catch pre-take-off issues)

·         Craig’s IMU1 (i.e. MPU6k) goes bad while for Artem it was IMU2 (the LSM303D)

·         Craig’s IMU keeps producing values although they’re very large (maybe 10x larger than normal) and the orientation seems incorrect (Y and Z swapped?)

 

     I don’t see anything in the logs that explains the IMU going bad but it’s unlikely that such a low-level failure would show up as anything but bad data.

 

     Some guesses as to possible causes:

·         MPU6k reset during flight (possibly a power issue?)

·         Communication error leads to corruption of MPU6k’s configuration

·         Flight controller memory corruption affects the driver and values being returned

 

     Things we can do about it:

·         Craig to get the IRIS exactly as it is and run some tests on it to try and recreate the issue so we can narrow down on the failure

·         Add logging to AC to capture sensor health into the logs (this would allow us to know if the system knew that something had gone wrong)

·         Use the EKF’s variances as a measure of whether something has gone wrong (I’ll bet the EKF knew) and trigger the EKF Check.  AC3.2 doesn’t use the EKF by default, I suspect the EKF check would have triggered a land.

·         Test & ensure that when an single IMU goes bad that the attitude solution remains good

 

-Randy

Artem_IMU2_fail_01Sep2014.log
Artem_IMU2.png
Craig_IMU_fail_25Sep2014.png
Craig_IMU_fail_25Sep2014.bin
DCMvsEKF.PNG

Robert Lefebvre

unread,
Sep 25, 2014, 7:24:15 AM9/25/14
to drones-discuss
Some parts of that are somewhat similar to what my logs looked like from the gasser heli crash.  Namely my accels seemed to indicate the scaling went off.  Did you check if the logging rate changed?  Though in my case, both accels were reporting the same data.

Was the EKF able to use the second set of sensors and keep it flying?

I did have a PX4 go bad in flight about a year ago on my 450 heli.  Confirmed by Tridge, appears something went wrong with the SPI bus.  I was just hovering, and then it suddenly "freaked out" and crashed.

--
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.

Randy Mackay

unread,
Sep 26, 2014, 3:18:36 AM9/26/14
to drones-...@googlegroups.com

 

      I did some testing today to simulate an IMU failing similar to what we saw from Craig/3DRs flight earlier this week.  In this simulation the Y & Z axis accelerometer values were swapped and multiplied by 8x.

               https://www.youtube.com/watch?feature=player_detailpage&v=k83S1gg3ZVg

 

     With DCM/InertialNav:

-          the climbrate & altitude are affected badly so the vehicle would climb or fall quickly in autopilot modes (i.e. AltHold, Loiter, PosHold, RTL, etc.)

-          the horizontal position jumps by about 150m before starting to recover meaning the vehicle would also speed off horizontally in autopilot modes

-          the attitude remains good meaning the pilot could recover in stabilize mode

 

     With EKF:

-          climb rate and altitude are *not* affected meaning the vehicle would not climb

-          the horizontal position jumps perhaps even more than with DCM/Inertial Nav (only performed 1 test so slightly anecdotal)

-          the attitude remains good meaning the pilot could recover in stabilize or AltHold modes.

 

      In short the EKF did better in the test as expected although perhaps it could be improved further in the horizontal position estimate.

 

     Testing code is here (raising ch6 simulates the accels going crazy).  I’ve also attached from bin files in case Paul is interested.

      https://github.com/rmackay9/rmackay9-ardupilot/tree/imu_testfail1

 

-Randy

2014-09-26 13-13-16.bin
2014-09-26 13-20-33.bin
2014-09-26 13-26-27.bin

Paul Riseborough

unread,
Sep 26, 2014, 7:28:20 AM9/26/14
to drones-...@googlegroups.com
Randy,

I have been working on a patch in slow time for these types of IMU errors.

In the meantime there is a patch that improves the way that the EKF resets its position, velocity and height following recovery from an IMU error created created a couple of weeks ago that seems to have been missed. The stored states were not being reset which meant that the first few measurement after a reset could be rejected, which under stressing situations could cause another timeout, another reset and so on. There is a pull request for the outstanding items:

https://github.com/diydrones/ardupilot/pull/1410

I believe item 2) has already made it into RC10

I'll test my IMU error patch using your imu_testfail1 branch and report back.

Regards,

Paul



Paul Riseborough

unread,
Sep 26, 2014, 7:32:39 AM9/26/14
to drones-...@googlegroups.com
Randy,

I get the following compiler error when I try to compile the imu_testfail1 branch for PX4 v2

/home/prisebor/SourceCode/ardupilot/libraries/AP_HAL_PX4/RCOutput.cpp: In member function 'virtual bool PX4::PX4RCOutput::force_safety_on()':
/home/prisebor/SourceCode/ardupilot/libraries/AP_HAL_PX4/RCOutput.cpp:179:30: error: 'PWM_SERVO_SET_FORCE_SAFETY_ON' was not declared in this scope

Paul

Randy Mackay

unread,
Sep 26, 2014, 9:26:53 AM9/26/14
to drones-...@googlegroups.com

Paul,

 

     Hey thanks for looking at that.  I can also try pulling in the patch and see how it does.

 

     I actually tested on master instead of the ArduCopter-3.2 branch and master is missing some of your patches that I’ve put into AC3.2.

 

     I think if you update your PX4Firmware repository it’ll compile.

 

-Randy

Paul Riseborough

unread,
Sep 26, 2014, 5:20:35 PM9/26/14
to drones-...@googlegroups.com

Randy Mackay

unread,
Sep 26, 2014, 9:45:19 PM9/26/14
to drones-...@googlegroups.com

Paul,

 

     Thanks for that! now merged to AC3.2.

 

-Randy

--

Paul Riseborough

unread,
Sep 27, 2014, 4:11:36 AM9/27/14
to drones-...@googlegroups.com
Randy,

Here's my test branch with the IMU accel fault isolation patch for the EKF. It works OK on the bench using your CH6 induced IMU failure patch so you might like to give it a go.

It is a non-trivial modification and there are some hard-coded thresholds that will need to be fine-tuned on Replay or SITL.

Paul

On Friday, 26 September 2014 23:26:53 UTC+10, Randy Mackay wrote:
... I can also try pulling in the patch and see how it does.
Reply all
Reply to author
Forward
0 new messages