APM:Libraries
|
#include <RingBuffer.h>
Classes | |
struct | IoVec |
Public Member Functions | |
ByteBuffer (uint32_t size) | |
~ByteBuffer (void) | |
uint32_t | available (void) const |
void | clear (void) |
uint32_t | space (void) const |
bool | empty (void) const |
uint32_t | write (const uint8_t *data, uint32_t len) |
uint32_t | read (uint8_t *data, uint32_t len) |
bool | read_byte (uint8_t *data) |
bool | update (const uint8_t *data, uint32_t len) |
uint32_t | get_size (void) const |
bool | set_size (uint32_t size) |
bool | advance (uint32_t n) |
const uint8_t * | readptr (uint32_t &available_bytes) |
int16_t | peek (uint32_t ofs) const |
uint32_t | peekbytes (uint8_t *data, uint32_t len) |
uint8_t | peekiovec (IoVec vec[2], uint32_t len) |
uint8_t | reserve (IoVec vec[2], uint32_t len) |
bool | commit (uint32_t len) |
Private Attributes | |
uint8_t * | buf |
uint32_t | size |
std::atomic< uint32_t > | head {0} |
std::atomic< uint32_t > | tail {0} |
Definition at line 9 of file RingBuffer.h.
ByteBuffer::ByteBuffer | ( | uint32_t | size | ) |
Definition at line 6 of file RingBuffer.cpp.
Referenced by ObjectBuffer< GCS_MAVLINK::pending_param_request >::ObjectBuffer().
ByteBuffer::~ByteBuffer | ( | void | ) |
bool ByteBuffer::advance | ( | uint32_t | n | ) |
Definition at line 116 of file RingBuffer.cpp.
Referenced by HALSITL::UARTDriver::_check_reconnect(), PX4::PX4UARTDriver::_timer_tick(), VRBRAIN::VRBRAINUARTDriver::_timer_tick(), Linux::UARTDriver::_write_pending_bytes(), get_size(), read(), read_byte(), ChibiOS::UARTDriver::write_pending_bytes_DMA(), and ChibiOS::UARTDriver::write_pending_bytes_NODMA().
uint32_t ByteBuffer::available | ( | void | ) | const |
Definition at line 37 of file RingBuffer.cpp.
Referenced by Linux::UARTDriver::_parseDevicePath(), PX4::PX4UARTDriver::_timer_tick(), VRBRAIN::VRBRAINUARTDriver::_timer_tick(), ChibiOS::UARTDriver::_timer_tick(), Linux::UARTDriver::_write_pending_bytes(), advance(), PX4::PX4UARTDriver::available(), VRBRAIN::VRBRAINUARTDriver::available(), ChibiOS::UARTDriver::available(), peek(), peekiovec(), ChibiOS::UARTDriver::rxbuff_full_irq(), ChibiOS::UARTDriver::tx_complete(), update(), and ChibiOS::UARTDriver::write_pending_bytes().
void ByteBuffer::clear | ( | void | ) |
Definition at line 49 of file RingBuffer.cpp.
bool ByteBuffer::commit | ( | uint32_t | len | ) |
Definition at line 202 of file RingBuffer.cpp.
Referenced by PX4::PX4UARTDriver::_timer_tick(), VRBRAIN::VRBRAINUARTDriver::_timer_tick(), ChibiOS::UARTDriver::_timer_tick(), HALSITL::UARTDriver::_timer_tick(), and write().
bool ByteBuffer::empty | ( | void | ) | const |
Definition at line 74 of file RingBuffer.cpp.
Referenced by ObjectArray< mavlink_statustext_t >::pop().
|
inline |
Definition at line 42 of file RingBuffer.h.
Referenced by PX4::PX4UARTDriver::begin(), VRBRAIN::VRBRAINUARTDriver::begin(), and ChibiOS::UARTDriver::begin().
int16_t ByteBuffer::peek | ( | uint32_t | ofs | ) | const |
Definition at line 246 of file RingBuffer.cpp.
Referenced by Linux::UARTDriver::_write_pending_bytes(), get_size(), and read_byte().
uint32_t ByteBuffer::peekbytes | ( | uint8_t * | data, |
uint32_t | len | ||
) |
Definition at line 157 of file RingBuffer.cpp.
Referenced by Linux::UARTDriver::_write_pending_bytes(), get_size(), read(), and ChibiOS::UARTDriver::write_pending_bytes_DMA().
uint8_t ByteBuffer::peekiovec | ( | ByteBuffer::IoVec | iovec[2], |
uint32_t | len | ||
) |
Definition at line 125 of file RingBuffer.cpp.
Referenced by PX4::PX4UARTDriver::_timer_tick(), VRBRAIN::VRBRAINUARTDriver::_timer_tick(), Linux::UARTDriver::_write_pending_bytes(), peekbytes(), and ChibiOS::UARTDriver::write_pending_bytes_NODMA().
uint32_t ByteBuffer::read | ( | uint8_t * | data, |
uint32_t | len | ||
) |
Definition at line 212 of file RingBuffer.cpp.
Referenced by consumer_thread().
bool ByteBuffer::read_byte | ( | uint8_t * | data | ) |
Definition at line 219 of file RingBuffer.cpp.
Referenced by Linux::UARTDriver::_parseDevicePath(), VRBRAIN::VRBRAINUARTDriver::read(), PX4::PX4UARTDriver::read(), and ChibiOS::UARTDriver::read().
const uint8_t * ByteBuffer::readptr | ( | uint32_t & | available_bytes | ) |
Definition at line 238 of file RingBuffer.cpp.
Referenced by HALSITL::UARTDriver::_check_reconnect(), get_size(), and peekiovec().
uint8_t ByteBuffer::reserve | ( | ByteBuffer::IoVec | iovec[2], |
uint32_t | len | ||
) |
Definition at line 171 of file RingBuffer.cpp.
Referenced by PX4::PX4UARTDriver::_timer_tick(), VRBRAIN::VRBRAINUARTDriver::_timer_tick(), ChibiOS::UARTDriver::_timer_tick(), HALSITL::UARTDriver::_timer_tick(), and write().
bool ByteBuffer::set_size | ( | uint32_t | size | ) |
Definition at line 20 of file RingBuffer.cpp.
Referenced by Linux::UARTDriver::_allocate_buffers(), Linux::UARTDriver::_deallocate_buffers(), HALSITL::UARTDriver::_uart_start_connection(), Linux::SPIUARTDriver::begin(), VRBRAIN::VRBRAINUARTDriver::begin(), PX4::PX4UARTDriver::begin(), ChibiOS::UARTDriver::begin(), VRBRAIN::VRBRAINUARTDriver::end(), PX4::PX4UARTDriver::end(), ChibiOS::UARTDriver::end(), and get_size().
uint32_t ByteBuffer::space | ( | void | ) | const |
Definition at line 54 of file RingBuffer.cpp.
Referenced by HALSITL::UARTDriver::_check_reconnect(), Linux::UARTDriver::_parseDevicePath(), VRBRAIN::VRBRAINUARTDriver::_timer_tick(), PX4::PX4UARTDriver::_timer_tick(), ChibiOS::UARTDriver::_timer_tick(), HALSITL::UARTDriver::_timer_tick(), commit(), ObjectArray< mavlink_statustext_t >::push(), ObjectArray< mavlink_statustext_t >::push_force(), reserve(), PX4::PX4UARTDriver::txspace(), VRBRAIN::VRBRAINUARTDriver::txspace(), ChibiOS::UARTDriver::txspace(), ChibiOS::UARTDriver::update_rts_line(), VRBRAIN::VRBRAINUARTDriver::write(), PX4::PX4UARTDriver::write(), and ChibiOS::UARTDriver::write().
bool ByteBuffer::update | ( | const uint8_t * | data, |
uint32_t | len | ||
) |
uint32_t ByteBuffer::write | ( | const uint8_t * | data, |
uint32_t | len | ||
) |
Definition at line 79 of file RingBuffer.cpp.
Referenced by HALSITL::UARTDriver::_check_reconnect(), Linux::UARTDriver::_parseDevicePath(), ChibiOS::UARTDriver::_timer_tick(), Linux::SPIUARTDriver::_write_fd(), producer_thread(), ChibiOS::UARTDriver::rxbuff_full_irq(), PX4::PX4UARTDriver::write(), VRBRAIN::VRBRAINUARTDriver::write(), ChibiOS::UARTDriver::write(), and ChibiOS::UARTDriver::write_locked().
|
private |
Definition at line 87 of file RingBuffer.h.
Referenced by ByteBuffer(), peek(), peekiovec(), readptr(), reserve(), set_size(), update(), and ~ByteBuffer().
|
private |
Definition at line 90 of file RingBuffer.h.
Referenced by advance(), available(), clear(), empty(), peek(), readptr(), set_size(), space(), and update().
|
private |
Definition at line 88 of file RingBuffer.h.
Referenced by advance(), available(), ByteBuffer(), commit(), get_size(), peek(), readptr(), reserve(), set_size(), space(), and update().
|
private |
Definition at line 91 of file RingBuffer.h.
Referenced by available(), clear(), commit(), empty(), readptr(), reserve(), set_size(), and space().