APM:Libraries
UARTDevice.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "SerialDevice.h"
5 
6 class UARTDevice: public SerialDevice {
7 public:
8  UARTDevice(const char *device_path);
9  virtual ~UARTDevice();
10 
11  virtual bool open() override;
12  virtual bool close() override;
13  virtual ssize_t write(const uint8_t *buf, uint16_t n) override;
14  virtual ssize_t read(uint8_t *buf, uint16_t n) override;
15  virtual void set_blocking(bool blocking) override;
16  virtual void set_speed(uint32_t speed) override;
17  virtual void set_flow_control(enum AP_HAL::UARTDriver::flow_control flow_control_setting) override;
19  {
20  return _flow_control;
21  }
22 
23 private:
24  void _disable_crlf();
25  AP_HAL::UARTDriver::flow_control _flow_control = AP_HAL::UARTDriver::flow_control::FLOW_CONTROL_DISABLE;
26 
27  int _fd = -1;
28  const char *_device_path;
29 };
virtual void set_speed(uint32_t speed) override
Definition: UARTDevice.cpp:103
AP_HAL::UARTDriver::flow_control _flow_control
Definition: UARTDevice.h:25
virtual ssize_t read(uint8_t *buf, uint16_t n) override
Definition: UARTDevice.cpp:49
virtual AP_HAL::UARTDriver::flow_control get_flow_control(void) override
Definition: UARTDevice.h:18
virtual void set_blocking(bool blocking) override
Definition: UARTDevice.cpp:70
virtual ssize_t write(const uint8_t *buf, uint16_t n) override
Definition: UARTDevice.cpp:54
void _disable_crlf()
Definition: UARTDevice.cpp:87
const char * _device_path
Definition: UARTDevice.h:28
virtual void set_flow_control(enum AP_HAL::UARTDriver::flow_control flow_control_setting) override
Definition: UARTDevice.cpp:113
UARTDevice(const char *device_path)
Definition: UARTDevice.cpp:12
virtual bool close() override
Definition: UARTDevice.cpp:21
virtual ~UARTDevice()
Definition: UARTDevice.cpp:17
virtual bool open() override
Definition: UARTDevice.cpp:34