mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 02:04:00 -04:00
HAL_Linux: use ceilf()
This commit is contained in:
parent
ce5db7b813
commit
4404c95cc8
@ -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);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -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 */
|
||||||
|
Loading…
Reference in New Issue
Block a user