mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_Baro: Remove superfluous casts
This commit is contained in:
parent
55370ac1e6
commit
edfcac7d1f
@ -235,8 +235,8 @@ void AP_Baro_KellerLD::update()
|
||||
|
||||
_sem->give();
|
||||
|
||||
uint16_t raw_pressure_avg = ((float)sum_pressure) / num_samples;
|
||||
uint16_t raw_temperature_avg = ((float)sum_temperature) / num_samples;
|
||||
uint16_t raw_pressure_avg = sum_pressure / num_samples;
|
||||
uint16_t raw_temperature_avg = sum_temperature / num_samples;
|
||||
|
||||
// per datasheet
|
||||
float pressure = (raw_pressure_avg - 16384) * (_p_max - _p_min) / 32768 + _p_min;
|
||||
|
Loading…
Reference in New Issue
Block a user