HAL_Linux: use ceilf()

This commit is contained in:
Andrew Tridgell 2018-05-04 14:36:52 +10:00
parent ce5db7b813
commit 4404c95cc8
2 changed files with 2 additions and 2 deletions

View File

@ -73,7 +73,7 @@ Flow_PX4::Flow_PX4(uint32_t width, uint32_t bytesperline,
* So _num_blocks = _width / (2 * _search_size + 3) * So _num_blocks = _width / (2 * _search_size + 3)
*/ */
_num_blocks = _width / (2 * _search_size + 3); _num_blocks = _width / (2 * _search_size + 3);
_pixstep = ceil(((float)(_pixhi - _pixlo)) / _num_blocks); _pixstep = ceilf(((float)(_pixhi - _pixlo)) / _num_blocks);
} }
/** /**

View File

@ -133,7 +133,7 @@ void RCOutput_PCA9685::set_freq(uint32_t chmask, uint16_t freq_hz)
* different from @freq_hz due to rounding/ceiling. We use ceil() rather * different from @freq_hz due to rounding/ceiling. We use ceil() rather
* than round() so the resulting frequency is never greater than @freq_hz * than round() so the resulting frequency is never greater than @freq_hz
*/ */
uint8_t prescale = ceil(_osc_clock / (4096 * freq_hz)) - 1; uint8_t prescale = ceilf(_osc_clock / (4096 * freq_hz)) - 1;
_frequency = _osc_clock / (4096 * (prescale + 1)); _frequency = _osc_clock / (4096 * (prescale + 1));
/* Write prescale value to match frequency */ /* Write prescale value to match frequency */