Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update to BMI gyros to use OSR4 mode to reduce gyro lowpass filter cutoffs #11400

Merged
merged 12 commits into from Mar 18, 2022

Conversation

ChrisRosser
Copy link
Contributor

@ChrisRosser ChrisRosser commented Feb 12, 2022

Current situation

At present in BF 4.3-RC3 there is a significant discrepancy between the behaviour of the BMI gyros (BMI160 and BMI270) and the MPU/ICM gyros. The BMI gyros are significantly more sensitive to noise in above 350Hz. The reason for this is that the hardware digital low pass filter (HDLPF) in the BMI gyros is set at a much higher frequency than the HDLPF in the MPU/ICM gyros.

image

Complication:

The higher low pass filter in the BMI gyros causes a number of problems for users, BF developers and manufacturers:

Users:

  1. The higher DLPF cutoff makes BMI gyro equipped flight controllers much more sensitive to noise and vibration than MPU/ICM equipped flight controllers on Betaflight default filter settings. This makes them muh more prone to hot motors, flyaways, and burned ESCs than equivalent BMU/ICM gyro boards.

image

  1. When a user switches between an MPU/ICM based board and a BMI board on the exact same quad with the exact same filter settings the BMI board may have noise issues when the MPU/ICM board did not. This can be confusing and frustrating for the user.

BF Developers:
3. The above problems generates support requests for the devs and other knowlegable people in the community.

Manufacturers:
4. Manufacturers who switch to the BMI gyro due to better pricing or availability e.g. iFLight_Beast_F7_AIO (V1 was MPU6000 and V2 is BMI270) are unable to guarentee that the new version of the flight controller will perfrom similarly to the old version.
5. High noise sensitivity of BMI boards can increase the risk of burned ESCs, field failure rate of AIOs and RMA returns for BMI based boards.

Solution:

This code changes the gyro bandwidth setting for BMI270 and BMI160 gyro to use OSR4 mode. It also exposes a CLI command to allow the user, either manually or through presets to configure BMI gyros oversampling into any of the three available modes OSR4, OSR2 or NORMAL.

This resolves the above issues with BMI gyro boards and makes them perform much more similarly to MPU/ICM boards.

It also exposes a CLI command to adjust the oversample mode on Bosch gyros should a more advanced user wish to increase the hardware filter cutoffs as part of a more agressive tuning strategy.

Detail:

The BMI270 gyro normally has a much higher hardware low pass cutoff than the ICM/MPU gyros (750Hz vs 250Hz). However there is a gyro_bwp register that allows this to be altered. It is not explained in the BMI270 datasheet at all but the behaviour is documented in the register map and explained in other Bosch gyro datasheets and it appears to work the same. If we change gyr_bwp to 0x00 (OSR4 mode) this tells the gyro to use a given filter cutoff at 4x it's usual data rate e.g. at data rate of 3.2k use the filter cutoff for 800Hz. This reduces the filter cutoff from 751Hz to 300Hz at 3.2kHz for the BMI270 which is much more similar to the 250Hz that works well for MPU gyros. This removes the need for extra filtering on BMI gyro based boards which will simplify things for everyone. The same approach can be used for the BMI160 to reduce the filter cutoff at 3.2kHz sample rate from 890Hz to 254Hz

image

OSR mode is not described indetail in the BMI270 datasheet but is present in the register map and Boschs API for the sensor. It is also described in detail in the BMI160 datasheet and the mode works the same for both gyros.

image

I have tested all the OSR modes on the BMI 270 gyro and they behave as expected. Here is a comparison of BMI270 normal, BMI270 OSR4 and BMI270 OSR2 modes

image

Note how the HDLPF filter cutoff is reduced when OSR modes are enabled.

It is important to know the true cutoff frequencies for 3.2kHz ODR in OSR2 and OSR4 mode. I have done some testing to experimentally determine the 3dB cutoff frequencies. Tapping the gyro directly mulitiple times with a hard object (like a coin or screwdriver) while logging provides a relatively clean impulse with equal power spectral density up to quite high frequencies (500Hz+).

