2016-02-17 21:25:26 -04:00
|
|
|
#pragma once
|
2015-06-11 20:19:56 -03:00
|
|
|
|
|
|
|
#include "SerialDevice.h"
|
2023-12-25 22:21:11 -04:00
|
|
|
#include <AP_HAL/utility/Socket_native.h>
|
2015-06-11 20:19:56 -03:00
|
|
|
|
|
|
|
class ConsoleDevice: public SerialDevice {
|
|
|
|
public:
|
|
|
|
ConsoleDevice();
|
|
|
|
virtual ~ConsoleDevice();
|
|
|
|
|
|
|
|
virtual bool open() override;
|
|
|
|
virtual bool close() override;
|
|
|
|
virtual ssize_t write(const uint8_t *buf, uint16_t n) override;
|
|
|
|
virtual ssize_t read(uint8_t *buf, uint16_t n) override;
|
|
|
|
virtual void set_blocking(bool blocking) override;
|
|
|
|
virtual void set_speed(uint32_t speed) override;
|
|
|
|
|
|
|
|
private:
|
|
|
|
int _rd_fd = -1;
|
|
|
|
int _wr_fd = -1;
|
|
|
|
bool _closed = true;
|
2016-07-13 10:56:37 -03:00
|
|
|
|
|
|
|
bool _set_signal_handlers(void) const;
|
2015-06-11 20:19:56 -03:00
|
|
|
};
|