mirror of
https://github.com/wjwwood/serial.git
synced 2026-01-22 11:44:53 +08:00
Removed serial listener, reworking the example, completely removed boost. Builds on my laptop with boost uninstalled.
This commit is contained in:
parent
05fa4b8d77
commit
c429b0eede
@ -7,7 +7,6 @@ Coming Soon!
|
||||
## Dependencies
|
||||
|
||||
* CMake, for the build system: http://www.cmake.org/
|
||||
* Boost, for threading: http://www.boost.org/
|
||||
* (Optional) ROS
|
||||
|
||||
## Stand Alone Installation
|
||||
|
||||
@ -1,123 +1,79 @@
|
||||
#include <string>
|
||||
#include <iostream>
|
||||
#include <stdio.h>
|
||||
#include <time.h>
|
||||
|
||||
#ifdef __MACH__
|
||||
#include <mach/clock.h>
|
||||
#include <mach/mach.h>
|
||||
// OS Specific sleep
|
||||
#ifdef __WIN32__
|
||||
#include <windows.h>
|
||||
#else
|
||||
#include <unistd.h>
|
||||
#endif
|
||||
|
||||
#include <boost/thread.hpp>
|
||||
|
||||
#include "serial/serial.h"
|
||||
|
||||
using std::string;
|
||||
using std::exception;
|
||||
using std::cout;
|
||||
using std::cerr;
|
||||
using std::endl;
|
||||
|
||||
void my_sleep(unsigned long milliseconds) {
|
||||
#ifdef __WIN32__
|
||||
Sleep(milliseconds); // 100 ms
|
||||
#else
|
||||
usleep(milliseconds*1000); // 100 ms
|
||||
#endif
|
||||
}
|
||||
|
||||
int run(int argc, char **argv)
|
||||
{
|
||||
if(argc < 3) {
|
||||
std::cerr << "Usage: test_serial <serial port address> <baudrate>" << std::endl;
|
||||
return 0;
|
||||
cerr << "Usage: test_serial <serial port address> ";
|
||||
cerr << "<baudrate> [test string]" << endl;
|
||||
return 0;
|
||||
}
|
||||
std::string port(argv[1]);
|
||||
unsigned long baud = 0;
|
||||
// Argument 1 is the serial port
|
||||
string port(argv[1]);
|
||||
|
||||
// Argument 2 is the baudrate
|
||||
unsigned long baud = 0;
|
||||
sscanf(argv[2], "%lu", &baud);
|
||||
|
||||
// port, baudrate, timeout in milliseconds
|
||||
serial::Serial serial(port, baud, 10000);
|
||||
|
||||
std::cout << "Is the serial port open?";
|
||||
serial::Serial serial(port, baud, 1000);
|
||||
|
||||
cout << "Is the serial port open?";
|
||||
if(serial.isOpen())
|
||||
std::cout << " Yes." << std::endl;
|
||||
cout << " Yes." << endl;
|
||||
else
|
||||
std::cout << " No." << std::endl;
|
||||
|
||||
cout << " No." << endl;
|
||||
|
||||
int count = 0;
|
||||
while (count >= 0) {
|
||||
struct timespec start, end;
|
||||
double diff;
|
||||
string test_string;
|
||||
if (argc == 4) {
|
||||
test_string = argv[3];
|
||||
} else {
|
||||
test_string = "Testing.";
|
||||
}
|
||||
while (true) {
|
||||
size_t bytes_wrote = serial.write(test_string);
|
||||
|
||||
#ifdef __MACH__ // OS X does not have clock_gettime, use clock_get_time
|
||||
clock_serv_t cclock;
|
||||
mach_timespec_t mts;
|
||||
host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock);
|
||||
clock_get_time(cclock, &mts);
|
||||
mach_port_deallocate(mach_task_self(), cclock);
|
||||
start.tv_sec = mts.tv_sec;
|
||||
start.tv_nsec = mts.tv_nsec;
|
||||
string result = serial.read(test_string.length());
|
||||
|
||||
#else
|
||||
clock_gettime(CLOCK_REALTIME, &start);
|
||||
#endif
|
||||
cout << "Iteration: " << count << ", Bytes written: ";
|
||||
cout << bytes_wrote << ", Bytes read: ";
|
||||
cout << result.length() << ", String read: " << result << endl;
|
||||
|
||||
size_t bytes_wrote = serial.write("Testing.\n");
|
||||
|
||||
#ifdef __MACH__ // OS X does not have clock_gettime, use clock_get_time
|
||||
host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock);
|
||||
clock_get_time(cclock, &mts);
|
||||
mach_port_deallocate(mach_task_self(), cclock);
|
||||
end.tv_sec = mts.tv_sec;
|
||||
end.tv_nsec = mts.tv_nsec;
|
||||
|
||||
#else
|
||||
clock_gettime(CLOCK_REALTIME, &end);
|
||||
#endif
|
||||
|
||||
end.tv_sec -= start.tv_sec;
|
||||
end.tv_nsec -= start.tv_nsec;
|
||||
printf("write: %05lu.%09lu\n", end.tv_sec, end.tv_nsec);
|
||||
|
||||
#ifdef __MACH__ // OS X does not have clock_gettime, use clock_get_time
|
||||
host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock);
|
||||
clock_get_time(cclock, &mts);
|
||||
mach_port_deallocate(mach_task_self(), cclock);
|
||||
start.tv_sec = mts.tv_sec;
|
||||
start.tv_nsec = mts.tv_nsec;
|
||||
|
||||
#else
|
||||
clock_gettime(CLOCK_REALTIME, &start);
|
||||
#endif
|
||||
|
||||
std::string result = serial.readline();
|
||||
#ifdef __MACH__ // OS X does not have clock_gettime, use clock_get_time
|
||||
host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock);
|
||||
clock_get_time(cclock, &mts);
|
||||
mach_port_deallocate(mach_task_self(), cclock);
|
||||
end.tv_sec = mts.tv_sec;
|
||||
end.tv_nsec = mts.tv_nsec;
|
||||
|
||||
#else
|
||||
clock_gettime(CLOCK_REALTIME, &end);
|
||||
#endif
|
||||
|
||||
|
||||
end.tv_sec -= start.tv_sec;
|
||||
end.tv_nsec -= start.tv_nsec;
|
||||
printf("read: %05lu.%09lu\n", end.tv_sec, end.tv_nsec);
|
||||
|
||||
if (result == string("Testing.\n")) {
|
||||
}
|
||||
else {
|
||||
std::cout << ">" << count << ">" << bytes_wrote << ">";
|
||||
std::cout << result.length() << "<" << result << std::endl;
|
||||
cout << "No" << endl;
|
||||
}
|
||||
|
||||
count += 1;
|
||||
boost::this_thread::sleep(boost::posix_time::milliseconds(100));
|
||||
my_sleep(10);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int main(int argc, char **argv) {
|
||||
// try {
|
||||
try {
|
||||
return run(argc, argv);
|
||||
// } catch (std::exception &e) {
|
||||
// std::cerr << "Unhandled Exception: " << e.what() << std::endl;
|
||||
// }
|
||||
} catch (exception &e) {
|
||||
cerr << "Unhandled Exception: " << e.what() << endl;
|
||||
}
|
||||
}
|
||||
|
||||
@ -40,6 +40,8 @@
|
||||
|
||||
#include "serial/serial.h"
|
||||
|
||||
#include <pthread.h>
|
||||
|
||||
namespace serial {
|
||||
|
||||
using std::string;
|
||||
@ -98,40 +100,40 @@ public:
|
||||
|
||||
void
|
||||
setDTR(bool level);
|
||||
|
||||
|
||||
bool
|
||||
getCTS();
|
||||
|
||||
|
||||
bool
|
||||
getDSR();
|
||||
|
||||
|
||||
bool
|
||||
getRI();
|
||||
|
||||
|
||||
bool
|
||||
getCD();
|
||||
|
||||
void
|
||||
setPort (const string &port);
|
||||
|
||||
|
||||
string
|
||||
getPort () const;
|
||||
|
||||
void
|
||||
setTimeout (long timeout);
|
||||
|
||||
|
||||
long
|
||||
getTimeout () const;
|
||||
|
||||
void
|
||||
setBaudrate (unsigned long baudrate);
|
||||
|
||||
|
||||
unsigned long
|
||||
getBaudrate () const;
|
||||
|
||||
void
|
||||
setBytesize (bytesize_t bytesize);
|
||||
|
||||
|
||||
bytesize_t
|
||||
getBytesize () const;
|
||||
|
||||
@ -153,6 +155,18 @@ public:
|
||||
flowcontrol_t
|
||||
getFlowcontrol () const;
|
||||
|
||||
void
|
||||
readLock();
|
||||
|
||||
void
|
||||
readUnlock();
|
||||
|
||||
void
|
||||
writeLock();
|
||||
|
||||
void
|
||||
writeUnlock();
|
||||
|
||||
protected:
|
||||
void reconfigurePort ();
|
||||
|
||||
@ -171,6 +185,11 @@ private:
|
||||
bytesize_t bytesize_; // Size of the bytes
|
||||
stopbits_t stopbits_; // Stop Bits
|
||||
flowcontrol_t flowcontrol_; // Flow Control
|
||||
|
||||
// Mutex used to lock the read functions
|
||||
pthread_mutex_t read_mutex;
|
||||
// Mutex used to lock the write functions
|
||||
pthread_mutex_t write_mutex;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
177
include/serial/impl/windows.h
Normal file
177
include/serial/impl/windows.h
Normal file
@ -0,0 +1,177 @@
|
||||
/*!
|
||||
* \file serial/impl/windows.h
|
||||
* \author William Woodall <wjwwood@gmail.com>
|
||||
* \author John Harrison <ash@greaterthaninfinity.com>
|
||||
* \version 0.1
|
||||
*
|
||||
* \section LICENSE
|
||||
*
|
||||
* The MIT License
|
||||
*
|
||||
* Copyright (c) 2011 William Woodall, John Harrison
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a
|
||||
* copy of this software and associated documentation files (the "Software"),
|
||||
* to deal in the Software without restriction, including without limitation
|
||||
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
|
||||
* and/or sell copies of the Software, and to permit persons to whom the
|
||||
* Software is furnished to do so, subject to the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be included in
|
||||
* all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
|
||||
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
|
||||
* DEALINGS IN THE SOFTWARE.
|
||||
*
|
||||
* \section DESCRIPTION
|
||||
*
|
||||
* This provides a windows implementation of the Serial class interface.
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef SERIAL_IMPL_WINDOWS_H
|
||||
#define SERIAL_IMPL_WINDOWS_H
|
||||
|
||||
#include "serial/serial.h"
|
||||
|
||||
namespace serial {
|
||||
|
||||
using std::string;
|
||||
using std::invalid_argument;
|
||||
|
||||
using serial::SerialExecption;
|
||||
using serial::IOException;
|
||||
|
||||
class serial::Serial::SerialImpl {
|
||||
public:
|
||||
SerialImpl (const string &port,
|
||||
unsigned long baudrate,
|
||||
long timeout,
|
||||
bytesize_t bytesize,
|
||||
parity_t parity,
|
||||
stopbits_t stopbits,
|
||||
flowcontrol_t flowcontrol);
|
||||
|
||||
virtual ~SerialImpl ();
|
||||
|
||||
void
|
||||
open ();
|
||||
|
||||
void
|
||||
close ();
|
||||
|
||||
bool
|
||||
isOpen () const;
|
||||
|
||||
size_t
|
||||
available ();
|
||||
|
||||
size_t
|
||||
read (char* buf, size_t size = 1);
|
||||
|
||||
size_t
|
||||
write (const string &data);
|
||||
|
||||
void
|
||||
flush ();
|
||||
|
||||
void
|
||||
flushInput ();
|
||||
|
||||
void
|
||||
flushOutput ();
|
||||
|
||||
void
|
||||
sendBreak(int duration);
|
||||
|
||||
void
|
||||
setBreak(bool level);
|
||||
|
||||
void
|
||||
setRTS(bool level);
|
||||
|
||||
void
|
||||
setDTR(bool level);
|
||||
|
||||
bool
|
||||
getCTS();
|
||||
|
||||
bool
|
||||
getDSR();
|
||||
|
||||
bool
|
||||
getRI();
|
||||
|
||||
bool
|
||||
getCD();
|
||||
|
||||
void
|
||||
setPort (const string &port);
|
||||
|
||||
string
|
||||
getPort () const;
|
||||
|
||||
void
|
||||
setTimeout (long timeout);
|
||||
|
||||
long
|
||||
getTimeout () const;
|
||||
|
||||
void
|
||||
setBaudrate (unsigned long baudrate);
|
||||
|
||||
unsigned long
|
||||
getBaudrate () const;
|
||||
|
||||
void
|
||||
setBytesize (bytesize_t bytesize);
|
||||
|
||||
bytesize_t
|
||||
getBytesize () const;
|
||||
|
||||
void
|
||||
setParity (parity_t parity);
|
||||
|
||||
parity_t
|
||||
getParity () const;
|
||||
|
||||
void
|
||||
setStopbits (stopbits_t stopbits);
|
||||
|
||||
stopbits_t
|
||||
getStopbits () const;
|
||||
|
||||
void
|
||||
setFlowcontrol (flowcontrol_t flowcontrol);
|
||||
|
||||
flowcontrol_t
|
||||
getFlowcontrol () const;
|
||||
|
||||
protected:
|
||||
void reconfigurePort ();
|
||||
|
||||
private:
|
||||
string port_; // Path to the file descriptor
|
||||
int fd_; // The current file descriptor
|
||||
|
||||
bool isOpen_;
|
||||
bool xonxoff_;
|
||||
bool rtscts_;
|
||||
|
||||
long timeout_; // Timeout for read operations
|
||||
unsigned long baudrate_; // Baudrate
|
||||
|
||||
parity_t parity_; // Parity
|
||||
bytesize_t bytesize_; // Size of the bytes
|
||||
stopbits_t stopbits_; // Stop Bits
|
||||
flowcontrol_t flowcontrol_; // Flow Control
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // SERIAL_IMPL_WINDOWS_H
|
||||
@ -36,16 +36,12 @@
|
||||
#ifndef SERIAL_H
|
||||
#define SERIAL_H
|
||||
|
||||
#include <stdexcept>
|
||||
#include <string>
|
||||
#if defined(__linux__)
|
||||
#include <string.h>
|
||||
#endif
|
||||
#include <sstream>
|
||||
#include <vector>
|
||||
#include <limits>
|
||||
|
||||
#include <boost/thread/mutex.hpp>
|
||||
#include <vector>
|
||||
#include <string.h>
|
||||
#include <sstream>
|
||||
#include <exception>
|
||||
#include <stdexcept>
|
||||
|
||||
namespace serial {
|
||||
|
||||
@ -86,58 +82,6 @@ typedef enum {
|
||||
FLOWCONTROL_HARDWARE
|
||||
} flowcontrol_t;
|
||||
|
||||
class SerialExecption : public std::exception
|
||||
{
|
||||
const char* e_what_;
|
||||
public:
|
||||
SerialExecption (const char *description) : e_what_ (description) {}
|
||||
|
||||
virtual const char* what () const throw ()
|
||||
{
|
||||
std::stringstream ss;
|
||||
ss << "SerialException " << e_what_ << " failed.";
|
||||
return ss.str ().c_str ();
|
||||
}
|
||||
};
|
||||
|
||||
class IOException : public std::exception
|
||||
{
|
||||
const char* e_what_;
|
||||
int errno_;
|
||||
public:
|
||||
explicit IOException (int errnum)
|
||||
: e_what_ (strerror (errnum)), errno_(errnum) {}
|
||||
explicit IOException (const char * description)
|
||||
: e_what_ (description), errno_(0) {}
|
||||
|
||||
int getErrorNumber () { return errno_; }
|
||||
|
||||
virtual const char* what () const throw ()
|
||||
{
|
||||
std::stringstream ss;
|
||||
if (errno_ == 0)
|
||||
ss << "IO Exception " << e_what_ << " failed.";
|
||||
else
|
||||
ss << "IO Exception (" << errno_ << "): " << e_what_ << " failed.";
|
||||
return ss.str ().c_str ();
|
||||
}
|
||||
};
|
||||
|
||||
class PortNotOpenedException : public std::exception
|
||||
{
|
||||
const char * e_what_;
|
||||
public:
|
||||
PortNotOpenedException (const char * description) : e_what_ (description) {}
|
||||
|
||||
virtual const char* what () const throw ()
|
||||
{
|
||||
std::stringstream ss;
|
||||
ss << e_what_ << " called before port was opened.";
|
||||
return ss.str ().c_str ();
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
/*!
|
||||
* Class that provides a portable serial port interface.
|
||||
*/
|
||||
@ -462,7 +406,61 @@ private:
|
||||
class SerialImpl;
|
||||
SerialImpl *pimpl_;
|
||||
|
||||
boost::mutex mut;
|
||||
// Scoped Lock Classes
|
||||
class ScopedReadLock;
|
||||
class ScopedWriteLock;
|
||||
|
||||
};
|
||||
|
||||
class SerialExecption : public std::exception
|
||||
{
|
||||
const char* e_what_;
|
||||
public:
|
||||
SerialExecption (const char *description) : e_what_ (description) {}
|
||||
|
||||
virtual const char* what () const throw ()
|
||||
{
|
||||
std::stringstream ss;
|
||||
ss << "SerialException " << e_what_ << " failed.";
|
||||
return ss.str ().c_str ();
|
||||
}
|
||||
};
|
||||
|
||||
class IOException : public std::exception
|
||||
{
|
||||
const char* e_what_;
|
||||
int errno_;
|
||||
public:
|
||||
explicit IOException (int errnum)
|
||||
: e_what_ (strerror (errnum)), errno_(errnum) {}
|
||||
explicit IOException (const char * description)
|
||||
: e_what_ (description), errno_(0) {}
|
||||
|
||||
int getErrorNumber () { return errno_; }
|
||||
|
||||
virtual const char* what () const throw ()
|
||||
{
|
||||
std::stringstream ss;
|
||||
if (errno_ == 0)
|
||||
ss << "IO Exception " << e_what_ << " failed.";
|
||||
else
|
||||
ss << "IO Exception (" << errno_ << "): " << e_what_ << " failed.";
|
||||
return ss.str ().c_str ();
|
||||
}
|
||||
};
|
||||
|
||||
class PortNotOpenedException : public std::exception
|
||||
{
|
||||
const char * e_what_;
|
||||
public:
|
||||
PortNotOpenedException (const char * description) : e_what_ (description) {}
|
||||
|
||||
virtual const char* what () const throw ()
|
||||
{
|
||||
std::stringstream ss;
|
||||
ss << e_what_ << " called before port was opened.";
|
||||
return ss.str ().c_str ();
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace serial
|
||||
|
||||
@ -19,6 +19,7 @@ macro(build_serial)
|
||||
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
|
||||
|
||||
include_directories(include)
|
||||
include_directories(vendor)
|
||||
|
||||
set(SERIAL_SRCS src/serial.cc)
|
||||
if(UNIX)
|
||||
|
||||
@ -13,6 +13,7 @@
|
||||
#include <sys/select.h>
|
||||
#include <sys/time.h>
|
||||
#include <time.h>
|
||||
#include <pthread.h>
|
||||
|
||||
#if defined(__linux__)
|
||||
#include <linux/serial.h>
|
||||
@ -41,9 +42,11 @@ Serial::SerialImpl::SerialImpl (const string &port, unsigned long baudrate,
|
||||
parity_t parity, stopbits_t stopbits,
|
||||
flowcontrol_t flowcontrol)
|
||||
: port_ (port), fd_ (-1), isOpen_ (false), xonxoff_ (true), rtscts_ (false),
|
||||
timeout_ (timeout), baudrate_ (baudrate), parity_ (parity), bytesize_ (bytesize),
|
||||
stopbits_ (stopbits), flowcontrol_ (flowcontrol)
|
||||
timeout_ (timeout), baudrate_ (baudrate), parity_ (parity),
|
||||
bytesize_ (bytesize), stopbits_ (stopbits), flowcontrol_ (flowcontrol)
|
||||
{
|
||||
pthread_mutex_init(&this->read_mutex, NULL);
|
||||
pthread_mutex_init(&this->write_mutex, NULL);
|
||||
if (port_.empty () == false)
|
||||
open ();
|
||||
}
|
||||
@ -51,6 +54,8 @@ Serial::SerialImpl::SerialImpl (const string &port, unsigned long baudrate,
|
||||
Serial::SerialImpl::~SerialImpl ()
|
||||
{
|
||||
close();
|
||||
pthread_mutex_destroy(&this->read_mutex);
|
||||
pthread_mutex_destroy(&this->write_mutex);
|
||||
}
|
||||
|
||||
void
|
||||
@ -695,3 +700,34 @@ Serial::SerialImpl::getCD()
|
||||
return (s & TIOCM_CD) != 0;
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::readLock() {
|
||||
int result = pthread_mutex_lock(&this->read_mutex);
|
||||
if (result) {
|
||||
throw (IOException (result));
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::readUnlock() {
|
||||
int result = pthread_mutex_unlock(&this->read_mutex);
|
||||
if (result) {
|
||||
throw (IOException (result));
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::writeLock() {
|
||||
int result = pthread_mutex_lock(&this->write_mutex);
|
||||
if (result) {
|
||||
throw (IOException (result));
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::writeUnlock() {
|
||||
int result = pthread_mutex_unlock(&this->write_mutex);
|
||||
if (result) {
|
||||
throw (IOException (result));
|
||||
}
|
||||
}
|
||||
|
||||
671
src/impl/windows.cc
Normal file
671
src/impl/windows.cc
Normal file
@ -0,0 +1,671 @@
|
||||
/* Copyright 2012 William Woodall and John Harrison */
|
||||
|
||||
#include "serial/impl/windows.h"
|
||||
|
||||
using std::string;
|
||||
using std::invalid_argument;
|
||||
using serial::Serial;
|
||||
using serial::SerialExecption;
|
||||
using serial::PortNotOpenedException;
|
||||
using serial::IOException;
|
||||
|
||||
|
||||
Serial::SerialImpl::SerialImpl (const string &port, unsigned long baudrate,
|
||||
long timeout, bytesize_t bytesize,
|
||||
parity_t parity, stopbits_t stopbits,
|
||||
flowcontrol_t flowcontrol)
|
||||
: port_ (port), fd_ (-1), isOpen_ (false), xonxoff_ (true), rtscts_ (false),
|
||||
timeout_ (timeout), baudrate_ (baudrate), parity_ (parity), bytesize_ (bytesize),
|
||||
stopbits_ (stopbits), flowcontrol_ (flowcontrol)
|
||||
{
|
||||
if (port_.empty () == false)
|
||||
open ();
|
||||
}
|
||||
|
||||
Serial::SerialImpl::~SerialImpl ()
|
||||
{
|
||||
close();
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::open ()
|
||||
{
|
||||
if (port_.empty())
|
||||
{
|
||||
throw invalid_argument ("bad port specified");
|
||||
}
|
||||
if (isOpen_ == true)
|
||||
{
|
||||
throw SerialExecption ("port already open");
|
||||
}
|
||||
|
||||
fd_ = ::open (port_.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
|
||||
|
||||
if (fd_ == -1)
|
||||
{
|
||||
switch (errno)
|
||||
{
|
||||
case EINTR:
|
||||
// Recurse because this is a recoverable error.
|
||||
open ();
|
||||
return;
|
||||
case ENFILE:
|
||||
case EMFILE:
|
||||
throw IOException ("to many file handles open");
|
||||
break;
|
||||
default:
|
||||
throw IOException (errno);
|
||||
}
|
||||
}
|
||||
|
||||
reconfigurePort();
|
||||
isOpen_ = true;
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::reconfigurePort ()
|
||||
{
|
||||
if (fd_ == -1)
|
||||
{
|
||||
// Can only operate on a valid file descriptor
|
||||
throw IOException ("invalid file descriptor");
|
||||
}
|
||||
|
||||
struct termios options; // The options for the file descriptor
|
||||
|
||||
if (tcgetattr(fd_, &options) == -1)
|
||||
{
|
||||
throw IOException ("::tcgetattr");
|
||||
}
|
||||
|
||||
// set up raw mode / no echo / binary
|
||||
options.c_cflag |= (unsigned long) (CLOCAL|CREAD);
|
||||
options.c_lflag &= (unsigned long) ~(ICANON|ECHO|ECHOE|ECHOK|ECHONL|
|
||||
ISIG|IEXTEN); //|ECHOPRT
|
||||
|
||||
options.c_oflag &= (unsigned long) ~(OPOST);
|
||||
options.c_iflag &= (unsigned long) ~(INLCR|IGNCR|ICRNL|IGNBRK);
|
||||
#ifdef IUCLC
|
||||
options.c_iflag &= (unsigned long) ~IUCLC;
|
||||
#endif
|
||||
#ifdef PARMRK
|
||||
options.c_iflag &= (unsigned long) ~PARMRK;
|
||||
#endif
|
||||
|
||||
// setup baud rate
|
||||
bool custom_baud = false;
|
||||
speed_t baud;
|
||||
switch (baudrate_)
|
||||
{
|
||||
#ifdef B0
|
||||
case 0: baud = B0; break;
|
||||
#endif
|
||||
#ifdef B50
|
||||
case 50: baud = B50; break;
|
||||
#endif
|
||||
#ifdef B75
|
||||
case 75: baud = B75; break;
|
||||
#endif
|
||||
#ifdef B110
|
||||
case 110: baud = B110; break;
|
||||
#endif
|
||||
#ifdef B134
|
||||
case 134: baud = B134; break;
|
||||
#endif
|
||||
#ifdef B150
|
||||
case 150: baud = B150; break;
|
||||
#endif
|
||||
#ifdef B200
|
||||
case 200: baud = B200; break;
|
||||
#endif
|
||||
#ifdef B300
|
||||
case 300: baud = B300; break;
|
||||
#endif
|
||||
#ifdef B600
|
||||
case 600: baud = B600; break;
|
||||
#endif
|
||||
#ifdef B1200
|
||||
case 1200: baud = B1200; break;
|
||||
#endif
|
||||
#ifdef B1800
|
||||
case 1800: baud = B1800; break;
|
||||
#endif
|
||||
#ifdef B2400
|
||||
case 2400: baud = B2400; break;
|
||||
#endif
|
||||
#ifdef B4800
|
||||
case 4800: baud = B4800; break;
|
||||
#endif
|
||||
#ifdef B7200
|
||||
case 7200: baud = B7200; break;
|
||||
#endif
|
||||
#ifdef B9600
|
||||
case 9600: baud = B9600; break;
|
||||
#endif
|
||||
#ifdef B14400
|
||||
case 14400: baud = B14400; break;
|
||||
#endif
|
||||
#ifdef B19200
|
||||
case 19200: baud = B19200; break;
|
||||
#endif
|
||||
#ifdef B28800
|
||||
case 28800: baud = B28800; break;
|
||||
#endif
|
||||
#ifdef B57600
|
||||
case 57600: baud = B57600; break;
|
||||
#endif
|
||||
#ifdef B76800
|
||||
case 76800: baud = B76800; break;
|
||||
#endif
|
||||
#ifdef B38400
|
||||
case 38400: baud = B38400; break;
|
||||
#endif
|
||||
#ifdef B115200
|
||||
case 115200: baud = B115200; break;
|
||||
#endif
|
||||
#ifdef B128000
|
||||
case 128000: baud = B128000; break;
|
||||
#endif
|
||||
#ifdef B153600
|
||||
case 153600: baud = B153600; break;
|
||||
#endif
|
||||
#ifdef B230400
|
||||
case 230400: baud = B230400; break;
|
||||
#endif
|
||||
#ifdef B256000
|
||||
case 256000: baud = B256000; break;
|
||||
#endif
|
||||
#ifdef B460800
|
||||
case 460800: baud = B460800; break;
|
||||
#endif
|
||||
#ifdef B921600
|
||||
case 921600: baud = B921600; break;
|
||||
#endif
|
||||
default:
|
||||
custom_baud = true;
|
||||
// Mac OS X 10.x Support
|
||||
#if defined(__APPLE__) && defined(__MACH__)
|
||||
#define IOSSIOSPEED _IOW('T', 2, speed_t)
|
||||
int new_baud = static_cast<int> (baudrate_);
|
||||
if (ioctl (fd_, IOSSIOSPEED, &new_baud, 1) < 0)
|
||||
{
|
||||
throw IOException (errno);
|
||||
}
|
||||
// Linux Support
|
||||
#elif defined(__linux__)
|
||||
struct serial_struct ser;
|
||||
ioctl(fd_, TIOCGSERIAL, &ser);
|
||||
// set custom divisor
|
||||
ser.custom_divisor = ser.baud_base / baudrate_;
|
||||
// update flags
|
||||
ser.flags &= ~ASYNC_SPD_MASK;
|
||||
ser.flags |= ASYNC_SPD_CUST;
|
||||
|
||||
if (ioctl(fd_, TIOCSSERIAL, ser) < 0)
|
||||
{
|
||||
throw IOException (errno);
|
||||
}
|
||||
#else
|
||||
throw invalid_argument ("OS does not currently support custom bauds");
|
||||
#endif
|
||||
}
|
||||
if (custom_baud == false)
|
||||
{
|
||||
#ifdef _BSD_SOURCE
|
||||
::cfsetspeed(&options, baud);
|
||||
#else
|
||||
::cfsetispeed(&options, baud);
|
||||
::cfsetospeed(&options, baud);
|
||||
#endif
|
||||
}
|
||||
|
||||
// setup char len
|
||||
options.c_cflag &= (unsigned long) ~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 invalid_argument ("invalid char len");
|
||||
// setup stopbits
|
||||
if (stopbits_ == STOPBITS_ONE)
|
||||
options.c_cflag &= (unsigned long) ~(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 invalid_argument ("invalid stop bit");
|
||||
// setup parity
|
||||
options.c_iflag &= (unsigned long) ~(INPCK|ISTRIP);
|
||||
if (parity_ == PARITY_NONE)
|
||||
{
|
||||
options.c_cflag &= (unsigned long) ~(PARENB|PARODD);
|
||||
}
|
||||
else if (parity_ == PARITY_EVEN)
|
||||
{
|
||||
options.c_cflag &= (unsigned long) ~(PARODD);
|
||||
options.c_cflag |= (PARENB);
|
||||
}
|
||||
else if (parity_ == PARITY_ODD)
|
||||
{
|
||||
options.c_cflag |= (PARENB|PARODD);
|
||||
}
|
||||
else
|
||||
{
|
||||
throw invalid_argument ("invalid parity");
|
||||
}
|
||||
// setup flow control
|
||||
// xonxoff
|
||||
#ifdef IXANY
|
||||
if (xonxoff_)
|
||||
options.c_iflag |= (IXON|IXOFF); //|IXANY)
|
||||
else
|
||||
options.c_iflag &= (unsigned long) ~(IXON|IXOFF|IXANY);
|
||||
#else
|
||||
if (xonxoff_)
|
||||
options.c_iflag |= (IXON|IXOFF);
|
||||
else
|
||||
options.c_iflag &= (unsigned long) ~(IXON|IXOFF);
|
||||
#endif
|
||||
// rtscts
|
||||
#ifdef CRTSCTS
|
||||
if (rtscts_)
|
||||
options.c_cflag |= (CRTSCTS);
|
||||
else
|
||||
options.c_cflag &= (unsigned long) ~(CRTSCTS);
|
||||
#elif defined CNEW_RTSCTS
|
||||
if (rtscts_)
|
||||
options.c_cflag |= (CNEW_RTSCTS);
|
||||
else
|
||||
options.c_cflag &= (unsigned long) ~(CNEW_RTSCTS);
|
||||
#else
|
||||
#error "OS Support seems wrong."
|
||||
#endif
|
||||
|
||||
options.c_cc[VMIN] = 1; // Minimum of 1 character in the buffer
|
||||
options.c_cc[VTIME] = 0; // timeout on waiting for new data
|
||||
|
||||
// activate settings
|
||||
::tcsetattr (fd_, TCSANOW, &options);
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::close ()
|
||||
{
|
||||
if (isOpen_ == true)
|
||||
{
|
||||
if (fd_ != -1)
|
||||
{
|
||||
::close (fd_); // Ignoring the outcome
|
||||
fd_ = -1;
|
||||
}
|
||||
isOpen_ = false;
|
||||
}
|
||||
}
|
||||
|
||||
bool
|
||||
Serial::SerialImpl::isOpen () const
|
||||
{
|
||||
return isOpen_;
|
||||
}
|
||||
|
||||
size_t
|
||||
Serial::SerialImpl::available ()
|
||||
{
|
||||
if (!isOpen_)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
int count = 0;
|
||||
int result = ioctl (fd_, TIOCINQ, &count);
|
||||
if (result == 0)
|
||||
{
|
||||
return static_cast<size_t> (count);
|
||||
}
|
||||
else
|
||||
{
|
||||
throw IOException (errno);
|
||||
}
|
||||
}
|
||||
|
||||
size_t
|
||||
Serial::SerialImpl::read (char* buf, size_t size)
|
||||
{
|
||||
if (!isOpen_)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::read");
|
||||
}
|
||||
fd_set readfds;
|
||||
ssize_t bytes_read = 0;
|
||||
int count = 0;
|
||||
while (true)
|
||||
{
|
||||
count++;
|
||||
// printf("Counting: %u\n", count);
|
||||
if (timeout_ != -1)
|
||||
{
|
||||
FD_ZERO (&readfds);
|
||||
FD_SET (fd_, &readfds);
|
||||
struct timeval timeout;
|
||||
timeout.tv_sec = timeout_ / 1000;
|
||||
timeout.tv_usec = static_cast<int> (timeout_ % 1000) * 1000;
|
||||
int r = select (fd_ + 1, &readfds, NULL, NULL, &timeout);
|
||||
|
||||
if (r == -1 && errno == EINTR)
|
||||
continue;
|
||||
|
||||
if (r == -1)
|
||||
{
|
||||
throw IOException (errno);
|
||||
}
|
||||
}
|
||||
|
||||
if (timeout_ == -1 || FD_ISSET (fd_, &readfds))
|
||||
{
|
||||
bytes_read = ::read (fd_, buf, size);
|
||||
// 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 SerialExecption ("device reports readiness to read but "
|
||||
"returned no data (device disconnected?)");
|
||||
}
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
break;
|
||||
}
|
||||
}
|
||||
return static_cast<size_t> (bytes_read);
|
||||
}
|
||||
|
||||
size_t
|
||||
Serial::SerialImpl::write (const string &data)
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::write");
|
||||
}
|
||||
|
||||
fd_set writefds;
|
||||
ssize_t bytes_written = 0;
|
||||
while (true)
|
||||
{
|
||||
if (timeout_ != -1)
|
||||
{
|
||||
FD_ZERO (&writefds);
|
||||
FD_SET (fd_, &writefds);
|
||||
struct timeval timeout;
|
||||
timeout.tv_sec = timeout_ / 1000;
|
||||
timeout.tv_usec = static_cast<int> (timeout_ % 1000) * 1000;
|
||||
int r = select (fd_ + 1, NULL, &writefds, NULL, &timeout);
|
||||
|
||||
if (r == -1 && errno == EINTR)
|
||||
continue;
|
||||
|
||||
if (r == -1)
|
||||
{
|
||||
throw IOException (errno);
|
||||
}
|
||||
}
|
||||
|
||||
if (timeout_ == -1 || FD_ISSET (fd_, &writefds))
|
||||
{
|
||||
bytes_written = ::write (fd_, data.c_str (), data.length ());
|
||||
// read should always return some data as select reported it was
|
||||
// ready to read when we get to this point.
|
||||
if (bytes_written < 1)
|
||||
{
|
||||
// Disconnected devices, at least on Linux, show the
|
||||
// behavior that they are always ready to read immediately
|
||||
// but reading returns nothing.
|
||||
throw SerialExecption ("device reports readiness to read but "
|
||||
"returned no data (device disconnected?)");
|
||||
}
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return static_cast<size_t> (bytes_written);
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::setPort (const string &port)
|
||||
{
|
||||
port_ = port;
|
||||
}
|
||||
|
||||
string
|
||||
Serial::SerialImpl::getPort () const
|
||||
{
|
||||
return port_;
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::setTimeout (long timeout)
|
||||
{
|
||||
timeout_ = timeout;
|
||||
}
|
||||
|
||||
long
|
||||
Serial::SerialImpl::getTimeout () const
|
||||
{
|
||||
return timeout_;
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::setBaudrate (unsigned long baudrate)
|
||||
{
|
||||
baudrate_ = baudrate;
|
||||
if (isOpen_)
|
||||
reconfigurePort ();
|
||||
}
|
||||
|
||||
unsigned long
|
||||
Serial::SerialImpl::getBaudrate () const
|
||||
{
|
||||
return baudrate_;
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::setBytesize (serial::bytesize_t bytesize)
|
||||
{
|
||||
bytesize_ = bytesize;
|
||||
if (isOpen_)
|
||||
reconfigurePort ();
|
||||
}
|
||||
|
||||
serial::bytesize_t
|
||||
Serial::SerialImpl::getBytesize () const
|
||||
{
|
||||
return bytesize_;
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::setParity (serial::parity_t parity)
|
||||
{
|
||||
parity_ = parity;
|
||||
if (isOpen_)
|
||||
reconfigurePort ();
|
||||
}
|
||||
|
||||
serial::parity_t
|
||||
Serial::SerialImpl::getParity () const
|
||||
{
|
||||
return parity_;
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::setStopbits (serial::stopbits_t stopbits)
|
||||
{
|
||||
stopbits_ = stopbits;
|
||||
if (isOpen_)
|
||||
reconfigurePort ();
|
||||
}
|
||||
|
||||
serial::stopbits_t
|
||||
Serial::SerialImpl::getStopbits () const
|
||||
{
|
||||
return stopbits_;
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::setFlowcontrol (serial::flowcontrol_t flowcontrol)
|
||||
{
|
||||
flowcontrol_ = flowcontrol;
|
||||
if (isOpen_)
|
||||
reconfigurePort ();
|
||||
}
|
||||
|
||||
serial::flowcontrol_t
|
||||
Serial::SerialImpl::getFlowcontrol () const
|
||||
{
|
||||
return flowcontrol_;
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::flush ()
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::flush");
|
||||
}
|
||||
tcdrain (fd_);
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::flushInput ()
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::flushInput");
|
||||
}
|
||||
tcflush (fd_, TCIFLUSH);
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::flushOutput ()
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::flushOutput");
|
||||
}
|
||||
tcflush (fd_, TCOFLUSH);
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::sendBreak (int duration)
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::sendBreak");
|
||||
}
|
||||
tcsendbreak (fd_, static_cast<int> (duration/4));
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::setBreak (bool level)
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::setBreak");
|
||||
}
|
||||
if (level)
|
||||
{
|
||||
ioctl (fd_, TIOCSBRK);
|
||||
}
|
||||
else {
|
||||
ioctl (fd_, TIOCCBRK);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::setRTS (bool level)
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::setRTS");
|
||||
}
|
||||
if (level)
|
||||
{
|
||||
ioctl (fd_, TIOCMBIS, TIOCM_RTS);
|
||||
}
|
||||
else {
|
||||
ioctl (fd_, TIOCMBIC, TIOCM_RTS);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
Serial::SerialImpl::setDTR (bool level)
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::setDTR");
|
||||
}
|
||||
if (level)
|
||||
{
|
||||
ioctl (fd_, TIOCMBIS, TIOCM_DTR);
|
||||
}
|
||||
else
|
||||
{
|
||||
ioctl (fd_, TIOCMBIC, TIOCM_DTR);
|
||||
}
|
||||
}
|
||||
|
||||
bool
|
||||
Serial::SerialImpl::getCTS ()
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::getCTS");
|
||||
}
|
||||
int s = ioctl (fd_, TIOCMGET, 0);
|
||||
return (s & TIOCM_CTS) != 0;
|
||||
}
|
||||
|
||||
bool
|
||||
Serial::SerialImpl::getDSR()
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::getDSR");
|
||||
}
|
||||
int s = ioctl(fd_, TIOCMGET, 0);
|
||||
return (s & TIOCM_DSR) != 0;
|
||||
}
|
||||
|
||||
bool
|
||||
Serial::SerialImpl::getRI()
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::getRI");
|
||||
}
|
||||
int s = ioctl (fd_, TIOCMGET, 0);
|
||||
return (s & TIOCM_RI) != 0;
|
||||
}
|
||||
|
||||
bool
|
||||
Serial::SerialImpl::getCD()
|
||||
{
|
||||
if (isOpen_ == false)
|
||||
{
|
||||
throw PortNotOpenedException ("Serial::getCD");
|
||||
}
|
||||
int s = ioctl (fd_, TIOCMGET, 0);
|
||||
return (s & TIOCM_CD) != 0;
|
||||
}
|
||||
|
||||
@ -1,12 +1,5 @@
|
||||
/* Copyright 2012 William Woodall and John Harrison */
|
||||
|
||||
#include <alloca.h>
|
||||
|
||||
#include <cstring>
|
||||
#include <algorithm>
|
||||
|
||||
#include <boost/thread/mutex.hpp>
|
||||
|
||||
#include "serial/serial.h"
|
||||
|
||||
#ifdef _WIN32
|
||||
@ -31,14 +24,35 @@ using serial::parity_t;
|
||||
using serial::stopbits_t;
|
||||
using serial::flowcontrol_t;
|
||||
|
||||
using boost::mutex;
|
||||
class Serial::ScopedReadLock {
|
||||
public:
|
||||
ScopedReadLock(SerialImpl *pimpl) : pimpl_(pimpl) {
|
||||
this->pimpl_->readLock();
|
||||
}
|
||||
~ScopedReadLock() {
|
||||
this->pimpl_->readUnlock();
|
||||
}
|
||||
private:
|
||||
SerialImpl *pimpl_;
|
||||
};
|
||||
|
||||
class Serial::ScopedWriteLock {
|
||||
public:
|
||||
ScopedWriteLock(SerialImpl *pimpl) : pimpl_(pimpl) {
|
||||
this->pimpl_->writeLock();
|
||||
}
|
||||
~ScopedWriteLock() {
|
||||
this->pimpl_->writeUnlock();
|
||||
}
|
||||
private:
|
||||
SerialImpl *pimpl_;
|
||||
};
|
||||
|
||||
Serial::Serial (const string &port, unsigned long baudrate, long timeout,
|
||||
bytesize_t bytesize, parity_t parity, stopbits_t stopbits,
|
||||
flowcontrol_t flowcontrol)
|
||||
: read_cache_("")
|
||||
{
|
||||
mutex::scoped_lock scoped_lock(mut);
|
||||
pimpl_ = new SerialImpl (port, baudrate, timeout, bytesize, parity,
|
||||
stopbits, flowcontrol);
|
||||
}
|
||||
@ -75,7 +89,7 @@ Serial::available ()
|
||||
string
|
||||
Serial::read (size_t size)
|
||||
{
|
||||
mutex::scoped_lock scoped_lock (mut);
|
||||
ScopedReadLock(this->pimpl_);
|
||||
if (read_cache_.size() >= size)
|
||||
{
|
||||
// Don't need to do a new read.
|
||||
@ -89,10 +103,8 @@ Serial::read (size_t size)
|
||||
string result (read_cache_.substr (0, size));
|
||||
read_cache_.clear ();
|
||||
|
||||
int count = 0;
|
||||
while (true)
|
||||
{
|
||||
// printf("%u\n", count++);
|
||||
char buf[256];
|
||||
size_t chars_read = pimpl_->read (buf, 256);
|
||||
if (chars_read > 0)
|
||||
@ -173,14 +185,15 @@ Serial::readlines(string eol)
|
||||
size_t
|
||||
Serial::write (const string &data)
|
||||
{
|
||||
mutex::scoped_lock scoped_lock(mut);
|
||||
ScopedWriteLock(this->pimpl_);
|
||||
return pimpl_->write (data);
|
||||
}
|
||||
|
||||
void
|
||||
Serial::setPort (const string &port)
|
||||
{
|
||||
mutex::scoped_lock scoped_lock(mut);
|
||||
ScopedReadLock(this->pimpl_);
|
||||
ScopedWriteLock(this->pimpl_);
|
||||
bool was_open = pimpl_->isOpen();
|
||||
if (was_open) close();
|
||||
pimpl_->setPort (port);
|
||||
@ -266,19 +279,21 @@ Serial::getFlowcontrol () const
|
||||
|
||||
void Serial::flush ()
|
||||
{
|
||||
mutex::scoped_lock scoped_lock (mut);
|
||||
ScopedReadLock(this->pimpl_);
|
||||
ScopedWriteLock(this->pimpl_);
|
||||
pimpl_->flush ();
|
||||
read_cache_.clear ();
|
||||
}
|
||||
|
||||
void Serial::flushInput ()
|
||||
{
|
||||
ScopedReadLock(this->pimpl_);
|
||||
pimpl_->flushInput ();
|
||||
}
|
||||
|
||||
void Serial::flushOutput ()
|
||||
{
|
||||
mutex::scoped_lock scoped_lock (mut);
|
||||
ScopedWriteLock(this->pimpl_);
|
||||
pimpl_->flushOutput ();
|
||||
read_cache_.clear ();
|
||||
}
|
||||
@ -322,4 +337,3 @@ bool Serial::getCD ()
|
||||
{
|
||||
return pimpl_->getCD ();
|
||||
}
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user