image

The DLPF in the BMI270 is a 3rd order filter (18dB/Octave) and in OSR4 mode the 3dB cutoff is ~300Hz. This agrees closely with the datasheet value for 800Hz ODR confirming that in OSR4 mode the normal cutoff for 1/4 the ODR is used.

Evidence for the issue

Problems with vibration on BrainFPV Radix (BMI160): https://intofpv.com/t-i-am-new-to-tuning-be-merciful
logs: https://drive.google.com/file/d/1aUOnnhgo8uTBK3lpJpoH6RxLIl3UyiYy/view
https://drive.google.com/file/d/16Y0BZIov_okvYlQWy_WhsVJjpS7VZf5n/view

Review indicating burned ESC on throttle punch out iFlight Beast F7 V2 (BMI270): image
Log of BMI270 vs MPU6000 on the same quad with iFlight Beast F7 V1 and V2.
image

@haslinghuis
Copy link
Member

@mluessi any reason why Radix use 3.2K instead of 6.4K?

@Quick-Flash
Copy link
Contributor

why not allow users to set this setting?

// Set gyr_bwp = 0b010 so only the first filter stage is used
spiWriteReg(dev, BMI160_REG_GYR_CONF, 0x20 | BMI160_ODR_3200_Hz);
// Set gyr_bwp = 0b000 so only the OSR4 mode is used
spiWriteReg(dev, BMI160_REG_GYR_CONF, 0x00 | BMI160_ODR_3200_Hz);
Copy link
Contributor

@DusKing1 DusKing1 Feb 13, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is completely against the original development intent. At the time, although we wanted to find a good replacement for the MPU6000 gyroscope, we didn't want to make it similar to the MPU6000 in every way. If a certain gyroscope has better signal performance under certain conditions, why do extra work to weaken its performance for better "management"? That is not even betaflight's original development style.

Copy link
Member

@limonspb limonspb Feb 13, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@DusKing1 , a user with BMI gyro has to apply a BMI preset to make this gyro work nicely. So we have two options:

  1. leave it as is.
  2. try OSR4 mode - i guess then we don't need BMI filters presets maybe?
    Wondering which way provides better performance and how would you measure this performance to compare?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@etracer65 as you have worked on this please comment / review

Copy link
Contributor

@DusKing1 DusKing1 Feb 13, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Assuming that the signal quality of the gyroscope itself is not affected by the OSR4 register, only the SNR of the output signal changes. Then as we are still using the linear filtering method, Heisenberg principle still applies: if we wanna achieve same signal quality, then the amount of SLPF+DLPF should somehow be the same.
But how can me make sure they are the same considering the DLPF model inside the BMI270 is developed and own by Bosch and we have no idea what it is? That's the extra effort and work burden for other devs.
Our original idea at the beginning of development was to minimize the use of DLPF (rather than disable it completely) without causing extremely bad gyroscope signals, to minimize the signal delay due to DLPF, so that we can be in betaflight later filtering it in a controlled method, although this may result in some extra LPF settings, it still in line with what betaflight was developed for: to bring the best possible flight performance to the user, instead of the easiest.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In order to have sufficient attenuation of noise above 350Hz or so additional software filtering has to be used in BF. The total delay of DLPF + SLPF may actually be more than simply setting OSR4 mode and turning off the SLPF.

As an example I've produced attenuation and delay plots for OSR4 mode vs DLPF+SLPF assuming all filters are biquads:

image

Notice that even though both filters have equal attenuation in the region of interest (up to 500Hz) because the DLPF+SLPF has more attenuation at higher frequencies it ends up with more delay.

If we assume that we don't need more than second order gyro filtering for very high frequencies (which I would argue we don't looking at the above plots) then if we already have a second order DLPF that we cannot turn off we would want to use that and not add any additional filtering otherwise we end up overfiltering high frequencies and adding unnecessary delay.

Copy link
Contributor

