SerialDevice.h 822 B

1234567891011121314151617181920212223242526
  1. #pragma once
  2. #include <stdint.h>
  3. #include <stdlib.h>
  4. #include "AP_HAL_Linux.h"
  5. class SerialDevice {
  6. public:
  7. virtual ~SerialDevice() {}
  8. virtual bool open() = 0;
  9. virtual bool close() = 0;
  10. virtual ssize_t write(const uint8_t *buf, uint16_t n) = 0;
  11. virtual ssize_t read(uint8_t *buf, uint16_t n) = 0;
  12. virtual void set_blocking(bool blocking) = 0;
  13. virtual void set_speed(uint32_t speed) = 0;
  14. virtual AP_HAL::UARTDriver::flow_control get_flow_control(void) { return AP_HAL::UARTDriver::FLOW_CONTROL_ENABLE; }
  15. virtual void set_flow_control(AP_HAL::UARTDriver::flow_control flow_control_setting)
  16. {
  17. /* most devices simply ignore this setting */
  18. };
  19. /* Depends on lower level to implement, most devices are fine with defaults */
  20. virtual void set_parity(int v) { }
  21. };