#include <UART_OSD.h>
Definition at line 16 of file UART_OSD.h.
◆ UART_OSD()
F4Light::UART_OSD::UART_OSD |
( |
| ) |
|
◆ available()
uint32_t F4Light::UART_OSD::available |
( |
| ) |
|
|
overridevirtual |
◆ begin() [1/2]
void F4Light::UART_OSD::begin |
( |
uint32_t |
b | ) |
|
|
virtual |
◆ begin() [2/2]
void F4Light::UART_OSD::begin |
( |
uint32_t |
baud, |
|
|
uint16_t |
rxSpace, |
|
|
uint16_t |
txSpace |
|
) |
| |
|
inlinevirtual |
Extended port open method
Allows for both opening with specified buffer sizes, and re-opening to adjust a subset of the port's settings.
- Note
- Buffer sizes greater than ::_max_buffer_size will be rounded down.
- Parameters
-
baud | Selects the speed that the port will be configured to. If zero, the port speed is left unchanged. |
rxSpace | Sets the receive buffer size for the port. If zero then the buffer size is left unchanged if the port is open, or set to ::_default_rx_buffer_size if it is currently closed. |
txSpace | Sets the transmit buffer size for the port. If zero then the buffer size is left unchanged if the port is open, or set to ::_default_tx_buffer_size if it is currently closed. |
Implements AP_HAL::UARTDriver.
Definition at line 21 of file UART_OSD.h.
Referenced by begin().
◆ end()
void F4Light::UART_OSD::end |
( |
| ) |
|
|
inlinevirtual |
◆ flush()
void F4Light::UART_OSD::flush |
( |
void |
| ) |
|
|
inlinevirtual |
◆ is_initialized()
bool F4Light::UART_OSD::is_initialized |
( |
| ) |
|
|
inlinevirtual |
◆ read()
int16_t F4Light::UART_OSD::read |
( |
| ) |
|
|
overridevirtual |
◆ set_blocking_writes()
void F4Light::UART_OSD::set_blocking_writes |
( |
bool |
blocking | ) |
|
|
inlinevirtual |
◆ tx_pending()
bool F4Light::UART_OSD::tx_pending |
( |
| ) |
|
|
inlinevirtual |
◆ txspace()
uint32_t F4Light::UART_OSD::txspace |
( |
| ) |
|
|
overridevirtual |
◆ write() [1/2]
size_t F4Light::UART_OSD::write |
( |
uint8_t |
c | ) |
|
|
virtual |
◆ write() [2/2]
size_t F4Light::UART_OSD::write |
( |
const uint8_t * |
buffer, |
|
|
size_t |
size |
|
) |
| |
|
virtual |
◆ _blocking
bool F4Light::UART_OSD::_blocking |
|
private |
◆ _initialized
bool F4Light::UART_OSD::_initialized |
|
private |
The documentation for this class was generated from the following file: