]> Git Repo - serial.git/commitdiff
Adding in an internal buffer to Serial, this is independent of the SerialImpl and...
authorJohn Harrison <[email protected]>
Sun, 15 Jan 2012 08:06:38 +0000 (02:06 -0600)
committerJohn Harrison <[email protected]>
Sun, 15 Jan 2012 08:06:38 +0000 (02:06 -0600)
Also correcting my styles to match the style guide and adding in some documentation.

Makefile
README.md
include/serial/impl/unix.h
include/serial/serial.h
include/serial/serial_listener.h
serial.cmake
src/impl/unix.cc
src/serial.cc
src/serial_listener.cc
tests/serial_tests.cc

index 914dad535207a746c6a62e068c4ae31f63424302..c4c54486956a4f351fd4b22d7de9684774a426f0 100644 (file)
--- a/Makefile
+++ b/Makefile
@@ -1,10 +1,9 @@
-# ash_gti's dumb downed makefile so I can more easily test stuff
+# ash_gti's dumb downed makefile so I can more easily test stuff
 # CXX=clang++
-# CXXFLAGS=-g -I./include
+# CXXFLAGS=-g -I./include -ferror-limit=5 -O3 -Wall -Weffc++ -pedantic -pedantic-errors -Wextra  -Wall -Waggregate-return -Wcast-align -Wcast-qual  -Wchar-subscripts  -Wcomment -Wconversion -Wdisabled-optimization -Wfloat-equal  -Wformat  -Wformat=2 -Wformat-nonliteral -Wformat-security  -Wformat-y2k -Wimplicit  -Wimport  -Winit-self  -Winline -Winvalid-pch   -Wlong-long -Wmissing-braces -Wmissing-field-initializers -Wmissing-format-attribute   -Wmissing-include-dirs -Wmissing-noreturn -Wpacked -Wparentheses  -Wpointer-arith -Wredundant-decls -Wreturn-type -Wsequence-point  -Wshadow -Wsign-compare  -Wstack-protector -Wstrict-aliasing -Wstrict-aliasing=2 -Wswitch  -Wswitch-default -Wswitch-enum -Wtrigraphs  -Wuninitialized -Wunknown-pragmas  -Wunreachable-code -Wunused -Wunused-function  -Wunused-label  -Wunused-parameter -Wunused-value  -Wunused-variable  -Wvariadic-macros -Wvolatile-register-var  -Wwrite-strings
 # 
 # test: tests/serial_tests.o src/serial.o src/impl/unix.o
 #      $(CXX) -o test tests/serial_tests.o src/serial.o src/impl/unix.o
-# 
 ifdef ROS_ROOT
 include $(shell rospack find mk)/cmake.mk
 else
index ed820fef817aa8cd23a597e4ffd97e4551204bf0..201b165534c0d50902b1f5e4e10dcf3128232f77 100644 (file)
--- a/README.md
+++ b/README.md
@@ -49,13 +49,13 @@ Setup workspace (skip if you already have one):
     rosws init some_ros_workspace
     cd some_ros_workspace
     source setup.bash
-    
+
 Add the rosinstall entry for this stack:
-    
+
     echo "-git: {local-name: serial, uri: 'https://github.com/wjwwood/serial.git', version: 'master'}" >> .rosinstall
-    
+
 Rerun rosinstall:
-    
+
     rosinstall .
     source setup.bash
 
index 0f1801a27d0461848fe9b2dcd0b240de4f5f935f..1bb1eb3f7339269ed7c460e9d2d0c60430484f42 100644 (file)
@@ -8,7 +8,7 @@
  *
  * The MIT License
  *
- * Copyright (c) 2011 William Woodall
+ * Copyright (c) 2011 William Woodall, John Harrison
  *
  * Permission is hereby granted, free of charge, to any person obtaining a 
  * copy of this software and associated documentation files (the "Software"),
@@ -30,7 +30,9 @@
  *
  * \section DESCRIPTION
  *
- * This provides a unix based pimpl for the Serial class.
+ * This provides a unix based pimpl for the Serial class. This implementation is
+ * based off termios.h and uses select for multiplexing the IO ports.
+ *
  */
 
 #ifndef SERIAL_IMPL_UNIX_H
