APM:Libraries
UARTDriver.h
Go to the documentation of this file.
1 #pragma once
2 
4 
5 #include "AP_HAL_PX4.h"
6 #include <systemlib/perf_counter.h>
7 #include "Semaphores.h"
8 
10 public:
11  PX4UARTDriver(const char *devpath, const char *perf_name);
12  /* PX4 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  /* PX4 implementations of Stream virtual methods */
22  uint32_t available() override;
23  uint32_t txspace() override;
24  int16_t read() override;
25 
26  /* PX4 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) override;
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  /*
48  return timestamp estimate in microseconds for when the start of
49  a nbytes packet arrived on the uart. This should be treated as a
50  time constraint, not an exact time. It is guaranteed that the
51  packet did not start being received after this time, but it
52  could have been in a system buffer before the returned time.
53 
54  This takes account of the baudrate of the link. For transports
55  that have no baudrate (such as USB) the time estimate may be
56  less accurate.
57 
58  A return value of zero means the HAL does not support this API
59  */
60  uint64_t receive_time_constraint_us(uint16_t nbytes) override;
61 
62 private:
63  const char *_devpath;
64  int _fd;
65  uint32_t _baudrate;
66  volatile bool _initialised;
67  volatile bool _in_timer;
68 
71 
72  // we use in-task ring buffers to reduce the system call cost
73  // of ::read() and ::write() in the main loop
76  perf_counter_t _perf_uart;
77 
78  int _write_fd(const uint8_t *buf, uint16_t n);
79  int _read_fd(uint8_t *buf, uint16_t n);
81  uint64_t _last_write_time;
82 
83  void try_initialise(void);
85 
87  uint32_t _total_read;
88  uint32_t _total_written;
89  enum flow_control _flow_control;
90 
91  // timestamp for receiving data on the UART, avoiding a lock
92  uint64_t _receive_timestamp[2];
94 
96 
97  bool _is_usb;
98 };
bool _nonblocking_writes
Definition: UARTDriver.h:69
void configure_parity(uint8_t v)
Definition: UARTDriver.cpp:157
void try_initialise(void)
Definition: UARTDriver.cpp:207
uint32_t available() override
Definition: UARTDriver.cpp:253
uint64_t _receive_timestamp[2]
Definition: UARTDriver.h:92
PX4UARTDriver(const char *devpath, const char *perf_name)
Definition: UARTDriver.cpp:23
ByteBuffer _writebuf
Definition: UARTDriver.h:75
const char * _devpath
Definition: UARTDriver.h:63
#define on
Definition: Config.h:51
bool set_unbuffered_writes(bool on)
Definition: UARTDriver.cpp:190
int16_t read() override
Definition: UARTDriver.cpp:279
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
void set_flow_control(enum flow_control flow_control)
Definition: UARTDriver.cpp:135
uint32_t _total_written
Definition: UARTDriver.h:88
enum flow_control get_flow_control(void)
Definition: UARTDriver.h:41
uint32_t _baudrate
Definition: UARTDriver.h:65
int _read_fd(uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:444
void set_stop_bits(int n)
Definition: UARTDriver.cpp:179
enum flow_control _flow_control
Definition: UARTDriver.h:89
void begin(uint32_t b)
Definition: UARTDriver.cpp:195
uint64_t _last_write_time
Definition: UARTDriver.h:81
perf_counter_t _perf_uart
Definition: UARTDriver.h:76
float v
Definition: Printf.cpp:15
uint32_t txspace() override
Definition: UARTDriver.cpp:266
void set_device_path(const char *path)
Definition: UARTDriver.h:30
uint64_t receive_time_constraint_us(uint16_t nbytes) override
Definition: UARTDriver.cpp:545
volatile bool _in_timer
Definition: UARTDriver.h:67
uint8_t _receive_timestamp_idx
Definition: UARTDriver.h:93
int _write_fd(const uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:376
uint64_t _first_write_time
Definition: UARTDriver.h:80
uint32_t _os_start_auto_space
Definition: UARTDriver.h:86
void set_blocking_writes(bool blocking)
Definition: UARTDriver.cpp:243
uint32_t _last_initialise_attempt_ms
Definition: UARTDriver.h:84
void _timer_tick(void) override
Definition: UARTDriver.cpp:471
uint32_t _total_read
Definition: UARTDriver.h:87
size_t write(uint8_t c)
Definition: UARTDriver.cpp:303
ByteBuffer _readbuf
Definition: UARTDriver.h:74
int _get_fd(void)
Definition: UARTDriver.h:36
Semaphore _semaphore
Definition: UARTDriver.h:95
volatile bool _initialised
Definition: UARTDriver.h:66