mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: minor improvements to Baro HIL code health check
This commit is contained in:
parent
0df2dd9092
commit
a458f1bf5f
|
@ -125,7 +125,8 @@ void AP_Baro::calibrate()
|
|||
*/
|
||||
void AP_Baro::update_calibration()
|
||||
{
|
||||
_ground_pressure.set(get_pressure());
|
||||
float pressure = get_pressure();
|
||||
_ground_pressure.set(pressure);
|
||||
_ground_temperature.set(get_temperature());
|
||||
}
|
||||
|
||||
|
@ -166,7 +167,8 @@ float AP_Baro::get_altitude(void)
|
|||
return _altitude + _alt_offset;
|
||||
}
|
||||
|
||||
_altitude = get_altitude_difference(_ground_pressure, get_pressure());
|
||||
float pressure = get_pressure();
|
||||
_altitude = get_altitude_difference(_ground_pressure, pressure);
|
||||
|
||||
_last_altitude_t = _last_update;
|
||||
|
||||
|
|
|
@ -9,6 +9,7 @@ extern const AP_HAL::HAL& hal;
|
|||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
bool AP_Baro_HIL::init()
|
||||
{
|
||||
healthy = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -35,12 +36,14 @@ uint8_t AP_Baro_HIL::read()
|
|||
|
||||
void AP_Baro_HIL::setHIL(float pressure, float temperature)
|
||||
{
|
||||
if (pressure > 0) {
|
||||
_count = 1;
|
||||
_pressure_sum = pressure;
|
||||
_temperature_sum = temperature;
|
||||
_last_update = hal.scheduler->millis();
|
||||
healthy = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// ==========================================================================
|
||||
|
|
Loading…
Reference in New Issue