@DusKing1 DusKing1 Feb 13, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I just give you a rough guess and did you put any validation on that? Or you just blindly agree what I said? Where's the result of the no betaflight LPF spectrum chart to show how it looks like?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Prefiltered PSD plots are in the first post. 👍

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do you mean you just fly on the raw gyro signal even without dyn-notches or rpm-filters?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No I used gyro_scaled debug mode to log raw gyro.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the result of the no betaflight LPF spectrum chart

@Quick-Flash
Copy link
Contributor

@mluessi any reason why Radix use 3.2K instead of 6.4K?

I'd love to see it as an option.

@DusKing1
Copy link
Contributor

@Quick-Flash that's already an option.

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Feb 13, 2022

@Quick-Flash 6.4K has degraded signal quality. I think due to lack of oversampling and is inferior to 3.2K mode. It's only my speculation but I think 3.2k mode uses 4x oversampling and 6.4K mode uses no oversampling at all (not even 2x as you might expect).

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Feb 13, 2022

why not allow users to set this setting?

@Quick-Flash I would support that but OSR4 mode should definitely be the default to make all flight controllers behave similarly out of the box and work the same with all exisiting presets for MPU/ICM gyros. That will give a much smoother user experience and also avoid people freaking out when they see logs like this:

image

These logs are from the same build, just the effect of different LPFs.

@DusKing1
Copy link
Contributor

I would support that but OSR4 mode should definitely be the default to make all flight controllers behave similarly out of the box and work the same with all exisiting presets for MPU/ICM gyros.

Why should all flight controllers behave similarly out of the box if the native feature of the gyroscope on the FC is different compared to others'?

That will give a much smoother user experience and also avoid people freaking out when they see logs like this:

Why do you only focus on the UX instead of discussing the performance firstly then coming to the UX? Flight performance has the highest priority. Also the default chart of BBE is based on FFT instead of other method like PSD, which can't eliminate the effect of sampling frequency on results.

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Feb 13, 2022

I wouldn't want to speak for the core group of devs on this but I would feel that safety and getting as many quads in the air and flying well with as few burned motors and ESCs as possible should be the priority of the default settings. Maximum flight performance (with associated increased risk of flyaways) is the domain of tuning/more aggressive presets and it always has been.

I fully support options to allow people to tune for flight performance (and am happy to make a video to show people how to use them!) But forcing everyone to use very aggressive filtering from the get go is a recipe for burned motors, ESCs and unhappy pilots. Experienced pilots like you will simply apply the aggressive preset to raise the filter cutoff and never think about it again so you will not be negatively affected by this change.

Consistency between FCs is very important. If a user swaps an MPU gyro board for a BMI gyro board on a quad that was flying fine and the quad now flips out on arming that is a terrible situation. Especially because manufacturers sometimes change the gyro between board versions without warning. iFlight Beast F7 V1 - MPU6000, iFlight Beast F7 V2 - BMI270. If you bought two iFlight Beast F7 boards you would hope that on identical settings they would fly similarly. But that's not the case the BMI board is much more sensitive to noise.

@Quick-Flash
Copy link
Contributor

I wouldn't want to speak for the core group of devs on this but I would feel that safety and getting as many quads in the air and flying well with as few burned motors and ESCs as possible should be the priority of the default settings.

This way round is much better than requiring everyone (including very inexperienced users) to know to apply a special preset to avoid their quad flipping out on the first arm and potentially damaing itself (or them!) with a BMI gyro board when it would have flown fine with an MPU gyro. That sort of inconsistency, one FC working on a quad and another flipping out on the same quad with the same settings, is very bad for users.

So do you want all fc to act the same or do you want defaults that are safe for almost all setups? If the defaults create safe settings for the BMI gyro then your complaint is that it acts different to other gyros. Once users change settings isn't that up to them to see what settings will work?

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Feb 13, 2022

Both. I think that ideally all FCs no matter the gyro should behave similarly on the default BF filter settings and the default BF settings should also be safe for most quads most of the time.

There should absolutely be gyro-specific presets and settings to allow experienced users to maximise the performance of their unique setups. 100% agree on that.

@DusKing1
Copy link
Contributor

