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

Barometer temperature compensation #10382

Open
wants to merge 3 commits into
base: master
Choose a base branch
from

Conversation

breadoven
Copy link
Collaborator

@breadoven breadoven commented Sep 24, 2024

PR provides temperature compensation for barometer altitude drift with changing barometer temperature.

Setting added for temperature compensation factor in cm/K, currently limited to -50 to +50. It is possible to perform an auto calibration of the required compensation value by monitoring the altitude drift with the FC static for a period of time after boot up. This is currently triggered using a setting of 51 although it could use some other method. The auto calibration ends after a 5 minute timeout or on first arm.

Seems to work reasonably well for BMP280 barometers in the temperature range 15 to 40 C reducing drift of up to 4m down to < 1m. Needs more testing though because one board works with a value of 20 cm/K while another is closer to 40cm/K which seems excessive given the spec value for a BMP280 is supposed to be 12.6 cm/K.

Best tested by checking barometer altitude in the Configurator Sensor tab. First check drift with a setting of 0 and a cold FC. Then change setting to 51, power off and allow the FC to cool then power on again and recheck the barometer altitude. The barometer will drift as before until 5 mins after bootup at which point, if the calibration has worked, the barometer altitude should fall close to 0. This should be accompanied by a "success" beep (may need battery power for this rather than just USB). The calibrated setting can be saved by switching to the CLI and hitting "Save Settings" (or using the Save stick command or CMS). Power off again and allow the FC to cool down then recheck barometer altitude again, it should show much reduced altitude drift as it warms up.

@breadoven breadoven changed the title Barometer temp compensation Barometer temperature compensation Sep 24, 2024
@mmosca
Copy link
Collaborator

mmosca commented Sep 24, 2024

Do we apply the compensation values covered in section 3.11 of the datasheet already?

https://www.bosch-sensortec.com/media/boschsensortec/downloads/datasheets/bst-bmp280-ds001.pdf

image

image

@breadoven
Copy link
Collaborator Author

Do we apply the compensation values covered in section 3.11 of the datasheet already?

https://www.bosch-sensortec.com/media/boschsensortec/downloads/datasheets/bst-bmp280-ds001.pdf

image

image

Pressure and temperature are calculated as per the spec sheet but you still get drift regardless. I get the impression those compensation calibration values are set when the chip is manufactured and tested but their accuracy can be affected when the chip is subsequently soldered in place. In reality the drift is pretty minimal ... more of an issue for multirotors hovering at low level I'd say than for fixed wing where it wouldn't be so noticeable.

@Jetrell
Copy link

Jetrell commented Sep 25, 2024

When you ran your tests. Did your build include 10243 ?

I proceeded to run a baro temp calibration on a copter with a DPS310... The calibration was done with the flight battery connected, which also added to the boards heat by having the voltage regulator driving the VTX.
The air temperature inside the building was 18°c when calibrating.
Before I ran the calibration, altitude in the sensor tab was showing between -0.03 to +0.1meters.
Then I ran the calibration according to your recommendations. Of which I did a few times with a 10 minute cool down between all the processes... It came up with a 1.03, 3.42cm/K change. And 14.52cm/K change with only USB power, with all holding practically as close to zero as it did before the calibration. So I'm not sure how accurate calibration can actually be on this FC.

I then took it out for a hover. I did this without a GNSS fix, just in Althold, using the baro and IMU for vertical estimation.. The air temperature was 16°c, with some light wind.
After arming and entering a hover, then enabling Althold. The copter started to climb from 1 to 5 meters. So I landed and rebooted the FC.
On the next flight immediately after, Althold held within a meter of the altitude target. Although it did drift up and down considerably as the wind would lightly blow.

