Merge branch 'Jacob'

This commit is contained in:
Rustom Jehangir 2016-01-20 22:01:38 -08:00
commit c4e671b750
3 changed files with 4 additions and 4 deletions

View File

@ -404,7 +404,7 @@ void AP_Baro::update(void)
} else if(sensors[i].type == BARO_TYPE_WATER) {
//101325Pa is sea level air pressure, 9800 Pascal/ m depth in water.
//No temperature or depth compensation for density of water.
altitude = (sensors[i].ground_pressure - sensors[i].pressure) * sensors[i].precision_multiplier / 9800.0f / _specific_gravity;
altitude = (sensors[i].ground_pressure - sensors[i].pressure) / 9800.0f / _specific_gravity;
}
// sanity check altitude
sensors[i].alt_ok = !(isnan(altitude) || isinf(altitude));

View File

@ -43,7 +43,7 @@ public:
// pressure in Pascal. Divide by 100 for millibars or hectopascals
float get_pressure(void) const { return get_pressure(_primary); }
float get_pressure(uint8_t instance) const { return sensors[instance].pressure * sensors[instance].precision_multiplier; }
float get_pressure(uint8_t instance) const { return sensors[instance].pressure; }
// temperature in degrees C
float get_temperature(void) const { return get_temperature(_primary); }
@ -88,7 +88,7 @@ public:
// ground pressure in Pascal
// the ground values are only valid after calibration
float get_ground_pressure(void) const { return get_ground_pressure(_primary); }
float get_ground_pressure(uint8_t i) const { return sensors[i].ground_pressure.get() * sensors[i].precision_multiplier; }
float get_ground_pressure(uint8_t i) const { return sensors[i].ground_pressure.get(); }
// set the temperature to be used for altitude calibration. This
// allows an external temperature source (such as a digital

View File

@ -16,7 +16,7 @@ void AP_Baro_Backend::_copy_to_frontend(uint8_t instance, float pressure, float
if (instance >= _frontend._num_sensors) {
return;
}
_frontend.sensors[instance].pressure = pressure;
_frontend.sensors[instance].pressure = pressure * _frontend.sensors[instance].precision_multiplier;
_frontend.sensors[instance].temperature = temperature;
_frontend.sensors[instance].last_update_ms = AP_HAL::millis();
}