From b78a44e9a7401cc9668d030f982f6fd36944fe21 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 22 Mar 2011 10:39:28 -0500 Subject: [PATCH] Cleaned up the library, added a namespace. Also implemented some suggestions of john's. --- include/serial.h | 92 ++++++++++++++++++-------- src/serial.cpp | 158 +++++++++++++++++++++++++------------------- src/test_serial.cpp | 15 +++-- 3 files changed, 162 insertions(+), 103 deletions(-) diff --git a/include/serial.h b/include/serial.h index e176a16..8e25b04 100644 --- a/include/serial.h +++ b/include/serial.h @@ -55,11 +55,13 @@ #define DEFAULT_STOPBITS STOPBITS_ONE #define DEFAULT_FLOWCONTROL FLOWCONTROL_NONE +namespace serial { + // Serial Port settings CONSTANTS -enum { FIVEBITS, SIXBITS, SEVENBITS, EIGHTBITS }; -enum { PARITY_NONE, PARITY_ODD, PARITY_EVEN }; -enum { STOPBITS_ONE, STOPBITS_ONE_POINT_FIVE, STOPBITS_TWO }; -enum { FLOWCONTROL_NONE, FLOWCONTROL_SOFTWARE, FLOWCONTROL_HARDWARE }; +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: @@ -75,9 +77,12 @@ public: * * @param baudrate An integer that represents the buadrate * - * @param timeout A double that represents the time (in seconds) until a - * timeout on reads occur. Setting this to a number less than or - * equal to zero will silently disable the timeout on reads. + * @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, @@ -97,11 +102,11 @@ public: */ Serial(std::string port, int baudrate = DEFAULT_BAUDRATE, - double timeout = DEFAULT_TIMEOUT, - int bytesize = DEFAULT_BYTESIZE, - int parity = DEFAULT_PARITY, - int stopbits = DEFAULT_STOPBITS, - int flowcontrol = DEFAULT_FLOWCONTROL); + 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(); @@ -183,13 +188,23 @@ public: /** Sets the timeout for reads in seconds. * - * @param timeout A long that specifies how long the read timeout is 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. * - * @return A long that specifies how long the read timeout is 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(); @@ -210,58 +225,74 @@ public: * @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(int bytesize); + 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 */ - int getBytesize(); + bytesize_t getBytesize(); /** 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(int parity); + 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 */ - int getParity(); + parity_t getParity(); /** 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(int stopbits); + 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 */ - int getStopbits(); + stopbits_t getStopbits(); /** 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(int flowcontrol); + 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 */ - int getFlowcontrol(); + flowcontrol_t getFlowcontrol(); private: void init(); void read_complete(const boost::system::error_code& error, std::size_t bytes_transferred); @@ -269,23 +300,24 @@ private: boost::asio::io_service io_service; - boost::asio::io_service::work * work; + boost::asio::io_service::work work; boost::asio::serial_port * serial_port; - boost::asio::deadline_timer * timeout_timer; + boost::asio::deadline_timer timeout_timer; std::string port; - boost::asio::serial_port_base::baud_rate * baudrate; + 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; + 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 { @@ -360,4 +392,6 @@ public: } }; +} // namespace serial + #endif \ No newline at end of file diff --git a/src/serial.cpp b/src/serial.cpp index 50c258a..e2b0732 100644 --- a/src/serial.cpp +++ b/src/serial.cpp @@ -1,5 +1,7 @@ #include "serial.h" +using namespace serial; + /** Completion Conditions **/ class transfer_at_least_ignore_invalid_argument { @@ -110,17 +112,18 @@ private: /** Serial Class Implementation **/ -Serial::Serial() { +Serial::Serial() : io_service(), work(io_service), timeout_timer(io_service) { this->init(); } Serial::Serial(std::string port, int baudrate, - double timeout, - int bytesize, - int parity, - int stopbits, - int flowcontrol) + 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(); @@ -140,9 +143,7 @@ Serial::Serial(std::string port, void Serial::init() { // Boost asio variables - this->work = new boost::asio::io_service::work(this->io_service); this->serial_port = NULL; - this->timeout_timer = new boost::asio::deadline_timer(this->io_service); // Serial Port settings this->port = ""; @@ -153,6 +154,7 @@ void Serial::init() { this->bytes_read = 0; this->bytes_to_read = 0; this->reading = false; + this->nonblocking = false; } Serial::~Serial() { @@ -169,11 +171,11 @@ void Serial::open() { try { this->serial_port = 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); + 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) { throw(SerialPortFailedToOpenException(e.what())); this->serial_port = NULL; @@ -182,20 +184,28 @@ void Serial::open() { void Serial::close() { // Cancel the current timeout timer and async reads - this->timeout_timer->cancel(); + this->timeout_timer.cancel(); this->serial_port->cancel(); this->serial_port->close(); } int Serial::read(char* buffer, int size) { this->reading = true; - 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)); - timeout_timer->expires_from_now(*this->timeout); - timeout_timer->async_wait(boost::bind(&Serial::timeout_callback, this, - boost::asio::placeholders::error)); + if(this->nonblocking) // Do not wait for data + boost::asio::async_read(*this->serial_port, 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 != NULL) { // 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)); + } while(this->reading) this->io_service.run_one(); @@ -206,14 +216,16 @@ int Serial::read(char* buffer, int size) { } std::string Serial::read(int size) { - char serial_buffer[size]; + char *serial_buffer = new char[size]; int bytes_read_ = this->read(serial_buffer, size); - return std::string(serial_buffer, (std::size_t)bytes_read_); + std::string return_str(serial_buffer, (std::size_t)bytes_read_); + delete serial_buffer; + return return_str; } 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->timeout_timer.cancel(); // will cause timeout_callback to fire with an error } this->bytes_read = bytes_transferred; @@ -233,10 +245,11 @@ int Serial::write(char data[], int length) { } int Serial::write(std::string data) { - char * cstr; - cstr = new char[data.size()+1]; + char *cstr = new char[data.size()+1]; std::strcpy(cstr, data.c_str()); - return this->write(cstr, data.length()); + int bytes_wrote = this->write(cstr, data.length()); + delete cstr; + return bytes_wrote; } void Serial::setRTS(bool level) { @@ -258,11 +271,19 @@ bool Serial::getDSR() { } void Serial::setTimeoutMilliseconds(long timeout) { - if(timeout > 0.0) { + // 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 = new boost::posix_time::milliseconds(timeout); } else { this->timeout = NULL; } + + if(timeout == 0) + this->nonblocking = true; + else // Must be negative + this->nonblocking = false; } long Serial::getTimeoutMilliseconds() { @@ -270,26 +291,26 @@ long Serial::getTimeoutMilliseconds() { } void Serial::setBaudrate(int baudrate) { - this->baudrate = new boost::asio::serial_port_base::baud_rate(baudrate); + this->baudrate = boost::asio::serial_port_base::baud_rate(baudrate); } int Serial::getBaudrate() { - return this->baudrate->value(); + return this->baudrate.value(); } -void Serial::setBytesize(int bytesize) { +void Serial::setBytesize(bytesize_t bytesize) { switch(bytesize) { case FIVEBITS: - this->bytesize = new boost::asio::serial_port_base::character_size(5); + this->bytesize = boost::asio::serial_port_base::character_size(5); break; case SIXBITS: - this->bytesize = new boost::asio::serial_port_base::character_size(6); + this->bytesize = boost::asio::serial_port_base::character_size(6); break; case SEVENBITS: - this->bytesize = new boost::asio::serial_port_base::character_size(7); + this->bytesize = boost::asio::serial_port_base::character_size(7); break; case EIGHTBITS: - this->bytesize = new boost::asio::serial_port_base::character_size(8); + this->bytesize = boost::asio::serial_port_base::character_size(8); break; default: throw(InvalidBytesizeException(bytesize)); @@ -297,20 +318,20 @@ void Serial::setBytesize(int bytesize) { } } -int Serial::getBytesize() { - return this->bytesize->value(); +bytesize_t Serial::getBytesize() { + return bytesize_t(this->bytesize.value()); } -void Serial::setParity(int parity) { +void Serial::setParity(parity_t parity) { switch(parity) { case PARITY_NONE: - this->parity = new boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::none); + this->parity = boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::none); break; case PARITY_ODD: - this->parity = new boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::odd); + this->parity = boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::odd); break; case PARITY_EVEN: - this->parity = new boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::even); + this->parity = boost::asio::serial_port_base::parity(boost::asio::serial_port_base::parity::even); break; default: throw(InvalidParityException(parity)); @@ -318,28 +339,29 @@ void Serial::setParity(int parity) { } } -int Serial::getParity() { - switch(this->parity->value()) { +parity_t Serial::getParity() { + switch(this->parity.value()) { case boost::asio::serial_port_base::parity::none: - return PARITY_NONE; + return parity_t(PARITY_NONE); case boost::asio::serial_port_base::parity::odd: - return PARITY_ODD; + return parity_t(PARITY_ODD); case boost::asio::serial_port_base::parity::even: - return PARITY_EVEN; + return parity_t(PARITY_EVEN); + default: + throw(InvalidParityException(this->parity.value())); } - return -1; } -void Serial::setStopbits(int stopbits) { +void Serial::setStopbits(stopbits_t stopbits) { switch(stopbits) { case STOPBITS_ONE: - this->stopbits = new boost::asio::serial_port_base::stop_bits(boost::asio::serial_port_base::stop_bits::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 = new boost::asio::serial_port_base::stop_bits(boost::asio::serial_port_base::stop_bits::onepointfive); + this->stopbits = boost::asio::serial_port_base::stop_bits(boost::asio::serial_port_base::stop_bits::onepointfive); break; case STOPBITS_TWO: - this->stopbits = new boost::asio::serial_port_base::stop_bits(boost::asio::serial_port_base::stop_bits::two); + this->stopbits = boost::asio::serial_port_base::stop_bits(boost::asio::serial_port_base::stop_bits::two); break; default: throw(InvalidStopbitsException(stopbits)); @@ -347,28 +369,29 @@ void Serial::setStopbits(int stopbits) { } } -int Serial::getStopbits() { - switch(this->parity->value()) { +stopbits_t Serial::getStopbits() { + switch(this->stopbits.value()) { case boost::asio::serial_port_base::stop_bits::one: - return STOPBITS_ONE; + return stopbits_t(STOPBITS_ONE); case boost::asio::serial_port_base::stop_bits::onepointfive: - return STOPBITS_ONE_POINT_FIVE; + return stopbits_t(STOPBITS_ONE_POINT_FIVE); case boost::asio::serial_port_base::stop_bits::two: - return STOPBITS_TWO; + return stopbits_t(STOPBITS_TWO); + default: + throw(InvalidStopbitsException(this->stopbits.value())); } - return -1; } -void Serial::setFlowcontrol(int flowcontrol) { +void Serial::setFlowcontrol(flowcontrol_t flowcontrol) { switch(flowcontrol) { case FLOWCONTROL_NONE: - this->flowcontrol = new boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::none); + this->flowcontrol = boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::none); break; case FLOWCONTROL_SOFTWARE: - this->flowcontrol = new boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::software); + this->flowcontrol = boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::software); break; case FLOWCONTROL_HARDWARE: - this->flowcontrol = new boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::hardware); + this->flowcontrol = boost::asio::serial_port_base::flow_control(boost::asio::serial_port_base::flow_control::hardware); break; default: throw(InvalidFlowcontrolException(flowcontrol)); @@ -376,14 +399,15 @@ void Serial::setFlowcontrol(int flowcontrol) { } } -int Serial::getFlowcontrol() { - switch(this->parity->value()) { +flowcontrol_t Serial::getFlowcontrol() { + switch(this->flowcontrol.value()) { case boost::asio::serial_port_base::flow_control::none: - return FLOWCONTROL_NONE; + return flowcontrol_t(FLOWCONTROL_NONE); case boost::asio::serial_port_base::flow_control::software: - return FLOWCONTROL_SOFTWARE; + return flowcontrol_t(FLOWCONTROL_SOFTWARE); case boost::asio::serial_port_base::flow_control::hardware: - return FLOWCONTROL_HARDWARE; + return flowcontrol_t(FLOWCONTROL_HARDWARE); + default: + throw(InvalidFlowcontrolException(this->flowcontrol.value())); } - return -1; } \ No newline at end of file diff --git a/src/test_serial.cpp b/src/test_serial.cpp index b0dd850..568707b 100644 --- a/src/test_serial.cpp +++ b/src/test_serial.cpp @@ -3,19 +3,20 @@ #include "serial.h" -Serial *serial; - int main(int argc, char **argv) { - std::string port("/dev/tty.usbserial-A900cfJA"); - // std::string port("/dev/tty.usbmodemfa141"); + if(argc < 2) { + std::cerr << "Usage: test_serial " << std::endl; + return 0; + } + std::string port(argv[1]); - serial = new Serial(port, 115200, 250); + serial::Serial serial(port, 115200, 250); int count = 0; while (count >= 0) { - int bytes_wrote = serial->write("Testing."); - std::string result = serial->read(8); + int bytes_wrote = serial.write("Testing."); + std::string result = serial.read(8); if(count % 10 == 0) std::cout << ">" << count << ">" << bytes_wrote << ">" << result << std::endl;