Suggestion for Baro temperature in getEstimatedAltitude

This forum is dedicated to software development related to MultiWii.
It is not the right place to submit a setup problem.
Software download
Post Reply
pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Suggestion for Baro temperature in getEstimatedAltitude

Post by pm1 »

Hi
in getEstimatedAltitude a new formula been invented to calculate the altitude. In that formula the *ground* temperature of the atmosphere should be used. Here at *every calculation* the baro chip temperature is used. (not correctly copied from arducopter). Unfortunately this temperature climbs in the first minutes of operation (at least on BMP085) about 15 degrees above environment temperature.

I suggest to set the temperature either constant (for example 10 degrees C) or set it only at calibration time, which will even speed up the code..

Here the code to set it at calibration time:

Code: Select all

 uint8_t getEstimatedAltitude(){
...

  static float baroGroundTemperatureScale;
...


  if(calibratingB > 0) {
...
      baroGroundTemperatureScale = (baroTemperature + 27315) *  29.271267f;
...
    }
    calibratingB--;
  }
...

  BaroAlt = log( baroGroundPressure * (BARO_TAB_SIZE - 1)/ (float)baroPressureSum ) * baroGroundTemperatureScale; // in cemtimeter

timecop
Posts: 1880
Joined: Fri Sep 02, 2011 4:48 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by timecop »

Hm, are you sure?
I mean,, the "air" temperature could change quite a bit while flying high(er), plus the usual going from warm/cold room to outside with different temperature.

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by pm1 »

No, it's definitely the formula, which includes the *ground* temperature, which is used for all aviation around the world. All barometric altitudes in the aviation for a defined area are calculated based on barometric pressure and temperature of an airport. This is not correct, but since all airplanes are requested to do the same, they don't collide...

But even when this would not be correct:
In the atmosphere, there is a typical decrease of temperature of 0.7 degrees C/100 m. So if we assuming heights of 1000 m, we have a difference of 7 degrees in relation to 15 degrees from the unknown heating status of the baro chip...

Best regards
Peter

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Alexinparis »

Hi,

I think you're right.
According to AP_Baro.cpp, it's also the case.

Sebbi
Posts: 478
Joined: Sun Jul 08, 2012 1:08 am
Location: Germany
Contact:

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Sebbi »

MultiWii should transmit baro- (and gyro) temperatures in the GUI to confirm this problem.

Pressure calculation of these sensors heavily rely on the measured temperature (see i2c_MS561101BA_Calculate() and i2c_BMP085_Calculate()). Is there a heating element in those sensors which needs to be compensated for?

Sebbi
Posts: 478
Joined: Sun Jul 08, 2012 1:08 am
Location: Germany
Contact:

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Sebbi »

pm1 wrote:No, it's definitely the formula, which includes the *ground* temperature, which is used for all aviation around the world. All barometric altitudes in the aviation for a defined area are calculated based on barometric pressure and temperature of an airport. This is not correct, but since all airplanes are requested to do the same, they don't collide...


To expand on that ... aircrafts don't use temperature compensation. Altimeters just need a setting for ground pressure. This comes from the local airport so every plane's altimeter shows the same height even if it isn't the correct height ... because, temperature.

