APM:Libraries
UARTDriver.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
5 
6 #include <stdint.h>
7 #include <stdarg.h>
11 
13 public:
14  friend class HALSITL::SITL_State;
15 
16  UARTDriver(const uint8_t portNumber, SITL_State *sitlState) {
17  _portNumber = portNumber;
19 
20  _fd = -1;
21  _listen_fd = -1;
22  }
23 
25  return static_cast<UARTDriver*>(uart);
26  }
27 
28  /* Implementations of UARTDriver virtual methods */
29  void begin(uint32_t b) {
30  begin(b, 0, 0);
31  }
32  void begin(uint32_t b, uint16_t rxS, uint16_t txS);
33  void end();
34  void flush();
35  bool is_initialized() {
36  return true;
37  }
38 
39  void set_blocking_writes(bool blocking)
40  {
41  _nonblocking_writes = !blocking;
42  }
43 
44  bool tx_pending() {
45  return false;
46  }
47 
48  /* Implementations of Stream virtual methods */
49  uint32_t available() override;
50  uint32_t txspace() override;
51  int16_t read() override;
52 
53  /* Implementations of Print virtual methods */
54  size_t write(uint8_t c);
55  size_t write(const uint8_t *buffer, size_t size);
56 
57  // file descriptor, exposed so SITL_State::loop_hook() can use it
58  int _fd;
59 
61 
63 
64  void configure_parity(uint8_t v) override;
65  void set_stop_bits(int n) override;
66  bool set_unbuffered_writes(bool on) override;
67 
68  void _timer_tick(void);
69 
70  /*
71  return timestamp estimate in microseconds for when the start of
72  a nbytes packet arrived on the uart. This should be treated as a
73  time constraint, not an exact time. It is guaranteed that the
74  packet did not start being received after this time, but it
75  could have been in a system buffer before the returned time.
76 
77  This takes account of the baudrate of the link. For transports
78  that have no baudrate (such as USB) the time estimate may be
79  less accurate.
80 
81  A return value of zero means the HAL does not support this API
82  */
83  uint64_t receive_time_constraint_us(uint16_t nbytes) override;
84 
85 private:
86  uint8_t _portNumber;
87  bool _connected = false; // true if a client has connected
88  bool _use_send_recv = false;
89  int _listen_fd; // socket we are listening on
91  static bool _console;
95 
96  const char *_uart_path;
97  uint32_t _uart_baudrate;
98 
99  // IPv4 address of target for uartC
100  const char *_tcp_client_addr;
101 
102  void _tcp_start_connection(uint16_t port, bool wait_for_connection);
103  void _uart_start_connection(void);
104  void _check_reconnect();
105  void _tcp_start_client(const char *address, uint16_t port);
106  void _check_connection(void);
107  static bool _select_check(int );
108  static void _set_nonblocking(int );
109  bool set_speed(int speed);
110 
113 };
114 
115 #endif
size_t write(uint8_t c)
static bool _select_check(int)
Definition: UARTDriver.cpp:394
SITL_State * _sitlState
Definition: UARTDriver.h:111
uint32_t _uart_baudrate
Definition: UARTDriver.h:97
void _timer_tick(void)
Definition: UARTDriver.cpp:448
#define on
Definition: Config.h:51
bool set_unbuffered_writes(bool on) override
void _tcp_start_connection(uint16_t port, bool wait_for_connection)
Definition: UARTDriver.cpp:187
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
void _tcp_start_client(const char *address, uint16_t port)
Definition: UARTDriver.cpp:278
ByteBuffer _writebuffer
Definition: UARTDriver.h:94
static bool _console
Definition: UARTDriver.h:91
static void _set_nonblocking(int)
Definition: UARTDriver.cpp:415
bool set_speed(int speed)
Definition: UART_utils.cpp:37
UARTDriver(const uint8_t portNumber, SITL_State *sitlState)
Definition: UARTDriver.h:16
void configure_parity(uint8_t v) override
Definition: UART_utils.cpp:70
uint64_t receive_time_constraint_us(uint16_t nbytes) override
void _check_connection(void)
Definition: UARTDriver.cpp:373
enum flow_control get_flow_control(void)
Definition: UARTDriver.h:62
uint32_t available() override
const char * _uart_path
Definition: UARTDriver.h:96
float v
Definition: Printf.cpp:15
int16_t read() override
const char * _tcp_client_addr
Definition: UARTDriver.h:100
uint32_t txspace() override
static SITL_State sitlState
static UARTDriver * from(AP_HAL::UARTDriver *uart)
Definition: UARTDriver.h:24
uint64_t _receive_timestamp
Definition: UARTDriver.h:112
ByteBuffer _readbuffer
Definition: UARTDriver.h:93
void _uart_start_connection(void)
Definition: UARTDriver.cpp:329
void set_blocking_writes(bool blocking)
Definition: UARTDriver.h:39
void set_stop_bits(int n) override
Definition: UART_utils.cpp:107
void begin(uint32_t b)
Definition: UARTDriver.h:29