I find the baro altitude / temperature log data hard to gauge and interpret when comparing to line of sight video.

  • Wind blowing over the surface of the barometers hole can increase the air pressure on the sensor, making the FC think the copter is lower in altitude than it actually is for a time. So it commands the copter to climb.

  • While much cooler more dense air blowing over the sensing hole, might cool the charged air within the sensor case, if it can displace some of the warmer stationary air in contact with the piezo element... Under that condition, temperature compensation may stabilize altitude data, based on air density changes.. But how likely is this, when the baro sensor case is continuously being heated by the boards thermal mass ?

Open cell foam certainly helps to also divert some air flow around the sensor, as well as maintain a more consistent temperature. But the effect is still there.

Don't take my report as negative. I think it has to be a bit of both of the conditions above. I'm just trying to provide as much test data as possible. I wish it was a little more favorable.
I'll do some more tests with other Copters/FC's/baro's later when the weather clears.

@breadoven
Copy link
Collaborator Author

@Jetrell How did the DPS310 baro behave with no compensation, did it drift by several meters after 5 mins or so ? The spec sheet for it shows the same pressure temperature sensitivity as the BMP280 = 0.5 Pa/K so I'd expect similar behaviour, unless of course the original calibration for your particular baro was just less affected by the manufacturing process.

The auto calibration is really just to get a ball park figure. Ultimately you can just set a value and see how much the baro altitude drifts compared to no compensation and adjust from there. This compensation method also assumes a linear relationship which I don't think is the case over an extended temperature range. So you might find it overshoots at a lower temperature then undershoots at a higher temperature with a 0 point somewhere in between. Which I guess isn't a problem really since it's better than the situation without any compensation.

As far as the overall estimated Z is concerned the other issue is the IMU drifting, as shown in #10308. This may be more of a problem than baro and GPS drift since it's the baseline for the estimates so any constant offset in the Z acceleration will result in a constant offset in the estimates for altitude and velocity. Would be useful to improve this.

I did a test the other day using this PR with a multirotor with a BMP280 and a setting of 20 cm/K. Initially altitude control was poor until I realised the default alt sensor setting was set to GPS. It was flying in the back garden near trees and buildings which I think screws up the GPS accuracy badly, multi pathing etc I'd guess, position hold drifted badly and erratically. I switched to Baro Only and the altitude control was much better (position hold was still poor though ... as expected), probably the most stable altitude control I've had for a while, none of the yo yo'ing up and down and poor erratic response to the throttle stick corrections I've had recently.

@Jetrell
Copy link

Jetrell commented Sep 25, 2024

How did the DPS310 baro behave with no compensation, did it drift by several meters after 5 mins or so ?

When testing it today before the calibration, the difference wasn't any worse with the DPS310, than it was after the calibration tests were done. Meaning the drift was still there to a similar degree, but not majorly.
But in saying that. This copter generally drifts far worse than my others in the colder weather.. Which may say something about the temperature compensation for this baro being less needed at warmer ambient temperatures, than at lower ones.

As far as the overall estimated Z is concerned the other issue is the IMU drifting. This may be more of a problem than baro and GPS drift since it's the baseline for the estimates so any constant offset in the Z acceleration will result in a constant offset in the estimates for altitude and velocity. Would be useful to improve this.

I'm leaning that way too.. At select points in the logs I was looking over today. When comparing Baro and IMU temperatures, with baro and navPos[2] altitude, against navAcc[2], acc[Z]. I could occasionally see the Acc average increase, which pushed the navPos[2] higher, even at times when the baro altitude was relatively steady. This was in Althold with the GNSS disabled.

@breadoven
Copy link
Collaborator Author

breadoven commented Sep 26, 2024

I've used the same method to compensate for IMU Acc Z drift which seems to work possibly more reliably than the Baro, the Auto calibration correction factor is much more consistent. I did notice though that there is already some bias correction applied to Acc drift based on Baro and GPS altitude corrections, uses inav_w_acc_bias. However, it's slow to respond and that's with the FC static on the bench, not sure how well it would work in flight, so using a temperature based correction would be better.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants