AP_Airspeed: Temperature conversion in consistence with other libraries

This commit is contained in:
DOMINATOR\Eugene 2018-10-28 19:38:08 +02:00 committed by Francisco Ferreira
parent 99525410ee
commit d3eb24bc01
2 changed files with 3 additions and 3 deletions

View File

@ -129,7 +129,7 @@ void AP_Airspeed_UAVCAN::handle_airspeed(AP_UAVCAN* ap_uavcan, uint8_t node_id,
if (driver != nullptr) {
WITH_SEMAPHORE(driver->_sem_airspeed);
driver->_pressure = cb.msg->differential_pressure;
driver->_temperature = cb.msg->static_air_temperature;
driver->_temperature = cb.msg->static_air_temperature - C_TO_KELVIN;
driver->_last_sample_time_ms = AP_HAL::millis();
}
@ -164,7 +164,7 @@ bool AP_Airspeed_UAVCAN::get_temperature(float &temperature)
return false;
}
temperature = _temperature - C_TO_KELVIN;
temperature = _temperature;
return true;
}

View File

@ -32,7 +32,7 @@ private:
static AP_Airspeed_UAVCAN* get_uavcan_backend(AP_UAVCAN* ap_uavcan, uint8_t node_id);
float _pressure; // Pascal
float _temperature; // Kelvin
float _temperature; // Celcius
uint32_t _last_sample_time_ms;
HAL_Semaphore _sem_airspeed;