mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Airspeed: Temperature conversion in consistence with other libraries
This commit is contained in:
parent
99525410ee
commit
d3eb24bc01
@ -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;
|
||||
}
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user