APM:Libraries
UARTDriver.h
Go to the documentation of this file.
1 #pragma once
2 
5 
6 #include "AP_HAL_Linux.h"
7 #include "SerialDevice.h"
8 
9 namespace Linux {
10 
12 public:
13  UARTDriver(bool default_console);
14 
16  return static_cast<UARTDriver*>(uart);
17  }
18 
19  /* Linux implementations of UARTDriver virtual methods */
20  void begin(uint32_t b);
21  void begin(uint32_t b, uint16_t rxS, uint16_t txS);
22  void end();
23  void flush();
24  bool is_initialized();
25  void set_blocking_writes(bool blocking);
26  bool tx_pending();
27 
28  /* Linux implementations of Stream virtual methods */
29  uint32_t available() override;
30  uint32_t txspace() override;
31  int16_t read() override;
32 
33  /* Linux implementations of Print virtual methods */
34  size_t write(uint8_t c);
35  size_t write(const uint8_t *buffer, size_t size);
36 
37  void set_device_path(const char *path);
38 
39  bool _write_pending_bytes(void);
40  virtual void _timer_tick(void) override;
41 
42  virtual enum flow_control get_flow_control(void) override
43  {
44  return _device->get_flow_control();
45  }
46 
47  virtual void set_flow_control(enum flow_control flow_control_setting) override
48  {
49  _device->set_flow_control(flow_control_setting);
50  }
51 
52  /*
53  return timestamp estimate in microseconds for when the start of
54  a nbytes packet arrived on the uart. This should be treated as a
55  time constraint, not an exact time. It is guaranteed that the
56  packet did not start being received after this time, but it
57  could have been in a system buffer before the returned time.
58 
59  This takes account of the baudrate of the link. For transports
60  that have no baudrate (such as USB) the time estimate may be
61  less accurate.
62 
63  A return value of zero means the HAL does not support this API
64  */
65  uint64_t receive_time_constraint_us(uint16_t nbytes) override;
66 
67 private:
70  bool _console;
71  volatile bool _in_timer;
72  uint16_t _base_port;
73  uint32_t _baudrate;
74  char *_ip;
75  char *_flag;
76  bool _connected; // true if a client has connected
77  bool _packetise; // true if writes should try to be on mavlink boundaries
78 
79  void _allocate_buffers(uint16_t rxS, uint16_t txS);
80  void _deallocate_buffers();
81 
83  uint64_t _last_write_time;
84 
85  // timestamp for receiving data on the UART, avoiding a lock
86  uint64_t _receive_timestamp[2];
88 
89 protected:
90  const char *device_path;
91  volatile bool _initialised;
92 
93  // we use in-task ring buffers to reduce the system call cost
94  // of ::read() and ::write() in the main loop
97 
98  virtual int _write_fd(const uint8_t *buf, uint16_t n);
99  virtual int _read_fd(uint8_t *buf, uint16_t n);
100 };
101 
102 }
uint64_t _last_write_time
Definition: UARTDriver.h:83
size_t write(uint8_t c)
uint32_t _baudrate
Definition: UARTDriver.h:73
AP_HAL::OwnPtr< SerialDevice > _parseDevicePath(const char *arg)
Definition: UARTDriver.cpp:125
void set_blocking_writes(bool blocking)
static UARTDriver * from(AP_HAL::UARTDriver *uart)
Definition: UARTDriver.h:15
void begin(uint32_t b)
volatile bool _in_timer
Definition: UARTDriver.h:71
uint16_t _base_port
Definition: UARTDriver.h:72
bool _write_pending_bytes(void)
Definition: UARTDriver.cpp:353
virtual void set_flow_control(enum flow_control flow_control_setting) override
Definition: UARTDriver.h:47
ByteBuffer _writebuf
Definition: UARTDriver.h:96
void _allocate_buffers(uint16_t rxS, uint16_t txS)
Definition: UARTDriver.cpp:94
const char * device_path
Definition: UARTDriver.h:90
uint8_t _receive_timestamp_idx
Definition: UARTDriver.h:87
virtual void _timer_tick(void) override
void set_device_path(const char *path)
Definition: UARTDriver.cpp:46
uint64_t _receive_timestamp[2]
Definition: UARTDriver.h:86
bool _nonblocking_writes
Definition: UARTDriver.h:69
virtual AP_HAL::UARTDriver::flow_control get_flow_control(void)
Definition: SerialDevice.h:18
uint64_t receive_time_constraint_us(uint16_t nbytes) override
virtual void set_flow_control(AP_HAL::UARTDriver::flow_control flow_control_setting)
Definition: SerialDevice.h:19
volatile bool _initialised
Definition: UARTDriver.h:91
uint32_t txspace() override
uint32_t available() override
virtual int _write_fd(const uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:324
virtual int _read_fd(uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:343
AP_HAL::OwnPtr< SerialDevice > _device
Definition: UARTDriver.h:68
int16_t read() override
void _deallocate_buffers()
Definition: UARTDriver.cpp:113
virtual enum flow_control get_flow_control(void) override
Definition: UARTDriver.h:42
ByteBuffer _readbuf
Definition: UARTDriver.h:95