@@ -42,6 +44,7 @@ namespace serial {
 
 using std::string;
 using std::invalid_argument;
+
 using serial::SerialExecption;
 using serial::IOException;
 
@@ -57,47 +60,98 @@ public:
 
   virtual ~SerialImpl ();
 
-  void open ();
-  void close () ;
-  bool isOpen () const;
+  void
+  open ();
 
-  size_t available ();
-  string read (size_t size = 1);
-  size_t write (const string &data);
+  void
+  close ();
 
-  void flush ();
-  void flushInput ();
-  void flushOutput ();
+  bool
+  isOpen () const;
 
-  void sendBreak(int duration);
-  void setBreak(bool level);
-  void setRTS(bool level);
-  void setDTR(bool level);
-  bool getCTS();
-  bool getDSR();
-  bool getRI();
-  bool getCD();
+  size_t
+  available ();
 
-  void setPort (const string &port);
-  string getPort () const;
+  size_t
+  read (char* buf, size_t size = 1);
 
-  void setTimeout (long timeout);
-  long getTimeout () const;
+  size_t
+  write (const string &data);
 
-  void setBaudrate (unsigned long baudrate);
-  unsigned long getBaudrate () const;
+  void
+  flush ();
 
-  void setBytesize (bytesize_t bytesize);
-  bytesize_t getBytesize () const;
+  void
+  flushInput ();
 
-  void setParity (parity_t parity);
-  parity_t getParity () const;
+  void
+  flushOutput ();
 
-  void setStopbits (stopbits_t stopbits);
-  stopbits_t getStopbits () const;
+  void
+  sendBreak(int duration);
 
-  void setFlowcontrol (flowcontrol_t flowcontrol);
-  flowcontrol_t getFlowcontrol () const;
+  void
+  setBreak(bool level);
+
+  void
+  setRTS(bool level);
+
+  void
+  setDTR(bool level);
+  
+  bool
+  getCTS();
+  
+  bool
+  getDSR();
+  
+  bool
+  getRI();
+  
+  bool
+  getCD();
+
+  void
+  setPort (const string &port);
+  
+  string
+  getPort () const;
+
+  void
+  setTimeout (long timeout);
+  
+  long
+  getTimeout () const;
+
+  void
+  setBaudrate (unsigned long baudrate);
+  
+  unsigned long
+  getBaudrate () const;
+
+  void
+  setBytesize (bytesize_t bytesize);
+  
+  bytesize_t
+  getBytesize () const;
+
+  void
+  setParity (parity_t parity);
+
+  parity_t
+  getParity () const;
+
+  void
+  setStopbits (stopbits_t stopbits);
+
+  stopbits_t
+  getStopbits () const;
+
+  void
+  setFlowcontrol (flowcontrol_t flowcontrol);
+
+  flowcontrol_t
+  getFlowcontrol () const;
 
 protected:
   void reconfigurePort ();
@@ -106,17 +160,13 @@ private:
   string port_;               // Path to the file descriptor
   int fd_;                    // The current file descriptor
 
-  int interCharTimeout_;
-  int writeTimeout_;
   bool isOpen_;
   bool xonxoff_;
   bool rtscts_;
-  
-  char ___; // lol padding
 
   long timeout_;              // Timeout for read operations
   unsigned long baudrate_;    // Baudrate
-  
+
   parity_t parity_;           // Parity
   bytesize_t bytesize_;       // Size of the bytes
   stopbits_t stopbits_;       // Stop Bits
index d37fb966ce68afca01202a8652342dfab42941f6..473907ecd3376c50c8485e0ab6c3e93ee003fe4a 100644 (file)
@@ -10,7 +10,7 @@
  *
  * Copyright (c) 2011 William Woodall
  *
- * Permission is hereby granted, free of charge, to any person obtaining a 
+ * 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,
@@ -24,8 +24,8 @@
  * 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 
+ * 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
@@ -124,35 +124,38 @@ class Serial {
 public:
   /*!
   * 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 
+  *
+  * \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, 
+  *
+  * \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, 
+  *
+  * \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, 
+  *
+  * \param flowcontrol Type of flowcontrol used, default is
+  * FLOWCONTROL_NONE, possible values are: FLOWCONTROL_NONE,
   * FLOWCONTROL_SOFTWARE, FLOWCONTROL_HARDWARE
-  * 
+  *
+  * \param buffer_size The maximum size of the internal buffer, defaults
+  * to 256 bytes (2^8).
+  *
   * \throw PortNotOpenedException
   */
   Serial (const std::string &port = "",
@@ -161,7 +164,8 @@ public:
           bytesize_t bytesize = EIGHTBITS,
           parity_t parity = PARITY_NONE,
           stopbits_t stopbits = STOPBITS_ONE,
-          flowcontrol_t flowcontrol = FLOWCONTROL_NONE);
+          flowcontrol_t flowcontrol = FLOWCONTROL_NONE,
+          const size_t buffer_size = 256);
 
   /*! Destructor */
   virtual ~Serial ();
@@ -169,12 +173,12 @@ public:
   /*!
   * Opens the serial port as long as the portname is set and the port isn't
   * alreay open.
-  * 
-  * If the port is provided to the constructor then an explicit call to open 
+  *
+  * If the port is provided to the constructor then an explicit call to open
   * is not needed.
-  * 
+  *
   * \see Serial::Serial
-  * 
+  *
   * \throw std::invalid_argument
   * \throw serial::SerialExecption
   * \throw serial::IOException
@@ -183,7 +187,7 @@ public:
   open ();
 
   /*! Gets the open status of the serial port.
-  * 
+  *
   * \return Returns true if the port is open, false otherwise.
   */
   bool
@@ -198,70 +202,48 @@ public:
   available();
 
   /*! 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 or until an exception occurs.
-  * 
-  * \param buffer An unsigned char array large enough to hold incoming data 
-  * up to the requested size.
-  * 
+  *
   * \param size A size_t defining how many bytes to be read.
-  * 
-  * \return A size_t representing the number of bytes actually read.
-  */
-  //size_t
-  //read (unsigned char* buffer, size_t size = 1);
-
-  /*! 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 or until an exception occurs.
-  * 
-  * \param size A size_t defining how many bytes to be read.
-  * 
+  *
   * \return A std::string containing the data read.
   */
   std::string
   read (size_t size = 1);
 
-  std::string readline(size_t size = std::numeric_limits<std::size_t>::max(),
-                       std::string eol = "\n");
-
-  std::vector<std::string> readlines(std::string eol = "\n");
-
-  /*! Read a given amount of bytes from the serial port.
-  * 
-  * Reads into a std::string by reference rather than returning it.
-  * 
-  * \param buffer A std::string reference for reading to.
-  * \param size A size_t defining how many bytes to be read.
-  * 
-  * \return A size_t that represents how many bytes were read.
-  * 
-  * \see Serial::read(size_t)
+  /*! Reads in a line or until a given delimiter has been processed
+  *
+  * Reads from the serial port until a single line has been read.
+  *
+  * \param size A maximum length of a line defaults to size_t::max()
+  * \param eol A string to match against for the EOL.
+  *
+  * \return A std::string containing the line.
   */
-  //size_t
-  //read (std::string &buffer, size_t size = 1);
-
-  /*! Write bytes from the data to the serial port by given length.
-  * 
-  * \param data An unsigned char array containing data to be 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.
+  std::string
+  readline(size_t      size = std::numeric_limits<std::size_t>::max(),
+           std::string eol  = "\n");
+
+  /*! Reads in multiple lines until the serail port times out.
+  *
+  * This requires a timeout > 0 before it can be run. It will read until a
+  * timeout occurs and return a list of strings.
+  *
+  * \param eol A string to match against for the EOL.
+  *
+  * \return A vector<string> containing the lines.
   */
-  //size_t
-  //write (unsigned char* data, size_t length);
+  std::vector<std::string>
+  readlines(std::string eol = "\n");
 
   /*! Write a string to the serial port.
-  * 
-  * \param data A const std::string reference containg the data to be written 
+  *
+  * \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.
   */
@@ -269,27 +251,27 @@ public:
   write (const std::string &data);
 
   /*! Sets the serial port identifier.
-  * 
-  * \param port A const std::string reference containing the address of the 
-  * serial port, which would be something like 'COM1' on Windows and 
+  *
+  * \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
   setPort (const std::string &port);
 
   /*! Gets the serial port identifier.
-  * 
+  *
   * \see Serial::setPort
-  * 
+  *
   * \throw InvalidConfigurationException
   */
   std::string
   getPort () const;
 
   /*! Sets the timeout for reads in milliseconds.
-  * 
+  *
   * \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
@@ -302,127 +284,151 @@ public:
   setTimeout (long timeout);
 
   /*! Gets the timeout for reads in seconds.
-  * 
+  *
   * \see Serial::setTimeout
   */
   long
   getTimeout () const;
 
   /*! Sets the baudrate for the serial port.
-  * 
+  *
   * Possible baudrates depends on the system but some safe baudrates include:
   * 110, 300, 600, 1200, 2400, 4800, 9600, 14400, 19200, 28800, 38400, 56000,
   * 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
   */
   void
   setBaudrate (unsigned long baudrate);
 
   /*! Gets the baudrate for the serial port.
-  * 
+  *
   * \return An integer that sets the baud rate for the serial port.
-  * 
+  *
   * \see Serial::setBaudrate
-  * 
+  *
   * \throw InvalidConfigurationException
   */
   unsigned long
   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 InvalidConfigurationException
   */
   void
   setBytesize (bytesize_t bytesize);
 
   /*! Gets the bytesize for the serial port.
-  * 
+  *
   * \see Serial::setBytesize
-  * 
+  *
   * \throw InvalidConfigurationException
   */
   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 InvalidConfigurationException
   */
   void
   setParity (parity_t parity);
 
   /*! Gets the parity for the serial port.
-  * 
+  *
   * \see Serial::setParity
-  * 
+  *
   * \throw InvalidConfigurationException
   */
   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 InvalidConfigurationException
   */
   void
   setStopbits (stopbits_t stopbits);
 
   /*! Gets the stopbits for the serial port.
-  * 
+  *
   * \see Serial::setStopbits
-  * 
+  *
   * \throw InvalidConfigurationException
   */
   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 InvalidConfigurationException
   */
   void
   setFlowcontrol (flowcontrol_t flowcontrol);
 
   /*! Gets the flow control for the serial port.
-  * 
+  *
   * \see Serial::setFlowcontrol
-  * 
+  *
   * \throw InvalidConfigurationException
   */
   flowcontrol_t
   getFlowcontrol () const;
 
-  void flush();
-  void flushInput();
-  void flushOutput();
-  void sendBreak(int duration);
-  void setBreak(bool level = true);
-  void setRTS(bool level = true);
-  void setDTR(bool level = true);
-  bool getCTS();
-  bool getDSR();
-  bool getRI();
-  bool getCD();
+  /*! Flush the input and output buffers */
+  void
+  flush ();
+
+  /*! Flush only the input buffer */
+  void
+  flushInput ();
+
+  /*! Flush only the output buffer */
+  void
+  flushOutput ();
+
+  void
+  sendBreak (int duration);
+
+  void
+  setBreak (bool level = true);
+
+  void
+  setRTS (bool level = true);
+
+  void
+  setDTR (bool level = true);
+
+  bool
+  getCTS ();
+
+  bool
+  getDSR ();
+
+  bool
+  getRI ();
+
+  bool
+  getCD ();
 
 private:
   // Disable copy constructors
@@ -430,9 +436,12 @@ private:
   void operator=(const Serial&);
   const Serial& operator=(Serial);
 
+  const size_t buffer_size_;
+  char *read_cache_; //!< Cache for doing reads in chunks.
+
   // Pimpl idiom, d_pointer
   class SerialImpl;
-  SerialImpl *pimpl;
+  SerialImpl *pimpl_;
 };
 
 } // namespace serial
index 0aebffad7351e10c47b2517747e63ed0bd019d06..781acbbd6cd04321aa0ac9efce112ff82b296a0d 100644 (file)
@@ -9,11 +9,11 @@
  *
  * 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 
+ * 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
  * 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 
+ * 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 class that allows for asynchronous serial port reading.
- * 
+ *
  */
 
 #ifndef SERIAL_LISTENER_H