Let me be clear, I'm not against changing the OSR4's settings or anything related to the BMI270. What I'm against is arbitrary modification of the default configuration without extensive validation. Also, we should deeply consider the impact on existing presets, configurator tooltips and what might brings to users' drones, like why the previous BMI270 preset not work anymore, why with new default my motor burnt up/flight to the moon etc.

We should certainly allow experienced pilots/developers/preset_authors to provide ways to maximize performance, but any change that modifies the defaults behaviour should be done with caution, in this case when there are already safe presets for BMI270 gyroscope.

@etracer65
Copy link
Member

etracer65 commented Feb 13, 2022

My only comments are related to the project management aspects of this and I will not discuss filtering.

If this is something that is considered worth trying, then it should be part of 4.4 to give ample time for testing and validation. An entire population of Radix2 users have been flying with BMI270 for a while now and seem to be happy with the performance so clearly there's nothing to "fix" as part of 4.3.

Secondarily it would be a shame to lock in an undocumented OSR4 mode with the user being unable to exploit the lower latency mode that's currently in use. Doing so would likely change the flight behavior that a large group of users already like for one that they may not, with no recourse.

Lastly, the microcode for the BMI270 is loaded at boot and is updatable (already been two different versions used in Betaflight). So there's a risk that the OSR4 behavior might change unexpectedly in a future update as the current observed operation is undocumented and might be considered a bug. For example there is already a microcode update (01-DEC-2021) that has not been applied added to Betaflight and the OSR4 behavior is unknown with this version.

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Feb 13, 2022

I tend to agree that allowing this setting to be adjusted via CLI commands would be preferable to a hardcoded value. It could then be easily adjusted via presets. There is an OSR2 mode we could expose also to provide maximum flexibility which sits between normal mode and OSR4.

The feature is documented in the BMI270 register map and present in most other Bosch gyros, it just doesn't have an explanation in the datasheet text (unlike for the BMI160) so I don't think there is any risk of it changing on us. It's not like we are using a "reserved" register or anything like that! (From the BMI270 datasheet)

image

@ChrisRosser ChrisRosser force-pushed the BMI_update branch 2 times, most recently from 4c03279 to d99b3f6 Compare February 14, 2022 22:47
@etracer65
Copy link
Member

I don't think the changes to expose the settings are the correct way to approach this. We really don't want to have settings for specific gyro hardware. We shouldn't have "bmi" settings.

There is already a setting for this: gyro_hardware_lpf. It's purpose is to tune the DLPF settings in the gyro. Currently it's only implemented for Invensense gyros and the BMI270. For Invensense it allows switching between the default NORMAL ~250hz 3dB cutoff filter, to the EXPERIMENTAL ~3.2khz cutoff available on ICM gyros. It technically also works for MPU6000 but the data sheet says the setting is "reserved" so the exact behavior is unknown (but appears to be very noisy so probably DLPF disabled).

For BMI270 the EXPERIMENTAL setting enables 6.4khz ODR which activates the FIFO requires the DLPF to be disabled (effectively unfiltered data).

So a better solution would be to expand the range of options for the gyro_hardware_lpf in a generic way and not using BMI terminology like OSR2, OSR4, etc. There are technically other lower DLPF settings for Invensense but they're probably not useful to us. Look in the datasheets for register 26 and the DLPF_CFG bits.

@limonspb
Copy link
Member

limonspb commented Feb 15, 2022

if we expand gyro_hardware_lpf then how would it be possible to make OSR4 a default value? I think that's the goal here - to make sure BMI gyros behave similar to other gyros with the same BF filter settings.

Should we then make NORMAL = OSR4 under the hood for BMI gyros? And then if someone wants "advanced" performance from BMI, he can use set gyro_hardware_lpf = ?something else?

@mathiasvr
Copy link
Contributor

Yes I think the idea is to make OSR4 mode the default for BMI gyros.
Then for OSR2 and "normal" mode we could have gyro_hardware_lpf options like medium_cutoff and high_cutoff, or something like that.

@ctzsnooze
Copy link
Member

