serial.h
Go to the documentation of this file.
1 /***
2  * MIT License
3  *
4  * Copyright (c) 2020 Alessandro Tondo
5  * Copyright (c) 2012 William Woodall, John Harrison
6  *
7  * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated
8  * documentation files (the "Software"), to deal in the Software without restriction, including without limitation
9  * the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and
10  * to permit persons to whom the Software is furnished to do so, subject to the following conditions:
11  *
12  * The above copyright notice and this permission notice shall be included in all copies or substantial portions of
13  * the Software.
14  *
15  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO
16  * THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
17  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT,
18  * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
19  * SOFTWARE.
20  */
21 
22 #ifndef SERIAL_H
23 #define SERIAL_H
24 
25 #include <chrono>
26 #include <map>
27 #include <memory>
28 #include <mutex>
29 #include <regex>
30 #include <string>
31 #include <thread>
32 #include <vector>
33 
34 namespace serial {
35 
36 /***
37  * Enumeration defines the possible bytesizes for the serial port.
38  */
39 typedef enum {
40  fivebits = 5,
41  sixbits = 6,
42  sevenbits = 7,
43  eightbits = 8
44 } bytesize_t;
45 
46 /***
47  * Enumeration defines the possible parity types for the serial port.
48  */
49 typedef enum {
50  parity_none = 0,
51  parity_odd = 1,
52  parity_even = 2,
53  parity_mark = 3,
54  parity_space = 4
55 } parity_t;
56 
57 /***
58  * Enumeration defines the possible stopbit types for the serial port.
59  */
60 typedef enum {
61  stopbits_one = 1,
62  stopbits_two = 2,
64 } stopbits_t;
65 
66 /***
67  * Enumeration defines the possible flowcontrol types for the serial port.
68  */
69 typedef enum {
70  flowcontrol_none = 0,
74 
75 /***
76  * Class that provides a portable serial port interface.
77  */
78 class Serial {
79  public:
80  class Timeout {
81  public:
82  /***
83  * Create a non-blocking communication mode (since the Timeout structure is filled with 0).
84  */
85  Timeout() = default;
86 
87  /***
88  * Create a simplified constant-time Timeout structure (@sa Timeout below).
89  * @param read_write_constant A constant used to calculate the total timeout period for read/write operations.
90  */
91  explicit Timeout(uint32_t read_write_constant)
92  // the ugly parentheses around `(std::max)()` are required on Windows (this is to avoid to `#undef max` or to `#define NOMINMAX`)
93  : Timeout((std::numeric_limits<uint32_t>::max)(), read_write_constant, 0, read_write_constant, 0) {}
94 
95  /***
96  * Create a Timeout structure where all the parameters are expressed in milliseconds and refer to the documentation
97  * of @p COMMTIMEOUTS (https://docs.microsoft.com/en-us/windows/win32/api/winbase/ns-winbase-commtimeouts).@n
98  * @param inter_byte The maximum time allowed to elapse before the arrival of the next byte.
99  * @param read_constant A constant used to calculate the total timeout period for read operations.
100  * @param read_multiplier The multiplier used to calculate the total timeout period for read operations.
101  * @param write_constant A constant used to calculate the total timeout period for write operations.
102  * @param write_multiplier The multiplier used to calculate the total timeout period for write operations.
103  */
104  explicit Timeout(uint32_t inter_byte, uint32_t read_constant, uint32_t read_multiplier, uint32_t write_constant, uint32_t write_multiplier)
105  : inter_byte_(inter_byte),
106  read_constant_(read_constant),
107  read_multiplier_(read_multiplier),
108  write_constant_(write_constant),
109  write_multiplier_(write_multiplier) {}
110 
111  ~Timeout() = default;
112 
113  std::chrono::milliseconds getInterByte() { return inter_byte_; }
114  uint32_t getInterByteMilliseconds() { return inter_byte_.count(); }
115  std::chrono::milliseconds getReadConstant() { return read_constant_; }
116  uint32_t getReadConstantMilliseconds() { return read_constant_.count(); }
117  std::chrono::milliseconds getReadMultiplier() { return read_multiplier_; }
118  uint32_t getReadMultiplierMilliseconds() { return read_multiplier_.count(); }
119  std::chrono::milliseconds getWriteConstant() { return write_constant_; }
120  uint32_t getWriteConstantMilliseconds() { return write_constant_.count(); }
121  std::chrono::milliseconds getWriteMultiplier() { return write_multiplier_; }
122  uint32_t getWriteMultiplierMilliseconds() { return write_multiplier_.count(); }
123 
124  /***
125  * @param size The byte size expected to be read.
126  * @return The next timeout deadline for the current read settings and the given byte size.
127  */
128  std::chrono::steady_clock::time_point getReadDeadline(size_t size = 0) {
129  return std::chrono::steady_clock::now() + read_constant_ + read_multiplier_*size;
130  }
131 
132  /***
133  * @param size The byte size expected to be written.
134  * @return The next timeout deadline for the current write settings and the given byte size.
135  */
136  std::chrono::steady_clock::time_point getWriteDeadline(size_t size = 0) {
137  return std::chrono::steady_clock::now() + write_constant_ + write_multiplier_*size;
138  }
139 
140  /***
141  * @param deadline The read/write timeout deadline.
142  * @return The remaining microseconds w.r.t. the given deadline.
143  * @sa getReadDeadline, getWriteDeadline
144  */
145  static std::chrono::microseconds remainingMicroseconds(std::chrono::steady_clock::time_point deadline) {
146  return std::chrono::duration_cast<std::chrono::microseconds>(deadline - std::chrono::steady_clock::now());
147  }
148 
149  private:
150  std::chrono::duration<uint32_t, std::milli> inter_byte_;
151  std::chrono::duration<uint32_t, std::milli> read_constant_;
152  std::chrono::duration<uint32_t, std::milli> read_multiplier_;
153  std::chrono::duration<uint32_t, std::milli> write_constant_;
154  std::chrono::duration<uint32_t, std::milli> write_multiplier_;
155  };
156 
157  /***
158  * Create a Serial object and open the serial port if its name is provided. If not, it remains closed until
159  * @p Serial::open is called.
160  * @param port_name The path of the serial port, e.g. 'COM1' on Windows and '/dev/ttyS0' on Linux.
161  * @param baudrate The baud rate of the serial communication.
162  * @param timeout The timeout conditions of the serial communication. @sa Serial::Timeout
163  * @param bytesize The payload size of the serial communication (default is @p eightbits). @sa bytesize_t
164  * @param parity The parity method of the serial communication (default is @p parity_none). @sa parity_t
165  * @param stopbits The number of stop bits of the serial communication (default is @p stopbits_one). @sa stopbits_t
166  * @param flowcontrol The type of flow control of the serial communication (default is @p flowcontrol_none). @sa flowcontrol_t
167  * @throw serial::SerialIOException
168  * @throw serial::SerialInvalidArgumentException
169  */
170  explicit Serial(const std::string &port_name = "", uint32_t baudrate = 9600, Timeout timeout = Timeout(),
171  bytesize_t bytesize = eightbits, parity_t parity = parity_none, stopbits_t stopbits = stopbits_one,
172  flowcontrol_t flowcontrol = flowcontrol_none);
173 
174  virtual ~Serial();
175 
176  Serial(const Serial &) = delete;
177  Serial &operator=(const Serial &) = delete;
178 
179  /***
180  * Open the serial port as long as the port name is set into the Serial object (do nothing if already open).@n
181  * If the port name is provided to the constructor then an explicit call to open is not needed.
182  * @sa Serial::Serial
183  * @throw serial::SerialIOException
184  * @throw serial::SerialInvalidArgumentException
185  */
186  void open();
187 
188  /***
189  * @return @p true if the port is open.
190  */
191  bool isOpen() const;
192 
193  /***
194  * Close the serial port.
195  * @throw serial::SerialIOException
196  */
197  void close();
198 
199  /***
200  * @return The number of characters available in the input buffer.
201  * @throw serial::SerialIOException
202  * @throw serial::SerialPortNotOpenException
203  */
204  size_t available();
205 
206  /***
207  * Block until the port is in a readable state or timeout @p read_constant_ milliseconds have elapsed.
208  * @note Not implemented on Windows.
209  * @return @p true if the port is in a readable state.
210  * @throw serial::SerialException (only on Windows systems)
211  * @throw serial::SerialIOException
212  * @throw serial::SerialPortNotOpenException
213  */
214  bool waitReadable();
215 
216  /***
217  * Block until the port is in a writable state or timeout @p write_constant_ milliseconds have elapsed.
218  * @note Not implemented on Windows.
219  * @return @p true if the port is in a writable state.
220  * @throw serial::SerialException (only on Windows systems)
221  * @throw serial::SerialIOException
222  * @throw serial::SerialPortNotOpenException
223  */
224  bool waitWritable();
225 
226  /***
227  * Block for a period of time corresponding to the transmission time of count characters at present serial settings.
228  * This may be used in conjunction with @p Serial::waitReadable to read larger blocks of data from the port.
229  * @sa Serial::waitReadable
230  */
231  void waitByteTimes(size_t count);
232 
233  /***
234  * Read at most the given amount of bytes from the serial port and store them into the given buffer.@n
235  * This method returns as soon as @p size bytes are read or when the timeout triggers (either when the inter byte or
236  * the total timeouts expire, @sa Serial::Timeout).
237  * @param buffer The array of at least the given size (the caller must size it accordingly) where the data is stored.
238  * @param size The number of bytes that should be read.
239  * @return The number of bytes actually read.
240  * @throw serial::SerialIOException
241  * @throw serial::SerialPortNotOpenException
242  */
243  size_t read(uint8_t *buffer, size_t size);
244 
245  /***
246  * Read at most the given amount of bytes from the serial port and store them into the given buffer.@n
247  * This method returns as soon as @p size bytes are read or when the timeout triggers (either when the inter byte or
248  * the total timeouts expire, @sa Serial::Timeout).
249  * @param buffer The vector where the data is stored.
250  * @param size The number of bytes that should be read.
251  * @return The number of bytes actually read.
252  * @throw serial::SerialIOException
253  * @throw serial::SerialPortNotOpenException
254  */
255  size_t read(std::vector<uint8_t> &buffer, size_t size = 1);
256 
257  /***
258  * Read at most the given amount of characters from the serial port and store them into the given buffer.@n
259  * This method returns as soon as @p size characters are read or when the timeout triggers (either when the inter
260  * byte or the total timeouts expire, @sa Serial::Timeout).
261  * @param buffer The string where the data is stored.
262  * @param size The number of characters that should be read.
263  * @return The number of characters actually read.
264  * @throw serial::SerialIOException
265  * @throw serial::SerialPortNotOpenException
266  */
267  size_t read(std::string &buffer, size_t size = 1);
268 
269  /***
270  * Read at most the given amount of characters from the serial port and return them as string.@n
271  * This method returns as soon as @p size characters are read or when the timeout triggers (either when the inter
272  * byte or the total timeouts expire, @sa Serial::Timeout).
273  * @param size The number of characters that should be read.
274  * @return The string where the data is stored.
275  * @throw serial::SerialIOException
276  * @throw serial::SerialPortNotOpenException
277  */
278  std::string read(size_t size = 1);
279 
280  /***
281  * Read characters from the serial port until the given delimiter is found and store them into the given buffer.@n
282  * This method returns as soon as the given delimiter is found or @p size characters are read or when the timeout
283  * triggers (either when the inter byte or the total timeouts expire, @sa Serial::Timeout).
284  * @param line The string where the data is stored.
285  * @param size The maximum number of characters that can be read.
286  * @param eol The string to match against for the EOL.
287  * @return The number of characters actually read.
288  * @throw serial::SerialIOException
289  * @throw serial::SerialPortNotOpenException
290  */
291  size_t readline(std::string &line, size_t size = 65536, const std::string &eol = "\n");
292 
293  /***
294  * Read characters from the serial port until the given delimiter is found and store them into the given buffer.@n
295  * This method returns as soon as the given delimiter is found or @p size characters are read or when the timeout
296  * triggers (either when the inter byte or the total timeouts expire, @sa Serial::Timeout).
297  * @param size The maximum number of characters that can be read.
298  * @param eol The string to match against for the EOL.
299  * @return The string where the data is stored.
300  * @throw serial::SerialIOException
301  * @throw serial::SerialPortNotOpenException
302  */
303  std::string readline(size_t size = 65536, const std::string &eol = "\n");
304 
305  /***
306  * Read multiple lines from the serial port (identified by the given delimiter) and store them into the given vector
307  * (one line per element of the vector).@n
308  * This method returns when @p size characters are read or when the timeout triggers (either when the inter byte or
309  * the total timeouts expire, @sa Serial::Timeout).
310  * @param size The maximum number of characters that can be read.
311  * @param eol The string to match against for the EOL.
312  * @return The vector of strings where the data lines is stored.
313  * @throw serial::SerialIOException
314  * @throw serial::SerialPortNotOpenException
315  */
316  std::vector<std::string> readlines(size_t size = 65536, const std::string &eol = "\n");
317 
318  /***
319  * Write at most the given amount of bytes to the serial port.@n
320  * This method returns as soon as @p size bytes are written or when the timeout triggers (either when the inter byte
321  * or the total timeouts expire, @sa Serial::Timeout).@n
322  * @param data The array of at least the given size (the caller must size it accordingly) where the data is stored.
323  * @param size The number of bytes that should be written.
324  * @return The number of bytes actually written.
325  * @throw serial::SerialIOException
326  * @throw serial::SerialPortNotOpenException
327  */
328  size_t write(const uint8_t *data, size_t size);
329 
330  /***
331  * Write at most the given amount of bytes to the serial port.@n
332  * This method returns as soon as @p data.size() bytes are written or when the timeout triggers (either when the
333  * inter byte or the total timeouts expire, @sa Serial::Timeout).
334  * @param data The vector where the data is stored.
335  * @return The number of bytes actually written.
336  * @throw serial::SerialIOException
337  * @throw serial::SerialPortNotOpenException
338  */
339  size_t write(const std::vector<uint8_t> &data);
340 
341  /***
342  * Write at most the given amount of characters to the serial port.@n
343  * This method returns as soon as @p data.size() characters are written or when the timeout triggers (either when the
344  * inter byte or the total timeouts expire, @sa Serial::Timeout).
345  * @param data The string where the data is stored.
346  * @return The number of bytes actually written.
347  * @throw serial::SerialIOException
348  * @throw serial::SerialPortNotOpenException
349  */
350  size_t write(const std::string &data);
351 
352  /***
353  * Set the serial port identifier.
354  * @param port_name The path of the serial port, e.g. 'COM1' on Windows and '/dev/ttyS0' on Linux.
355  * @throw serial::SerialIOException
356  * @throw serial::SerialInvalidArgumentException
357  */
358  void setPort(const std::string &port_name);
359 
360  /***
361  * @return The serial port identifier.
362  */
363  std::string getPort() const;
364 
365  /***
366  * Sets the timeout for reads and writes using the Timeout struct.
367  * @param timeout A Timeout struct containing the inter byte timeout, and read/write timeout constants and multipliers.
368  * @sa Serial::Timeout
369  * @throw serial::SerialIOException (only on Windows systems)
370  * @throw serial::SerialInvalidArgumentException (only on Windows systems)
371  */
372  void setTimeout(const Timeout &timeout);
373 
374  /***
375  * Sets the timeouts for reads and writes.
376  * @param inter_byte The maximum time allowed to elapse before the arrival of the next byte.
377  * @param read_constant A constant used to calculate the total timeout period for read operations.
378  * @param read_multiplier The multiplier used to calculate the total timeout period for read operations.
379  * @param write_constant A constant used to calculate the total timeout period for write operations.
380  * @param write_multiplier The multiplier used to calculate the total timeout period for write operations.
381  * @sa Serial::Timeout
382  * @throw serial::SerialIOException (only on Windows systems)
383  * @throw serial::SerialInvalidArgumentException (only on Windows systems)
384  */
385  void setTimeout(uint32_t inter_byte, uint32_t read_constant, uint32_t read_multiplier, uint32_t write_constant, uint32_t write_multiplier);
386 
387  /***
388  * @return A Timeout struct containing the inter byte timeout, and read/write timeout constants and multipliers.
389  * @sa Serial::Timeout
390  */
391  Timeout getTimeout() const;
392 
393  /***
394  * Sets the baudrate for the serial port.
395  * @param baudrate The baud rate of the serial communication.
396  * @throw serial::SerialIOException
397  * @throw serial::SerialInvalidArgumentException
398  */
399  void setBaudrate(uint32_t baudrate);
400 
401  /***
402  * @return The baud rate of the serial communication.
403  */
404  uint32_t getBaudrate() const;
405 
406  /***
407  * Sets the byte size for the serial port.
408  * @param bytesize The payload size of the serial communication.
409  * @sa bytesize_t
410  * @throw serial::SerialIOException
411  * @throw serial::SerialInvalidArgumentException
412  */
413  void setBytesize(bytesize_t bytesize);
414 
415  /***
416  * @return The payload size of the serial communication.
417  * @sa bytesize_t
418  */
419  bytesize_t getBytesize() const;
420 
421  /***
422  * Sets the parity for the serial port.
423  * @param parity The parity method of the serial communication.
424  * @sa parity_t
425  * @throw serial::SerialIOException
426  * @throw serial::SerialInvalidArgumentException
427  */
428  void setParity(parity_t parity);
429 
430  /***
431  * @return The parity method of the serial communication.
432  * @sa parity_t
433  */
434  parity_t getParity() const;
435 
436  /***
437  * Sets the stop bits for the serial port.
438  * @param stopbits The number of stop bits of the serial communication.
439  * @sa stopbits_t
440  * @throw serial::SerialIOException
441  * @throw serial::SerialInvalidArgumentException
442  */
443  void setStopbits(stopbits_t stopbits);
444 
445  /***
446  * @return The number of stop bits of the serial communication.
447  * @sa stopbits_t
448  */
449  stopbits_t getStopbits() const;
450 
451  /***
452  * Sets the flow control for the serial port.
453  * @param flowcontrol The type of flow control of the serial communication.
454  * @sa flowcontrol_t
455  * @throw serial::SerialIOException
456  * @throw serial::SerialInvalidArgumentException
457  */
458  void setFlowcontrol(flowcontrol_t flowcontrol);
459 
460  /***
461  * @return The type of flow control of the serial communication.
462  * @sa flowcontrol_t
463  */
465 
466  /***
467  * Flush the input and output buffers of the serial communication.
468  * @throw serial::SerialIOException
469  * @throw serial::SerialPortNotOpenException
470  */
471  void flush();
472 
473  /***
474  * Flush the input buffer of the serial communication.
475  * @throw serial::SerialIOException
476  * @throw serial::SerialPortNotOpenException
477  */
478  void flushInput();
479 
480  /***
481  * Flush the output buffer of the serial communication.
482  * @throw serial::SerialIOException
483  * @throw serial::SerialPortNotOpenException
484  */
485  void flushOutput();
486 
487  /***
488  * Sends the serial break signal, see @p tcsendbreak().
489  * @note Not implemented on Windows.
490  * @throw serial::SerialException (only on Windows systems)
491  * @throw serial::SerialIOException
492  * @throw serial::SerialPortNotOpenException
493  */
494  void sendBreak(int duration);
495 
496  /***
497  * Set the break condition to the given level (default is @p true, high).
498  * @throw serial::SerialIOException
499  * @throw serial::SerialPortNotOpenException
500  */
501  void setBreak(bool level = true);
502 
503  /***
504  * Set the RTS handshaking line to the given level (default is @p true, high).
505  * @throw serial::SerialIOException
506  * @throw serial::SerialPortNotOpenException
507  */
508  void setRTS(bool level = true);
509 
510  /***
511  * Set the DTR handshaking line to the given level (default is @p true, high).
512  * @throw serial::SerialIOException
513  * @throw serial::SerialPortNotOpenException
514  */
515  void setDTR(bool level = true);
516 
517  /***
518  * Blocks until CTS, DSR, RI, CD changes or something interrupts it.
519  * @return @p true if one of the lines changed, @p false otherwise.
520  * @throw serial::SerialException (#ifndef TIOCMIWAIT on unix systems)
521  * @throw serial::SerialIOException
522  * @throw serial::SerialPortNotOpenException
523  */
524  void waitForModemChanges();
525 
526  /***
527  * @return The current status of the CTS line.
528  * @throw serial::SerialIOException
529  * @throw serial::SerialPortNotOpenException
530  */
531  bool getCTS();
532 
533  /***
534  * @return The current status of the DSR line.
535  * @throw serial::SerialIOException
536  * @throw serial::SerialPortNotOpenException
537  */
538  bool getDSR();
539 
540  /***
541  * @return The current status of the RI line.
542  * @throw serial::SerialIOException
543  * @throw serial::SerialPortNotOpenException
544  */
545  bool getRI();
546 
547  /***
548  * @return The current status of the CD line.
549  * @throw serial::SerialIOException
550  * @throw serial::SerialPortNotOpenException
551  */
552  bool getCD();
553 
554  private:
555  class SerialImpl;
556  std::unique_ptr<SerialImpl> pimpl_;
557  std::mutex read_mutex_;
558  std::mutex write_mutex_;
559 
560  size_t readline_(std::string &line, size_t size = 65536, const std::string &eol = "\n"); // core method which does not lock on mutex
561 };
562 
563 class SerialException : public std::runtime_error {
564  public:
565  SerialException() : SerialException("generic fault") {}
566  explicit SerialException(const std::string &what_arg) : std::runtime_error("Serial Exception: " + what_arg + ".") {}
567 };
568 
569 class SerialInvalidArgumentException : public std::invalid_argument {
570  public:
572  explicit SerialInvalidArgumentException(const std::string &what_arg) : std::invalid_argument("Serial Invalid Argument Exception: " + what_arg + ".") {}
573 };
574 
575 class SerialIOException : public std::runtime_error {
576  public:
577  SerialIOException() : SerialIOException("generic fault") {}
578  explicit SerialIOException(const std::string &what_arg) : std::runtime_error("Serial IO Exception: " + what_arg + "'.") {}
579  explicit SerialIOException(const std::string &what_arg, uint32_t error) : std::runtime_error("Serial IO Exception: " + what_arg + ", error has been set to '" + std::to_string(error) + "'.") {}
580 };
581 
582 class SerialPortNotOpenException : public std::runtime_error {
583  public:
584  SerialPortNotOpenException() : std::runtime_error("Serial Port Not Open Exception.") {}
585 };
586 
587 /***
588  * Structure that describes a serial device.
589  */
590 class PortInfo {
591  public:
592  PortInfo() = default;
593  ~PortInfo() = default;
594 
595  uint16_t busnum {0};
596  uint16_t devnum {0};
597  uint16_t id_product {0};
598  uint16_t id_vendor {0};
599  std::string manufacturer;
600  std::string product;
601  std::string serial_number;
602  std::string serial_port;
603 
604  /***
605  * Fill all the @p PortInfo members with the data from the given serial port node (if found in the system).@n
606  * If the serial port is not a USB device, only the @p serial_port field is filled.
607  * @param serial_port_name The serial port name to search for, e.g. 'COM1' on Windows and '/dev/ttyS0' on Linux.
608  * @return @p 0 on success, @p -1 otherwise.
609  */
610  int getPortInfo(const std::string &serial_port_name);
611 };
612 
613 /***
614  * Return through the given vector the @p PortInfo of all the serial port connected to the system.
615  * @param serial_ports The vector of serial port info.
616  * @return @p 0 on success, @p -1 otherwise.
617  * @sa PortInfo
618  */
619 int getPortsInfo(std::vector<PortInfo> &serial_ports);
620 
621 /***
622  * Return through the given vector the names of all the serial port connected to the system.
623  * @param serial_port_names The vector of serial port names.
624  * @return @p 0 on success, @p -1 otherwise.
625  */
626 int getPortsList(std::vector<std::string> &serial_port_names);
627 
628 } // namespace serial
629 
630 #endif
serial::PortInfo::getPortInfo
int getPortInfo(const std::string &serial_port_name)
serial::Serial::setBaudrate
void setBaudrate(uint32_t baudrate)
Definition: serial.cpp:178
serial::parity_t
parity_t
Definition: serial.h:68
serial::PortInfo
Definition: serial.h:609
serial::parity_mark
@ parity_mark
Definition: serial.h:74
serial::Serial::flushInput
void flushInput()
Definition: serial.cpp:224
serial::Serial::getTimeout
Timeout getTimeout() const
Definition: serial.cpp:174
serial::Serial::Timeout::getWriteConstantMilliseconds
uint32_t getWriteConstantMilliseconds()
Definition: serial.h:143
serial::Serial::setTimeout
void setTimeout(const Timeout &timeout)
Definition: serial.cpp:166
serial::SerialIOException
Definition: serial.h:594
serial::Serial::Timeout::Timeout
Timeout()=default
serial::Serial::setPort
void setPort(const std::string &port_name)
Definition: serial.cpp:149
serial::Serial::Timeout::read_multiplier_
std::chrono::duration< uint32_t, std::milli > read_multiplier_
Definition: serial.h:175
serial::Serial::Timeout::getReadMultiplier
std::chrono::milliseconds getReadMultiplier()
Definition: serial.h:140
serial::Serial::setParity
void setParity(parity_t parity)
Definition: serial.cpp:194
serial
Definition: impl.h:56
serial::SerialPortNotOpenException::SerialPortNotOpenException
SerialPortNotOpenException()
Definition: serial.h:603
serial::Serial::Timeout::getInterByteMilliseconds
uint32_t getInterByteMilliseconds()
Definition: serial.h:137
serial::PortInfo::PortInfo
PortInfo()=default
serial::PortInfo::id_product
uint16_t id_product
Definition: serial.h:618
serial::Serial::waitForModemChanges
void waitForModemChanges()
Definition: serial.cpp:250
serial::Serial::readline
size_t readline(std::string &line, size_t size=65536, const std::string &eol="\n")
Definition: serial.cpp:110
serial::Serial::Timeout::getWriteConstant
std::chrono::milliseconds getWriteConstant()
Definition: serial.h:142
serial::PortInfo::manufacturer
std::string manufacturer
Definition: serial.h:620
serial::Serial::getDSR
bool getDSR()
Definition: serial.cpp:258
serial::Serial::Timeout::inter_byte_
std::chrono::duration< uint32_t, std::milli > inter_byte_
Definition: serial.h:173
serial::SerialException::SerialException
SerialException()
Definition: serial.h:584
serial::Serial::Timeout
Definition: serial.h:101
serial::Serial::close
void close()
Definition: serial.cpp:41
serial::Serial::getParity
parity_t getParity() const
Definition: serial.cpp:198
serial::PortInfo::serial_number
std::string serial_number
Definition: serial.h:622
serial::stopbits_one
@ stopbits_one
Definition: serial.h:82
serial::Serial::setRTS
void setRTS(bool level=true)
Definition: serial.cpp:242
serial::Serial::setBytesize
void setBytesize(bytesize_t bytesize)
Definition: serial.cpp:186
serial::Serial::Timeout::getWriteMultiplierMilliseconds
uint32_t getWriteMultiplierMilliseconds()
Definition: serial.h:145
serial::Serial::flush
void flush()
Definition: serial.cpp:218
serial::PortInfo::serial_port
std::string serial_port
Definition: serial.h:623
serial::Serial::Timeout::getWriteMultiplier
std::chrono::milliseconds getWriteMultiplier()
Definition: serial.h:144
serial::flowcontrol_software
@ flowcontrol_software
Definition: serial.h:92
serial::SerialInvalidArgumentException::SerialInvalidArgumentException
SerialInvalidArgumentException()
Definition: serial.h:590
serial::parity_even
@ parity_even
Definition: serial.h:73
serial::Serial::waitReadable
bool waitReadable()
Definition: serial.cpp:53
serial::Serial::readlines
std::vector< std::string > readlines(size_t size=65536, const std::string &eol="\n")
Definition: serial.cpp:122
serial::Serial::getStopbits
stopbits_t getStopbits() const
Definition: serial.cpp:206
serial::PortInfo::~PortInfo
~PortInfo()=default
serial::Serial::Timeout::~Timeout
~Timeout()=default
serial::bytesize_t
bytesize_t
Definition: serial.h:58
serial::Serial::getRI
bool getRI()
Definition: serial.cpp:262
serial::Serial::flushOutput
void flushOutput()
Definition: serial.cpp:229
serial::PortInfo::id_vendor
uint16_t id_vendor
Definition: serial.h:619
serial::Serial::Timeout::read_constant_
std::chrono::duration< uint32_t, std::milli > read_constant_
Definition: serial.h:174
serial::Serial::getCD
bool getCD()
Definition: serial.cpp:266
serial::Serial
Definition: serial.h:97
serial::Serial::Timeout::getReadConstantMilliseconds
uint32_t getReadConstantMilliseconds()
Definition: serial.h:139
serial::PortInfo::product
std::string product
Definition: serial.h:621
serial::Serial::pimpl_
std::unique_ptr< SerialImpl > pimpl_
Definition: serial.h:576
serial::parity_odd
@ parity_odd
Definition: serial.h:72
serial::Serial::setFlowcontrol
void setFlowcontrol(flowcontrol_t flowcontrol)
Definition: serial.cpp:210
serial::PortInfo::devnum
uint16_t devnum
Definition: serial.h:617
serial::Serial::SerialImpl
Definition: impl.h:88
serial::Serial::getBaudrate
uint32_t getBaudrate() const
Definition: serial.cpp:182
serial::Serial::~Serial
virtual ~Serial()
Definition: serial.cpp:33
serial::Serial::getCTS
bool getCTS()
Definition: serial.cpp:254
serial::Serial::open
void open()
Definition: serial.cpp:37
serial::Serial::Timeout::getReadDeadline
std::chrono::steady_clock::time_point getReadDeadline(size_t size=0)
Definition: serial.h:151
serial::Serial::sendBreak
void sendBreak(int duration)
Definition: serial.cpp:234
serial::Serial::getFlowcontrol
flowcontrol_t getFlowcontrol() const
Definition: serial.cpp:214
serial::Serial::Timeout::write_constant_
std::chrono::duration< uint32_t, std::milli > write_constant_
Definition: serial.h:176
serial::flowcontrol_t
flowcontrol_t
Definition: serial.h:88
serial::sevenbits
@ sevenbits
Definition: serial.h:82
serial::Serial::Timeout::getReadMultiplierMilliseconds
uint32_t getReadMultiplierMilliseconds()
Definition: serial.h:141
serial::Serial::Timeout::getInterByte
std::chrono::milliseconds getInterByte()
Definition: serial.h:136
std
serial::Serial::setStopbits
void setStopbits(stopbits_t stopbits)
Definition: serial.cpp:202
serial::SerialIOException::SerialIOException
SerialIOException()
Definition: serial.h:596
serial::Serial::available
size_t available()
Definition: serial.cpp:49
serial::Serial::isOpen
bool isOpen() const
Definition: serial.cpp:45
serial::stopbits_one_point_five
@ stopbits_one_point_five
Definition: serial.h:84
serial::Serial::Timeout::getReadConstant
std::chrono::milliseconds getReadConstant()
Definition: serial.h:138
serial::parity_space
@ parity_space
Definition: serial.h:75
serial::stopbits_t
stopbits_t
Definition: serial.h:79
serial::flowcontrol_none
@ flowcontrol_none
Definition: serial.h:91
serial::Serial::setDTR
void setDTR(bool level=true)
Definition: serial.cpp:246
serial::Serial::getBytesize
bytesize_t getBytesize() const
Definition: serial.cpp:190
serial::SerialPortNotOpenException
Definition: serial.h:601
serial::flowcontrol_hardware
@ flowcontrol_hardware
Definition: serial.h:93
serial::Serial::waitByteTimes
void waitByteTimes(size_t count)
Definition: serial.cpp:61
serial::Serial::readline_
size_t readline_(std::string &line, size_t size=65536, const std::string &eol="\n")
Definition: serial.cpp:92
serial::getPortsList
int getPortsList(std::vector< std::string > &serial_port_names)
serial::fivebits
@ fivebits
Definition: serial.h:80
serial::SerialException
Definition: serial.h:582
serial::parity_none
@ parity_none
Definition: serial.h:71
serial::Serial::Timeout::remainingMicroseconds
static std::chrono::microseconds remainingMicroseconds(std::chrono::steady_clock::time_point deadline)
Definition: serial.h:168
serial::stopbits_two
@ stopbits_two
Definition: serial.h:83
serial::Serial::read_mutex_
std::mutex read_mutex_
Definition: serial.h:578
serial::Serial::operator=
Serial & operator=(const Serial &)=delete
serial::Serial::Serial
Serial(const std::string &port_name="", uint32_t baudrate=9600, Timeout timeout=Timeout(), bytesize_t bytesize=eightbits, parity_t parity=parity_none, stopbits_t stopbits=stopbits_one, flowcontrol_t flowcontrol=flowcontrol_none)
Definition: serial.cpp:27
serial::Serial::getPort
std::string getPort() const
Definition: serial.cpp:162
serial::Serial::setBreak
void setBreak(bool level=true)
Definition: serial.cpp:238
serial::getPortsInfo
int getPortsInfo(std::vector< PortInfo > &serial_ports)
serial::Serial::write
size_t write(const uint8_t *data, size_t size)
Definition: serial.cpp:144
serial::sixbits
@ sixbits
Definition: serial.h:81
serial::Serial::read
size_t read(uint8_t *buffer, size_t size)
Definition: serial.cpp:65
serial::Serial::Timeout::getWriteDeadline
std::chrono::steady_clock::time_point getWriteDeadline(size_t size=0)
Definition: serial.h:159
serial::Serial::Timeout::write_multiplier_
std::chrono::duration< uint32_t, std::milli > write_multiplier_
Definition: serial.h:177
serial::Serial::write_mutex_
std::mutex write_mutex_
Definition: serial.h:579
serial::eightbits
@ eightbits
Definition: serial.h:83
serial::PortInfo::busnum
uint16_t busnum
Definition: serial.h:616
serial::Serial::waitWritable
bool waitWritable()
Definition: serial.cpp:57


qb_device_driver
Author(s): qbroboticsĀ®
autogenerated on Thu Apr 27 2023 02:36:32