APM:Libraries
UARTDriver.h
Go to the documentation of this file.
1 #pragma once
2 
4 
5 #include "AP_HAL_VRBRAIN.h"
6 #include <systemlib/perf_counter.h>
7 #include "Semaphores.h"
8 
10 public:
11  VRBRAINUARTDriver(const char *devpath, const char *perf_name);
12  /* VRBRAIN implementations of UARTDriver virtual methods */
13  void begin(uint32_t b);
14  void begin(uint32_t b, uint16_t rxS, uint16_t txS);
15  void end();
16  void flush();
17  bool is_initialized();
18  void set_blocking_writes(bool blocking);
19  bool tx_pending();
20 
21  /* VRBRAIN implementations of Stream virtual methods */
22  uint32_t available() override;
23  uint32_t txspace() override;
24  int16_t read() override;
25 
26  /* VRBRAIN implementations of Print virtual methods */
27  size_t write(uint8_t c);
28  size_t write(const uint8_t *buffer, size_t size);
29 
30  void set_device_path(const char *path) {
31  _devpath = path;
32  }
33 
34  void _timer_tick(void);
35 
36  int _get_fd(void) {
37  return _fd;
38  }
39 
41  enum flow_control get_flow_control(void) { return _flow_control; }
42 
43  void configure_parity(uint8_t v);
44  void set_stop_bits(int n);
45  bool set_unbuffered_writes(bool on);
46 
47 private:
48  const char *_devpath;
49  int _fd;
50  uint32_t _baudrate;
51  volatile bool _initialised;
52  volatile bool _in_timer;
53 
56 
57  // we use in-task ring buffers to reduce the system call cost
58  // of ::read() and ::write() in the main loop
61  perf_counter_t _perf_uart;
62 
63  int _write_fd(const uint8_t *buf, uint16_t n);
64  int _read_fd(uint8_t *buf, uint16_t n);
66  uint64_t _last_write_time;
67 
68  void try_initialise(void);
70 
72  uint32_t _total_read;
73  uint32_t _total_written;
74  enum flow_control _flow_control;
75 
77 };
perf_counter_t _perf_uart
Definition: UARTDriver.h:61
enum flow_control get_flow_control(void)
Definition: UARTDriver.h:41
#define on
Definition: Config.h:51
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
int _write_fd(const uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:375
size_t write(uint8_t c)
Definition: UARTDriver.cpp:302
VRBRAINUARTDriver(const char *devpath, const char *perf_name)
Definition: UARTDriver.cpp:23
void set_blocking_writes(bool blocking)
Definition: UARTDriver.cpp:242
volatile bool _initialised
Definition: UARTDriver.h:51
int16_t read() override
Definition: UARTDriver.cpp:278
uint32_t available() override
Definition: UARTDriver.cpp:252
float v
Definition: Printf.cpp:15
uint32_t _last_initialise_attempt_ms
Definition: UARTDriver.h:69
uint32_t txspace() override
Definition: UARTDriver.cpp:265
void begin(uint32_t b)
Definition: UARTDriver.cpp:194
bool set_unbuffered_writes(bool on)
Definition: UARTDriver.cpp:189
void set_flow_control(enum flow_control flow_control)
Definition: UARTDriver.cpp:134
int _read_fd(uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:443
void set_device_path(const char *path)
Definition: UARTDriver.h:30
volatile bool _in_timer
Definition: UARTDriver.h:52
enum flow_control _flow_control
Definition: UARTDriver.h:74
void configure_parity(uint8_t v)
Definition: UARTDriver.cpp:156