UARTDriver.h 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107
  1. #pragma once
  2. #include <stdint.h>
  3. #include "AP_HAL_Namespace.h"
  4. #include "utility/BetterStream.h"
  5. /* Pure virtual UARTDriver class */
  6. class AP_HAL::UARTDriver : public AP_HAL::BetterStream {
  7. public:
  8. UARTDriver() {}
  9. // begin() implicitly clears rx/tx buffers, even if the port was already open (unless the UART is the console UART)
  10. virtual void begin(uint32_t baud) = 0;
  11. /// Extended port open method
  12. ///
  13. /// Allows for both opening with specified buffer sizes, and re-opening
  14. /// to adjust a subset of the port's settings.
  15. ///
  16. /// @note Buffer sizes greater than ::_max_buffer_size will be rounded
  17. /// down.
  18. ///
  19. /// @param baud Selects the speed that the port will be
  20. /// configured to. If zero, the port speed is left
  21. /// unchanged.
  22. /// @param rxSpace Sets the receive buffer size for the port. If zero
  23. /// then the buffer size is left unchanged if the port
  24. /// is open, or set to ::_default_rx_buffer_size if it is
  25. /// currently closed.
  26. /// @param txSpace Sets the transmit buffer size for the port. If zero
  27. /// then the buffer size is left unchanged if the port
  28. /// is open, or set to ::_default_tx_buffer_size if it
  29. /// is currently closed.
  30. ///
  31. virtual void begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) = 0;
  32. virtual void end() = 0;
  33. virtual void flush() = 0;
  34. virtual bool is_initialized() = 0;
  35. virtual void set_blocking_writes(bool blocking) = 0;
  36. virtual bool tx_pending() = 0;
  37. // lock a port for exclusive use. Use a key of 0 to unlock
  38. virtual bool lock_port(uint32_t write_key, uint32_t read_key) { return false; }
  39. // write to a locked port. If port is locked and key is not correct then 0 is returned
  40. // and write is discarded
  41. virtual size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) { return 0; }
  42. // read from a locked port. If port is locked and key is not correct then 0 is returned
  43. virtual int16_t read_locked(uint32_t key) { return -1; }
  44. // control optional features
  45. virtual bool set_options(uint8_t options) { return options==0; }
  46. virtual uint8_t get_options(void) const { return 0; }
  47. enum {
  48. OPTION_RXINV=(1U<<0), // invert RX line
  49. OPTION_TXINV=(1U<<1), // invert TX line
  50. OPTION_HDPLEX=(1U<<2), // half-duplex (one-wire) mode
  51. OPTION_SWAP=(1U<<3), // swap RX and TX pins
  52. };
  53. enum flow_control {
  54. FLOW_CONTROL_DISABLE=0, FLOW_CONTROL_ENABLE=1, FLOW_CONTROL_AUTO=2
  55. };
  56. virtual void set_flow_control(enum flow_control flow_control_setting) {};
  57. virtual enum flow_control get_flow_control(void) { return FLOW_CONTROL_DISABLE; }
  58. virtual void configure_parity(uint8_t v){};
  59. virtual void set_stop_bits(int n){};
  60. /* unbuffered writes bypass the ringbuffer and go straight to the
  61. * file descriptor
  62. */
  63. virtual bool set_unbuffered_writes(bool on){ return false; };
  64. /*
  65. wait for at least n bytes of incoming data, with timeout in
  66. milliseconds. Return true if n bytes are available, false if
  67. timeout
  68. */
  69. virtual bool wait_timeout(uint16_t n, uint32_t timeout_ms) { return false; }
  70. /*
  71. * Optional method to control the update of the motors. Derived classes
  72. * can implement it if their HAL layer requires.
  73. */
  74. virtual void _timer_tick(void) { }
  75. /*
  76. return timestamp estimate in microseconds for when the start of
  77. a nbytes packet arrived on the uart. This should be treated as a
  78. time constraint, not an exact time. It is guaranteed that the
  79. packet did not start being received after this time, but it
  80. could have been in a system buffer before the returned time.
  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. A return value of zero means the HAL does not support this API
  85. */
  86. virtual uint64_t receive_time_constraint_us(uint16_t nbytes) { return 0; }
  87. virtual uint32_t bw_in_kilobytes_per_second() const {
  88. return 57;
  89. }
  90. };