@@ -53,14 +53,14 @@ namespace serial {
 
 /*!
  * This is an alias to boost::shared_ptr<const std::string> used for tokens.
- * 
+ *
  * This is the type used internally and is the type returned in a vector by
  * the tokenizer.  The shared_ptr allows for the token to be stored and kept
  * around long enough to be used by the comparators and callbacks, but no
  * longer.  This internal storage is passed as a const std::string reference
  * to callbacks, like the DataCallback function type, to prevent implicit
  * copying.
- * 
+ *
  * \see serial::TokenizerType, serial::SerialListener::setTokenizer
  */
 typedef boost::shared_ptr<const std::string> TokenPtr;
@@ -69,11 +69,11 @@ typedef boost::shared_ptr<const std::string> TokenPtr;
  * This is a general function type that is used as the callback prototype
  * for asynchronous functions like the default handler callback and the
  * listenFor callbacks.
- * 
+ *
  * The function takes a std::string reference and returns nothing, it is
  * simply passing the resulting line detected by the comparator to the user's
  * callback for processing.
- * 
+ *
  * \see SerialListener::listenFor, SerialListener::setDefaultHandler
  */
 typedef boost::function<void(const std::string&)> DataCallback;
@@ -81,57 +81,57 @@ typedef boost::function<void(const std::string&)> DataCallback;
 /*!
  * This is a general function type that is used as the comparator callback
  * prototpe for the listenFor* type functions.
- * 
+ *
  * The function takes a std::string reference and returns true if the string
  * matches what the comparator is looking for and false if it does not, unless
  * otherwise specified.
- * 
+ *
  * \see SerialListener::listenFor, SerialListener::listenForOnce
  */
 typedef boost::function<bool(const std::string&)> ComparatorType;
 
 /*!
  * This function type describes the prototype for the logging callbacks.
- * 
+ *
  * The function takes a std::string reference and returns nothing.  It is
  * called from the library when a logging message occurs.  This
  * allows the library user to hook into this and integrate it with their own
  * logging system.  It can be set with any of the set<log level>Handler
  * functions.
- * 
- * \see SerialListener::setInfoHandler, SerialListener::setDebugHandler, 
+ *
+ * \see SerialListener::setInfoHandler, SerialListener::setDebugHandler,
  * SerialListener::setWarningHandler
  */
 typedef boost::function<void(const std::string&)> LoggingCallback;
 
 /*!
  * This function type describes the prototype for the exception callback.
- * 
- * The function takes a std::exception reference and returns nothing.  It is 
+ *
+ * The function takes a std::exception reference and returns nothing.  It is
  * called from the library when an exception occurs in a library thread.
  * This exposes these exceptions to the user so they can to error handling.
- * 
+ *
  * \see SerialListener::setExceptionHandler
  */
 typedef boost::function<void(const std::exception&)> ExceptionCallback;
 
 /*!
  * This function type describes the prototype for the tokenizer callback.
- * 
+ *
  * The function should take a std::string reference and tokenize it into a
- * several TokenPtr's and store them in the given std::vector<TokenPtr> 
+ * several TokenPtr's and store them in the given std::vector<TokenPtr>
  * reference.  There are some default ones or the user can create their own.
- * 
+ *
  * The last element in the std::vector of TokenPtr's should always be
  * either an empty string ("") or the last partial message.  The last element
  * in the std::vector will be put back into the data buffer so that if it is
  * incomplete it can be completed when more data is read.
- * 
+ *
  * Example: A delimeter tokenizer with a delimeter of "\r".  The result would
  * be: "msg1\rmsg2\r" -> ["msg1", "msg2", ""] for two complete messages, or:
- * "msg1\rpartial_msg2" -> ["msg1","partial_msg2"] for one complete message 
+ * "msg1\rpartial_msg2" -> ["msg1","partial_msg2"] for one complete message
  * and one partial message.
- * 
+ *
  * \see SerialListener::setTokenizer, serial::delimeter_tokenizer,
  * serial::TokenPtr
  */
@@ -140,19 +140,19 @@ TokenizerType;
 
 /*!
  * Represents a filter which new data is passed through.
- * 
- * The filter consists of a comparator and a callback.  The comparator takes a 
- * token and returns true if it matches, false if it doesn't.  If a match 
- * occurs the serial listener will dispatch a call of the callback with the 
- * matched data in a another thread.  The comparator should be as short as 
- * possible, but the callback can be longer since it is executed in a thread 
+ *
+ * The filter consists of a comparator and a callback.  The comparator takes a
+ * token and returns true if it matches, false if it doesn't.  If a match
+ * occurs the serial listener will dispatch a call of the callback with the
+ * matched data in a another thread.  The comparator should be as short as
+ * possible, but the callback can be longer since it is executed in a thread
  * or thread pool.
- * 
- * \param comparator A ComparatorType that matches incoming data, returns true 
+ *
+ * \param comparator A ComparatorType that matches incoming data, returns true
  * for a match, false othewise.
- * 
+ *
  * \param callback A DataCallback that gets called when a match occurs.
- * 
+ *
  * \see serial::ComparatorType, serial::DataCallback, serial::FilterPtr
  */
 class Filter
@@ -168,11 +168,11 @@ public:
 
 /*!
  * This is an alias to boost::shared_ptr<Filter> used for tokens.
- * 
+ *
  * This is used internally and is returned from SerialListener::listenFor like
  * functions so that users can later remove those filters by passing the
  * FilterPtr.
- * 
+ *
  * \see serial::Filter, serial::SerialListener::listenFor,
  * serial::SerialListener::listenForOnce
  */
@@ -183,7 +183,7 @@ class BlockingFilter;
 /*!
  * Shared Pointer of BlockingFilter, returned by
  * SerialListener::createBlockingFilter.
- * 
+ *
  * \see serial::BlockingFilter, SerialListener::createBlockingFilter
  */
 typedef boost::shared_ptr<BlockingFilter> BlockingFilterPtr;
@@ -193,16 +193,16 @@ class BufferedFilter;
 /*!
  * Shared Pointer of BufferedFilter, returned by
  * SerialListener::createBufferedFilter.
- * 
+ *
  * \see serial::BufferedFilter, SerialListener::createBufferedFilter
  */
 typedef boost::shared_ptr<BufferedFilter> BufferedFilterPtr;
 
 /*!
  * This is a general exception generated by the SerialListener class.
- * 
+ *
  * Check the SerialListenerException::what function for the cause.
- * 
+ *
  * \param e_what is a std::string that describes the cause of the error.
  */
 class SerialListenerException : public std::exception {
@@ -275,11 +275,11 @@ public:
     popped_value=the_queue.front();
     the_queue.pop();
   }
-  
+
   size_t size() const {
     return the_queue.size();
   }
-  
+
   void cancel() {
     the_condition_variable.notify_one();
   }
@@ -312,14 +312,14 @@ public:
 
   /*!
    * Sets the tokenizer to be used when tokenizing the data into tokens.
-   * 
-   * This function is given a std::string of data and is responsible for 
+   *
+   * This function is given a std::string of data and is responsible for
    * tokenizing that data into a std::vector<TokenPtr> of data tokens.
    * The default tokenizer splits the data by the ascii return carriage.
    * The user can create their own tokenizer or use one of the default ones.
-   * 
+   *
    * \param tokenizer Function for tokenizing the incoming data.
-   * 
+   *
    * \see serial::TokenizerType, serial::delimeter_tokenizer
    */
   void
@@ -329,7 +329,7 @@ public:
 
   /*!
    * Sets the number of bytes to be read at a time by the listener.
-   * 
+   *
    * \param chunk_size Number of bytes to be read at a time.
    */
   void
@@ -341,8 +341,8 @@ public:
 
   /*!
    * Starts a thread to listen for messages and process them through filters.
-   * 
-   * \param serial_port Pointer to a serial::Serial object that is used to 
+   *
+   * \param serial_port Pointer to a serial::Serial object that is used to
    * retrieve new data.
    */
   void
@@ -350,8 +350,8 @@ public:
 
   /*!
    * Stops the listening thread and blocks until it completely stops.
-   * 
-   * This function also clears all of the active filters from listenFor and 
+   *
+   * This function also clears all of the active filters from listenFor and
    * similar functions.
    */
   void
@@ -361,21 +361,21 @@ public:
 
   /*!
    * Creates a filter that calls a callback when the comparator returns true.
-   * 
+   *
    * The user provides a comparator and a callback, and every time a line is
    * received the comparator is called and the comparator has to evaluate the
    * line and return true if it matches and false if it doesn't.  If it does
    * match, the callback is called with the resulting line.
-   * 
+   *
    * \param comparator This is a comparator for detecting if a line matches.
    * The comparartor receives a std::string reference and must return a true
    * if it matches and false if it doesn't.
-   * 
+   *
    * \param callback This is the handler for when a match occurs. It is given
    * a std::string reference of the line that matched your comparator.
-   * 
+   *
    * \return boost::shared_ptr<Filter> so you can remove it later.
-   * 
+   *
    * \see SerialListener::removeFilter
    */
   FilterPtr
@@ -383,21 +383,21 @@ public:
 
   /*!
    * Creates a BlockingFilter which blocks until the comparator returns true.
-   * 
+   *
    * The user provides a comparator, and every time a line is
    * received the comparator is called and the comparator has to evaluate the
    * line and return true if it matches and false if it doesn't.  If it does
    * match, any threads that have called BlockingFilter::wait will be
    * notified.  The BlockingFilter will remove itself when its destructor is
-   * called, i.e. when it leaves the scope, so in those cases an explicit call 
+   * called, i.e. when it leaves the scope, so in those cases an explicit call
    * to SerialListener::removeFilter is not needed.
-   * 
+   *
    * \param comparator This is a comparator for detecting if a line matches.
    * The comparartor receives a std::string reference and must return a true
    * if it matches and false if it doesn't.
-   * 
+   *
    * \return BlockingFilterPtr So you can call BlockingFilter::wait on it.
-   * 
+   *
    * \see SerialListener::removeFilter, serial::BlockingFilter,
    * serial::BlockingFilterPtr
    */
@@ -406,24 +406,24 @@ public:
 
   /*!
    * Creates a BlockingFilter blocks until the comparator returns true.
-   * 
+   *
    * The user provides a comparator, and every time a line is
    * received the comparator is called and the comparator has to evaluate the
    * line and return true if it matches and false if it doesn't.  If it does
    * match, any threads that have called BlockingFilter::wait will be
    * notified.  The BlockingFilter will remove itself when its destructor is
-   * called, i.e. when it leaves the scope, so in those cases an explicit call 
+   * called, i.e. when it leaves the scope, so in those cases an explicit call
    * to SerialListener::removeFilter is not needed.
-   * 
+   *
    * \param comparator This is a comparator for detecting if a line matches.
    * The comparartor receives a std::string reference and must return a true
    * if it matches and false if it doesn't.
-   * 
+   *
    * \param buffer_size This is the number of tokens to be buffered by the
    * BufferedFilter, defaults to 1024.
-   * 
+   *
    * \return BlockingFilter So you can call BlockingFilter::wait on it.
-   * 
+   *
    * \see SerialListener::removeFilter, serial::BufferedFilter,
    * serial::BufferedFilterPtr
    */
@@ -432,9 +432,9 @@ public:
 
   /*!
    * Removes a filter by a given FilterPtr.
-   * 
+   *
    * \param filter_ptr A shared pointer to the filter to be removed.
-   * 
+   *
    * \see SerialListener::createFilter
    */
   void
@@ -442,11 +442,11 @@ public:
 
   /*!
    * Removes a BlockingFilter.
-   * 
+   *
    * The BlockingFilter will remove itself if the destructor is called.
-   * 
+   *
    * \param blocking_filter A BlockingFilter to be removed.
-   * 
+   *
    * \see SerialListener::createBlockingFilter
    */
   void
@@ -454,11 +454,11 @@ public:
 
   /*!
    * Removes a BufferedFilter.
-   * 
+   *
    * The BufferedFilter will remove itself if the destructor is called.
-   * 
+   *
    * \param buffered_filter A BufferedFilter to be removed.
-   * 
+   *
    * \see SerialListener::createBufferedFilter
    */
   void
@@ -474,15 +474,15 @@ public:
 
   /*!
    * Sets the handler to be called when a lines is not caught by a filter.
-   * 
-   * This allows you to set a catch all function that will get called 
+   *
+   * This allows you to set a catch all function that will get called
    * everytime a line is not matched by a filter and the ttl expires.
-   * 
+   *
    * Setting the callbacks works just like SerialListener::setInfoHandler.
-   * 
-   * \param default_handler A function pointer to the callback to handle 
+   *
+   * \param default_handler A function pointer to the callback to handle
    * unmatched and expired messages.
-   * 
+   *
    * \see serial::DataCallback, SerialListener::setInfoHandler
    */
   void
@@ -492,10 +492,10 @@ public:
 
   /*!
    * Sets the function to be called when an info logging message occurs.
-   * 
+   *
    * This allows you to hook into the message reporting of the library and use
    * your own logging facilities.
-   * 
+   *
    * The provided function must follow this prototype:
    * <pre>
    *    void yourInfoCallback(const std::string &msg)
@@ -514,9 +514,9 @@ public:
    * Alternatively you can use a class method as a callback using boost::bind:
    * <pre>
    *    #include <boost/bind.hpp>
-   *    
+   *
    *    #include "serial/serial_listener.h"
-   *    
+   *
    *    class MyClass
    *    {
    *    public:
@@ -524,55 +524,55 @@ public:
    *      listener.setInfoHandler(
    *          boost::bind(&MyClass::handleInfo, this, _1));
    *     }
-   *    
+   *
    *     void handleInfo(const std::string &msg) {
    *       std::cout << "MyClass Info: " << msg << std::endl;
    *     }
-   *    
+   *
    *    private:
    *     serial::SerialListener listener;
    *    };
    * </pre>
-   * 
-   * \param info_handler A function pointer to the callback to handle new 
+   *
+   * \param info_handler A function pointer to the callback to handle new
    * Info messages.
-   * 
+   *
    * \see serial::LoggingCallback
    */
   void
   setInfoHandler (LoggingCallback info_handler) {
     this->info = info_handler;
   }
-  
+
   /*!
    * Sets the function to be called when a debug logging message occurs.
-   * 
+   *
    * This allows you to hook into the message reporting of the library and use
    * your own logging facilities.
-   * 
+   *
    * This works just like SerialListener::setInfoHandler.
-   * 
-   * \param debug_handler A function pointer to the callback to handle new 
+   *
+   * \param debug_handler A function pointer to the callback to handle new
    * Debug messages.
-   * 
+   *
    * \see serial::LoggingCallback, SerialListener::setInfoHandler
    */
   void
   setDebugHandler (LoggingCallback debug_handler) {
     this->debug = debug_handler;
   }
-  
+
   /*!
    * Sets the function to be called when a warning logging message occurs.
-   * 
+   *
    * This allows you to hook into the message reporting of the library and use
    * your own logging facilities.
-   * 
+   *
    * This works just like SerialListener::setInfoHandler.
-   * 
-   * \param warning_handler A function pointer to the callback to handle new 
+   *
+   * \param warning_handler A function pointer to the callback to handle new
    * Warning messages.
-   * 
+   *
    * \see serial::LoggingCallback, SerialListener::setInfoHandler
    */
   void
@@ -584,7 +584,7 @@ public:
 
   /*!
    * Sleeps for a given number of milliseconds.
-   * 
+   *
    * \param milliseconds number of milliseconds to sleep.
    */
   static void
@@ -595,21 +595,21 @@ public:
 
   /*!
    * This returns a tokenizer that splits on a given delimeter.
-   * 
-   * The delimeter is passed into the function and a TokenizerType is returned 
+   *
+   * The delimeter is passed into the function and a TokenizerType is returned
    * that can be passed to SerialListener::setTokenizer.
-   * 
+   *
    * Example:
    * <pre>
    *   my_listener.setTokenizer(SerialListener::delimeter_tokenizer("\r"));
    * <\pre>
-   * 
-   * \param delimeter A std::string that is used as a delimeter when 
+   *
+   * \param delimeter A std::string that is used as a delimeter when
    * tokenizing data.
-   * 
-   * \return TokenizerType A tokenizer function type that can be passed to 
+   *
+   * \return TokenizerType A tokenizer function type that can be passed to
    * SerialListener::setTokenizer.
-   * 
+   *
    * \see SerialListener::setTokenizer, serial::TokenizerType
    */
   static TokenizerType
@@ -620,22 +620,22 @@ public:
 
   /*!
    * This returns a comparator that matches only the exact string given.
-   * 
+   *
    * This can be used with listenFor or listenForOnce:
-   * 
+   *
    * Example:
    * <pre>
    *   my_listener.listenFor(SerialListener::exactly("my_string"),
    *                         my_callback);
    * <\pre>
-   * 
-   * \param exact_str A std::string that is used as the exact string to match 
+   *
+   * \param exact_str A std::string that is used as the exact string to match
    * when comparing tokens for matching.
-   * 
-   * \return ComparatorType A comparator function type that can be passed to 
+   *
+   * \return ComparatorType A comparator function type that can be passed to
    * SerialListener::listenFor or SerialListener::listenForOnce.
    *
-   * \see SerialListener::listenFor, SerialListener::listenForOnce, 
+   * \see SerialListener::listenFor, SerialListener::listenForOnce,
    * serial::ComparatorType
    */
   static ComparatorType
@@ -645,21 +645,21 @@ public:
 
   /*!
    * This returns a comparator that looks for a given prefix.
-   * 
+   *
    * This can be used with listenFor or listenForOnce:
-   * 
+   *
    * Example:
    * <pre>
    *   my_listener.listenFor(SerialListener::startsWith("V="), my_callback);
    * <\pre>
-   * 
-   * \param prefix A std::string that is used as the prefix string to match 
+   *
+   * \param prefix A std::string that is used as the prefix string to match
    * when comparing tokens for matching.
-   * 
-   * \return ComparatorType A comparator function type that can be passed to 
+   *
+   * \return ComparatorType A comparator function type that can be passed to
    * SerialListener::listenFor or SerialListener::listenForOnce.
    *
-   * \see SerialListener::listenFor, SerialListener::listenForOnce, 
+   * \see SerialListener::listenFor, SerialListener::listenForOnce,
    * serial::ComparatorType
    */
   static ComparatorType
@@ -669,21 +669,21 @@ public:
 
   /*!
    * This returns a comparator that looks for a given postfix.
-   * 
+   *
    * This can be used with listenFor or listenForOnce:
-   * 
+   *
    * Example:
    * <pre>
    *   my_listener.listenFor(SerialListener::endsWith(";"), my_callback);
    * <\pre>
-   * 
-   * \param postfix A std::string that is used as the postfix string to match 
+   *
+   * \param postfix A std::string that is used as the postfix string to match
    * when comparing tokens for matching.
-   * 
-   * \return ComparatorType A comparator function type that can be passed to 
+   *
+   * \return ComparatorType A comparator function type that can be passed to
    * SerialListener::listenFor or SerialListener::listenForOnce.
    *
-   * \see SerialListener::listenFor, SerialListener::listenForOnce, 
+   * \see SerialListener::listenFor, SerialListener::listenForOnce,
    * serial::ComparatorType
    */
   static ComparatorType
@@ -693,22 +693,22 @@ public:
 
   /*!
    * This returns a comparator that looks for a given substring in the token.
-   * 
+   *
    * This can be used with listenFor or listenForOnce:
-   * 
+   *
    * Example:
    * <pre>
    *   my_listener.listenFor(SerialListener::contains("some string"),
    *                         my_callback);
    * <\pre>
-   * 
-   * \param substr A std::string that is used as the search substring to match 
+   *
+   * \param substr A std::string that is used as the search substring to match
    * when comparing tokens for matching.
-   * 
-   * \return ComparatorType A comparator function type that can be passed to 
+   *
+   * \return ComparatorType A comparator function type that can be passed to
    * SerialListener::listenFor or SerialListener::listenForOnce.
    *
-   * \see SerialListener::listenFor, SerialListener::listenForOnce, 
+   * \see SerialListener::listenFor, SerialListener::listenForOnce,
    * serial::ComparatorType
    */
   static ComparatorType
@@ -809,13 +809,13 @@ private:
 };
 
 /*!
- * This is the a filter that provides a wait function for blocking until a 
+ * This is the a filter that provides a wait function for blocking until a
  * match is found.
- * 
- * This should probably not be created manually, but instead should be 
+ *
+ * This should probably not be created manually, but instead should be
  * constructed using SerialListener::createBlockingFilter(ComparatorType)
  * function which returns a BlockingFilter instance.
- * 
+ *
  * \see serial::SerialListener::ComparatorType,
  * serial::SerialListener::createBlockingFilter
  */
