2016-02-17 21:25:26 -04:00
|
|
|
#pragma once
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2016-07-07 10:44:05 -03:00
|
|
|
#include <AP_HAL/utility/OwnPtr.h>
|
2016-07-29 21:40:56 -03:00
|
|
|
#include <AP_HAL/utility/RingBuffer.h>
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2016-07-07 10:44:05 -03:00
|
|
|
#include "AP_HAL_Linux.h"
|
2015-06-11 15:30:36 -03:00
|
|
|
#include "SerialDevice.h"
|
|
|
|
|
2016-07-29 16:14:02 -03:00
|
|
|
namespace Linux {
|
|
|
|
|
|
|
|
class UARTDriver : public AP_HAL::UARTDriver {
|
2013-09-22 03:01:24 -03:00
|
|
|
public:
|
2015-10-20 18:13:25 -03:00
|
|
|
UARTDriver(bool default_console);
|
2015-09-13 15:28:02 -03:00
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
static UARTDriver *from(AP_HAL::UARTDriver *uart) {
|
|
|
|
return static_cast<UARTDriver*>(uart);
|
2015-09-13 15:28:02 -03:00
|
|
|
}
|
|
|
|
|
2013-09-22 03:01:24 -03:00
|
|
|
/* Linux implementations of UARTDriver virtual methods */
|
|
|
|
void begin(uint32_t b);
|
|
|
|
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
|
|
|
|
void end();
|
|
|
|
void flush();
|
|
|
|
bool is_initialized();
|
|
|
|
void set_blocking_writes(bool blocking);
|
|
|
|
bool tx_pending();
|
|
|
|
|
|
|
|
/* Linux implementations of Stream virtual methods */
|
2016-08-02 10:42:50 -03:00
|
|
|
uint32_t available() override;
|
|
|
|
uint32_t txspace() override;
|
|
|
|
int16_t read() override;
|
2013-09-22 03:01:24 -03:00
|
|
|
|
|
|
|
/* Linux implementations of Print virtual methods */
|
|
|
|
size_t write(uint8_t c);
|
2013-09-28 21:13:51 -03:00
|
|
|
size_t write(const uint8_t *buffer, size_t size);
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-06-28 15:57:19 -03:00
|
|
|
void set_device_path(const char *path);
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-07-29 01:03:30 -03:00
|
|
|
bool _write_pending_bytes(void);
|
2018-01-21 15:45:31 -04:00
|
|
|
virtual void _timer_tick(void) override;
|
2013-09-28 21:13:51 -03:00
|
|
|
|
2016-07-07 12:46:12 -03:00
|
|
|
virtual enum flow_control get_flow_control(void) override
|
|
|
|
{
|
|
|
|
return _device->get_flow_control();
|
|
|
|
}
|
|
|
|
|
|
|
|
virtual void set_flow_control(enum flow_control flow_control_setting) override
|
|
|
|
{
|
|
|
|
_device->set_flow_control(flow_control_setting);
|
|
|
|
}
|
2014-10-08 22:21:50 -03:00
|
|
|
|
2013-09-22 03:01:24 -03:00
|
|
|
private:
|
2016-07-07 10:44:05 -03:00
|
|
|
AP_HAL::OwnPtr<SerialDevice> _device;
|
2013-09-28 21:13:51 -03:00
|
|
|
bool _nonblocking_writes;
|
2013-09-30 23:49:58 -03:00
|
|
|
bool _console;
|
2013-09-28 21:13:51 -03:00
|
|
|
volatile bool _in_timer;
|
2014-06-11 03:34:07 -03:00
|
|
|
uint16_t _base_port;
|
|
|
|
char *_ip;
|
|
|
|
char *_flag;
|
2016-07-29 16:14:02 -03:00
|
|
|
bool _connected; // true if a client has connected
|
2014-10-06 01:10:48 -03:00
|
|
|
bool _packetise; // true if writes should try to be on mavlink boundaries
|
2014-11-07 06:17:50 -04:00
|
|
|
|
2015-06-11 08:53:52 -03:00
|
|
|
void _allocate_buffers(uint16_t rxS, uint16_t txS);
|
2015-06-11 15:35:48 -03:00
|
|
|
void _deallocate_buffers();
|
2016-07-07 14:57:06 -03:00
|
|
|
|
|
|
|
AP_HAL::OwnPtr<SerialDevice> _parseDevicePath(const char *arg);
|
2016-07-29 16:14:02 -03:00
|
|
|
uint64_t _last_write_time;
|
2013-09-28 21:13:51 -03:00
|
|
|
|
2014-11-07 06:17:50 -04:00
|
|
|
protected:
|
2015-06-28 15:57:19 -03:00
|
|
|
const char *device_path;
|
2014-11-07 06:17:50 -04:00
|
|
|
volatile bool _initialised;
|
2016-07-29 21:40:56 -03:00
|
|
|
|
2013-09-28 21:13:51 -03:00
|
|
|
// we use in-task ring buffers to reduce the system call cost
|
|
|
|
// of ::read() and ::write() in the main loop
|
2016-07-29 21:40:56 -03:00
|
|
|
ByteBuffer _readbuf{0};
|
|
|
|
ByteBuffer _writebuf{0};
|
2013-09-28 21:13:51 -03:00
|
|
|
|
2014-11-07 06:17:50 -04:00
|
|
|
virtual int _write_fd(const uint8_t *buf, uint16_t n);
|
|
|
|
virtual int _read_fd(uint8_t *buf, uint16_t n);
|
2013-09-22 03:01:24 -03:00
|
|
|
};
|
2016-07-29 16:14:02 -03:00
|
|
|
|
|
|
|
}
|