AP_HAL_Linux: use MIN where possible
This commit is contained in:
parent
05a7eef1a2
commit
c898b28962
@ -4,6 +4,7 @@
|
|||||||
#include <cstdio>
|
#include <cstdio>
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
#include "px4io_protocol.h"
|
#include "px4io_protocol.h"
|
||||||
|
|
||||||
@ -162,19 +163,11 @@ void RPIOUARTDriver::_timer_tick(void)
|
|||||||
struct IOPacket _dma_packet_tx = {0}, _dma_packet_rx = {0};
|
struct IOPacket _dma_packet_tx = {0}, _dma_packet_rx = {0};
|
||||||
|
|
||||||
/* get write_buf bytes */
|
/* get write_buf bytes */
|
||||||
uint32_t n = _writebuf.available();
|
uint32_t max_size = MIN(PKT_MAX_REGS * 2,
|
||||||
|
_baudrate / 10 / (1000000 / RPIOUART_POLL_TIME_INTERVAL));
|
||||||
if (n > PKT_MAX_REGS * 2) {
|
uint32_t n = MIN(_writebuf.available(), max_size);
|
||||||
n = PKT_MAX_REGS * 2;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t _max_size = _baudrate / 10 / (1000000 / RPIOUART_POLL_TIME_INTERVAL);
|
|
||||||
if (n > _max_size) {
|
|
||||||
n = _max_size;
|
|
||||||
}
|
|
||||||
|
|
||||||
_writebuf.read(&((uint8_t *)_dma_packet_tx.regs)[0], n);
|
_writebuf.read(&((uint8_t *)_dma_packet_tx.regs)[0], n);
|
||||||
|
|
||||||
_dma_packet_tx.count_code = PKT_MAX_REGS | PKT_CODE_SPIUART;
|
_dma_packet_tx.count_code = PKT_MAX_REGS | PKT_CODE_SPIUART;
|
||||||
_dma_packet_tx.page = PX4IO_PAGE_UART_BUFFER;
|
_dma_packet_tx.page = PX4IO_PAGE_UART_BUFFER;
|
||||||
_dma_packet_tx.offset = n;
|
_dma_packet_tx.offset = n;
|
||||||
@ -203,18 +196,10 @@ void RPIOUARTDriver::_timer_tick(void)
|
|||||||
/* release sem */
|
/* release sem */
|
||||||
_dev->get_semaphore()->give();
|
_dev->get_semaphore()->give();
|
||||||
|
|
||||||
/* add bytes to read buf */
|
|
||||||
n = _readbuf.space();
|
|
||||||
|
|
||||||
if (_dma_packet_rx.page == PX4IO_PAGE_UART_BUFFER) {
|
if (_dma_packet_rx.page == PX4IO_PAGE_UART_BUFFER) {
|
||||||
|
/* add bytes to read buf */
|
||||||
if (n > _dma_packet_rx.offset) {
|
max_size = MIN(_dma_packet_rx.offset, PKT_MAX_REGS * 2);
|
||||||
n = _dma_packet_rx.offset;
|
n = MIN(_readbuf.space(), max_size);
|
||||||
}
|
|
||||||
|
|
||||||
if (n > PKT_MAX_REGS * 2) {
|
|
||||||
n = PKT_MAX_REGS * 2;
|
|
||||||
}
|
|
||||||
|
|
||||||
_readbuf.write(&((uint8_t *)_dma_packet_rx.regs)[0], n);
|
_readbuf.write(&((uint8_t *)_dma_packet_rx.regs)[0], n);
|
||||||
}
|
}
|
||||||
|
@ -5,6 +5,7 @@
|
|||||||
#include <cstdio>
|
#include <cstdio>
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
@ -123,9 +124,7 @@ int SPIUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
|
|||||||
* doesn't like to be waiting. Making transactions more frequent but shorter
|
* doesn't like to be waiting. Making transactions more frequent but shorter
|
||||||
* is a win.
|
* is a win.
|
||||||
*/
|
*/
|
||||||
if (n > 100) {
|
n = MIN(n, 100);
|
||||||
n = 100;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!_dev->get_semaphore()->take_nonblocking()) {
|
if (!_dev->get_semaphore()->take_nonblocking()) {
|
||||||
return 0;
|
return 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user