mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Baro: cleaned up temperature and pressure units
thanks to Mike McCauley for pointing this out
This commit is contained in:
parent
7de47931a8
commit
fc119d9b80
@ -115,7 +115,7 @@ void AP_Baro::calibrate()
|
||||
}
|
||||
|
||||
_ground_pressure.set_and_save(ground_pressure);
|
||||
_ground_temperature.set_and_save(ground_temperature / 10.0f);
|
||||
_ground_temperature.set_and_save(ground_temperature);
|
||||
}
|
||||
|
||||
// return current altitude estimate relative to time that calibrate()
|
||||
|
@ -18,11 +18,12 @@ public:
|
||||
|
||||
virtual bool init()=0;
|
||||
virtual uint8_t read() = 0;
|
||||
virtual float get_pressure() = 0;
|
||||
virtual float get_temperature() = 0;
|
||||
|
||||
virtual int32_t get_raw_pressure() = 0;
|
||||
virtual int32_t get_raw_temp() = 0;
|
||||
// pressure in Pascal. Divide by 100 for millibars or hectopascals
|
||||
virtual float get_pressure() = 0;
|
||||
|
||||
// temperature in degrees C
|
||||
virtual float get_temperature() = 0;
|
||||
|
||||
// accumulate a reading - overridden in some drivers
|
||||
virtual void accumulate(void) {}
|
||||
@ -49,10 +50,14 @@ public:
|
||||
// going up
|
||||
float get_climb_rate(void);
|
||||
|
||||
// ground temperature in degrees C
|
||||
// the ground values are only valid after calibration
|
||||
float get_ground_temperature(void) {
|
||||
return _ground_temperature.get();
|
||||
}
|
||||
|
||||
// ground pressure in Pascal
|
||||
// the ground values are only valid after calibration
|
||||
float get_ground_pressure(void) {
|
||||
return _ground_pressure.get();
|
||||
}
|
||||
|
@ -141,7 +141,7 @@ uint8_t AP_Baro_BMP085::read()
|
||||
}
|
||||
_last_update = hal.scheduler->millis();
|
||||
|
||||
Temp = _temp_sum / _count;
|
||||
Temp = 0.1f * _temp_sum / _count;
|
||||
Press = _press_sum / _count;
|
||||
|
||||
_pressure_samples = _count;
|
||||
@ -160,14 +160,6 @@ float AP_Baro_BMP085::get_temperature() {
|
||||
return Temp;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_BMP085::get_raw_pressure() {
|
||||
return RawPress;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_BMP085::get_raw_temp() {
|
||||
return RawTemp;
|
||||
}
|
||||
|
||||
// Private functions: /////////////////////////////////////////////////////////
|
||||
|
||||
// Send command to Read Pressure
|
||||
|
@ -22,9 +22,6 @@ public:
|
||||
float get_pressure();
|
||||
float get_temperature();
|
||||
|
||||
int32_t get_raw_pressure();
|
||||
int32_t get_raw_temp();
|
||||
|
||||
private:
|
||||
int32_t RawPress;
|
||||
int32_t RawTemp;
|
||||
|
@ -96,11 +96,3 @@ float AP_Baro_HIL::get_pressure() {
|
||||
float AP_Baro_HIL::get_temperature() {
|
||||
return Temp;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_HIL::get_raw_pressure() {
|
||||
return Press;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_HIL::get_raw_temp() {
|
||||
return Temp;
|
||||
}
|
||||
|
@ -20,8 +20,6 @@ public:
|
||||
uint8_t read();
|
||||
float get_pressure();
|
||||
float get_temperature();
|
||||
int32_t get_raw_pressure();
|
||||
int32_t get_raw_temp();
|
||||
void setHIL(float altitude_msl);
|
||||
};
|
||||
|
||||
|
@ -22,7 +22,7 @@
|
||||
* Chip Select pin: Analog2 (provisional until Jordi defines the pin)!!
|
||||
*
|
||||
* Variables:
|
||||
* Temp : Calculated temperature (in Celsius degrees * 100)
|
||||
* Temp : Calculated temperature (in Celsius degrees)
|
||||
* Press : Calculated pressure (in mbar units * 100)
|
||||
*
|
||||
*
|
||||
@ -404,7 +404,7 @@ void AP_Baro_MS5611::_calculate()
|
||||
}
|
||||
|
||||
P = (D1*SENS/2097152 - OFF)/32768;
|
||||
Temp = TEMP + 2000;
|
||||
Temp = (TEMP + 2000) * 0.01f;
|
||||
Press = P;
|
||||
}
|
||||
|
||||
@ -415,16 +415,7 @@ float AP_Baro_MS5611::get_pressure()
|
||||
|
||||
float AP_Baro_MS5611::get_temperature()
|
||||
{
|
||||
// callers want the temperature in 0.1C units
|
||||
return Temp/10;
|
||||
// temperature in degrees C units
|
||||
return Temp;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_MS5611::get_raw_pressure() {
|
||||
return _raw_press;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_MS5611::get_raw_temp() {
|
||||
return _raw_temp;
|
||||
}
|
||||
|
||||
|
||||
|
@ -77,10 +77,7 @@ public:
|
||||
bool init();
|
||||
uint8_t read();
|
||||
float get_pressure(); // in mbar*100 units
|
||||
float get_temperature(); // in celsius degrees * 100 units
|
||||
|
||||
int32_t get_raw_pressure();
|
||||
int32_t get_raw_temp();
|
||||
float get_temperature(); // in celsius degrees
|
||||
|
||||
void _calculate();
|
||||
|
||||
|
@ -52,7 +52,7 @@ uint8_t AP_Baro_PX4::read(void)
|
||||
}
|
||||
|
||||
_pressure = (_pressure_sum / _sum_count) * 100.0f;
|
||||
_temperature = (_temperature_sum / _sum_count) * 10.0f;
|
||||
_temperature = _temperature_sum / _sum_count;
|
||||
_pressure_samples = _sum_count;
|
||||
_last_update = (uint32_t)_last_timestamp/1000;
|
||||
_pressure_sum = 0;
|
||||
@ -83,12 +83,4 @@ float AP_Baro_PX4::get_temperature() {
|
||||
return _temperature;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_PX4::get_raw_pressure() {
|
||||
return _pressure;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_PX4::get_raw_temp() {
|
||||
return _temperature;
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
@ -12,8 +12,6 @@ public:
|
||||
uint8_t read();
|
||||
float get_pressure();
|
||||
float get_temperature();
|
||||
int32_t get_raw_pressure();
|
||||
int32_t get_raw_temp();
|
||||
|
||||
private:
|
||||
float _temperature;
|
||||
|
Loading…
Reference in New Issue
Block a user