APM:Libraries
|
#include <UARTDriver.h>
Public Member Functions | |
VRBRAINUARTDriver (const char *devpath, const char *perf_name) | |
void | begin (uint32_t b) |
void | begin (uint32_t b, uint16_t rxS, uint16_t txS) |
void | end () |
void | flush () |
bool | is_initialized () |
void | set_blocking_writes (bool blocking) |
bool | tx_pending () |
uint32_t | available () override |
uint32_t | txspace () override |
int16_t | read () override |
size_t | write (uint8_t c) |
size_t | write (const uint8_t *buffer, size_t size) |
void | set_device_path (const char *path) |
void | _timer_tick (void) |
int | _get_fd (void) |
void | set_flow_control (enum flow_control flow_control) |
enum flow_control | get_flow_control (void) |
void | configure_parity (uint8_t v) |
void | set_stop_bits (int n) |
bool | set_unbuffered_writes (bool on) |
Public Member Functions inherited from AP_HAL::UARTDriver | |
UARTDriver () | |
virtual bool | lock_port (uint32_t key) |
virtual size_t | write_locked (const uint8_t *buffer, size_t size, uint32_t key) |
virtual void | set_flow_control (enum flow_control flow_control_setting) |
virtual bool | wait_timeout (uint16_t n, uint32_t timeout_ms) |
virtual uint64_t | receive_time_constraint_us (uint16_t nbytes) |
Public Member Functions inherited from AP_HAL::BetterStream | |
virtual void | printf (const char *,...) FMT_PRINTF(2 |
virtual void virtual void | vprintf (const char *, va_list) |
void | print (const char *str) |
void | println (const char *str) |
size_t | write (const char *str) |
Private Member Functions | |
int | _write_fd (const uint8_t *buf, uint16_t n) |
int | _read_fd (uint8_t *buf, uint16_t n) |
void | try_initialise (void) |
Private Attributes | |
const char * | _devpath |
int | _fd |
uint32_t | _baudrate |
volatile bool | _initialised |
volatile bool | _in_timer |
bool | _nonblocking_writes |
bool | _unbuffered_writes |
ByteBuffer | _readbuf {0} |
ByteBuffer | _writebuf {0} |
perf_counter_t | _perf_uart |
uint64_t | _first_write_time |
uint64_t | _last_write_time |
uint32_t | _last_initialise_attempt_ms |
uint32_t | _os_start_auto_space |
uint32_t | _total_read |
uint32_t | _total_written |
enum flow_control | _flow_control |
Semaphore | _semaphore |
Additional Inherited Members | |
Public Types inherited from AP_HAL::UARTDriver | |
enum | flow_control { FLOW_CONTROL_DISABLE =0, FLOW_CONTROL_ENABLE =1, FLOW_CONTROL_AUTO =2 } |
Definition at line 9 of file UARTDriver.h.
VRBRAINUARTDriver::VRBRAINUARTDriver | ( | const char * | devpath, |
const char * | perf_name | ||
) |
Definition at line 23 of file UARTDriver.cpp.
|
inline |
Definition at line 36 of file UARTDriver.h.
Referenced by VRBRAIN::VRBRAINUtil::run_debug_shell().
|
private |
Definition at line 443 of file UARTDriver.cpp.
Referenced by _timer_tick().
|
virtual |
Reimplemented from AP_HAL::UARTDriver.
Definition at line 470 of file UARTDriver.cpp.
Referenced by set_device_path().
|
private |
Definition at line 375 of file UARTDriver.cpp.
Referenced by _timer_tick(), and write().
|
overridevirtual |
Implements AP_HAL::BetterStream.
Definition at line 252 of file UARTDriver.cpp.
|
virtual |
Implements AP_HAL::UARTDriver.
Definition at line 194 of file UARTDriver.cpp.
Referenced by try_initialise().
|
virtual |
Extended port open method
Allows for both opening with specified buffer sizes, and re-opening to adjust a subset of the port's settings.
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 43 of file UARTDriver.cpp.
|
virtual |
Reimplemented from AP_HAL::UARTDriver.
Definition at line 156 of file UARTDriver.cpp.
Referenced by get_flow_control().
|
virtual |
Implements AP_HAL::UARTDriver.
Definition at line 221 of file UARTDriver.cpp.
|
virtual |
Implements AP_HAL::UARTDriver.
Definition at line 234 of file UARTDriver.cpp.
|
inlinevirtual |
Reimplemented from AP_HAL::UARTDriver.
Definition at line 41 of file UARTDriver.h.
|
virtual |
Implements AP_HAL::UARTDriver.
Definition at line 236 of file UARTDriver.cpp.
|
overridevirtual |
Implements AP_HAL::BetterStream.
Definition at line 278 of file UARTDriver.cpp.
Referenced by _read_fd().
|
virtual |
Implements AP_HAL::UARTDriver.
Definition at line 242 of file UARTDriver.cpp.
|
inline |
Definition at line 30 of file UARTDriver.h.
Referenced by HAL_VRBRAIN::run().
void VRBRAINUARTDriver::set_flow_control | ( | enum flow_control flow_control | ) |
Definition at line 134 of file UARTDriver.cpp.
Referenced by _get_fd(), and _write_fd().
|
virtual |
Reimplemented from AP_HAL::UARTDriver.
Definition at line 178 of file UARTDriver.cpp.
Referenced by get_flow_control().
|
virtual |
Reimplemented from AP_HAL::UARTDriver.
Definition at line 189 of file UARTDriver.cpp.
Referenced by get_flow_control().
|
private |
Definition at line 206 of file UARTDriver.cpp.
Referenced by available(), is_initialized(), read(), txspace(), and write().
|
virtual |
Implements AP_HAL::UARTDriver.
Definition at line 247 of file UARTDriver.cpp.
|
overridevirtual |
Implements AP_HAL::BetterStream.
Definition at line 265 of file UARTDriver.cpp.
|
virtual |
Implements AP_HAL::BetterStream.
Definition at line 302 of file UARTDriver.cpp.
Referenced by _write_fd(), and write().
|
virtual |
Reimplemented from AP_HAL::BetterStream.
Definition at line 337 of file UARTDriver.cpp.
|
private |
Definition at line 50 of file UARTDriver.h.
Referenced by begin().
|
private |
Definition at line 48 of file UARTDriver.h.
Referenced by _timer_tick(), _write_fd(), begin(), and set_device_path().
|
private |
Definition at line 49 of file UARTDriver.h.
Referenced by _get_fd(), _read_fd(), _write_fd(), begin(), configure_parity(), end(), set_flow_control(), and set_stop_bits().
|
private |
Definition at line 65 of file UARTDriver.h.
Referenced by _write_fd(), and set_flow_control().
|
private |
Definition at line 74 of file UARTDriver.h.
Referenced by _write_fd(), get_flow_control(), and set_flow_control().
|
private |
Definition at line 52 of file UARTDriver.h.
Referenced by _timer_tick(), begin(), and end().
|
private |
Definition at line 51 of file UARTDriver.h.
Referenced by _timer_tick(), available(), begin(), end(), is_initialized(), read(), try_initialise(), txspace(), and write().
|
private |
Definition at line 69 of file UARTDriver.h.
Referenced by try_initialise().
|
private |
Definition at line 66 of file UARTDriver.h.
Referenced by _write_fd().
|
private |
Definition at line 54 of file UARTDriver.h.
Referenced by set_blocking_writes(), and write().
|
private |
Definition at line 71 of file UARTDriver.h.
Referenced by _write_fd().
|
private |
Definition at line 61 of file UARTDriver.h.
Referenced by _timer_tick().
|
private |
Definition at line 59 of file UARTDriver.h.
Referenced by _timer_tick(), available(), begin(), end(), and read().
|
private |
Definition at line 76 of file UARTDriver.h.
|
private |
Definition at line 72 of file UARTDriver.h.
Referenced by _read_fd().
|
private |
Definition at line 73 of file UARTDriver.h.
Referenced by _write_fd(), and set_flow_control().
|
private |
Definition at line 55 of file UARTDriver.h.
Referenced by set_unbuffered_writes(), and write().
|
private |
Definition at line 60 of file UARTDriver.h.
Referenced by _timer_tick(), begin(), end(), txspace(), and write().