change constant to float 44330.0

This commit is contained in:
Jason Short 2012-02-14 08:55:32 -08:00
parent 2f81776b0d
commit 026e4a6567
4 changed files with 16 additions and 16 deletions

View File

@ -99,7 +99,7 @@ void Navigator_Dcm::calibrate() {
}
flashcount++;
}
_groundPressure.save();
_groundTemperature.save();
@ -133,10 +133,10 @@ void Navigator_Dcm::updateFast(float dt) {
* temp input is in deg C *10
*/
_board->baro->Read(); // Get new data from absolute pressure sensor
float reference = 44330 * (1.0 - (pow(_groundPressure.get()/101325.0,0.190295)));
setAlt(_baroLowPass.update((44330 * (1.0 - (pow((_board->baro->Press/101325.0),0.190295)))) - reference,dt));
float reference = 44330.0 * (1.0 - (pow(_groundPressure.get()/101325.0,0.190295)));
setAlt(_baroLowPass.update((44330.0 * (1.0 - (pow((_board->baro->Press/101325.0),0.190295)))) - reference,dt));
//_board->debug->printf_P(PSTR("Ground Pressure %f\tAltitude = %f\tGround Temperature = %f\tPress = %ld\tTemp = %d\n"),_groundPressure.get(),getAlt(),_groundTemperature.get(),_board->baro->Press,_board->baro->Temp);
// last resort, use gps altitude
} else if (_board->gps && _board->gps->fix) {
setAlt_intM(_board->gps->altitude * 10); // gps in cm, intM in mm

View File

@ -116,7 +116,7 @@ bool AP_Baro_MS5611::init( AP_PeriodicProcess *scheduler )
pinMode(MS5611_CS, OUTPUT); // Chip select Pin
digitalWrite(MS5611_CS, HIGH);
delay(1);
_spi_write(CMD_MS5611_RESET);
delay(4);
@ -136,7 +136,7 @@ bool AP_Baro_MS5611::init( AP_PeriodicProcess *scheduler )
_state = 1;
Temp=0;
Press=0;
scheduler->register_process( AP_Baro_MS5611::_update );
healthy = true;
@ -159,7 +159,7 @@ void AP_Baro_MS5611::_update(uint32_t tnow)
}
_timer = tnow;
if (_state == 1) {
_s_D2 = _spi_read_adc(); // On state 1 we read temp
_state++;
@ -208,7 +208,7 @@ void AP_Baro_MS5611::_calculate()
// sub -20c temperature compensation is not included
dT = D2-((long)C5*256);
TEMP = 2000 + ((int64_t)dT * C6)/8388608;
OFF = (int64_t)C2 * 65536 + ((int64_t)C4 * dT ) / 128;
OFF = (int64_t)C2 * 65536 + ((int64_t)C4 * dT ) / 128;
SENS = (int64_t)C1 * 32768 + ((int64_t)C3 * dT) / 256;
if (TEMP < 2000){ // second order temperature compensation
@ -220,7 +220,7 @@ void AP_Baro_MS5611::_calculate()
OFF = OFF - OFF2;
SENS = SENS - SENS2;
}
P = (D1*SENS/2097152 - OFF)/32768;
Temp = TEMP;
Press = P;
@ -245,7 +245,7 @@ float AP_Baro_MS5611::get_altitude()
tmp_float = (Press / 101325.0);
tmp_float = pow(tmp_float, 0.190295);
Altitude = 44330 * (1.0 - tmp_float);
Altitude = 44330.0 * (1.0 - tmp_float);
return (Altitude);
}

View File

@ -28,7 +28,7 @@ Arduino_Mega_ISR_Registry isr_registry;
AP_TimerProcess scheduler;
void setup()
{
{
Serial.begin(115200);
Serial.println("ArduPilot Mega BMP085 library test");
Serial.println("Initialising barometer..."); delay(100);
@ -53,7 +53,7 @@ void loop()
{
float tmp_float;
float Altitude;
if((micros()- timer) > 50000L){
timer = micros();
APM_BMP085.read();
@ -69,7 +69,7 @@ void loop()
Serial.print(" Altitude:");
tmp_float = (APM_BMP085.get_pressure() / 101325.0);
tmp_float = pow(tmp_float, 0.190295);
Altitude = 44330 * (1.0 - tmp_float);
Altitude = 44330.0 * (1.0 - tmp_float);
Serial.print(Altitude);
Serial.printf(" t=%u", (unsigned)read_time);
Serial.println();

View File

@ -18,7 +18,7 @@ AP_TimerProcess scheduler;
unsigned long timer;
void setup()
{
{
Serial.begin(115200, 128, 128);
Serial.println("ArduPilot Mega MeasSense Barometer library test");
@ -40,7 +40,7 @@ void loop()
{
float tmp_float;
float Altitude;
if((micros()- timer) > 50000L){
timer = micros();
baro.read();
@ -56,7 +56,7 @@ void loop()
Serial.print(" Altitude:");
tmp_float = (baro.get_pressure() / 101325.0);
tmp_float = pow(tmp_float, 0.190295);
Altitude = 44330 * (1.0 - tmp_float);
Altitude = 44330.0 * (1.0 - tmp_float);
Serial.print(Altitude);
Serial.printf(" t=%u", (unsigned)read_time);
Serial.println();