CUAV-X7 IMU cliping - ArduCopter vs. PX4

Hello all,

I have a CUAV-X7 FC on copter that has strange behavior:

  • when I run PX4 on it, the IMUs do not clip during flight
  • When I put ArduCopter 4.1.0, the first IMU clips during flight at a rate of around 100 clippings per minute, and the second one clips around 4 times per minute.

What could be the cause? I think PX4 just uses higher G limits in their IMU configuration, and ArduCopter uses 4G and the first two and 16G on the third.
Is this the cause?

Arducopter’s PID’s are not edgy, and we do use ESC telemetry based dynamic notch filters. FTT of the output noise is very clean.

Can you share the PX4 log? https://logs.px4.io

Perhaps it is not relevant but I have observed that in Cube Orange IMU1 and IMU2 always cause higher acceleration. The first two IMUs are soft mounted and vibe caused by them are much higher than the third IMU. The Cube was hard mounted in my hex 32inch props frame.
Is this IMU installation similar in CUAV-X7?

no, ArduPilot uses the maximum limits of the IMUs.
The reason is likely to be that px4 uses the downsampled data when calculating clipping, which hides clipping. That is what ArduPilot used to do.
In ArduPilot we transfer samples at the maximum rate (8 or 9kHz for most sensors these days). The samples are checked against the clipping limit for every sample.
What we used to do (and what px4 may still be doing) is averaging these samples down to the rate that the two-pole butterworth is applied before checking for clipping.
Note that I’m basing this on my memory of the px4 IMU code. From memory I originally wrote that clipping detection code for px4 back in the days when ArduPilot shared the sensor layer with px4. I could be out of date. @dagar may be able to correct me.
You get the same effect in ArduPilot if you set INS_FAST_SAMPLE=0 to disable “fast sampling”. You will see a lot less clipping logged. The clipping is still happening, it is just hidden.
We changed to calculating clipping on every high rate sample as it is important to fix installations where you are getting this clipping as it does distort the data. A clipping rate of 100 per minute will likely not be noticeable in flight (it is a clipping rate of 0.02% as there will be approximately 480000 samples per minute), but it shows your setup doesn’t have much margin. Under higher throttle the clipping could rapidly become much higher and lead to very poor IMU data.

3 Likes

These days in PX4 the IMU drivers have all sensor side filtering disabled and do full raw transfers at the maximum rate. One difference here might be the threshold that’s actually considered clipping, for the IMUs with FIFOs we’re checking the min/max directly on the raw int16 accel data.

1 Like

back when we used the px4 sensor layer we also disabled sensor side filtering and did transfers at max rate, but the data was downsampled to a lower rate in the FMU before the butterworth was applied (this was done to reduce CPU load). The clipping detection was done on the downsampled data, just before the butterworth filter was applied.
Are you sure that doesn’t still happen? I had a quick look but the code has changed so much I am not really sure.

ArduPilot uses a few percent below the limit, for example 15.5g on a 16g sensor. This is to allow for the ADC integration time in the sensor. I doubt that difference would make the difference @amilcarlucas notes.
Amilcar, which variant of the X7 do you have? My X7 has an ADIS1647 primary:

INS_ACC_ID: bus_type:SPI(2)  bus:1 address:2(0x2) devtype:49(0x31) INS_ADIS1647x (3211786)
INS_ACC2_ID: bus_type:SPI(2)  bus:4 address:2(0x2) devtype:43(0x2b) INS_BMI088 (2818594)
INS_ACC3_ID: bus_type:SPI(2)  bus:6 address:2(0x2) devtype:46(0x2e) INS_ICM20649 (3015218)

I think the later ones don’t have that? Perhaps you could post a log.

This is a soft-mounted FC.
@coptingtech can you provide the device list that @tridge is asking?