1
0
mirror of https://github.com/wjwwood/serial.git synced 2026-01-22 19:54:57 +08:00

working on new boostless serial with a pimpl setup

This commit is contained in:
William Woodall 2012-01-10 14:19:56 -06:00
parent 709fa5e174
commit 18284ae764
7 changed files with 1034 additions and 397 deletions

View File

@ -13,7 +13,7 @@ void callback(std::string line) {
std::cout << "callback got a: " << line << std::endl; std::cout << "callback got a: " << line << std::endl;
} }
#if 0 #if 1
int main(void) { int main(void) {
Serial serial("/dev/tty.usbmodemfd1231", 115200); Serial serial("/dev/tty.usbmodemfd1231", 115200);
@ -41,6 +41,7 @@ int main(void) {
} }
#endif #endif
#if 0
int main(void) { int main(void) {
Serial serial("/dev/tty.usbmodemfd1231", 115200); Serial serial("/dev/tty.usbmodemfd1231", 115200);
@ -59,3 +60,4 @@ int main(void) {
} }
} }
#endif

View File

@ -0,0 +1,90 @@
/*!
* \file serial/impl/unix.h
* \author William Woodall <wjwwood@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 unix based pimpl for the Serial class.
*/
#ifndef SERIAL_IMPL_UNIX_H
#define SERIAL_IMPL_UNIX_H
#include "serial/serial.h"
namespace {
class Serial::Serial_pimpl {
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 ();
void open ();
void close ();
bool isOpen ();
size_t read (unsigned char* buffer, size_t size = 1);
std::string read (size_t size = 1);
size_t read (std::string &buffer, size_t size = 1);
size_t write (unsigned char* data, size_t length);
size_t write (const std::string &data);
void setPort (const std::string &port);
std::string getPort () const;
void setTimeout (long timeout);
long getTimeout () const;
void setBaudrate (int baudrate);
int 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;
};
}
#endif // SERIAL_IMPL_UNIX_H

View File

