mirror of
https://github.com/wjwwood/serial.git
synced 2026-01-22 19:54:57 +08:00
Removing vestigial files.
This commit is contained in:
parent
c2ad2721f3
commit
4cdb42987f
@ -1,448 +0,0 @@
|
||||
/**
|
||||
* @file serial.h
|
||||
* @author William Woodall <wjwwood@gmail.com>
|
||||
* @author John Harrison <ash.gti@gmail.com>
|
||||
* @version 0.1
|
||||
*
|
||||
* @section LICENSE
|
||||
*
|
||||
* The MIT License
|
||||
*
|
||||
* Copyright (c) 2011 William Woodall
|
||||
*
|
||||
* 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 cross platform interface for interacting with Serial Ports.
|
||||
*/
|
||||
|
||||
|
||||
#ifndef SERIAL_H
|
||||
#define SERIAL_H
|
||||
|
||||
#include <iostream>
|
||||
#include <sstream>
|
||||
#include <string>
|
||||
|
||||
#include <boost/asio.hpp>
|
||||
#include <boost/asio/serial_port.hpp>
|
||||
#include <boost/bind.hpp>
|
||||
#include <boost/thread.hpp>
|
||||
#include <boost/scoped_ptr.hpp>
|
||||
|
||||
// A macro to disallow the copy constructor and operator= functions
|
||||
// This should be used in the private: declarations for a class
|
||||
#define DISALLOW_COPY_AND_ASSIGN(TypeName) \
|
||||
TypeName(const TypeName&); \
|
||||
void operator=(const TypeName&)
|
||||
|
||||
// If on Windows undefine the PARITY_* defines that are in winbase.h
|
||||
#ifdef _WIN32
|
||||
#undef PARITY_NONE
|
||||
#undef PARITY_ODD
|
||||
#undef PARITY_EVEN
|
||||
#endif
|
||||
|
||||
// DEFINES
|
||||
#ifndef DEFAULT_BAUDRATE
|
||||
#define DEFAULT_BAUDRATE 9600
|
||||
#endif
|
||||
#ifndef DEFAULT_TIMEOUT
|
||||
#define DEFAULT_TIMEOUT 0
|
||||
#endif
|
||||
#ifndef DEFAULT_BYTESIZE
|
||||
#define DEFAULT_BYTESIZE EIGHTBITS
|
||||
#endif
|
||||
#ifndef DEFAULT_PARITY
|
||||
#define DEFAULT_PARITY PARITY_NONE
|
||||
#endif
|
||||
#ifndef DEFAULT_STOPBITS
|
||||
#define DEFAULT_STOPBITS STOPBITS_ONE
|
||||
#endif
|
||||
#ifndef DEFAULT_FLOWCONTROL
|
||||
#define DEFAULT_FLOWCONTROL FLOWCONTROL_NONE
|
||||
#endif
|
||||
|
||||
namespace serial {
|
||||
|
||||
// Serial Port settings CONSTANTS
|
||||
enum bytesize_t { FIVEBITS = 5, SIXBITS = 6, SEVENBITS = 7, EIGHTBITS = 8 };
|
||||
enum parity_t { PARITY_NONE, PARITY_ODD, PARITY_EVEN };
|
||||
enum stopbits_t { STOPBITS_ONE, STOPBITS_ONE_POINT_FIVE, STOPBITS_TWO };
|
||||
enum flowcontrol_t { FLOWCONTROL_NONE, FLOWCONTROL_SOFTWARE, FLOWCONTROL_HARDWARE };
|
||||
|
||||
class Serial {
|
||||
public:
|
||||
/** Constructor, Creates a Serial object but doesn't open the serial port. */
|
||||
Serial();
|
||||
|
||||
/**
|
||||
* Constructor, creates a SerialPortBoost object and opens the port.
|
||||
*
|
||||
* @param port A std::string containing the address of the serial port,
|
||||
* which would be something like 'COM1' on Windows and '/dev/ttyS0'
|
||||
* on Linux.
|
||||
*
|
||||
* @param baudrate An integer that represents the buadrate
|
||||
*
|
||||
* @param timeout A long that represents the time (in milliseconds) until a
|
||||
* timeout on reads occur. Setting this to zero (0) will cause reading
|
||||
* to be non-blocking, i.e. the available data will be returned immediately,
|
||||
* but it will not block to wait for more. Setting this to a number less than
|
||||
* zero (-1) will result in infinite blocking behaviour, i.e. the serial port will
|
||||
* block until either size bytes have been read or an exception has occured.
|
||||
*
|
||||
* @param bytesize Size of each byte in the serial transmission of data,
|
||||
* default is EIGHTBITS, possible values are: FIVEBITS,
|
||||
* SIXBITS, SEVENBITS, EIGHTBITS
|
||||
*
|
||||
* @param parity Method of parity, default is PARITY_NONE, possible values
|
||||
* are: PARITY_NONE, PARITY_ODD, PARITY_EVEN
|
||||
*
|
||||
* @param stopbits Number of stop bits used, default is STOPBITS_ONE, possible
|
||||
* values are: STOPBITS_ONE, STOPBITS_ONE_POINT_FIVE, STOPBITS_TWO
|
||||
*
|
||||
* @param flowcontrol Type of flowcontrol used, default is FLOWCONTROL_NONE, possible
|
||||
* values are: FLOWCONTROL_NONE, FLOWCONTROL_SOFTWARE, FLOWCONTROL_HARDWARE
|
||||
*
|
||||
* @throw SerialPortAlreadyOpenException
|
||||
* @throw SerialPortFailedToOpenException
|
||||
*/
|
||||
Serial(std::string port,
|
||||
int baudrate = DEFAULT_BAUDRATE,
|
||||
long timeout = DEFAULT_TIMEOUT,
|
||||
bytesize_t bytesize = DEFAULT_BYTESIZE,
|
||||
parity_t parity = DEFAULT_PARITY,
|
||||
stopbits_t stopbits = DEFAULT_STOPBITS,
|
||||
flowcontrol_t flowcontrol = DEFAULT_FLOWCONTROL);
|
||||
|
||||
/** Destructor */
|
||||
~Serial();
|
||||
|
||||
/**
|
||||
* Opens the serial port as long as the portname is set and the port isn't alreay open.
|
||||
*
|
||||
* @throw SerialPortAlreadyOpenException
|
||||
* @throw SerialPortFailedToOpenException
|
||||
*/
|
||||
void open();
|
||||
|
||||
/** Gets the status of the serial port.
|
||||
*
|
||||
* @return A boolean value that represents whether or not the serial port is open.
|
||||
*/
|
||||
bool isOpen();
|
||||
|
||||
/** Closes the serial port and terminates threads. */
|
||||
void close();
|
||||
|
||||
/** Read size bytes from the serial port.
|
||||
* If a timeout is set it may return less characters than requested. With no timeout
|
||||
* it will block until the requested number of bytes have been read.
|
||||
*
|
||||
* @param buffer A char[] of length >= the size parameter to hold incoming data.
|
||||
*
|
||||
* @param size An integer defining how many bytes to be read.
|
||||
*
|
||||
* @return An integer representing the number of bytes read.
|
||||
*/
|
||||
int read(char* buffer, int size = 1);
|
||||
|
||||
/** Read size bytes from the serial port.
|
||||
* If a timeout is set it may return less characters than requested. With no timeout
|
||||
* it will block until the requested number of bytes have been read.
|
||||
*
|
||||
* @param size An integer defining how many bytes to be read.
|
||||
*
|
||||
* @return A std::string containing the data read.
|
||||
*/
|
||||
std::string read(int size = 1);
|
||||
|
||||
std::string read_until(char delim, size_t size = -1);
|
||||
std::string read_until(std::string delim, size_t size = -1);
|
||||
|
||||
/** Write length bytes from buffer to the serial port.
|
||||
*
|
||||
* @param data A char[] with data to be written to the serial port.
|
||||
*
|
||||
* @param length An integer representing the number of bytes to be written.
|
||||
*
|
||||
* @return An integer representing the number of bytes written.
|
||||
*/
|
||||
int write(char data[], int length);
|
||||
|
||||
/** Write a string to the serial port.
|
||||
*
|
||||
* @param data A std::string to be written to the serial port. (must be null terminated)
|
||||
*
|
||||
* @return An integer representing the number of bytes written to the serial port.
|
||||
*/
|
||||
int write(std::string data);
|
||||
|
||||
/** Sets the logic level of the RTS line.
|
||||
*
|
||||
* @param level The logic level to set the RTS to. Defaults to true.
|
||||
*/
|
||||
void setRTS(bool level = true);
|
||||
|
||||
/** Sets the logic level of the DTR line.
|
||||
*
|
||||
* @param level The logic level to set the DTR to. Defaults to true.
|
||||
*/
|
||||
void setDTR(bool level = true);
|
||||
|
||||
/** Gets the status of the CTS line.
|
||||
*
|
||||
* @return A boolean value that represents the current logic level of the CTS line.
|
||||
*/
|
||||
bool getCTS() const;
|
||||
|
||||
/** Gets the status of the DSR line.
|
||||
*
|
||||
* @return A boolean value that represents the current logic level of the DSR line.
|
||||
*/
|
||||
bool getDSR() const;
|
||||
|
||||
/** Sets the serial port identifier.
|
||||
*
|
||||
* @param port A std::string containing the address of the serial port,
|
||||
* which would be something like 'COM1' on Windows and '/dev/ttyS0'
|
||||
* on Linux.
|
||||
*/
|
||||
void setPort(std::string port);
|
||||
|
||||
/** Gets the serial port identifier.
|
||||
*
|
||||
* @return A std::string containing the address of the serial port,
|
||||
* which would be something like 'COM1' on Windows and '/dev/ttyS0'
|
||||
* on Linux.
|
||||
*/
|
||||
std::string getPort() const;
|
||||
|
||||
/** Sets the timeout for reads in seconds.
|
||||
*
|
||||
* @param timeout A long that represents the time (in milliseconds) until a
|
||||
* timeout on reads occur. Setting this to zero (0) will cause reading
|
||||
* to be non-blocking, i.e. the available data will be returned immediately,
|
||||
* but it will not block to wait for more. Setting this to a number less than
|
||||
* zero (-1) will result in infinite blocking behaviour, i.e. the serial port will
|
||||
* block until either size bytes have been read or an exception has occured.
|
||||
*/
|
||||
void setTimeoutMilliseconds(long timeout);
|
||||
|
||||
/** Gets the timeout for reads in seconds.
|
||||
*
|
||||
* @param timeout A long that represents the time (in milliseconds) until a
|
||||
* timeout on reads occur. Setting this to zero (0) will cause reading
|
||||
* to be non-blocking, i.e. the available data will be returned immediately,
|
||||
* but it will not block to wait for more. Setting this to a number less than
|
||||
* zero (-1) will result in infinite blocking behaviour, i.e. the serial port will
|
||||
* block until either size bytes have been read or an exception has occured.
|
||||
*/
|
||||
long getTimeoutMilliseconds() const;
|
||||
|
||||
/** Sets the baudrate for the serial port.
|
||||
*
|
||||
* @param baudrate An integer that sets the baud rate for the serial port.
|
||||
*/
|
||||
void setBaudrate(int baudrate);
|
||||
|
||||
/** Gets the baudrate for the serial port.
|
||||
*
|
||||
* @return An integer that sets the baud rate for the serial port.
|
||||
*/
|
||||
int getBaudrate() const;
|
||||
|
||||
/** Sets the bytesize for the serial port.
|
||||
*
|
||||
* @param bytesize Size of each byte in the serial transmission of data,
|
||||
* default is EIGHTBITS, possible values are: FIVEBITS,
|
||||
* SIXBITS, SEVENBITS, EIGHTBITS
|
||||
*
|
||||
* @throw InvalidBytesizeException
|
||||
*/
|
||||
void setBytesize(bytesize_t bytesize);
|
||||
|
||||
/** Gets the bytesize for the serial port.
|
||||
*
|
||||
* @return Size of each byte in the serial transmission of data,
|
||||
* default is EIGHTBITS, possible values are: FIVEBITS,
|
||||
* SIXBITS, SEVENBITS, EIGHTBITS
|
||||
*
|
||||
* @throw InvalidBytesizeException
|
||||
*/
|
||||
bytesize_t getBytesize() const;
|
||||
|
||||
/** Sets the parity for the serial port.
|
||||
*
|
||||
* @param parity Method of parity, default is PARITY_NONE, possible values
|
||||
* are: PARITY_NONE, PARITY_ODD, PARITY_EVEN
|
||||
*
|
||||
* @throw InvalidParityException
|
||||
*/
|
||||
void setParity(parity_t parity);
|
||||
|
||||
/** Gets the parity for the serial port.
|
||||
*
|
||||
* @return Method of parity, default is PARITY_NONE, possible values
|
||||
* are: PARITY_NONE, PARITY_ODD, PARITY_EVEN
|
||||
*
|
||||
* @throw InvalidParityException
|
||||
*/
|
||||
parity_t getParity() const;
|
||||
|
||||
/** Sets the stopbits for the serial port.
|
||||
*
|
||||
* @param stopbits Number of stop bits used, default is STOPBITS_ONE, possible
|
||||
* values are: STOPBITS_ONE, STOPBITS_ONE_POINT_FIVE, STOPBITS_TWO
|
||||
*
|
||||
* @throw InvalidStopbitsException
|
||||
*/
|
||||
void setStopbits(stopbits_t stopbits);
|
||||
|
||||
/** Gets the stopbits for the serial port.
|
||||
*
|
||||
* @return Number of stop bits used, default is STOPBITS_ONE, possible
|
||||
* values are: STOPBITS_ONE, STOPBITS_ONE_POINT_FIVE, STOPBITS_TWO
|
||||
*
|
||||
* @throw InvalidStopbitsException
|
||||
*/
|
||||
stopbits_t getStopbits() const;
|
||||
|
||||
/** Sets the flow control for the serial port.
|
||||
*
|
||||
* @param flowcontrol Type of flowcontrol used, default is FLOWCONTROL_NONE, possible
|
||||
* values are: FLOWCONTROL_NONE, FLOWCONTROL_SOFTWARE, FLOWCONTROL_HARDWARE
|
||||
*
|
||||
* @throw InvalidFlowcontrolException
|
||||
*/
|
||||
void setFlowcontrol(flowcontrol_t flowcontrol);
|
||||
|
||||
/** Gets the flow control for the serial port.
|
||||
*
|
||||
* @return Type of flowcontrol used, default is FLOWCONTROL_NONE, possible
|
||||
* values are: FLOWCONTROL_NONE, FLOWCONTROL_SOFTWARE, FLOWCONTROL_HARDWARE
|
||||
*
|
||||
* @throw InvalidFlowcontrolException
|
||||
*/
|
||||
flowcontrol_t getFlowcontrol() const;
|
||||
private:
|
||||
DISALLOW_COPY_AND_ASSIGN(Serial);
|
||||
void init();
|
||||
void read_complete(const boost::system::error_code& error, std::size_t bytes_transferred);
|
||||
void timeout_callback(const boost::system::error_code& error);
|
||||
|
||||
boost::asio::io_service io_service;
|
||||
|
||||
boost::asio::io_service::work work;
|
||||
|
||||
boost::scoped_ptr<boost::asio::serial_port> serial_port;
|
||||
|
||||
boost::asio::deadline_timer timeout_timer;
|
||||
|
||||
std::string port;
|
||||
boost::asio::serial_port_base::baud_rate baudrate;
|
||||
boost::posix_time::time_duration timeout;
|
||||
boost::asio::serial_port_base::character_size bytesize;
|
||||
boost::asio::serial_port_base::parity parity;
|
||||
boost::asio::serial_port_base::stop_bits stopbits;
|
||||
boost::asio::serial_port_base::flow_control flowcontrol;
|
||||
|
||||
int bytes_read;
|
||||
int bytes_to_read;
|
||||
bool reading;
|
||||
bool nonblocking;
|
||||
};
|
||||
|
||||
class SerialPortAlreadyOpenException : public std::exception {
|
||||
const char * port;
|
||||
public:
|
||||
SerialPortAlreadyOpenException(const char * port) {this->port = port;}
|
||||
|
||||
virtual const char* what() const throw() {
|
||||
std::stringstream ss;
|
||||
ss << "Serial Port already open: " << this->port;
|
||||
return ss.str().c_str();
|
||||
}
|
||||
};
|
||||
|
||||
class SerialPortFailedToOpenException : public std::exception {
|
||||
const char * e_what;
|
||||
public:
|
||||
SerialPortFailedToOpenException(const char * e_what) {this->e_what = e_what;}
|
||||
|
||||
virtual const char* what() const throw() {
|
||||
std::stringstream ss;
|
||||
ss << "Serial Port failed to open: " << this->e_what;
|
||||
return ss.str().c_str();
|
||||
}
|
||||
};
|
||||
|
||||
class InvalidBytesizeException : public std::exception {
|
||||
int bytesize;
|
||||
public:
|
||||
InvalidBytesizeException(int bytesize) {this->bytesize = bytesize;}
|
||||
|
||||
virtual const char* what() const throw() {
|
||||
std::stringstream ss;
|
||||
ss << "Invalid bytesize provided: " << this->bytesize;
|
||||
return ss.str().c_str();
|
||||
}
|
||||
};
|
||||
|
||||
class InvalidParityException : public std::exception {
|
||||
int parity;
|
||||
public:
|
||||
InvalidParityException(int parity) {this->parity = parity;}
|
||||
|
||||
virtual const char* what() const throw() {
|
||||
std::stringstream ss;
|
||||
ss << "Invalid parity provided: " << this->parity;
|
||||
return ss.str().c_str();
|
||||
}
|
||||
};
|
||||
|
||||
class InvalidStopbitsException : public std::exception {
|
||||
int stopbits;
|
||||
public:
|
||||
InvalidStopbitsException(int stopbits) {this->stopbits = stopbits;}
|
||||
|
||||
virtual const char* what() const throw() {
|
||||
std::stringstream ss;
|
||||
ss << "Invalid stopbits provided: " << this->stopbits;
|
||||
return ss.str().c_str();
|
||||
}
|
||||
};
|
||||
|
||||
class InvalidFlowcontrolException : public std::exception {
|
||||
int flowcontrol;
|
||||
public:
|
||||
InvalidFlowcontrolException(int flowcontrol) {this->flowcontrol = flowcontrol;}
|
||||
|
||||
virtual const char* what() const throw() {
|
||||
std::stringstream ss;
|
||||
ss << "Invalid flowcontrol provided: " << this->flowcontrol;
|
||||
return ss.str().c_str();
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace serial
|
||||
|
||||
#endif
|
||||
@ -1,468 +0,0 @@
|
||||
#include "serial/serial.h"
|
||||
#include <iostream>
|
||||
|
||||
using namespace serial;
|
||||
|
||||
/** Completion Conditions **/
|
||||
|
||||
class transfer_at_least_ignore_invalid_argument {
|
||||
public:
|
||||
typedef bool result_type;
|
||||
|
||||
explicit transfer_at_least_ignore_invalid_argument(std::size_t minimum) : minimum_(minimum) {}
|
||||
|
||||
template <typename Error>
|
||||
bool operator()(const Error& err, std::size_t bytes_transferred) {
|
||||
if(err) {// There is an Error
|
||||
if(err == boost::asio::error::invalid_argument)
|
||||
std::cout << "Invalid Argument Error" << std::endl;
|
||||
if(err == boost::asio::error::operation_aborted) {
|
||||
return 1;
|
||||
}
|
||||
if(err != boost::asio::error::invalid_argument) {// The Error is not invalid argument
|
||||
return 1; // Stop reading
|
||||
}
|
||||
}
|
||||
if(bytes_transferred >= minimum_) {// We have all the bytes we need
|
||||
return 1; // Stop
|
||||
} else {
|
||||
return 0; // Continue
|
||||
}
|
||||
}
|
||||
|
||||
private:
|
||||
std::size_t minimum_;
|
||||
};
|
||||
|
||||
/** Classes for Handshaking control **/
|
||||
|
||||
#if defined(BOOST_WINDOWS) || defined(__CYGWIN__)
|
||||
# define BOOST_ASIO_OPTION_STORAGE DCB
|
||||
#else
|
||||
# define BOOST_ASIO_OPTION_STORAGE termios
|
||||
#endif
|
||||
|
||||
class DTRControl {
|
||||
public:
|
||||
explicit DTRControl(bool enable = false) : m_enable(enable) {};
|
||||
|
||||
boost::system::error_code store(BOOST_ASIO_OPTION_STORAGE& storage,
|
||||
boost::system::error_code& ec) const
|
||||
{
|
||||
#if defined(BOOST_WINDOWS) || defined(__CYGWIN__)
|
||||
if(m_enable)
|
||||
storage.fDtrControl = DTR_CONTROL_ENABLE;
|
||||
else
|
||||
storage.fDtrControl = DTR_CONTROL_DISABLE;
|
||||
#else
|
||||
ec = boost::asio::error::operation_not_supported;
|
||||
ec = boost::system::error_code();
|
||||
#endif
|
||||
return ec;
|
||||
};
|
||||
|
||||
boost::system::error_code load(const BOOST_ASIO_OPTION_STORAGE& storage,
|
||||
boost::system::error_code& ec)
|
||||
{
|
||||
#if defined(BOOST_WINDOWS) || defined(__CYGWIN__)
|
||||
if(storage.fDtrControl == DTR_CONTROL_ENABLE)
|
||||
m_enable = true;
|
||||
else
|
||||
m_enable = true;
|
||||
#else
|
||||
#endif
|
||||
return ec;
|
||||
};
|
||||
private:
|
||||
bool m_enable;
|
||||
};
|
||||
|
||||
class RTSControl {
|
||||
public:
|
||||
explicit RTSControl(bool enable = false) : m_enable(enable) {};
|
||||
boost::system::error_code store(BOOST_ASIO_OPTION_STORAGE& storage,
|
||||
boost::system::error_code& ec) const
|
||||
{
|
||||
#if defined(BOOST_WINDOWS) || defined(__CYGWIN__)
|
||||
if(m_enable)
|
||||
storage.fRtsControl = RTS_CONTROL_ENABLE;
|
||||
else
|
||||
storage.fRtsControl = RTS_CONTROL_DISABLE;
|
||||
#else
|
||||
ec = boost::asio::error::operation_not_supported;
|
||||
ec = boost::system::error_code();
|
||||
#endif
|
||||
return ec;
|
||||
};
|
||||
|
||||
boost::system::error_code load(const BOOST_ASIO_OPTION_STORAGE& storage,
|
||||
boost::system::error_code& ec)
|
||||
{
|
||||
#if defined(BOOST_WINDOWS) || defined(__CYGWIN__)
|
||||
if(storage.fRtsControl == RTS_CONTROL_ENABLE)
|
||||
m_enable = true;
|
||||
else
|
||||
m_enable = true;
|
||||
#else
|
||||
#endif
|
||||
return ec;
|
||||
};
|
||||
private:
|
||||
bool m_enable;
|
||||
};
|
||||
|
||||
/** Serial Class Implementation **/
|
||||
|
||||
Serial::Serial() : io_service(), work(io_service), timeout_timer(io_service) {
|
||||
this->init();
|
||||
}
|
||||
|
||||
Serial::Serial(std::string port,
|
||||
int baudrate,
|
||||
long timeout,
|
||||
bytesize_t bytesize,
|
||||
parity_t parity,
|
||||
stopbits_t stopbits,
|
||||
flowcontrol_t flowcontrol)
|
||||
: io_service(), work(io_service), timeout_timer(io_service)
|
||||
{
|
||||
// Call default constructor to initialize variables
|
||||
this->init();
|
||||
|
||||
// Write provided settings
|
||||
this->port = port;
|
||||
this->setBaudrate(baudrate);
|
||||
this->setTimeoutMilliseconds(timeout);
|
||||
this->setBytesize(bytesize);
|
||||
this->setParity(parity);
|
||||
this->setStopbits(stopbits);
|
||||
this->setFlowcontrol(flowcontrol);
|
||||
|
||||
// Open the serial port
|
||||
this->open();
|
||||
}
|
||||
|
||||
void Serial::init() {
|
||||
// Boost asio variables
|
||||
this->serial_port.reset();
|
||||
|
||||
// Serial Port settings
|
||||
this->port = "";
|
||||
this->setBaudrate(DEFAULT_BAUDRATE);
|
||||
this->setTimeoutMilliseconds(DEFAULT_TIMEOUT);
|
||||
|
||||
// Private variables
|
||||
this->bytes_read = 0;
|
||||
this->bytes_to_read = 0;
|
||||
this->reading = false;
|
||||
this->nonblocking = false;
|
||||
}
|
||||
|
||||
Serial::~Serial() {
|
||||
this->close();
|
||||
}
|
||||
|
||||
void Serial::open() {
|
||||
// Make sure the Serial port is not already open.
|
||||
if(this->serial_port != NULL && this->serial_port->is_open()) {
|
||||
throw(SerialPortAlreadyOpenException(this->port.c_str()));
|
||||
}
|
||||
|
||||
// Try to open the serial port
|
||||
try {
|
||||
this->serial_port.reset(
|
||||
new boost::asio::serial_port(this->io_service, this->port));
|
||||
|
||||
this->serial_port->set_option(this->baudrate);
|
||||
this->serial_port->set_option(this->flowcontrol);
|
||||
this->serial_port->set_option(this->parity);
|
||||
this->serial_port->set_option(this->stopbits);
|
||||
this->serial_port->set_option(this->bytesize);
|
||||
} catch(std::exception &e) {
|
||||
this->serial_port.reset();
|
||||
throw(SerialPortFailedToOpenException(e.what()));
|
||||
}
|
||||
}
|
||||
|
||||
bool Serial::isOpen() {
|
||||
if(this->serial_port != NULL)
|
||||
return this->serial_port->is_open();
|
||||
return false;
|
||||
}
|
||||
|
||||
void Serial::close() {
|
||||
// Cancel the current timeout timer and async reads
|
||||
this->timeout_timer.cancel();
|
||||
if(this->serial_port != NULL) {
|
||||
this->serial_port->cancel();
|
||||
this->serial_port->close();
|
||||
this->serial_port.reset();
|
||||
}
|
||||
}
|
||||
|
||||
static const boost::posix_time::time_duration
|
||||
timeout_zero_comparison(boost::posix_time::milliseconds(0));
|
||||
|
||||
int Serial::read(char* buffer, int size) {
|
||||
this->reading = true;
|
||||
if(this->nonblocking) {// Do not wait for data
|
||||
this->serial_port->async_read_some(boost::asio::buffer(buffer, size),
|
||||
boost::bind(&Serial::read_complete, this,
|
||||
boost::asio::placeholders::error,
|
||||
boost::asio::placeholders::bytes_transferred));
|
||||
} else { // Wait for data until size is read or timeout occurs
|
||||
boost::asio::async_read(*this->serial_port, boost::asio::buffer(buffer, size), transfer_at_least_ignore_invalid_argument(size),
|
||||
boost::bind(&Serial::read_complete, this,
|
||||
boost::asio::placeholders::error,
|
||||
boost::asio::placeholders::bytes_transferred));
|
||||
}
|
||||
if(this->timeout > timeout_zero_comparison) { // Only set a timeout_timer if there is a valid timeout
|
||||
this->timeout_timer.expires_from_now(this->timeout);
|
||||
this->timeout_timer.async_wait(boost::bind(&Serial::timeout_callback, this,
|
||||
boost::asio::placeholders::error));
|
||||
} else if(this->nonblocking) {
|
||||
this->timeout_timer.expires_from_now(boost::posix_time::milliseconds(1));
|
||||
this->timeout_timer.async_wait(boost::bind(&Serial::timeout_callback, this,
|
||||
boost::asio::placeholders::error));
|
||||
}
|
||||
|
||||
while(this->reading)
|
||||
this->io_service.run_one();
|
||||
|
||||
this->bytes_to_read = size;
|
||||
|
||||
return this->bytes_read;
|
||||
}
|
||||
|
||||
std::string Serial::read(int size) {
|
||||
char *serial_buffer = new char[size];
|
||||
int bytes_read_ = this->read(serial_buffer, size);
|
||||
std::string return_str(serial_buffer, (std::size_t)bytes_read_);
|
||||
delete[] serial_buffer;
|
||||
return return_str;
|
||||
}
|
||||
|
||||
std::string
|
||||
Serial::read_until(char delim, size_t size) {
|
||||
using namespace std;
|
||||
string r = "";
|
||||
|
||||
while (r.find(delim) == string::npos) {
|
||||
string s = read(1);
|
||||
if (s.length() > 0)
|
||||
r += s;
|
||||
}
|
||||
|
||||
return r;
|
||||
}
|
||||
|
||||
std::string
|
||||
Serial::read_until(std::string delim, size_t size) {
|
||||
using namespace std;
|
||||
string r = "";
|
||||
|
||||
while (r.find(delim) == string::npos) {
|
||||
string s = read(1);
|
||||
if (s.length() > 0)
|
||||
r += s;
|
||||
}
|
||||
|
||||
return r;
|
||||
}
|
||||
|
||||
void Serial::read_complete(const boost::system::error_code& error, std::size_t bytes_transferred) {
|
||||
if(!error || error != boost::asio::error::operation_aborted) { // If there was no error OR the error wasn't operation aborted (canceled), Cancel the timer
|
||||
this->timeout_timer.cancel(); // will cause timeout_callback to fire with an error
|
||||
}
|
||||
|
||||
this->bytes_read = bytes_transferred;
|
||||
|
||||
this->reading = false;
|
||||
}
|
||||
|
||||
void Serial::timeout_callback(const boost::system::error_code& error) {
|
||||
if (!error) {
|
||||
// The timeout wasn't canceled, so cancel the async read
|
||||
this->serial_port->cancel();
|
||||
}
|
||||
}
|
||||
|
||||
int Serial::write(char data[], int length) {
|
||||
return boost::asio::write(*this->serial_port, boost::asio::buffer(data, length), boost::asio::transfer_all());
|
||||
}
|
||||
|
||||
int Serial::write(std::string data) {
|
||||
char *cstr = new char[data.size()+1];
|
||||
std::strcpy(cstr, data.c_str());
|
||||
int bytes_wrote = this->write(cstr, data.length());
|
||||
delete[] cstr;
|
||||
return bytes_wrote;
|
||||
}
|
||||
|
||||
void Serial::setRTS(bool level) {
|
||||
this->serial_port->set_option(RTSControl(level));
|
||||
}
|
||||
|
||||
void Serial::setDTR(bool level) {
|
||||
this->serial_port->set_option(DTRControl(level));
|
||||
}
|
||||
|
||||
bool Serial::getCTS() const {
|
||||
throw(boost::asio::error::operation_not_supported);
|
||||
return false;
|
||||
}
|
||||
|
||||
bool Serial::getDSR() const {
|
||||
throw(boost::asio::error::operation_not_supported);
|
||||
return false;
|
||||
}
|
||||
|
||||
void Serial::setPort(std::string port) {
|
||||
this->port = port;
|
||||
}
|
||||
|
||||
std::string Serial::getPort() const {
|
||||
return this->port;
|
||||
}
|
||||
|
||||
void Serial::setTimeoutMilliseconds(long timeout) {
|
||||
// If timeout > 0 then read until size or timeout occurs
|
||||
// If timeout == 0 then read nonblocking, return data available immediately up to size
|
||||
// If timeout < 0 then read blocking, until size is read, period.
|
||||
if(timeout > 0) {
|
||||
this->timeout = boost::posix_time::time_duration(boost::posix_time::milliseconds(timeout));
|
||||
} else {
|
||||
this->timeout = boost::posix_time::time_duration(boost::posix_time::milliseconds(0));
|
||||
}
|
||||
|
||||
if(timeout == 0)
|
||||
this->nonblocking = true;
|
||||
else // Must be negative
|
||||
this->nonblocking = false;
|
||||
}
|
||||
|
||||
long Serial::getTimeoutMilliseconds() const {
|
||||
return this->timeout.total_milliseconds();
|
||||
}
|
||||
|
||||
void Serial::setBaudrate(int baudrate) {
|
||||
this->baudrate = boost::asio::serial_port_base::baud_rate(baudrate);
|
||||
}
|
||||
|
||||
int Serial::getBaudrate() const {
|
||||
return this->baudrate.value();
|
||||
}
|
||||
|
||||
void Serial::setBytesize(bytesize_t bytesize) {
|
||||
switch(bytesize) {
|
||||
case FIVEBITS:
|
||||
this->bytesize = boost::asio::serial_port_base::character_size(5);
|
||||
break;
|
||||
case SIXBITS:
|
||||
this->bytesize = boost::asio::serial_port_base::character_size(6);
|
||||
break;
|
||||
case SEVENBITS:
|
||||
this->bytesize = boost::asio::serial_port_base::character_size(7);
|
||||
break;
|
||||
case EIGHTBITS:
|
||||
this->bytesize = boost::asio::serial_port_base::character_size(8);
|
||||
break;
|
||||
default:
|
||||
throw(InvalidBytesizeException(bytesize));
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
bytesize_t Serial::getBytesize() const {
|
||||
return bytesize_t(this->bytesize.value());
|
||||
}
|
||||
|
||||
void Serial::setParity(parity_t parity) {
|
||||
switch(parity) {
|
||||
case PARITY_NONE:
|
||||
this->parity = boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::none);
|
||||
break;
|
||||
case PARITY_ODD:
|
||||
this->parity = boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::odd);
|
||||
break;
|
||||
case PARITY_EVEN:
|
||||
this->parity = boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::even);
|
||||
break;
|
||||
default:
|
||||
throw(InvalidParityException(parity));
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
parity_t Serial::getParity() const {
|
||||
switch(this->parity.value()) {
|
||||
case boost::asio::serial_port_base::parity::none:
|
||||
return parity_t(PARITY_NONE);
|
||||
case boost::asio::serial_port_base::parity::odd:
|
||||
return parity_t(PARITY_ODD);
|
||||
case boost::asio::serial_port_base::parity::even:
|
||||
return parity_t(PARITY_EVEN);
|
||||
default:
|
||||
throw(InvalidParityException(this->parity.value()));
|
||||
}
|
||||
}
|
||||
|
||||
void Serial::setStopbits(stopbits_t stopbits) {
|
||||
switch(stopbits) {
|
||||
case STOPBITS_ONE:
|
||||
this->stopbits = boost::asio::serial_port_base::stop_bits(boost::asio::serial_port_base::stop_bits::one);
|
||||
break;
|
||||
case STOPBITS_ONE_POINT_FIVE:
|
||||
this->stopbits = boost::asio::serial_port_base::stop_bits(boost::asio::serial_port_base::stop_bits::onepointfive);
|
||||
break;
|
||||
case STOPBITS_TWO:
|
||||
this->stopbits = boost::asio::serial_port_base::stop_bits(boost::asio::serial_port_base::stop_bits::two);
|
||||
break;
|
||||
default:
|
||||
throw(InvalidStopbitsException(stopbits));
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
stopbits_t Serial::getStopbits() const {
|
||||
switch(this->stopbits.value()) {
|
||||
case boost::asio::serial_port_base::stop_bits::one:
|
||||
return stopbits_t(STOPBITS_ONE);
|
||||
case boost::asio::serial_port_base::stop_bits::onepointfive:
|
||||
return stopbits_t(STOPBITS_ONE_POINT_FIVE);
|
||||
case boost::asio::serial_port_base::stop_bits::two:
|
||||
return stopbits_t(STOPBITS_TWO);
|
||||
default:
|
||||
throw(InvalidStopbitsException(this->stopbits.value()));
|
||||
}
|
||||
}
|
||||
|
||||
void Serial::setFlowcontrol(flowcontrol_t flowcontrol) {
|
||||
switch(flowcontrol) {
|
||||
case FLOWCONTROL_NONE:
|
||||
this->flowcontrol = boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::none);
|
||||
break;
|
||||
case FLOWCONTROL_SOFTWARE:
|
||||
this->flowcontrol = boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::software);
|
||||
break;
|
||||
case FLOWCONTROL_HARDWARE:
|
||||
this->flowcontrol = boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::hardware);
|
||||
break;
|
||||
default:
|
||||
throw(InvalidFlowcontrolException(flowcontrol));
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
flowcontrol_t Serial::getFlowcontrol() const {
|
||||
switch(this->flowcontrol.value()) {
|
||||
case boost::asio::serial_port_base::flow_control::none:
|
||||
return flowcontrol_t(FLOWCONTROL_NONE);
|
||||
case boost::asio::serial_port_base::flow_control::software:
|
||||
return flowcontrol_t(FLOWCONTROL_SOFTWARE);
|
||||
case boost::asio::serial_port_base::flow_control::hardware:
|
||||
return flowcontrol_t(FLOWCONTROL_HARDWARE);
|
||||
default:
|
||||
throw(InvalidFlowcontrolException(this->flowcontrol.value()));
|
||||
}
|
||||
}
|
||||
Loading…
x
Reference in New Issue
Block a user