There is no question that the gyro itself is sampled at 6.4k and it seems very likely that the default 750hz filter is intended to provide some antialiasing prior to decimation to 3200hHz. I would say it only does a passable job because I often see aliasing type artefacts in the 'gyro scaled' trace of BMI gyros.

I would have anticipated that getting un-filtered data (their raw 6.4kHz gyro data, OIS mode, over FIFO, using gyro_hardware_lof = experimental) and then either running a 6.4k PID loop with whatever gyro filtering works best, or using a suitable gyro lowpass for antialiasing purposes, should, theoretcially give us the best possible outcome.

I appreciate that when Chris logged the FIFO 6.4k data, he found there was more low frequency noise than when he logged 3.2k data. This is surprising since there is no logical reason why this should be the case. Lowpass filtering around 400hz, the presence or absence thereof, should have no influence noise around 50hz, yet Chris found more noise in 6.4k mode at 50hz. It is possible that in 'experimental' or 6.4k mode there is some error in the way we collect the data. This should be investigated and resolved if we are to support these gyros better.

It's very unclear, in the Bosch documentation, as to exactly what OSR4 achieves.

The Bosch data sheets say that there is oversampling, then four point averaging, and that the cutoff ends up being 'approximately' four times lower than it would otherwise be. The example they give is an output data rate which would ordinarily receive a lowpass cutoff of 50hz, but when set to OSR4 the cutoff is 6.25hz. Now it is really tough to achieve this with 4 point averaging. I have emulated the effect of 4 point averaging at different output data rates. At our 3.2kHz ODR, 4 point averaging achieves approximately the same filtering effect as a 420hz PT1. But a 420hz PT1 won't reduce the cutoff from 750hz by a factor of 4 to something like 187hz. It gets close, due our PT1 cutoff approximation not being exact at low PID loop rates, but is not exact. 4 point averaging, followed by decimation to ¼ the loop speed, then smoothing at ¼ of 750hz, and then oversampling back to 3.2k, will achieve the exact cutoff change, but causes massive delay.

Until we really get to the bottom of exactly what these settings do, I think it simpler for bosch users to ensure they have two gyro lowpass filters active. Currently I run one single static gyro lowpass at 500hz in lowpass 2 for my MPU and ICM gyros. Adding a 400hz static lowpass 1 filter in the Bosch gyros (ie a fixed lowpass 1 at 400hz and a fixed lowpass 2 at 500hz, at a 3.2k PID loop) appears to convert their noise spectrums to something comparable to an ICM or MPU gyro.

This is the solution that I think we should run with until we get a clearer understanding of the exact behaviour of OSR mode. We do know that it filters more, but we don't know the delay implications. or exactly how it achieves that filtering outcome.

@limonspb
Copy link
Member

limonspb commented Feb 15, 2022

Until we really get to the bottom of exactly what these settings do, I think it simpler for bosch users to ensure they have two gyro lowpass filters active. Currently I run one single static gyro lowpass at 500hz in lowpass 2 for my MPU and ICM gyros. Adding a 400hz static lowpass 1 filter in the Bosch gyros (ie a fixed lowpass 1 at 400hz and a fixed lowpass 2 at 500hz, at a 3.2k PID loop) appears to convert their noise spectrums to something comparable to an ICM or MPU gyro.

This is the solution that I think we should run with until we get a clearer understanding of the exact behaviour of OSR mode. We do know that it filters more, but we don't know the delay implications. or exactly how it achieves that filtering outcome.

It has been frustrating to see users with BMI gyros having problems with defaults. The current solution with "recommendations" somewhere, and "special presets" is just not nice. If someone can test-fly-log these gyros with OSR4 and show it works close to MPU6000, i think we should go this way. It would mean that ALL our tune/filter presets (Karate, Supafly, Ctz etc) will work with BMI, and that would be great.

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Feb 15, 2022

@ctzsnooze

Hi Chris! 😁 OSR4 mode does not implement a 4 point moving average. It's not an additional filter stage. What OSR mode does is it allows you to use a given DLPF configuration at a higher data rate.

For example:

In NORMAL mode at 800Hz data rate the normal filter configuration has a 3dB cutoff at 300Hz