@ -1,21 +1,21 @@
/** /*!
* @file serial.h * \file serial/serial.h
* @author William Woodall <wjwwood@gmail.com> * \author William Woodall <wjwwood@gmail.com>
* @author John Harrison <ash.gti@gmail.com> * \author John Harrison <ash.gti@gmail.com>
* @version 0.1 * \version 0.1
* *
* @section LICENSE * \section LICENSE
* *
* The MIT License * The MIT License
* *
* Copyright (c) 2011 William Woodall * Copyright (c) 2011 William Woodall
* *
* Permission is hereby granted, free of charge, to any person obtaining a copy * Permission is hereby granted, free of charge, to any person obtaining a
* of this software and associated documentation files (the "Software"), to deal * copy of this software and associated documentation files (the "Software"),
* in the Software without restriction, including without limitation the rights * to deal in the Software without restriction, including without limitation
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell * the rights to use, copy, modify, merge, publish, distribute, sublicense,
* copies of the Software, and to permit persons to whom the Software is * and/or sell copies of the Software, and to permit persons to whom the
* furnished to do so, subject to the following conditions: * Software is furnished to do so, subject to the following conditions:
* *
* The above copyright notice and this permission notice shall be included in * The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software. * all copies or substantial portions of the Software.
@ -24,11 +24,11 @@
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* THE SOFTWARE. * DEALINGS IN THE SOFTWARE.
* *
* @section DESCRIPTION * \section DESCRIPTION
* *
* This provides a cross platform interface for interacting with Serial Ports. * This provides a cross platform interface for interacting with Serial Ports.
*/ */
@ -37,356 +37,345 @@
#ifndef SERIAL_H #ifndef SERIAL_H
#define 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 { namespace serial {
// Serial Port settings CONSTANTS /*!
enum bytesize_t { FIVEBITS = 5, SIXBITS = 6, SEVENBITS = 7, EIGHTBITS = 8 }; * Enumeration defines the possible bytesizes for the serial port.
enum parity_t { PARITY_NONE, PARITY_ODD, PARITY_EVEN }; */
enum stopbits_t { STOPBITS_ONE, STOPBITS_ONE_POINT_FIVE, STOPBITS_TWO }; typedef enum {
enum flowcontrol_t { FLOWCONTROL_NONE, FLOWCONTROL_SOFTWARE, FLOWCONTROL_HARDWARE }; FIVEBITS = 5,
SIXBITS = 6,
SEVENBITS = 7,
EIGHTBITS = 8
} bytesize_t;
/*!
* Enumeration defines the possible parity types for the serial port.
*/
typedef enum {
PARITY_NONE = 0,
PARITY_ODD = 1,
PARITY_EVEN = 2
} parity_t;
/*!
* Enumeration defines the possible stopbit types for the serial port.
*/
typedef enum {
STOPBITS_ONE = 1,
STOPBITS_ONE_POINT_FIVE,
STOPBITS_TWO = 2
} stopbits_t;
/*!
* Enumeration defines the possible flowcontrol types for the serial port.
*/
typedef enum {
FLOWCONTROL_NONE = 0,
FLOWCONTROL_SOFTWARE,
FLOWCONTROL_HARDWARE
} flowcontrol_t;
/*!
* Class that provides a portable serial port interface.
*/
class Serial { class Serial {
public: public:
/** Constructor, Creates a Serial object but doesn't open the serial port. */ /*!
Serial();
/**
* Constructor, creates a SerialPortBoost object and opens the port. * Constructor, creates a SerialPortBoost object and opens the port.
* *
* @param port A std::string containing the address of the serial port, * \param port A std::string containing the address of the serial port,
* which would be something like 'COM1' on Windows and '/dev/ttyS0' * which would be something like 'COM1' on Windows and '/dev/ttyS0'
* on Linux. * on Linux.
* *
* @param baudrate An integer that represents the buadrate * \param baudrate An integer that represents the buadrate
* *
* @param timeout A long that represents the time (in milliseconds) until a * \param timeout A long that represents the time (in milliseconds) until a
* timeout on reads occur. Setting this to zero (0) will cause reading * timeout on reads occur. Setting this to zero (0) will cause reading to
* to be non-blocking, i.e. the available data will be returned immediately, * 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 * but it will not block to wait for more. Setting this to a number less
* zero (-1) will result in infinite blocking behaviour, i.e. the serial port will * than zero (-1) will result in infinite blocking behaviour, i.e. the
* block until either size bytes have been read or an exception has occured. * 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, * \param bytesize Size of each byte in the serial transmission of data,
* default is EIGHTBITS, possible values are: FIVEBITS, * default is EIGHTBITS, possible values are: FIVEBITS, SIXBITS, SEVENBITS,
* SIXBITS, SEVENBITS, EIGHTBITS * EIGHTBITS
* *
* @param parity Method of parity, default is PARITY_NONE, possible values * \param parity Method of parity, default is PARITY_NONE, possible values
* are: PARITY_NONE, PARITY_ODD, PARITY_EVEN * are: PARITY_NONE, PARITY_ODD, PARITY_EVEN
* *
* @param stopbits Number of stop bits used, default is STOPBITS_ONE, possible * \param stopbits Number of stop bits used, default is STOPBITS_ONE,
* values are: STOPBITS_ONE, STOPBITS_ONE_POINT_FIVE, STOPBITS_TWO * possible values are: STOPBITS_ONE, STOPBITS_ONE_POINT_FIVE, STOPBITS_TWO
* *
* @param flowcontrol Type of flowcontrol used, default is FLOWCONTROL_NONE, possible * \param flowcontrol Type of flowcontrol used, default is
* values are: FLOWCONTROL_NONE, FLOWCONTROL_SOFTWARE, FLOWCONTROL_HARDWARE * FLOWCONTROL_NONE, possible values are: FLOWCONTROL_NONE,
* FLOWCONTROL_SOFTWARE, FLOWCONTROL_HARDWARE
* *
* @throw SerialPortAlreadyOpenException * \throw PortNotOpenedException
* @throw SerialPortFailedToOpenException
*/ */
Serial(std::string port, Serial (const std::string &port = "",
int baudrate = DEFAULT_BAUDRATE, int baudrate = 9600,
long timeout = DEFAULT_TIMEOUT, long timeout = 0,
bytesize_t bytesize = DEFAULT_BYTESIZE, bytesize_t bytesize = EIGHTBITS,
parity_t parity = DEFAULT_PARITY, parity_t parity = PARITY_NONE,
stopbits_t stopbits = DEFAULT_STOPBITS, stopbits_t stopbits = STOPBITS_ONE,
flowcontrol_t flowcontrol = DEFAULT_FLOWCONTROL); flowcontrol_t flowcontrol = FLOWCONTROL_NONE);
/** Destructor */ /*! Destructor */
~Serial(); virtual ~Serial ();
/** /*!
* Opens the serial port as long as the portname is set and the port isn't alreay open. * Opens the serial port as long as the portname is set and the port isn't
* alreay open.
* *
* @throw SerialPortAlreadyOpenException * If the port is provided to the constructor then an explicit call to open
* @throw SerialPortFailedToOpenException * is not needed.
*
* \see Serial::Serial
*
* \throw PortNotOpenedException
*/ */
void open(); void
open ();
/** Gets the status of the serial port. /*! Gets the open status of the serial port.
* *
* @return A boolean value that represents whether or not the serial port is open. * \return Returns true if the port is open, false otherwise.
*/ */
bool isOpen(); bool
isOpen ();
/** Closes the serial port and terminates threads. */ /*! Closes the serial port. */
void close(); void
close ();
/** Read size bytes from the serial port. /*! Read a given amount of 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. * 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 or until an exception occurs.
* *
* @param size An integer defining how many bytes to be read. * \param buffer An unsigned char array large enough to hold incoming data
* up to the requested size.
* *
* @return An integer representing the number of bytes read. * \param size A size_t defining how many bytes to be read.
*
* \return A size_t representing the number of bytes actually read.
*/ */
int read(char* buffer, int size = 1); size_t
read (unsigned char* buffer, size_t size = 1);
/** Read size bytes from the serial port. /*! Read a given amount of 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. * 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 or until an exception occurs.
* *
* @return A std::string containing the data read. * \param size A size_t defining how many bytes to be read.
*
* \return A std::string containing the data read.
*/ */
std::string read(int size = 1); std::string
read (size_t size = 1);
std::string read_until(char delim, size_t size = -1); /*! Read a given amount of bytes from the serial port.
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. * Reads into a std::string by reference rather than returning it.
* *
* @param length An integer representing the number of bytes to be written. * \param buffer A std::string reference for reading to.
* \param size A size_t defining how many bytes to be read.
* *
* @return An integer representing the number of bytes written. * \return A size_t that represents how many bytes were read.
*
* \see Serial::read(size_t)
*/ */
int write(char data[], int length); size_t
read (const std::string &buffer, size_t size = 1);
/** Write a string to the serial port. /*! Write bytes from the data to the serial port by given length.
* *
* @param data A std::string to be written to the serial port. (must be null terminated) * \param data An unsigned char array containing data to be written to the
* serial port.
* *
* @return An integer representing the number of bytes written to the serial port. * \param length A size_t representing the number of bytes to be written.
*
* \return A size_t representing the number of bytes actually written.
*/ */
int write(std::string data); size_t
write (unsigned char* data, size_t length);
/** Sets the logic level of the RTS line. /*! Write a string to the serial port.
* *
* @param level The logic level to set the RTS to. Defaults to true. * \param data A const std::string reference containg the data to be written
* to the serial port.
*
* \return A size_t representing the number of bytes actually written to
* the serial port.
*/ */
void setRTS(bool level = true); size_t
write (const std::string &data);
/** Sets the logic level of the DTR line. /*! Sets the serial port identifier.
* *
* @param level The logic level to set the DTR to. Defaults to true. * \param port A const std::string reference containing the address of the
* serial port, which would be something like 'COM1' on Windows and
* '/dev/ttyS0' on Linux.
*
* \throw InvalidConfigurationException
*/ */
void setDTR(bool level = true); void
setPort (const std::string &port);
/** Gets the status of the CTS line. /*! Gets the serial port identifier.
* *
* @return A boolean value that represents the current logic level of the CTS line. * \see Serial::setPort
*
* \throw InvalidConfigurationException
*/ */
bool getCTS() const; std::string
getPort () const;
/** Gets the status of the DSR line. /*! Sets the timeout for reads in milliseconds.
* *
* @return A boolean value that represents the current logic level of the DSR line. * \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.
*/ */
bool getDSR() const; void
setTimeout (long timeout);
/** Sets the serial port identifier. /*! Gets the timeout for reads in seconds.
* *
* @param port A std::string containing the address of the serial port, * \see Serial::setTimeout
* which would be something like 'COM1' on Windows and '/dev/ttyS0'
* on Linux.
*/ */
void setPort(std::string port); long
getTimeout () const;
/** Gets the serial port identifier. /*! Sets the baudrate for the serial port.
* *
* @return A std::string containing the address of the serial port, * Possible baudrates depends on the system but some safe baudrates include:
* which would be something like 'COM1' on Windows and '/dev/ttyS0' * 110, 300, 600, 1200, 2400, 4800, 9600, 14400, 19200, 28800, 38400, 56000,
* on Linux. * 57600, 115200
* Some other baudrates that are supported by some comports:
* 128000, 153600, 230400, 256000, 460800, 921600
*
* \param baudrate An integer that sets the baud rate for the serial port.
*
* \throw InvalidConfigurationException
*/ */
std::string getPort() const; void
setBaudrate (int baudrate);
/** Sets the timeout for reads in seconds. /*! Gets the baudrate for the serial port.
* *
* @param timeout A long that represents the time (in milliseconds) until a * \return An integer that sets the baud rate for the serial port.
* 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, * \see Serial::setBaudrate
* 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 * \throw InvalidConfigurationException
* block until either size bytes have been read or an exception has occured.
*/ */
void setTimeoutMilliseconds(long timeout); int
getBaudrate () const;
/** Gets the timeout for reads in seconds. /*! Sets the bytesize for the serial port.
* *
* @param timeout A long that represents the time (in milliseconds) until a * \param bytesize Size of each byte in the serial transmission of data,
* timeout on reads occur. Setting this to zero (0) will cause reading * default is EIGHTBITS, possible values are: FIVEBITS, SIXBITS, SEVENBITS,
* to be non-blocking, i.e. the available data will be returned immediately, * EIGHTBITS
* 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 * \throw InvalidConfigurationException
* block until either size bytes have been read or an exception has occured.
*/ */
long getTimeoutMilliseconds() const; void
setBytesize (bytesize_t bytesize);
/** Sets the baudrate for the serial port. /*! Gets the bytesize for the serial port.
* *
* @param baudrate An integer that sets the baud rate for the serial port. * \see Serial::setBytesize
*
* \throw InvalidConfigurationException
*/ */
void setBaudrate(int baudrate); bytesize_t
getBytesize () const;
/** Gets the baudrate for the serial port. /*! Sets the parity for the serial port.
* *
* @return An integer that sets the baud rate for the serial port. * \param parity Method of parity, default is PARITY_NONE, possible values
*/
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 * are: PARITY_NONE, PARITY_ODD, PARITY_EVEN
* *
* @throw InvalidParityException * \throw InvalidConfigurationException
*/ */
void setParity(parity_t parity); void
setParity (parity_t parity);
/** Gets the parity for the serial port. /*! Gets the parity for the serial port.
* *
* @return Method of parity, default is PARITY_NONE, possible values * \see Serial::setParity
* are: PARITY_NONE, PARITY_ODD, PARITY_EVEN
* *
* @throw InvalidParityException * \throw InvalidConfigurationException
*/ */
parity_t getParity() const; parity_t
getParity () const;
/** Sets the stopbits for the serial port. /*! Sets the stopbits for the serial port.
* *
* @param stopbits Number of stop bits used, default is STOPBITS_ONE, possible * \param stopbits Number of stop bits used, default is STOPBITS_ONE,
* values are: STOPBITS_ONE, STOPBITS_ONE_POINT_FIVE, STOPBITS_TWO * possible values are: STOPBITS_ONE, STOPBITS_ONE_POINT_FIVE, STOPBITS_TWO
* *
* @throw InvalidStopbitsException * \throw InvalidConfigurationException
*/ */
void setStopbits(stopbits_t stopbits); void
setStopbits (stopbits_t stopbits);
/** Gets the stopbits for the serial port. /*! Gets the stopbits for the serial port.
* *
* @return Number of stop bits used, default is STOPBITS_ONE, possible * \see Serial::setStopbits
* values are: STOPBITS_ONE, STOPBITS_ONE_POINT_FIVE, STOPBITS_TWO
* *
* @throw InvalidStopbitsException * \throw InvalidConfigurationException
*/ */
stopbits_t getStopbits() const; stopbits_t
getStopbits () const;
/** Sets the flow control for the serial port. /*! Sets the flow control for the serial port.
* *
* @param flowcontrol Type of flowcontrol used, default is FLOWCONTROL_NONE, possible * \param flowcontrol Type of flowcontrol used, default is FLOWCONTROL_NONE,
* values are: FLOWCONTROL_NONE, FLOWCONTROL_SOFTWARE, FLOWCONTROL_HARDWARE * possible values are: FLOWCONTROL_NONE, FLOWCONTROL_SOFTWARE,
* FLOWCONTROL_HARDWARE
* *
* @throw InvalidFlowcontrolException * \throw InvalidConfigurationException
*/ */
void setFlowcontrol(flowcontrol_t flowcontrol); void
setFlowcontrol (flowcontrol_t flowcontrol);
/** Gets the flow control for the serial port. /*! Gets the flow control for the serial port.
* *
* @return Type of flowcontrol used, default is FLOWCONTROL_NONE, possible * \see Serial::setFlowcontrol
* values are: FLOWCONTROL_NONE, FLOWCONTROL_SOFTWARE, FLOWCONTROL_HARDWARE
* *
* @throw InvalidFlowcontrolException * \throw InvalidConfigurationException
*/ */
flowcontrol_t getFlowcontrol() const; flowcontrol_t
getFlowcontrol () const;
private: private:
DISALLOW_COPY_AND_ASSIGN(Serial); // Disable copy constructors
void init(); Serial(const Serial&);
void read_complete(const boost::system::error_code& error, std::size_t bytes_transferred); void operator=(const Serial&);
void timeout_callback(const boost::system::error_code& error); const Serial& operator=(Serial);
boost::asio::io_service io_service; // Pimpl idiom, d_pointer
class Serial_pimpl;
std::shared_ptr<Serial_pimpl> pimpl;
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 { class IOException : 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; const char * e_what;
public: public:
SerialPortFailedToOpenException(const char * e_what) {this->e_what = e_what;} IOException(const char * e_what) {this->e_what = e_what;}
virtual const char* what() const throw() { virtual const char* what() const throw() {
std::stringstream ss; std::stringstream ss;
@ -395,50 +384,26 @@ public:
} }
}; };
class InvalidBytesizeException : public std::exception { class PortNotOpenedException : public std::exception {
const char * e_what;
public:
PortNotOpenedException(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 InvalidConfigurationException : public std::exception {
int bytesize; int bytesize;
public: public:
InvalidBytesizeException(int bytesize) {this->bytesize = bytesize;} InvalidConfigurationException(int bytesize) {this->bytesize = bytesize;}
virtual const char* what() const throw() { virtual const char* what() const throw() {
std::stringstream ss; std::stringstream ss;
ss << "Invalid bytesize provided: " << this->bytesize; ss << "Invalid configuration 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(); return ss.str().c_str();
} }
}; };

448
include/serial/serial_old.h Normal file
View File

@ -0,0 +1,448 @@
/**
* @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

132
src/impl/unix.cc Normal file
View File

@ -0,0 +1,132 @@
#include "serial/impl/unix.h"
using namespace serial;
Serial_pimpl::Serial_pimpl (const std::string &port, int baudrate,
long timeout, bytesize_t bytesize,
parity_t parity, stopbits_t stopbits,
flowcontrol_t flowcontrol)
: port(port), baudrate(baudrate), timeout(timeout), bytesize(bytesize),
parity(parity), stopbits(stopbits), flowcontrol(flowcontrol)
{
}
Serial_pimpl::~Serial_pimpl () {
}
void
Serial_pimpl::open () {
}
void
Serial_pimpl::close () {
}
bool
Serial_pimpl::isOpen () {
}
size_t
Serial_pimpl::read (unsigned char* buffer, size_t size = 1) {
}
std::string
Serial_pimpl::read (size_t size = 1) {
}
size_t
Serial_pimpl::read (std::string &buffer, size_t size = 1) {
}
size_t
Serial_pimpl::write (unsigned char* data, size_t length) {
}
size_t
Serial_pimpl::write (const std::string &data) {
}
void
Serial_pimpl::setPort (const std::string &port) {
}
std::string
Serial_pimpl::getPort () const {
}
void
Serial_pimpl::setTimeout (long timeout) {
}
long
Serial_pimpl::getTimeout () const {
}
void
Serial_pimpl::setBaudrate (int baudrate) {
}
int
Serial_pimpl::getBaudrate () const {
}
void
Serial_pimpl::setBytesize (bytesize_t bytesize) {
}
bytesize_t
Serial_pimpl::getBytesize () const {
}
void
Serial_pimpl::setParity (parity_t parity) {
}
parity_t
Serial_pimpl::getParity () const {
}
void
Serial_pimpl::setStopbits (stopbits_t stopbits) {
}
stopbits_t
Serial_pimpl::getStopbits () const {
}
void
Serial_pimpl::setFlowcontrol (flowcontrol_t flowcontrol) {
}
flowcontrol_t
Serial_pimpl::getFlowcontrol () const {
}

View File

@ -146,7 +146,7 @@ SerialListener::determineAmountToRead() {
// TODO: Make a more intelligent method based on the length of the things // TODO: Make a more intelligent method based on the length of the things
// filters are looking for. i.e.: if the filter is looking for 'V=XX\r' // filters are looking for. i.e.: if the filter is looking for 'V=XX\r'
// make the read amount at least 5. // make the read amount at least 5.
return 1024; return 5;
} }
void void