mirror of
https://github.com/wjwwood/serial.git
synced 2026-01-23 04:04:54 +08:00
Adding in my unix implementation. reconfigurePort and read should probably work, but I haven't tested them yet. I am going to work on write later.
This commit is contained in:
parent
c8e7841223
commit
0a6aabe719
@ -1,6 +1,7 @@
|
|||||||
/*!
|
/*!
|
||||||
* \file serial/impl/unix.h
|
* \file serial/impl/unix.h
|
||||||
* \author William Woodall <wjwwood@gmail.com>
|
* \author William Woodall <wjwwood@gmail.com>
|
||||||
|
* \author John Harrison <ash@greaterthaninfinity.com>
|
||||||
* \version 0.1
|
* \version 0.1
|
||||||
*
|
*
|
||||||
* \section LICENSE
|
* \section LICENSE
|
||||||
@ -39,31 +40,43 @@
|
|||||||
|
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
class Serial::Serial_pimpl {
|
using std::string;
|
||||||
public:
|
|
||||||
Serial_pimpl (const std::string &port,
|
|
||||||
int baudrate,
|
|
||||||
long timeout,
|
|
||||||
bytesize_t bytesize,
|
|
||||||
parity_t parity,
|
|
||||||
stopbits_t stopbits,
|
|
||||||
flowcontrol_t flowcontrol);
|
|
||||||
|
|
||||||
virtual ~Serial_pimpl ();
|
class serial::Serial::SerialImpl {
|
||||||
|
public:
|
||||||
|
SerialImpl (const string &port,
|
||||||
|
int baudrate,
|
||||||
|
long timeout,
|
||||||
|
bytesize_t bytesize,
|
||||||
|
parity_t parity,
|
||||||
|
stopbits_t stopbits,
|
||||||
|
flowcontrol_t flowcontrol);
|
||||||
|
|
||||||
|
virtual ~SerialImpl ();
|
||||||
|
|
||||||
void open ();
|
void open ();
|
||||||
void close ();
|
void close ();
|
||||||
bool isOpen ();
|
bool isOpen ();
|
||||||
|
|
||||||
size_t read (unsigned char* buffer, size_t size = 1);
|
size_t available ();
|
||||||
std::string read (size_t size = 1);
|
string read (size_t size = 1);
|
||||||
size_t read (std::string &buffer, size_t size = 1);
|
size_t write (const string &data);
|
||||||
|
|
||||||
size_t write (unsigned char* data, size_t length);
|
void flush ();
|
||||||
size_t write (const std::string &data);
|
void flushInput ();
|
||||||
|
void flushOutput ();
|
||||||
|
|
||||||
void setPort (const std::string &port);
|
void sendBreak();
|
||||||
std::string getPort () const;
|
void setBreak();
|
||||||
|
void setRTS();
|
||||||
|
void setDTR();
|
||||||
|
void getCTS();
|
||||||
|
void getDSR();
|
||||||
|
void getRI();
|
||||||
|
void getCD();
|
||||||
|
|
||||||
|
void setPort (const string &port);
|
||||||
|
string getPort () const;
|
||||||
|
|
||||||
void setTimeout (long timeout);
|
void setTimeout (long timeout);
|
||||||
long getTimeout () const;
|
long getTimeout () const;
|
||||||
@ -83,9 +96,25 @@ public:
|
|||||||
void setFlowcontrol (flowcontrol_t flowcontrol);
|
void setFlowcontrol (flowcontrol_t flowcontrol);
|
||||||
flowcontrol_t getFlowcontrol () const;
|
flowcontrol_t getFlowcontrol () const;
|
||||||
|
|
||||||
private:
|
protected:
|
||||||
int fd;
|
void reconfigurePort ();
|
||||||
|
|
||||||
|
private:
|
||||||
|
int fd_; // The current file descriptor.
|
||||||
|
|
||||||
|
bool isOpen_;
|
||||||
|
|
||||||
|
int interCharTimeout_;
|
||||||
|
int xonxoff_;
|
||||||
|
int rtscts_;
|
||||||
|
|
||||||
|
string port_; // Path to the file descriptor
|
||||||
|
int baudrate_; // Baudrate
|
||||||
|
long timeout_; // Timeout for read operations
|
||||||
|
bytesize_t bytesize_; // Size of the bytes
|
||||||
|
parity_t parity_; // Parity
|
||||||
|
stopbits_t stopbits_; // Stop Bits
|
||||||
|
flowcontrol_t flowcontrol_; // Flow Control
|
||||||
};
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@ -37,6 +37,15 @@
|
|||||||
#ifndef SERIAL_H
|
#ifndef SERIAL_H
|
||||||
#define SERIAL_H
|
#define SERIAL_H
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <sstream>
|
||||||
|
|
||||||
|
#ifdef CXX_11
|
||||||
|
#include <memory>
|
||||||
|
#else
|
||||||
|
// #include <tr1/boost_shared_ptr.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
namespace serial {
|
namespace serial {
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
@ -191,7 +200,7 @@ public:
|
|||||||
* \see Serial::read(size_t)
|
* \see Serial::read(size_t)
|
||||||
*/
|
*/
|
||||||
size_t
|
size_t
|
||||||
read (const std::string &buffer, size_t size = 1);
|
read (std::string &buffer, size_t size = 1);
|
||||||
|
|
||||||
/*! Write bytes from the data to the serial port by given length.
|
/*! Write bytes from the data to the serial port by given length.
|
||||||
*
|
*
|
||||||
@ -367,9 +376,9 @@ private:
|
|||||||
const Serial& operator=(Serial);
|
const Serial& operator=(Serial);
|
||||||
|
|
||||||
// Pimpl idiom, d_pointer
|
// Pimpl idiom, d_pointer
|
||||||
class Serial_pimpl;
|
class SerialImpl;
|
||||||
std::shared_ptr<Serial_pimpl> pimpl;
|
// std::shared_ptr<Serial_pimpl> pimpl;
|
||||||
|
SerialImpl *pimpl;
|
||||||
};
|
};
|
||||||
|
|
||||||
class IOException : public std::exception {
|
class IOException : public std::exception {
|
||||||
|
|||||||
@ -13,7 +13,7 @@ project(Serial)
|
|||||||
# Use clang if available
|
# Use clang if available
|
||||||
IF(EXISTS /usr/bin/clang)
|
IF(EXISTS /usr/bin/clang)
|
||||||
set(CMAKE_CXX_COMPILER /usr/bin/clang++)
|
set(CMAKE_CXX_COMPILER /usr/bin/clang++)
|
||||||
set(CMAKE_CXX_FLAGS -ferror-limit=5)
|
set(CMAKE_CXX_FLAGS "-ferror-limit=5 -std=c++0x -stdlib=libc++")
|
||||||
ENDIF(EXISTS /usr/bin/clang)
|
ENDIF(EXISTS /usr/bin/clang)
|
||||||
|
|
||||||
option(SERIAL_BUILD_TESTS "Build all of the Serial tests." OFF)
|
option(SERIAL_BUILD_TESTS "Build all of the Serial tests." OFF)
|
||||||
@ -39,7 +39,7 @@ ENDIF(NOT DEFINED(LIBRARY_OUTPUT_PATH))
|
|||||||
include_directories(${PROJECT_SOURCE_DIR}/include)
|
include_directories(${PROJECT_SOURCE_DIR}/include)
|
||||||
|
|
||||||
# Add default source files
|
# Add default source files
|
||||||
set(SERIAL_SRCS src/serial.cc src/serial_listener.cc)
|
set(SERIAL_SRCS src/serial.cc src/impl/unix.cc) # src/serial_listener.cc)
|
||||||
# Add default header files
|
# Add default header files
|
||||||
set(SERIAL_HEADERS include/serial/serial.h include/serial/serial_listener.h)
|
set(SERIAL_HEADERS include/serial/serial.h include/serial/serial_listener.h)
|
||||||
|
|
||||||
|
|||||||
318
src/impl/unix.cc
318
src/impl/unix.cc
@ -1,127 +1,329 @@
|
|||||||
|
#include <stdio.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <sys/ioctl.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <paths.h>
|
||||||
|
#include <sysexits.h>
|
||||||
|
#include <termios.h>
|
||||||
|
#include <sys/param.h>
|
||||||
|
#include <sys/select.h>
|
||||||
|
#include <sys/time.h>
|
||||||
|
#include <time.h>
|
||||||
|
|
||||||
#include "serial/impl/unix.h"
|
#include "serial/impl/unix.h"
|
||||||
|
|
||||||
using namespace serial;
|
#ifndef TIOCINQ
|
||||||
|
#ifdef FIONREAD
|
||||||
|
#define TIOCINQ FIONREAD
|
||||||
|
#else
|
||||||
|
#define TIOCINQ 0x541B
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
Serial_pimpl::Serial_pimpl (const std::string &port, int baudrate,
|
using ::serial::Serial;
|
||||||
long timeout, bytesize_t bytesize,
|
using std::string;
|
||||||
parity_t parity, stopbits_t stopbits,
|
|
||||||
flowcontrol_t flowcontrol)
|
Serial::SerialImpl::SerialImpl (const string &port, int baudrate,
|
||||||
: port(port), baudrate(baudrate), timeout(timeout), bytesize(bytesize),
|
long timeout, bytesize_t bytesize,
|
||||||
parity(parity), stopbits(stopbits), flowcontrol(flowcontrol)
|
parity_t parity, stopbits_t stopbits,
|
||||||
|
flowcontrol_t flowcontrol)
|
||||||
|
: fd_(-1), isOpen_(false), interCharTimeout_(-1), port_(port), baudrate_(baudrate),
|
||||||
|
timeout_(timeout), bytesize_(bytesize), parity_(parity), stopbits_(stopbits),
|
||||||
|
flowcontrol_(flowcontrol)
|
||||||
{
|
{
|
||||||
|
if (port_.empty() == false) {
|
||||||
|
this->open();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
Serial_pimpl::~Serial_pimpl () {
|
Serial::SerialImpl::~SerialImpl () {
|
||||||
|
this->close();
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial_pimpl::open () {
|
Serial::SerialImpl::open () {
|
||||||
|
if (port_.empty() == false) {
|
||||||
|
throw "error";
|
||||||
|
}
|
||||||
|
if (isOpen_ == false) {
|
||||||
|
throw "error";
|
||||||
|
}
|
||||||
|
|
||||||
|
fd_ = ::open (port_.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
|
||||||
|
|
||||||
|
if (fd_ == -1) {
|
||||||
|
// printf("Error opening serial port %s - %s(%d).\n",
|
||||||
|
// port.c_str(), strerror(errno), errno);
|
||||||
|
throw "Error"; // Error
|
||||||
|
}
|
||||||
|
|
||||||
|
reconfigurePort();
|
||||||
|
isOpen_ = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial_pimpl::close () {
|
Serial::SerialImpl::reconfigurePort () {
|
||||||
|
if (fd_ == -1) {
|
||||||
|
throw "Error"; // Can only operate on a valid file descriptor
|
||||||
|
}
|
||||||
|
|
||||||
|
struct termios options; // The current options for the file descriptor
|
||||||
|
struct termios originalTTYAttrs; // The orignal file descriptor options
|
||||||
|
|
||||||
|
uint8_t vmin = 0, vtime = 0; // timeout is done via select
|
||||||
|
if (interCharTimeout_ == -1) {
|
||||||
|
vmin = 1;
|
||||||
|
vtime = int(interCharTimeout_ * 10);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (tcgetattr(fd_, &originalTTYAttrs) == -1) {
|
||||||
|
throw "Error";
|
||||||
|
}
|
||||||
|
|
||||||
|
options = originalTTYAttrs;
|
||||||
|
|
||||||
|
// set up raw mode / no echo / binary
|
||||||
|
options.c_cflag |= (CLOCAL|CREAD);
|
||||||
|
options.c_lflag &= ~(ICANON|ECHO|ECHOE|ECHOK|ECHONL|
|
||||||
|
ISIG|IEXTEN); //|ECHOPRT
|
||||||
|
|
||||||
|
options.c_oflag &= ~(OPOST);
|
||||||
|
options.c_iflag &= ~(INLCR|IGNCR|ICRNL|IGNBRK);
|
||||||
|
#ifdef IUCLC
|
||||||
|
options.c_iflag &= ~IUCLC;
|
||||||
|
#endif
|
||||||
|
#ifdef PARMRK
|
||||||
|
options.c_iflag &= ~PARMRK;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// setup baud rate
|
||||||
|
// TODO(ash_git): validate baud rate
|
||||||
|
cfsetspeed(&options, baudrate_);
|
||||||
|
|
||||||
|
// setup char len
|
||||||
|
options.c_cflag &= ~CSIZE;
|
||||||
|
if (bytesize_ == EIGHTBITS)
|
||||||
|
options.c_cflag |= CS8;
|
||||||
|
else if (bytesize_ == SEVENBITS)
|
||||||
|
options.c_cflag |= CS7;
|
||||||
|
else if (bytesize_ == SIXBITS)
|
||||||
|
options.c_cflag |= CS6;
|
||||||
|
else if (bytesize_ == FIVEBITS)
|
||||||
|
options.c_cflag |= CS5;
|
||||||
|
else
|
||||||
|
throw "ValueError(Invalid char len: %%r)";
|
||||||
|
// setup stopbits
|
||||||
|
if (stopbits_ == STOPBITS_ONE)
|
||||||
|
options.c_cflag &= ~(CSTOPB);
|
||||||
|
else if (stopbits_ == STOPBITS_ONE_POINT_FIVE)
|
||||||
|
options.c_cflag |= (CSTOPB); // XXX same as TWO.. there is no POSIX support for 1.5
|
||||||
|
else if (stopbits_ == STOPBITS_TWO)
|
||||||
|
options.c_cflag |= (CSTOPB);
|
||||||
|
else
|
||||||
|
throw "ValueError(Invalid stop bit specification:)";
|
||||||
|
// setup parity
|
||||||
|
options.c_iflag &= ~(INPCK|ISTRIP);
|
||||||
|
if (parity_ == PARITY_NONE) {
|
||||||
|
options.c_cflag &= ~(PARENB|PARODD);
|
||||||
|
}
|
||||||
|
else if (parity_ == PARITY_EVEN) {
|
||||||
|
options.c_cflag &= ~(PARODD);
|
||||||
|
options.c_cflag |= (PARENB);
|
||||||
|
}
|
||||||
|
else if (parity_ == PARITY_ODD) {
|
||||||
|
options.c_cflag |= (PARENB|PARODD);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
throw "ValueError(Invalid parity:";
|
||||||
|
}
|
||||||
|
// setup flow control
|
||||||
|
// xonxoff
|
||||||
|
#ifdef IXANY
|
||||||
|
if (xonxoff_)
|
||||||
|
options.c_iflag |= (IXON|IXOFF); //|IXANY)
|
||||||
|
else
|
||||||
|
options.c_iflag &= ~(IXON|IXOFF|IXANY);
|
||||||
|
#else
|
||||||
|
if (xonxoff_)
|
||||||
|
options.c_iflag |= (IXON|IXOFF);
|
||||||
|
else
|
||||||
|
options.c_iflag &= ~(IXON|IXOFF);
|
||||||
|
#endif
|
||||||
|
// rtscts
|
||||||
|
#ifdef CRTSCTS
|
||||||
|
if (rtscts_)
|
||||||
|
options.c_cflag |= (CRTSCTS);
|
||||||
|
else
|
||||||
|
options.c_cflag &= ~(CRTSCTS);
|
||||||
|
#elif defined CNEW_RTSCTS
|
||||||
|
if (rtscts_)
|
||||||
|
options.c_cflag |= (CNEW_RTSCTS);
|
||||||
|
else
|
||||||
|
options.c_cflag &= ~(CNEW_RTSCTS);
|
||||||
|
#else
|
||||||
|
#error "OS Support seems wrong."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// buffer
|
||||||
|
// vmin "minimal number of characters to be read. = for non blocking"
|
||||||
|
options.c_cc[VMIN] = vmin;
|
||||||
|
// vtime
|
||||||
|
options.c_cc[VTIME] = vtime;
|
||||||
|
|
||||||
|
// activate settings
|
||||||
|
::tcsetattr(fd_, TCSANOW, &options);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::close () {
|
||||||
|
if (isOpen_ == true) {
|
||||||
|
if (fd_ != -1) {
|
||||||
|
::close(fd_);
|
||||||
|
fd_ = -1;
|
||||||
|
}
|
||||||
|
isOpen_ = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
bool
|
bool
|
||||||
Serial_pimpl::isOpen () {
|
Serial::SerialImpl::isOpen () {
|
||||||
|
return isOpen_;
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t
|
size_t
|
||||||
Serial_pimpl::read (unsigned char* buffer, size_t size = 1) {
|
Serial::SerialImpl::available () {
|
||||||
|
if (!isOpen_) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
int count = 0;
|
||||||
|
int result = ioctl(fd_, TIOCINQ, &count);
|
||||||
|
if (result == 0) {
|
||||||
|
return count;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
throw "Error";
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string
|
string
|
||||||
Serial_pimpl::read (size_t size = 1) {
|
Serial::SerialImpl::read (size_t size) {
|
||||||
|
if (!isOpen_) {
|
||||||
|
throw "PortNotOpenError()"; //
|
||||||
|
}
|
||||||
|
string message = "";
|
||||||
|
char buf[1024];
|
||||||
|
fd_set readfds;
|
||||||
|
while (message.length() < size) {
|
||||||
|
FD_ZERO(&readfds);
|
||||||
|
FD_SET(fd_, &readfds);
|
||||||
|
struct timeval timeout;
|
||||||
|
timeout.tv_sec = timeout_ / 1000000;
|
||||||
|
timeout.tv_usec = timeout_ % 1000000;
|
||||||
|
int r = select(1, &readfds, NULL, NULL, &timeout);
|
||||||
|
|
||||||
|
if (r == -1 && errno == EINTR)
|
||||||
|
continue;
|
||||||
|
|
||||||
|
if (r == -1) {
|
||||||
|
perror("select()");
|
||||||
|
exit(EXIT_FAILURE);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (FD_ISSET(fd_, &readfds)) {
|
||||||
|
memset(buf, 0, 1024);
|
||||||
|
size_t bytes_read = ::read(fd_, buf, 1024);
|
||||||
|
// read should always return some data as select reported it was
|
||||||
|
// ready to read when we get to this point.
|
||||||
|
if (bytes_read < 1) {
|
||||||
|
// Disconnected devices, at least on Linux, show the
|
||||||
|
// behavior that they are always ready to read immediately
|
||||||
|
// but reading returns nothing.
|
||||||
|
throw "SerialException('device reports readiness to read but returned no data (device disconnected?)')";
|
||||||
|
}
|
||||||
|
message.append(buf, bytes_read);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
break; // Timeout
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return message;
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t
|
size_t
|
||||||
Serial_pimpl::read (std::string &buffer, size_t size = 1) {
|
Serial::SerialImpl::write (const string &data) {
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
size_t
|
|
||||||
Serial_pimpl::write (unsigned char* data, size_t length) {
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
size_t
|
|
||||||
Serial_pimpl::write (const std::string &data) {
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial_pimpl::setPort (const std::string &port) {
|
Serial::SerialImpl::setPort (const string &port) {
|
||||||
|
port_ = port;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string
|
string
|
||||||
Serial_pimpl::getPort () const {
|
Serial::SerialImpl::getPort () const {
|
||||||
|
return port_;
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial_pimpl::setTimeout (long timeout) {
|
Serial::SerialImpl::setTimeout (long timeout) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
long
|
long
|
||||||
Serial_pimpl::getTimeout () const {
|
Serial::SerialImpl::getTimeout () const {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial_pimpl::setBaudrate (int baudrate) {
|
Serial::SerialImpl::setBaudrate (int baudrate) {
|
||||||
|
baudrate_ = baudrate;
|
||||||
|
reconfigurePort();
|
||||||
}
|
}
|
||||||
|
|
||||||
int
|
int
|
||||||
Serial_pimpl::getBaudrate () const {
|
Serial::SerialImpl::getBaudrate () const {
|
||||||
|
return baudrate_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
Serial::SerialImpl::setBytesize (serial::bytesize_t bytesize) {
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
serial::bytesize_t
|
||||||
|
Serial::SerialImpl::getBytesize () const {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial_pimpl::setBytesize (bytesize_t bytesize) {
|
Serial::SerialImpl::setParity (serial::parity_t parity) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bytesize_t
|
serial::parity_t
|
||||||
Serial_pimpl::getBytesize () const {
|
Serial::SerialImpl::getParity () const {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial_pimpl::setParity (parity_t parity) {
|
Serial::SerialImpl::setStopbits (serial::stopbits_t stopbits) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
parity_t
|
serial::stopbits_t
|
||||||
Serial_pimpl::getParity () const {
|
Serial::SerialImpl::getStopbits () const {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial_pimpl::setStopbits (stopbits_t stopbits) {
|
Serial::SerialImpl::setFlowcontrol (serial::flowcontrol_t flowcontrol) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
stopbits_t
|
serial::flowcontrol_t
|
||||||
Serial_pimpl::getStopbits () const {
|
Serial::SerialImpl::getFlowcontrol () const {
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
Serial_pimpl::setFlowcontrol (flowcontrol_t flowcontrol) {
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
flowcontrol_t
|
|
||||||
Serial_pimpl::getFlowcontrol () const {
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@ -6,127 +6,134 @@
|
|||||||
#include "serial/impl/unix.h"
|
#include "serial/impl/unix.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
Serial::Serial (const std::string &port, int baudrate,
|
using serial::Serial;
|
||||||
|
using serial::bytesize_t;
|
||||||
|
using serial::parity_t;
|
||||||
|
using serial::stopbits_t;
|
||||||
|
using serial::flowcontrol_t;
|
||||||
|
using std::string;
|
||||||
|
|
||||||
|
Serial::Serial (const string &port, int baudrate,
|
||||||
long timeout, bytesize_t bytesize,
|
long timeout, bytesize_t bytesize,
|
||||||
parity_t parity, stopbits_t stopbits,
|
parity_t parity, stopbits_t stopbits,
|
||||||
flowcontrol_t flowcontrol)
|
flowcontrol_t flowcontrol)
|
||||||
: impl(new Serial_pimpl(port,baudrate,timeout,bytesize,parity,stopbits,
|
: pimpl(new SerialImpl(port,baudrate,timeout,bytesize,parity,stopbits,
|
||||||
flowcontrol))
|
flowcontrol))
|
||||||
{
|
{
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
Serial::~Serial () {
|
Serial::~Serial () {
|
||||||
delete impl;
|
delete pimpl;
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial::open () {
|
Serial::open () {
|
||||||
this->impl->open ();
|
this->pimpl->open ();
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial::close () {
|
Serial::close () {
|
||||||
this->impl->close ();
|
this->pimpl->close ();
|
||||||
}
|
}
|
||||||
bool
|
bool
|
||||||
Serial::isOpen () {
|
Serial::isOpen () {
|
||||||
return this->impl->isOpen ();
|
return this->pimpl->isOpen ();
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t
|
size_t
|
||||||
Serial::read (unsigned char* buffer, size_t size = 1) {
|
Serial::read (unsigned char* buffer, size_t size) {
|
||||||
return this->impl->read (buffer, size);
|
// return this->pimpl->read (buffer, size);
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string
|
string
|
||||||
Serial::read (size_t size = 1) {
|
Serial::read (size_t size) {
|
||||||
return this->impl->read (size);
|
return this->pimpl->read (size);
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t
|
size_t
|
||||||
Serial::read (std::string &buffer, size_t size = 1) {
|
Serial::read (string &buffer, size_t size) {
|
||||||
return this->impl->read (buffer, size);
|
// return this->pimpl->read (buffer, size);
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t
|
//size_t
|
||||||
Serial::write (unsigned char* data, size_t length) {
|
//Serial::write (unsigned char* data, size_t length) {
|
||||||
return this->impl->write (data, length);
|
// return this->pimpl->write (data, length);
|
||||||
}
|
//}
|
||||||
|
|
||||||
size_t
|
size_t
|
||||||
Serial::write (const std::string &data) {
|
Serial::write (const string &data) {
|
||||||
return this->impl->write (data);
|
return this->pimpl->write (data);
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial::setPort (const std::string &port) {
|
Serial::setPort (const string &port) {
|
||||||
this->impl->setPort (port);
|
this->pimpl->setPort (port);
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string
|
string
|
||||||
Serial::getPort () const {
|
Serial::getPort () const {
|
||||||
return this->impl->getPort ();
|
return this->pimpl->getPort ();
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial::setTimeout (long timeout) {
|
Serial::setTimeout (long timeout) {
|
||||||
this->impl->setTimeout (timeout);
|
this->pimpl->setTimeout (timeout);
|
||||||
}
|
}
|
||||||
|
|
||||||
long
|
long
|
||||||
Serial::getTimeout () const {
|
Serial::getTimeout () const {
|
||||||
return this->impl->getTimeout ();
|
return this->pimpl->getTimeout ();
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial::setBaudrate (int baudrate) {
|
Serial::setBaudrate (int baudrate) {
|
||||||
this->impl->setBaudrate (baudrate);
|
this->pimpl->setBaudrate (baudrate);
|
||||||
}
|
}
|
||||||
|
|
||||||
int
|
int
|
||||||
Serial::getBaudrate () const {
|
Serial::getBaudrate () const {
|
||||||
return this->impl->getBaudrate ();
|
return this->pimpl->getBaudrate ();
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial::setBytesize (bytesize_t bytesize) {
|
Serial::setBytesize (bytesize_t bytesize) {
|
||||||
this->impl->setBytesize (bytesize);
|
this->pimpl->setBytesize (bytesize);
|
||||||
}
|
}
|
||||||
|
|
||||||
bytesize_t
|
bytesize_t
|
||||||
Serial::getBytesize () const {
|
Serial::getBytesize () const {
|
||||||
return this->impl->getBytesize ();
|
return this->pimpl->getBytesize ();
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial::setParity (parity_t parity) {
|
Serial::setParity (parity_t parity) {
|
||||||
this->impl->setParity (parity);
|
this->pimpl->setParity (parity);
|
||||||
}
|
}
|
||||||
|
|
||||||
parity_t
|
parity_t
|
||||||
Serial::getParity () const {
|
Serial::getParity () const {
|
||||||
return this->impl->getParity ();
|
return this->pimpl->getParity ();
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial::setStopbits (stopbits_t stopbits) {
|
Serial::setStopbits (stopbits_t stopbits) {
|
||||||
this->impl->setStopbits (stopbits);
|
this->pimpl->setStopbits (stopbits);
|
||||||
}
|
}
|
||||||
|
|
||||||
stopbits_t
|
stopbits_t
|
||||||
Serial::getStopbits () const {
|
Serial::getStopbits () const {
|
||||||
return this->impl->getStopbits ();
|
return this->pimpl->getStopbits ();
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
Serial::setFlowcontrol (flowcontrol_t flowcontrol) {
|
Serial::setFlowcontrol (flowcontrol_t flowcontrol) {
|
||||||
this->impl->setFlowcontrol (flowcontrol);
|
this->pimpl->setFlowcontrol (flowcontrol);
|
||||||
}
|
}
|
||||||
|
|
||||||
flowcontrol_t
|
flowcontrol_t
|
||||||
Serial::getFlowcontrol () const {
|
Serial::getFlowcontrol () const {
|
||||||
return this->impl->getFlowcontrol ();
|
return this->pimpl->getFlowcontrol ();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user