It is definelty not ground temperature that is being used in the barometric formula (http://en.wikipedia.org/wiki/Barometric_formula). It is the air temperature at the specific height that is influencing pressure, not the temperature on the ground.

Formula is:

Code: Select all

P_height = P_ground * e ^ [-(M * G) / (R * T) * height]


Or:

Code: Select all

height = log (P_ground / P_height) * T * [R / (M * G)]


With M (molar mass of air) being 0.0289644 kg/mol, G (gravity) being 9.80665 m/s^2 and R (gas constant for air) being 8.31432 Nm/molK the formula is:

Code: Select all

height = log (P_ground / P_height) * T * 29.2712671552


T in Kelvin and height will be in meters. Don't see where MultiWii got it wrong ...

crazyal
Posts: 84
Joined: Tue Sep 04, 2012 11:25 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by crazyal »

Sebbi wrote:
pm1 wrote:No, it's definitely the formula, which includes the *ground* temperature, which is used for all aviation around the world. All barometric altitudes in the aviation for a defined area are calculated based on barometric pressure and temperature of an airport. This is not correct, but since all airplanes are requested to do the same, they don't collide...


To expand on that ... aircrafts don't use temperature compensation. Altimeters just need a setting for ground pressure. This comes from the local airport so every plane's altimeter shows the same height even if it isn't the correct height ... because, temperature.

It is definelty not ground temperature that is being used in the barometric formula (http://en.wikipedia.org/wiki/Barometric_formula). It is the air temperature at the specific height that is influencing pressure, not the temperature on the ground.

Formula is:

Code: Select all

P_height = P_ground * e ^ [-(M * G) / (R * T) * height]


Or:

Code: Select all

height = log (P_ground / P_height) * T * [R / (M * G)]


With M (molar mass of air) being 0.0289644 kg/mol, G (gravity) being 9.80665 m/s^2 and R (gas constant for air) being 8.31432 Nm/molK the formula is:

Code: Select all

height = log (P_ground / P_height) * T * 29.2712671552


T in Kelvin and height will be in meters. Don't see where MultiWii got it wrong ...


It may look right because there is T in the formula, but that refers to the standard Temperature which is constant. See the table below. Just think logically how the formula is derived.
To calculate the height from a pressure change you have to know the density of the air inbetween your height change which is temperature dependent and probably even changes if the air moves etc.
So if you want to do it the "correct" way you would have to use equation one which uses the ground temperature and also accustoms for a temperature change vs height.
For the constant T you should use 288.15K as it says in the table subscipt b.
Edit: what I worte earlier isn't correct, T isn't that constant, it only is 15°C at sea level. For different starting altitudes using GroundTemperature might be an ok approximation.
The only problem I discovered is the baro heating up. After the board runs a few minutes the baro reports a Temperature of 30°C instead of 22°C room temperature.

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Crashpilot1000 »

Hi!

@pm1: Thank you very much for wrapping your head around that subject. From my observation the baro heating up seems to be greatly dependent on the hardware implementation and foam coverage. I posted my results here: http://diydrones.com/profiles/blogs/bar ... 2#comments.
On Naze rev.4 the nearby serial chip seems to heat up the baro considerably under foam cover, when serial traffic is present. The uncovered Freeimu did not show that beaviour.
However I implemented the compensation you hinted at with the more precise approach here https://github.com/diydrones/ardupilot/ ... o.cpp#L141. The result on the bench is better for MS5611 on naze rev4, BMP seems more or less the same (soldered on older naze). Inflight test has to be done (bad weather here).
So far my practical results, thanks again for hinting at that arducopter approach!

Cheers
Rob

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by pm1 »

Sebbi wrote:To expand on that ... aircrafts don't use temperature compensation. Altimeters just need a setting for ground pressure. This comes from the local airport so every plane's altimeter shows the same height even if it isn't the correct height ... because, temperature.


You are right: For the alltitude up to 11000 m the "standard atmosphere" with 1013.25 hPa and 15 degrees celsius is assumed.


The temperature gradient and the typical ground temperature for each plane is used in the table.

But as I already said: Due to increasing temperature of the baro chip we definitely are using the worst value. After thinking about that again, I suggest to set the temperature fixed to 15 degrees. I cannot think of any advantage to use the baro chip temperature at all.
Last edited by pm1 on Mon Sep 16, 2013 8:40 pm, edited 2 times in total.

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by pm1 »

Crashpilot1000 wrote:On Naze rev.4 the nearby serial chip seems to heat up the baro considerably under foam cover, when serial traffic is present. The uncovered Freeimu did not show that beaviour.


I think, the foam cover still makes sense to isolate the chip from radiating heat sources as the sun (directly or housing in sunlight). Only significant temperture changes within seconds are affecting the baro as much as all the other sources of problems here ;)...

pm1
Posts: 136
Joined: Sun Jan 22, 2012 7:26 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by pm1 »

Sebbi wrote:MultiWii should transmit baro- (and gyro) temperatures in the GUI to confirm this problem.

Pressure calculation of these sensors heavily rely on the measured temperature (see i2c_MS561101BA_Calculate() and i2c_BMP085_Calculate()). Is there a heating element in those sensors which needs to be compensated for?


The pressure measurement in that sensors is *heavily* temperature sensitive. I tried to use the BMP085 assuming a fixed temperature (I tested, where the noise came from..). When I did put a finger at the border of the chip, I was off 100 m within seconds... ;)