@@ -837,9 +837,9 @@ public:
   /*!
    * Waits a given number of milliseconds or until a token is matched.  If a
    * token is matched it is returned, otherwise an empty string is returned.
-   * 
+   *
    * \param ms Time in milliseconds to wait on a new token.
-   * 
+   *
    * \return std::string token that was matched or "" if none were matched.
    */
  std::string wait(long ms) {
@@ -868,22 +868,22 @@ private:
  * This is the a filter that provides a wait function for blocking until a
  * match is found.  It will also buffer up to a given buffer size of tokens so
  * that they can be counted or accessed after they are matched by the filter.
- * 
- * This should probably not be created manually, but instead should be 
+ *
+ * This should probably not be created manually, but instead should be
  * constructed using SerialListener::createBufferedFilter(ComparatorType)
  * function which returns a BufferedFilter instance.
- * 
+ *
  * The internal buffer is a circular queue buffer, so when the buffer is full,
  * the oldest token is dropped and the new one is added.  Additionally, when
  * wait is a called the oldest available token is returned.
- * 
+ *
  * \see serial::SerialListener::ComparatorType,
  * serial::SerialListener::createBufferedFilter
  */
 class BufferedFilter
 {
 public:
-  BufferedFilter (ComparatorType comparator, size_t buffer_size, 
+  BufferedFilter (ComparatorType comparator, size_t buffer_size,
                   SerialListener &listener)
   : buffer_size_(buffer_size)
   {
@@ -899,14 +899,14 @@ public:
   }
 
   /*!
-   * Waits a given number of milliseconds or until a matched token is 
+   * Waits a given number of milliseconds or until a matched token is
    * available in the buffer.  If a token is matched it is returned, otherwise
    * an empty string is returned.
-   * 
-   * \param ms Time in milliseconds to wait on a new token.  If ms is set to 0 
-   * then it will try to get a new token if one is available but will not 
+   *
+   * \param ms Time in milliseconds to wait on a new token.  If ms is set to 0
+   * then it will try to get a new token if one is available but will not
    * block.
-   * 
+   *
    * \return std::string token that was matched or "" if none were matched.
    */
   std::string wait(long ms) {
index e7d5e4bda7bb5514f9241abf6dafe80b8d1e7e60..f6d81a6e4017c2fdb959fbb9d54eee605b30a0eb 100644 (file)
@@ -15,7 +15,7 @@ IF(EXISTS /usr/bin/clang)
   set(CMAKE_CXX_COMPILER /usr/bin/clang++)
   set(CMAKE_OSX_DEPLOYMENT_TARGET "")
   # set(CMAKE_CXX_FLAGS "-ferror-limit=5 -std=c++0x -stdlib=libc++")
-  set(CMAKE_CXX_FLAGS "-ferror-limit=5 -m64 -Wall -Weffc++ -pedantic -pedantic-errors -Wextra  -Wall -Waggregate-return -Wcast-align -Wcast-qual  -Wchar-subscripts  -Wcomment -Wconversion -Wdisabled-optimization -Wfloat-equal  -Wformat  -Wformat=2 -Wformat-nonliteral -Wformat-security  -Wformat-y2k -Wimplicit  -Wimport  -Winit-self  -Winline -Winvalid-pch   -Wlong-long -Wmissing-braces -Wmissing-field-initializers -Wmissing-format-attribute   -Wmissing-include-dirs -Wmissing-noreturn -Wpacked  -Wpadded -Wparentheses  -Wpointer-arith -Wredundant-decls -Wreturn-type -Wsequence-point  -Wshadow -Wsign-compare  -Wstack-protector -Wstrict-aliasing -Wstrict-aliasing=2 -Wswitch  -Wswitch-default -Wswitch-enum -Wtrigraphs  -Wuninitialized -Wunknown-pragmas  -Wunreachable-code -Wunused -Wunused-function  -Wunused-label  -Wunused-parameter -Wunused-value  -Wunused-variable  -Wvariadic-macros -Wvolatile-register-var  -Wwrite-strings")
+  set(CMAKE_CXX_FLAGS "-ferror-limit=5 -O3 -Wall -Weffc++ -pedantic -pedantic-errors -Wextra  -Wall -Waggregate-return -Wcast-align -Wcast-qual  -Wchar-subscripts  -Wcomment -Wconversion -Wdisabled-optimization -Wfloat-equal  -Wformat  -Wformat=2 -Wformat-nonliteral -Wformat-security  -Wformat-y2k -Wimplicit  -Wimport  -Winit-self  -Winline -Winvalid-pch   -Wlong-long -Wmissing-braces -Wmissing-field-initializers -Wmissing-format-attribute   -Wmissing-include-dirs -Wmissing-noreturn -Wpacked -Wparentheses  -Wpointer-arith -Wredundant-decls -Wreturn-type -Wsequence-point  -Wshadow -Wsign-compare  -Wstack-protector -Wstrict-aliasing -Wstrict-aliasing=2 -Wswitch  -Wswitch-default -Wswitch-enum -Wtrigraphs  -Wuninitialized -Wunknown-pragmas  -Wunreachable-code -Wunused -Wunused-function  -Wunused-label  -Wunused-parameter -Wunused-value  -Wunused-variable  -Wvariadic-macros -Wvolatile-register-var  -Wwrite-strings")
   set(CMAKE_BUILD_TYPE Debug)
 ENDIF(EXISTS /usr/bin/clang)
 
index f583eb46a7315528cf1e2c9ddca922f20bedc1aa..5a7c89fe251bd567f14adc117a683cf2bfb73a79 100644 (file)
@@ -1,3 +1,5 @@
+/* Copyright 2012 William Woodall and John Harrison */
+
 #include <stdio.h>
 #include <string.h>
 #include <unistd.h>
@@ -33,31 +35,36 @@ Serial::SerialImpl::SerialImpl (const string &port, unsigned long baudrate,
                                 long timeout, bytesize_t bytesize,
                                 parity_t parity, stopbits_t stopbits,
                                 flowcontrol_t flowcontrol)
-: port_(port), fd_(-1), interCharTimeout_(-1), writeTimeout_(-1),
-  isOpen_(false), xonxoff_(false), rtscts_(false), ___(0), timeout_(timeout),
-  baudrate_(baudrate), parity_(parity), bytesize_(bytesize),
-  stopbits_(stopbits), flowcontrol_(flowcontrol)
+: port_ (port), fd_ (-1), isOpen_ (false), xonxoff_ (true), rtscts_ (false),
+  timeout_ (timeout), baudrate_ (baudrate), parity_ (parity), bytesize_ (bytesize),
+  stopbits_ (stopbits), flowcontrol_ (flowcontrol)
 {
-  if (port_.empty() == false) this->open();
+  if (port_.empty () == false)
+    open ();
 }
 
-Serial::SerialImpl::~SerialImpl () {
-  this->close();
+Serial::SerialImpl::~SerialImpl ()
+{
+  close();
 }
 
 void
-Serial::SerialImpl::open () {
-  if (port_.empty()) {
-    throw invalid_argument("bad port specified");
+Serial::SerialImpl::open ()
+{
+  if (port_.empty())
+  {
+    throw invalid_argument ("bad port specified");
   }
-  if (isOpen_ == true) {
-    throw SerialExecption("port already open");
+  if (isOpen_ == true)
+  {
+    throw SerialExecption ("port already open");
   }
-  
+
   fd_ = ::open (port_.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
 
-  if (fd_ == -1) {
-    throw IOException("invalid file descriptor");
+  if (fd_ == -1)
+  {
+    throw IOException ("invalid file descriptor");
   }
 
   reconfigurePort();
@@ -65,31 +72,25 @@ Serial::SerialImpl::open () {
 }
 
 void
-Serial::SerialImpl::reconfigurePort () {
-  if (fd_ == -1) {
+Serial::SerialImpl::reconfigurePort ()
+{
+  if (fd_ == -1)
+  {
     // Can only operate on a valid file descriptor
-    throw IOException("invalid file descriptor");
+    throw IOException ("invalid file descriptor");
   }
 
-  struct termios options; // The current options for the file descriptor
-  struct termios originalTTYAttrs; // The orignal file descriptor options
+  struct termios options; // The options for the file descriptor
 
-  uint8_t vmin = 0, vtime = 0; // timeout is done via select
-  if (interCharTimeout_ == -1) {
-    vmin = 1;
-    vtime = uint8_t(interCharTimeout_ * 10);
+  if (tcgetattr(fd_, &options) == -1)
+  {
+    throw IOException ("::tcgetattr");
   }
 
-  if (tcgetattr(fd_, &originalTTYAttrs) == -1) {
-    throw IOException("::tcgetattr");
-  }
-
-  options = originalTTYAttrs;
-
   // set up raw mode / no echo / binary
-  options.c_cflag |= (unsigned long)(CLOCAL|CREAD);
-  options.c_lflag &= (unsigned long) ~(ICANON|ECHO|ECHOE|ECHOK
-                       |ECHONL|ISIG|IEXTEN); //|ECHOPRT
+  options.c_cflag |= (unsigned long)  (CLOCAL|CREAD);
+  options.c_lflag &= (unsigned long) ~(ICANON|ECHO|ECHOE|ECHOK|ECHONL|
+                                       ISIG|IEXTEN); //|ECHOPRT
 
   options.c_oflag &= (unsigned long) ~(OPOST);
   options.c_iflag &= (unsigned long) ~(INLCR|IGNCR|ICRNL|IGNBRK);
@@ -115,7 +116,7 @@ Serial::SerialImpl::reconfigurePort () {
   else if (bytesize_ == FIVEBITS)
       options.c_cflag |= CS5;
   else
-      throw invalid_argument("Invalid char len");
+      throw invalid_argument ("Invalid char len");
   // setup stopbits
   if (stopbits_ == STOPBITS_ONE)
       options.c_cflag &= (unsigned long) ~(CSTOPB);
@@ -123,22 +124,26 @@ Serial::SerialImpl::reconfigurePort () {
       options.c_cflag |=  (CSTOPB);  // XXX same as TWO.. there is no POSIX support for 1.5
   else if (stopbits_ == STOPBITS_TWO)
       options.c_cflag |=  (CSTOPB);
-  else 
-      throw invalid_argument("invalid stop bit");
+  else
+      throw invalid_argument ("invalid stop bit");
   // setup parity
   options.c_iflag &= (unsigned long) ~(INPCK|ISTRIP);
-  if (parity_ == PARITY_NONE) {
+  if (parity_ == PARITY_NONE)
+  {
     options.c_cflag &= (unsigned long) ~(PARENB|PARODD);
   }
-  else if (parity_ == PARITY_EVEN) {
+  else if (parity_ == PARITY_EVEN)
+  {
     options.c_cflag &= (unsigned long) ~(PARODD);
     options.c_cflag |=  (PARENB);
-  } 
-  else if (parity_ == PARITY_ODD) {
+  }
+  else if (parity_ == PARITY_ODD)
+  {
     options.c_cflag |=  (PARENB|PARODD);
   }
-  else {
-    throw invalid_argument("invalid parity");
+  else
+  {
+    throw invalid_argument ("invalid parity");
   }
   // setup flow control
   // xonxoff
@@ -168,21 +173,21 @@ Serial::SerialImpl::reconfigurePort () {
 #error "OS Support seems wrong."
 #endif
 
-  // buffer
-  // vmin "minimal number of characters to be read. = for non blocking"
-  options.c_cc[VMIN] = vmin;
-  // vtime
-  options.c_cc[VTIME] = vtime;
+  options.c_cc[VMIN] = 1; // Minimum of 1 character in the buffer
+  options.c_cc[VTIME] = 0; // timeout on waiting for new data
 
   // activate settings
-  ::tcsetattr(fd_, TCSANOW, &options);
+  ::tcsetattr (fd_, TCSANOW, &options);
 }
 
 void
-Serial::SerialImpl::close () {
-  if (isOpen_ == true) {
-    if (fd_ != -1) {
-      ::close(fd_); // Ignoring the outcome
+Serial::SerialImpl::close ()
+{
+  if (isOpen_ == true)
+  {
+    if (fd_ != -1)
+    {
+      ::close (fd_); // Ignoring the outcome
       fd_ = -1;
     }
     isOpen_ = false;
@@ -190,266 +195,318 @@ Serial::SerialImpl::close () {
 }
 
 bool
-Serial::SerialImpl::isOpen () const {
+Serial::SerialImpl::isOpen () const
+{
   return isOpen_;
 }
 
 size_t
-Serial::SerialImpl::available () {
-  if (!isOpen_) {
+Serial::SerialImpl::available ()
+{
+  if (!isOpen_)
+  {
     return 0;
   }
   int count = 0;
-  int result = ioctl(fd_, TIOCINQ, &count);
-  if (result == 0) {
-    return (size_t)count;
+  int result = ioctl (fd_, TIOCINQ, &count);
+  if (result == 0)
+  {
+    return static_cast<size_t> (count);
   }
-  else {
-    throw IOException("ioctl");
+  else
+  {
+    throw IOException ("ioctl");
   }
 }
 
-string
-Serial::SerialImpl::read (size_t size) {
-  if (!isOpen_) {
-    throw PortNotOpenedException("Serial::read");
-  }
-  string message = "";
-  char *buf = NULL;
-  // Using size+1 to leave room for a null character
-  if (size > 1024) {
-    buf = (char*)malloc((size + 1) * sizeof(*buf));
-  }
-  else {
-    buf = (char*)alloca((size + 1) * sizeof(*buf));
+size_t
+Serial::SerialImpl::read (char* buf, size_t size)
+{
+  if (!isOpen_)
+  {
+    throw PortNotOpenedException ("Serial::read");
   }
   fd_set readfds;
-  memset(buf, 0, (size + 1) * sizeof(*buf));
   ssize_t bytes_read = 0;
-  while (bytes_read < size) {
-    if (timeout_ != -1) {
-      FD_ZERO(&readfds);
-      FD_SET(fd_, &readfds);
+  while (true)
+  {
+    if (timeout_ != -1)
+    {
+      FD_ZERO (&readfds);
+      FD_SET (fd_, &readfds);
       struct timeval timeout;
-      timeout.tv_sec =        timeout_ / 1000;
-      timeout.tv_usec = (int) timeout_ % 1000;
-      int r = select(fd_ + 1, &readfds, NULL, NULL, &timeout);
+      timeout.tv_sec =                    timeout_ / 1000;
+      timeout.tv_usec = static_cast<int> (timeout_ % 1000);
+      int r = select (fd_ + 1, &readfds, NULL, NULL, &timeout);
 
       if (r == -1 && errno == EINTR)
         continue;
 
-      if (r == -1) {
+      if (r == -1)
+      {
         perror("select()");
         exit(EXIT_FAILURE);
       }
     }
 
-    if (timeout_ == -1 || FD_ISSET(fd_, &readfds)) {
-      ssize_t newest_read = ::read(fd_,
-                                   buf + bytes_read,
-                                   size - static_cast<size_t>(bytes_read));
+    if (timeout_ == -1 || FD_ISSET (fd_, &readfds))
+    {
+      bytes_read = ::read (fd_, buf, size);
       // read should always return some data as select reported it was
       // ready to read when we get to this point.
-      if (newest_read < 1) {
+      // printf("bytes_read: %lu\n", bytes_read);
+      if (bytes_read < 1)
+      {
         // Disconnected devices, at least on Linux, show the
         // behavior that they are always ready to read immediately
         // but reading returns nothing.
-        throw SerialExecption("device reports readiness to read but "
-                              "returned no data (device disconnected?)");
+        throw SerialExecption ("device reports readiness to read but "
+                               "returned no data (device disconnected?)");
       }
-      bytes_read += newest_read;
-    }
-    else {
-      break; // Timeout
+      break;
     }
   }
-  if (bytes_read > 0)
-    message.append(buf, (size_t)bytes_read);
-  if (size > 1024)
-    free(buf);
-  return message;
+  return static_cast<size_t> (bytes_read);
 }
 
 size_t
-Serial::SerialImpl::write (const string &data) {
+Serial::SerialImpl::write (const string &data)
+{
   if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::write");
+    throw PortNotOpenedException ("Serial::write");
   }
-  ssize_t n = ::write(fd_, data.c_str(), data.length());
+  ssize_t n = ::write (fd_, data.c_str (), data.length ());
   if (n == -1) {
-    throw IOException("Write");
+    throw IOException ("Write");
   }
-  return (size_t)n;
+  return static_cast<size_t> (n);
 }
 
 void
-Serial::SerialImpl::setPort (const string &port) {
+Serial::SerialImpl::setPort (const string &port)
+{
   port_ = port;
 }
 
 string
-Serial::SerialImpl::getPort () const {
+Serial::SerialImpl::getPort () const
+{
   return port_;
 }
 
 void
-Serial::SerialImpl::setTimeout (long timeout) {
+Serial::SerialImpl::setTimeout (long timeout)
+{
   timeout_ = timeout;
-  if (isOpen_) reconfigurePort();
+  if (isOpen_)
+    reconfigurePort ();
 }
 
 long
-Serial::SerialImpl::getTimeout () const {
+Serial::SerialImpl::getTimeout () const
+{
   return timeout_;
 }
 
 void
-Serial::SerialImpl::setBaudrate (unsigned long baudrate) {
+Serial::SerialImpl::setBaudrate (unsigned long baudrate)
+{
   baudrate_ = baudrate;
-  if (isOpen_) reconfigurePort();
+  if (isOpen_)
+    reconfigurePort ();
 }
 
 unsigned long
-Serial::SerialImpl::getBaudrate () const {
+Serial::SerialImpl::getBaudrate () const
+{
   return baudrate_;
 }
 
 void
-Serial::SerialImpl::setBytesize (serial::bytesize_t bytesize) {
+Serial::SerialImpl::setBytesize (serial::bytesize_t bytesize)
+{
   bytesize_ = bytesize;
-  if (isOpen_) reconfigurePort();
+  if (isOpen_)
+    reconfigurePort ();
 }
 
 serial::bytesize_t
-Serial::SerialImpl::getBytesize () const {
+Serial::SerialImpl::getBytesize () const
+{
   return bytesize_;
 }
 
 void
-Serial::SerialImpl::setParity (serial::parity_t parity) {
+Serial::SerialImpl::setParity (serial::parity_t parity)
+{
   parity_ = parity;
-  if (isOpen_) reconfigurePort();
+  if (isOpen_)
+    reconfigurePort ();
 }
 
 serial::parity_t
-Serial::SerialImpl::getParity () const {
+Serial::SerialImpl::getParity () const
+{
   return parity_;
 }
 
 void
-Serial::SerialImpl::setStopbits (serial::stopbits_t stopbits) {
+Serial::SerialImpl::setStopbits (serial::stopbits_t stopbits)
+{
   stopbits_ = stopbits;
-  if (isOpen_) reconfigurePort();
+  if (isOpen_)
+    reconfigurePort ();
 }
 
 serial::stopbits_t
-Serial::SerialImpl::getStopbits () const {
+Serial::SerialImpl::getStopbits () const
+{
   return stopbits_;
 }
 
 void
-Serial::SerialImpl::setFlowcontrol (serial::flowcontrol_t flowcontrol) {
+Serial::SerialImpl::setFlowcontrol (serial::flowcontrol_t flowcontrol)
+{
   flowcontrol_ = flowcontrol;
-  if (isOpen_) reconfigurePort();
+  if (isOpen_)
+    reconfigurePort ();
 }
 
 serial::flowcontrol_t
-Serial::SerialImpl::getFlowcontrol () const {
+Serial::SerialImpl::getFlowcontrol () const
+{
   return flowcontrol_;
 }
 
-void Serial::SerialImpl::flush () {
-  if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::flush");
+void
+Serial::SerialImpl::flush ()
+{
+  if (isOpen_ == false)
+  {
+    throw PortNotOpenedException ("Serial::flush");
   }
-  tcdrain(fd_);
+  tcdrain (fd_);
 }
 
-void Serial::SerialImpl::flushInput () {
-  if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::flushInput");
+void
+Serial::SerialImpl::flushInput ()
+{
+  if (isOpen_ == false)
+  {
+    throw PortNotOpenedException ("Serial::flushInput");
   }
-  tcflush(fd_, TCIFLUSH);
+  tcflush (fd_, TCIFLUSH);
 }
 
-void Serial::SerialImpl::flushOutput () {
-  if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::flushOutput");
+void
+Serial::SerialImpl::flushOutput ()
+{
+  if (isOpen_ == false)
+  {
+    throw PortNotOpenedException ("Serial::flushOutput");
   }
-  tcflush(fd_, TCOFLUSH);
+  tcflush (fd_, TCOFLUSH);
 }
 
-void Serial::SerialImpl::sendBreak(int duration) {
-  if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::sendBreak");
+void
+Serial::SerialImpl::sendBreak (int duration)
+{
+  if (isOpen_ == false)
+  {
+    throw PortNotOpenedException ("Serial::sendBreak");
   }
-  tcsendbreak(fd_, int(duration/4));
+  tcsendbreak (fd_, static_cast<int> (duration/4));
 }
 
-void Serial::SerialImpl::setBreak(bool level) {
-  if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::setBreak");
+void
+Serial::SerialImpl::setBreak (bool level)
+{
+  if (isOpen_ == false)
+  {
+    throw PortNotOpenedException ("Serial::setBreak");
   }
-  if (level) {
-    ioctl(fd_, TIOCSBRK);
+  if (level)
+  {
+    ioctl (fd_, TIOCSBRK);
   }
   else {
-    ioctl(fd_, TIOCCBRK);
+    ioctl (fd_, TIOCCBRK);
   }
 }
 
-void Serial::SerialImpl::setRTS(bool level) {
-  if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::setRTS");
+void
+Serial::SerialImpl::setRTS (bool level)
+{
+  if (isOpen_ == false)
+  {
+    throw PortNotOpenedException ("Serial::setRTS");
   }
-  if (level) {
-    ioctl(fd_, TIOCMBIS, TIOCM_RTS);
+  if (level)
+  {
+    ioctl (fd_, TIOCMBIS, TIOCM_RTS);
   }
   else {
-    ioctl(fd_, TIOCMBIC, TIOCM_RTS);
+    ioctl (fd_, TIOCMBIC, TIOCM_RTS);
   }
 }
 
-void Serial::SerialImpl::setDTR(bool level) {
-  if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::setDTR");
+void
+Serial::SerialImpl::setDTR (bool level)
+{
+  if (isOpen_ == false)
+  {
+    throw PortNotOpenedException ("Serial::setDTR");
   }
-  if (level) {
-    ioctl(fd_, TIOCMBIS, TIOCM_DTR);
+  if (level)
+  {
+    ioctl (fd_, TIOCMBIS, TIOCM_DTR);
   }
-  else {
-    ioctl(fd_, TIOCMBIC, TIOCM_DTR);
+  else
+  {
+    ioctl (fd_, TIOCMBIC, TIOCM_DTR);
   }
 }
 
-bool Serial::SerialImpl::getCTS() {
-  if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::getCTS");
+bool
+Serial::SerialImpl::getCTS ()
+{
+  if (isOpen_ == false)
+  {
+    throw PortNotOpenedException ("Serial::getCTS");
   }
-  int s = ioctl(fd_, TIOCMGET, 0);
+  int s = ioctl (fd_, TIOCMGET, 0);
   return (s & TIOCM_CTS) != 0;
 }
 
-bool Serial::SerialImpl::getDSR() {
-  if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::getDSR");
+bool
+Serial::SerialImpl::getDSR()
+{
+  if (isOpen_ == false)
+  {
+    throw PortNotOpenedException ("Serial::getDSR");
   }
   int s = ioctl(fd_, TIOCMGET, 0);
   return (s & TIOCM_DSR) != 0;
 }
 
-bool Serial::SerialImpl::getRI() {
-  if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::getRI");
+bool
+Serial::SerialImpl::getRI()
+{
+  if (isOpen_ == false)
+  {
+    throw PortNotOpenedException ("Serial::getRI");
   }
-  int s = ioctl(fd_, TIOCMGET, 0);
+  int s = ioctl (fd_, TIOCMGET, 0);
   return (s & TIOCM_RI) != 0;
 }
 
-bool Serial::SerialImpl::getCD() {
-  if (isOpen_ == false) {
-    throw PortNotOpenedException("Serial::getCD");
+bool
+Serial::SerialImpl::getCD()
+{
+  if (isOpen_ == false)
+  {
+    throw PortNotOpenedException ("Serial::getCD");
   }
-  int s = ioctl(fd_, TIOCMGET, 0);
+  int s = ioctl (fd_, TIOCMGET, 0);
   return (s & TIOCM_CD) != 0;
 }
index 9a5def847f2e602bec257575680c90eceeb90b1b..beed5bafdd6a8263a5e60add12eb1b83daa0cfe9 100644 (file)
@@ -1,3 +1,10 @@
+/* Copyright 2012 William Woodall and John Harrison */
+
+#include <alloca.h>
+
+#include <cstring>
+#include <algorithm>
+
 #include "serial/serial.h"
 
 #ifdef _WIN32
 #include "serial/impl/unix.h"
 #endif
 
-using std::string;
-using std::vector;
+using std::invalid_argument;
+using std::memset;
+using std::min;
 using std::numeric_limits;
+using std::vector;
 using std::size_t;
-using std::invalid_argument;
+using std::string;
+
 using serial::Serial;
 using serial::SerialExecption;
 using serial::IOException;
@@ -21,204 +31,301 @@ using serial::flowcontrol_t;
 
 Serial::Serial (const string &port, unsigned long baudrate, long timeout,
                 bytesize_t bytesize, parity_t parity, stopbits_t stopbits,
-                flowcontrol_t flowcontrol)
+                flowcontrol_t flowcontrol, const size_t buffer_size)
+ : buffer_size_(buffer_size)
 {
-  pimpl = new SerialImpl(port, baudrate, timeout, bytesize, parity,
+  pimpl_ = new SerialImpl (port, baudrate, timeout, bytesize, parity,
                            stopbits, flowcontrol);
+  read_cache_ = new char[buffer_size_];
+  memset (read_cache_, 0, buffer_size_ * sizeof (char));
 }
 
-Serial::~Serial () {
-  delete pimpl;
+Serial::~Serial ()
+{
+  delete   pimpl_;
+  delete[] read_cache_;
 }
 
 void
-Serial::open () {
-  this->pimpl->open ();
+Serial::open ()
+{
+  pimpl_->open ();
 }
 
 void
-Serial::close () {
-  this->pimpl->close ();
+Serial::close ()
+{
+  pimpl_->close ();
+  memset (read_cache_, 0, buffer_size_ * sizeof (char));
 }
 
 bool
-Serial::isOpen () const {
-  return this->pimpl->isOpen ();
+Serial::isOpen () const
+{
+  return pimpl_->isOpen ();
 }
 
 size_t
-Serial::available () {
-  return this->pimpl->available();
+Serial::available ()
+{
+  return pimpl_->available ();
 }
 
 string
-Serial::read (size_t size) {
-  return this->pimpl->read (size);
+Serial::read (size_t size)
+{
+  size_t cache_size = strlen (read_cache_);
+  if (cache_size >= size)
+  {
+    // Don't need to do a new read.
+    string result (read_cache_, size);
+    memmove (read_cache_, read_cache_ + size, cache_size - size);
+    *(read_cache_ + cache_size - size) = '\0';
+    return result;
+  }
+  else
+  {
+    // Needs to read, loop until we have read enough... or timeout
+    size_t chars_left = 0;
+    string result = "";
+
+    if (cache_size > 0)
+    {
+      result.append (read_cache_, cache_size);
+      memset (read_cache_, 0, buffer_size_);
+      chars_left = size - cache_size;
+    }
+    else
+    {
+      chars_left = size;
+    }
+
+    while (true)
+    {
+      size_t chars_read = pimpl_->read (read_cache_, buffer_size_ - 1);
+      if (chars_read > 0)
+      {
+        *(read_cache_ + chars_read) = '\0';
+        if (chars_left > chars_read)
+        {
+          memset (read_cache_, 0, buffer_size_);
+          result.append (read_cache_);
+          chars_left -= chars_read;
+        }
+        else
+        {
+          result.append (read_cache_, static_cast<size_t> (chars_left));
+          memmove (read_cache_, read_cache_ + chars_left, chars_read - chars_left);
+          *(read_cache_ + chars_read - chars_left) = '\0';
+          memset (read_cache_ + chars_read - chars_left, 0,
+                  buffer_size_ - chars_read - chars_left);
+          // Finished reading all of the data
+          break;
+        }
+      }
+      else
+        break; // Timeout occured
+    }
+    return result;
+  }
 }
 
 string
-Serial::readline(size_t size, string eol) {
-  size_t leneol = eol.length();
+Serial::readline (size_t size, string eol)
+{
+  size_t leneol = eol.length ();
   string line = "";
-  while (true) {
-    string c = pimpl->read(1);
-    if (!c.empty()) {
-      line.append(c);
-      if (line.length() > leneol
-       && line.substr(line.length() - leneol, leneol) == eol)
+  while (true)
+  {
+    string c = read (1);
+    if (!c.empty ())
+    {
+      line.append (c);
+      if (line.length () > leneol &&
+          line.substr (line.length () - leneol, leneol) == eol)
         break;
-      if (line.length() >= size) {
+      if (line.length () >= size)
+      {
         break;
       }
     }
-    else {
+    else
       // Timeout
       break;
-    }
   }
   return line;
 }
 
 vector<string>
-Serial::readlines(string eol) {
-  if (this->pimpl->getTimeout() < 0) {
+Serial::readlines(string eol)
+{
+  if (pimpl_->getTimeout () < 0)
+  {
     throw "Error, must be set for readlines";
   }
-  size_t leneol = eol.length();
+  size_t leneol = eol.length ();
   vector<string> lines;
-  while (true) {
-    string line = readline(numeric_limits<size_t>::max(), eol);
-    if (!line.empty()) {
-      lines.push_back(line);
-      if (line.substr(line.length() - leneol, leneol) == eol)
+  while (true)
+  {
+    string line = readline (numeric_limits<size_t>::max (), eol);
+    if (!line.empty ())
+    {
+      lines.push_back (line);
+      if (line.substr (line.length () - leneol, leneol) == eol)
         break;
     }
-    else {
+    else
       // Timeout
       break;
-    }
   }
   return lines;
 }
 
 size_t
-Serial::write (const string &data) {
-  return this->pimpl->write (data);
+Serial::write (const string &data)
+{
+  return pimpl_->write (data);
 }
 
 void
-Serial::setPort (const string &port) {
-  bool was_open = pimpl->isOpen();
-  if (was_open) this->close();
-  this->pimpl->setPort (port);
-  if (was_open) this->open();
+Serial::setPort (const string &port)
+{
+  bool was_open = pimpl_->isOpen();
+  if (was_open) close();
+  pimpl_->setPort (port);
+  if (was_open) open();
 }
 
 string
-Serial::getPort () const {
-  return this->pimpl->getPort ();
+Serial::getPort () const
+{
+  return pimpl_->getPort ();
 }
 
 void
-Serial::setTimeout (long timeout) {
-  this->pimpl->setTimeout (timeout);
+Serial::setTimeout (long timeout)
+{
+  pimpl_->setTimeout (timeout);
 }
 
 long
 Serial::getTimeout () const {
-  return this->pimpl->getTimeout ();
+  return pimpl_->getTimeout ();
 }
 
 void
-Serial::setBaudrate (unsigned long baudrate) {
-  this->pimpl->setBaudrate (baudrate);
+Serial::setBaudrate (unsigned long baudrate)
+{
+  pimpl_->setBaudrate (baudrate);
 }
 
 unsigned long
-Serial::getBaudrate () const {
-  return this->pimpl->getBaudrate ();
+Serial::getBaudrate () const
+{
+  return pimpl_->getBaudrate ();
 }
 
 void
-Serial::setBytesize (bytesize_t bytesize) {
-  this->pimpl->setBytesize (bytesize);
+Serial::setBytesize (bytesize_t bytesize)
+{
+  pimpl_->setBytesize (bytesize);
 }
 
 bytesize_t
-Serial::getBytesize () const {
-  return this->pimpl->getBytesize ();
+Serial::getBytesize () const
+{
+  return pimpl_->getBytesize ();
 }
 
 void
-Serial::setParity (parity_t parity) {
-  this->pimpl->setParity (parity);
+Serial::setParity (parity_t parity)
+{
+  pimpl_->setParity (parity);
 }
 
 parity_t
-Serial::getParity () const {
-  return this->pimpl->getParity ();
+Serial::getParity () const
+{
+  return pimpl_->getParity ();
 }
 
 void
-Serial::setStopbits (stopbits_t stopbits) {
-  this->pimpl->setStopbits (stopbits);
+Serial::setStopbits (stopbits_t stopbits)
+{
+  pimpl_->setStopbits (stopbits);
 }
 
 stopbits_t
-Serial::getStopbits () const {
-  return this->pimpl->getStopbits ();
+Serial::getStopbits () const
+{
+  return pimpl_->getStopbits ();
 }
 
 void
-Serial::setFlowcontrol (flowcontrol_t flowcontrol) {
-  this->pimpl->setFlowcontrol (flowcontrol);
+Serial::setFlowcontrol (flowcontrol_t flowcontrol)
+{
+  pimpl_->setFlowcontrol (flowcontrol);
 }
 
 flowcontrol_t
-Serial::getFlowcontrol () const {
-  return this->pimpl->getFlowcontrol ();
+Serial::getFlowcontrol () const
+{
+  return pimpl_->getFlowcontrol ();
 }
 
-void Serial::flush() {
-  this->pimpl->flush();
+void Serial::flush ()
+{
+  pimpl_->flush ();
+  memset (read_cache_, 0, buffer_size_);
 }
 
-void Serial::flushInput() {
-  this->pimpl->flushInput();
+void Serial::flushInput ()
+{
+  pimpl_->flushInput ();
 }
 
-void Serial::flushOutput() {
-  this->pimpl->flushOutput();
+void Serial::flushOutput ()
+{
+  pimpl_->flushOutput ();
+  memset (read_cache_, 0, buffer_size_);
 }
 
-void Serial::sendBreak(int duration) {
-  this->pimpl->sendBreak(duration);
+void Serial::sendBreak (int duration)
+{
+  pimpl_->sendBreak (duration);
 }
 
-void Serial::setBreak(bool level) {
-  this->pimpl->setBreak(level);
+void Serial::setBreak (bool level)
+{
+  pimpl_->setBreak (level);
 }
 
-void Serial::setRTS(bool level) {
-  this->pimpl->setRTS(level);
+void Serial::setRTS (bool level)
+{
+  pimpl_->setRTS (level);
 }
 
-void Serial::setDTR(bool level) {
-  this->pimpl->setDTR(level);
+void Serial::setDTR (bool level)
+{
+  pimpl_->setDTR (level);
 }
 
-bool Serial::getCTS() {
-  return this->pimpl->getCTS();
+bool Serial::getCTS ()
+{
+  return pimpl_->getCTS ();
 }
 
-bool Serial::getDSR() {
-  return this->pimpl->getDSR();
+bool Serial::getDSR ()
+{
+  return pimpl_->getDSR ();
 }
 
-bool Serial::getRI() {
-  return this->pimpl->getRI();
+bool Serial::getRI ()
+{
+  return pimpl_->getRI ();
 }
 
-bool Serial::getCD() {
-  return this->pimpl->getCD();
+bool Serial::getCD ()
+{
+  return pimpl_->getCD ();
 }
index 85055dbd9d960d962f4a8a8ed1e15d6744acf834..b106d0002be2691241bee1cefa45d5b773ed806a 100644 (file)
@@ -1,3 +1,5 @@
+/* Copyright 2012 William Woodall and John Harrison */
+
 #include "serial/serial_listener.h"
 
 /***** Inline Functions *****/
index bef6352fcff0e9e9e9be858a8c0abd0ce947cd7f..184d99dd40422e7d0f9a0e753ddf0e0dce1d3700 100644 (file)
@@ -1,10 +1,3 @@
-#include "gtest/gtest.h"
-
-#include <boost/bind.hpp>
-
-// OMG this is so nasty...
-// #define private public
-// #define protected public
 #include <string>
 #include <iostream>
 
@@ -14,17 +7,27 @@ using std::string;
 using std::cout;
 using std::endl;
 using serial::Serial;
+using serial::SerialExecption;
 
 int main(int argc, char **argv) {
-  Serial s("/dev/tty.usbserial-A900adHq", 115200, 2000);
-  s.flush();
-  int count = 0;
-  while (1) {
-    size_t available = s.available();
-    cout << "avialable: " << available << endl;
-    string line = s.readline();
-    cout << count << ": " << line;
-    count++;
+  try {
+    Serial s("/dev/tty.usbserial-A900adHq", 115200, 2000);
+    s.flush();
+    long long count = 0;
+    while (1) {
+      // size_t available = s.available();
+      // cout << "avialable: " << available << endl;
+      string line = s.readline();
+      cout << count << ": " << line << line.length() << endl;
+      count++;
+    }
+  }
+  catch (SerialExecption e)
+  {
+    cout << "Caught SerialException: " << e.what() << endl;
+  }
+  catch (...)
+  {
+    cout << "Caught an error." << endl;
   }
-  cout << endl << endl;
 }
This page took 0.109651 seconds and 4 git commands to generate.