OSR2 mode allows you to use that filter configuration with that cutoff at 2x the data rate.
So now you can use the 800Hz filter config (with 300Hz cutoff) at 1600Hz

OSR4 mode allows you to use that filter configuration with that cutoff at 4x the data rate.
So now you can use the 800Hz filter config (with 300Hz cutoff) at 3200Hz.

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Feb 15, 2022

@etracer65

I propose the following solution, let me know if this would be the right approach in your opinion.

gyro_hardware_lpf = NORMAL :
MPU/ICM Gyros cutoff at 250Hz, BMI Gyro OSR4 mode (cutoff at 300Hz)
gyro_hardware_lpf = HIGH_CUTOFF :
MPU/ICM Gyros cutoff at 250Hz, BMI Gyro OSR2 mode (cutoff at 550Hz)
gyro_hardware_lpf = VERY_HIGH_CUTOFF :
MPU/ICM Gyros cutoff at 250Hz, BMI Gyro NORMAL mode (cutoff at 750Hz)
gyro_hardware_lpf = EXPERIMENTAL :
No change from current implementation.

@DusKing1
Copy link
Contributor

DusKing1 commented Feb 15, 2022

@ChrisRosser We have the reply from bosch and the cutoff is as what I expected. https://community.bosch-sensortec.com/t5/MEMS-sensors-forum/BMI270-OSR-mode-behaviour/m-p/52043/highlight/true#M9955

  • Normal/Performance mode DLPF at 751hz
  • OSR2 mode DLPF at 375.5hz
  • OSR4 mode DLPF at 187.75hz

image

@DusKing1
Copy link
Contributor

DusKing1 commented Feb 15, 2022

So it turns out the simulations based on my previous brave assumption (which I just guess and I haven't put any effort to and only told @ChrisRosser before this PR) is not correct. The group delay (let's assume they are constant curve) in those OSRx modes is greater than MPU6000 for example.

From MPU6000 Register Map:
image

And this is from BMI270 datasheet:
image

@DusKing1
Copy link
Contributor

DusKing1 commented Feb 15, 2022

So the OSR2 or OSR4 mode will increase the built-in delay (as using vague definition here since the "delay" listed on MPU6000 Register Map might be something else than group delay) and might turns to worse than MPU6000? That's not what we want at the beginning. @etracer65

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Feb 15, 2022

So the OSR2 or OSR4 mode will increase the built-in delay (as using vague definition here since the "delay" listed on MPU6000 Register Map might be something else than group delay) and might turns to worse than MPU6000? That's not what we want at the beginning. @etracer65

I don't know if we can trust those delay numbers, apparently the accelerometer has a 0ms delay 260Hz low pass filter. That's mathematically impossible...

@DusKing1
Copy link
Contributor

The accelerometer works sightly different compared to gyroscope. That makes sense to me if they were using an approximate number to reflect the amplitude attenuation of the accelerometer readout data. Using low confidence in the output signal characteristics of other sensors in the same row in the list to negate the signal characteristics of a gyroscope at a given output rate despite the fact that its inner workings may not be consistent is not a persuasive approach.

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Feb 15, 2022

The accelerometer works sightly different compared to gyroscope. That makes sense to me if they were using an approximate number to reflect the amplitude attenuation of the accelerometer readout data. Using low confidence in the output signal characteristics of other sensors in the same row in the list to negate the signal characteristics of a gyroscope at a given output rate despite the fact that its inner workings may not be consistent is not a persuasive approach.

My argument is only that those numbers probably do not represent the full group delay of the system and therefore may not be comparable to BMI numbers.

@etracer65 etracer65 added this to the 4.4 milestone Feb 15, 2022
@haslinghuis
Copy link
Member

haslinghuis commented Mar 13, 2022

Thanks looks good now. Please rebase and squash commits.

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Mar 13, 2022

@haslinghuis I learned recently that you can squash when you merge with GitHub, would this be OK?

image

@haslinghuis
Copy link
Member

@mathiasvr please look into adding this to our github actions workflow. But it should be an option as some commits needs to be separate (not in this PR)