P.S. I gave up to optimize the output of the BMP085. It`s crap... With the MS561101 I now only fight against the environment, not against the chip itself.

Sebbi
Posts: 478
Joined: Sun Jul 08, 2012 1:08 am
Location: Germany
Contact:

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Sebbi »

Well, the original idea was to speed up the altitude estimation which was a slow "pow()" implementation. The "log()" approach was faster, but needs the temperature. It could work with some medium value if you don't care about "correct" altitude display.

But if the chip itself heats up, the pressure measurements will also be incorrect, wont they? So even if only the pressure is used for alt hold your copter wont behave correctly :/

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Crashpilot1000 »

@Sebbi: Yes, definitely. I thought the heating/hight influence would be diminished but after further tests, I see the same results like before. Perhaps some temperature factor on the ground could be gathered during heatup for further compensation (the "curves" look rather linear in the interesting area http://de.wikipedia.org/wiki/Barometris ... 6henformel) ?
A quick spin with my copter showed def. worse results than I had with my previous code that is still based on the "slow" "pow" calculation.
@pm1: Thank you very much for your input and your effort, maybe it's just me but - will stick to my pair of working socks :)
Cheers Rob

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Alexinparis »

Sebbi wrote:Well, the original idea was to speed up the altitude estimation which was a slow "pow()" implementation. The "log()" approach was faster, but needs the temperature. It could work with some medium value if you don't care about "correct" altitude display.

But if the chip itself heats up, the pressure measurements will also be incorrect, wont they? So even if only the pressure is used for alt hold your copter wont behave correctly :/


Hi,

Don't forget there are currently 2 levels of temperature compensation:
1) in sensor part where dynamic pressure is dependant of dynamic temperature in calculation. This one is mandatory according to sensor spec
2) in IMU part where dynamic temp+ dynamic pressure is used to determine an alt

Before the IMU was upgraded to log approach, the formula was:
BaroAlt = (1.0f - pow(pressure/101325.0f, 0.190295f)) * 4433000.0f;
which was not dependant of dynamic temp

so I suppose 2) should be changed to not take intoo account dynamic temp => either a ground temp or a general static temp (like 15C deg) should be ok

copterrichie
Posts: 2261
Joined: Sat Feb 19, 2011 8:30 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by copterrichie »

I recall reading a suggestion in one of the APM threads, to power up the electronics, allow to set for 5 minutes, then calibrate. I believe this was to allow the chips to reach their operating temperature before establishing the baseline. Maybe, that is something we can do here.

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Crashpilot1000 »

@AlexIP: BaroAlt = (1.0f - pow(pressure/101325.0f, 0.190295f)) * 4433000.0f;
That actually IS temperature compensated, because the baro does its own temperature compensation based on it's calibration data. But it can not overcome a problematic hardwaredesign. The Arducopter approach in the IMU will not overcome that either - like shown in the DIY Drones Forum thread.
@CopterR: Of course, wait 3 minutes (>95% of the heating done) will solve for this. You will want a FC with a reset button for that......

copterrichie
Posts: 2261
Joined: Sat Feb 19, 2011 8:30 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by copterrichie »

Crashpilot1000 wrote:@CopterR: Of course, wait 3 miniutes (>95% of the heating done) will solve for this. You will want a FC with a reset button for that......


I would think, powering off, then back on would be a temporary fix right?

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Crashpilot1000 »

You can start directly but expect a slow decrease in althold hight when enabling during heatuptime (depending on hardware/foam etc). Just be aware to compensate for that (if needed in low alt) in the first minutes - not nice but not such a big deal after all.
P.s.: That will not win you a price in an autonomous vehicle competition, when flying through a gate and your internal hight is 5 meters off (or so).....
Last edited by Crashpilot1000 on Tue Sep 17, 2013 8:06 pm, edited 1 time in total.

copterrichie
Posts: 2261
Joined: Sat Feb 19, 2011 8:30 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by copterrichie »

Thank you.

User avatar
Bizin
Posts: 1
Joined: Sun Sep 22, 2013 2:08 pm
Location: Russia

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Bizin »

IMHO, this optimisation may be usefull.

Code: Select all

267   static float baroGroundTemperatureScale,baroGroundPressureSum;
278   baroGroundPressureSum = baroPressureSum;
285   BaroAlt = log( baroGroundPressureSum / baroPressureSum ) * baroGroundTemperatureScale;

Change to:

Code: Select all

267   static float baroGroundTemperatureScale,logbaroGroundPressureSum;
278   logbaroGroundPressureSum = log(baroPressureSum);
285   BaroAlt = ( logbaroGroundPressureSum - log(baroPressureSum) ) * baroGroundTemperatureScale;

Or compilator do this automaticaly?

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Alexinparis »

Bizin wrote:IMHO, this optimisation may be usefull.

Code: Select all

267   static float baroGroundTemperatureScale,baroGroundPressureSum;
278   baroGroundPressureSum = baroPressureSum;
285   BaroAlt = log( baroGroundPressureSum / baroPressureSum ) * baroGroundTemperatureScale;

Change to:

Code: Select all

267   static float baroGroundTemperatureScale,logbaroGroundPressureSum;
278   logbaroGroundPressureSum = log(baroPressureSum);
285   BaroAlt = ( logbaroGroundPressureSum - log(baroPressureSum) ) * baroGroundTemperatureScale;

Or compilator do this automaticaly?


Hi,

Interesting, it's more optimized like this as it replace a costly / by a - in recurrent computations.

User avatar
Crashpilot1000
Posts: 631
Joined: Tue Apr 03, 2012 7:38 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Crashpilot1000 »

BTW: According to the datasheet you need to calculate "T2" to get a correct temperature readout below 20 Degree for MS5611. Just saying...

Alexinparis
Posts: 1630
Joined: Wed Jan 19, 2011 9:07 pm

Re: Suggestion for Baro temperature in getEstimatedAltitude

Post by Alexinparis »

Crashpilot1000 wrote:BTW: According to the datasheet you need to calculate "T2" to get a correct temperature readout below 20 Degree for MS5611. Just saying...

right, according to spec
an offset of T2 = dT2 / 2^31 should be used to the temperature,
we need to evaluate it under 20deg to see if it is really relevant in the final alt estimation (I doubt)

Post Reply