APM:Libraries
UARTDriver.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <stdint.h>
4 
5 #include "AP_HAL_Namespace.h"
6 #include "utility/BetterStream.h"
7 
8 /* Pure virtual UARTDriver class */
10 public:
12  virtual void begin(uint32_t baud) = 0;
33  virtual void begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) = 0;
34  virtual void end() = 0;
35  virtual void flush() = 0;
36  virtual bool is_initialized() = 0;
37  virtual void set_blocking_writes(bool blocking) = 0;
38  virtual bool tx_pending() = 0;
39 
40  // lock a port for exclusive use. Use a key of 0 to unlock
41  virtual bool lock_port(uint32_t key) { return false; }
42 
43  // write to a locked port. If port is locked and key is not correct then 0 is returned
44  // and write is discarded
45  virtual size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) { return 0; }
46 
47  enum flow_control {
49  };
50  virtual void set_flow_control(enum flow_control flow_control_setting) {};
51  virtual enum flow_control get_flow_control(void) { return FLOW_CONTROL_DISABLE; }
52 
53  virtual void configure_parity(uint8_t v){};
54  virtual void set_stop_bits(int n){};
55 
56  /* unbuffered writes bypass the ringbuffer and go straight to the
57  * file descriptor
58  */
59  virtual bool set_unbuffered_writes(bool on){ return false; };
60 
61  /*
62  wait for at least n bytes of incoming data, with timeout in
63  milliseconds. Return true if n bytes are available, false if
64  timeout
65  */
66  virtual bool wait_timeout(uint16_t n, uint32_t timeout_ms) { return false; }
67 
68  /*
69  * Optional method to control the update of the motors. Derived classes
70  * can implement it if their HAL layer requires.
71  */
72  virtual void _timer_tick(void) { }
73 
74  /*
75  return timestamp estimate in microseconds for when the start of
76  a nbytes packet arrived on the uart. This should be treated as a
77  time constraint, not an exact time. It is guaranteed that the
78  packet did not start being received after this time, but it
79  could have been in a system buffer before the returned time.
80 
81  This takes account of the baudrate of the link. For transports
82  that have no baudrate (such as USB) the time estimate may be
83  less accurate.
84 
85  A return value of zero means the HAL does not support this API
86  */
87  virtual uint64_t receive_time_constraint_us(uint16_t nbytes) { return 0; }
88 };
virtual void set_blocking_writes(bool blocking)=0
virtual bool tx_pending()=0
virtual bool set_unbuffered_writes(bool on)
Definition: UARTDriver.h:59
#define on
Definition: Config.h:51
virtual void begin(uint32_t baud)=0
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
virtual bool is_initialized()=0
virtual void configure_parity(uint8_t v)
Definition: UARTDriver.h:53
virtual void _timer_tick(void)
Definition: UARTDriver.h:72
virtual void set_stop_bits(int n)
Definition: UARTDriver.h:54
virtual bool lock_port(uint32_t key)
Definition: UARTDriver.h:41
virtual size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key)
Definition: UARTDriver.h:45
virtual void flush()=0
virtual void set_flow_control(enum flow_control flow_control_setting)
Definition: UARTDriver.h:50
virtual void end()=0
float v
Definition: Printf.cpp:15
virtual bool wait_timeout(uint16_t n, uint32_t timeout_ms)
Definition: UARTDriver.h:66
virtual uint64_t receive_time_constraint_us(uint16_t nbytes)
Definition: UARTDriver.h:87
virtual enum flow_control get_flow_control(void)
Definition: UARTDriver.h:51