@mathiasvr
Copy link
Contributor

@haslinghuis when merging you should be able to choose 'squash and merge' by clicking the arrow next to the merge button, unless this is disabled in the repo settings.

@haslinghuis
Copy link
Member

Never saw that option when merging. Have to wait for the next PR to be ready to check it.

@hydra
Copy link
Contributor

hydra commented Mar 15, 2022

I was ping'd by @haslinghuis to comment on this. If these comments are in the wrong place feel free to point me at an appropriate place to make them.

There has been a suggestion to add new targets with different defaults for when manufacturers switch from MPU6xxx gyros to BMIxxx gyros, or indeed from any gyro to any other gyro...

Adding a new target is bad for several reasons:

  • the current UI to select a target uses a dropdown list which is already unusable due to the amount of targets, adding it it makes the problem even worse.
  • more targets = more confusion.
  • more targets = more maintenance, either for FW devs or unified target config maintainers.

Additionally, it's the PCB footprint and schematic that decides which gyros might be fitted at assembly without doing a new PCB revision. However there are flash-space concerns with enabling all schematic-compatible gyros. The H7RF schematic for instance is compatible with at least 8 gyros that I'm aware of, probably more, as the industry has more or less standardised on the gyro footprint, BMI270/ICM42688P/LSM6DO being examples of footprint compatible gyros, special attention needs to be placed on pins 2/3 and 10/11 when designing a schematic, a single 2-way zero-ohm resistor network can be fitted, or not, when assembled with the gyro.

There is no way to guard against a manufacturer doing a new PCB revision with an entirely different gyro, advice from maintainers should be sought before doing so. Since manufacturers will do what manufacturers will do and that BF is an open-source project there is no way to prevent them. But for the sake of the USERS it's ideal if both parties agree.

IMHO the configurator, not the firmware, is the place where sensible filter defaults should be chosen for the gyro.

e.g.

  1. plug in new FC to PC.
  2. load configurator and connect.
  3. FC detects gyro.
  4. configurator detects that the FC has all-default settings.
  5. configurator ask user if they want to apply 'sensible defaults' for the DETECTED gyro, or does it automatically.
  6. user is free to inspect and/or modify configuration as they like.

another option would be to have a 'settings check' system in the configurator which reports mismatches and recommends changes, again, based on detected gyro and current config.

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Mar 15, 2022

@hydra

Your comment is definitely in the right place. Thank you for the information it's very informative and not somthing I was aware of beforehand.

I think the PR as currently proposed addresses the issues you've raised in a neat way. Let me know if you agree:

  • With this PR the BMI gyros will behave almost identically to MPU and ICM gyros in terms of gyro hardware filtering (both in noise attenuation and filter delay).
  • This means one target can be used for BMI, MPU or ICM gyros. There will no longer be a need to configure software filters differently for a BMI vs an MPU/ICM gyro at all. BMI gyros will "just work" the same as MPU and ICM gyros do today.
  • I absolutely support your position that the number of different targets should be minimised. It may even be possible to reduce the number of targets if BMI gyro boards no longer require different settings to work well.

@hydra
Copy link
Contributor

hydra commented Mar 16, 2022

@ChrisRosser "This means one target can be used for BMI, MPU or ICM gyros. There will no longer be a need to configure software filters differently for a BMI vs an MPU/ICM gyro at all. BMI gyros will "just work" the same as MPU and ICM gyros do today."

@DusKing1 "Why should all flight controllers behave similarly out of the box if the native feature of the gyroscope on the FC is different compared to others'?"

I find myself agreeing with both of these points.

However, not all gyros are equal, some gyros will need additional settings, trying to shoe-horn gyro-specific configuration into existing configuration commands is not necessarily the best choice and is actually more confusing to users, not less. It also creates dependencies between the gyro drivers and the gyro configuration system. If you have per-gyro family configuration settings then gyros from a one family will not depend on gyros from a different family.

e.g.
Good dependency graph:

System -> BMIxxx Config -> BMI270.
System -> MPU6xxx Config -> MPU6000/MPU6500
System -> ICM20xxx Config -> ICM20602/ICM20409
System -> ICM42xxx Config -> ICM42605/ICM42688P

Bad dependency graph:

System -> GyroConfig -> (BMI270 && MPU6000 && MPU6500 && ICM20602 && ICM20409 && ICM42605 && ICM42688P)

Fixing the dependencies by keeping things separate allows you to make changes to one component without affecting the others and allows greater flexibility where needed.

I still find my position that the Configurator is the best place to apply defaults based on the detected gyro is best as there is no code-size impact compared to doing it on the FC which is already code-size constrained.

@hydra
Copy link
Contributor

hydra commented Mar 16, 2022

Further to my point above, I recall a situation we had where BF enabled motor outputs by default. This was eventually deemed bad for many reasons. What happened next, IMHO, is the same situation we're in now.

  1. The FC stopped enabling motors by default.
  2. The configurator tells users to configure the motor output.

This is 100% analogous to the issue we have with bad gyro config.

e.g.

  1. The FC doesn't configure the gyro.
  2. The Configurator tells the user to configure the gyro.

For 2. above, we can make it easy for them, e.g. using presets or something.

also, Doing this might even allow us to delete a bunch of code in fixAndValidateConfig too, freeing up code-space in the FC and simplifying the system.

@ChrisRosser
Copy link
Contributor Author

ChrisRosser commented Mar 16, 2022

  1. The FC stopped enabling motors by default.
  2. The configurator tells users to configure the motor output.

I may be mistaken here, but I think for most FCs the default motor outputs are configured in the target and applied as custom defaults. At least I don't remember ever having to configure motor outputs on any of my FCs. They all "just work" when plugged into an ESC. If that wasn't the case I think a lot of users, myself included, would have problems.

Applying the same reasoning:

  1. Have a safe and consistent setting as default so no-one gets hurt (OSR4 mode)
  2. Allow easy configuration of all available modes through presets or targets as appropriate

@daleckystepan daleckystepan added this to Bug Tracker in Finalizing Firmware 4.3 Release via automation Mar 16, 2022
@daleckystepan daleckystepan moved this from Bug Tracker to Firmware in Finalizing Firmware 4.3 Release Mar 16, 2022
@daleckystepan daleckystepan modified the milestones: 4.4, 4.3 Mar 16, 2022
@daleckystepan
Copy link
Member

daleckystepan commented Mar 16, 2022

Changed to BF 4.3 as it is considered as a bugfix for BMI gyros. Discussed on Slack.

@haslinghuis
Copy link
Member

haslinghuis commented Mar 16, 2022

Looking how to implement in configurator only found FC.PID_ADVANCED_CONFIG.gyroCheckOverflow

Maybe need a getter and setter here but If configurator knows the gyro being used we can apply save defaults for every gyro being used upon connection.

@hydra
Copy link
Contributor

hydra commented Mar 17, 2022

I may be mistaken here, but I think for most FCs the default motor outputs are configured in the target and applied as custom defaults.

@ChrisRosser I'm referring to motor output /protocol/, e.g. DSHOT+/- BiDir/OneShot/PWM, etc. not io pins/resources here.

@hydra
Copy link
Contributor

hydra commented Mar 17, 2022

Changed to BF 4.3 as it is considered as a bugfix for BMI gyros. Discussed on Slack.

@haslinghuis Can you give a summary or quote the conversation here. I can't find it.

Copy link
Member

@haslinghuis haslinghuis left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Agree on both sides but due to less default filtering in 4.3 we need to make a practical decision for safety concerns. The scope is limited to BMI 160/270 gyro's as manufacturers are better off with a gyro like a ICM42866P anyway.

Please note I'd like the idea to do this is configurator but this should be a quick fix for now.

@daleckystepan daleckystepan merged commit a96ae37 into betaflight:master Mar 18, 2022
Finalizing Firmware 4.3 Release automation moved this from Firmware to Finished (Merged) Mar 18, 2022
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
No open projects
Development

Successfully merging this pull request may close these issues.

None yet