serial_port.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2010, ISR University of Coimbra.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the ISR University of Coimbra nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Gonçalo Cabrita on 01/10/2010
36 *********************************************************************/
37 
38 #ifndef KVH_SERIAL_PORT_H
39 #define KVH_SERIAL_PORT_H
40 
41 #include <stdint.h>
42 #include <termios.h>
43 #include <stdexcept>
44 #include <string>
45 #include <vector>
46 
47 #include <functional>
48 #include <thread> // NOLINT(build/c++11)
49 
50 class SerialException : public std::runtime_error
51 {
52 public:
53  explicit SerialException(const char* msg) : std::runtime_error(msg)
54  {
55  }
56 };
57 
59 {
60 public:
61  explicit SerialBufferFilledException(const char* msg) : SerialException(msg)
62  {
63  }
64 };
65 
67 {
68 public:
69  explicit SerialTimeoutException(const char* msg) : SerialException(msg)
70  {
71  }
72 };
73 
81 {
82 public:
84  SerialPort();
86  ~SerialPort();
87 
89 
96  void open(const char* port_name, int baud_rate = 115200);
97 
99 
102  void close();
103 
105  bool portOpen()
106  {
107  return fd_ != -1;
108  }
109 
111  int baudRate()
112  {
113  return baud_;
114  }
115 
117 
125  int write(const char* data, int length = -1);
126 
128 
137  int read(char* data, int max_length, int timeout = -1);
138 
140 
151  int readBytes(char* data, int length, int timeout = -1);
152 
154 
165  int readLine(char* data, int length, int timeout = -1);
166 
168 
178  bool readLine(std::string* data, int timeout = -1);
179 
181 
191  bool readBetween(std::string* data, char start, char end, int timeout = -1);
192 
194  int flush();
195 
196  //*** Stream functions ***
197 
199 
208  bool startReadStream(std::function<void(char*, int)> f);
209 
211 
220  bool startReadLineStream(std::function<void(std::string*)> f);
221 
223 
234  bool startReadBetweenStream(std::function<void(std::string*)> f, char start, char end);
235 
237  void stopStream();
239  void pauseStream();
241  void resumeStream();
242 
243 private:
245  int fd_;
247  int baud_;
248 
249  // std::vector<char> leftovers;
250 
252 
255  void readThread();
256 
258 
261  void readLineThread();
262 
264 
271  void readBetweenThread(char start, char end);
272 
274  std::thread* stream_thread_;
275 
277  std::function<void(char*, int)> readCallback;
279  std::function<void(std::string*)> readLineCallback;
281  std::function<void(std::string*)> readBetweenCallback;
282 
287 };
288 
289 #endif // KVH_SERIAL_PORT_H
SerialException(const char *msg)
Definition: serial_port.h:53
ROSCPP_DECL void start()
f
std::function< void(std::string *)> readBetweenCallback
Stream readBetween callback boost function.
Definition: serial_port.h:281
SerialBufferFilledException(const char *msg)
Definition: serial_port.h:61
bool stream_paused_
Whether streaming is paused or not.
Definition: serial_port.h:284
SerialTimeoutException(const char *msg)
Definition: serial_port.h:69
std::thread * stream_thread_
Stream thread.
Definition: serial_port.h:274
int fd_
File descriptor.
Definition: serial_port.h:245
bool stream_stopped_
Whether streaming is stopped or not.
Definition: serial_port.h:286
bool portOpen()
Check whether the port is open or not.
Definition: serial_port.h:105
std::function< void(std::string *)> readLineCallback
Stream readLine callback boost function.
Definition: serial_port.h:279
std::function< void(char *, int)> readCallback
Stream read callback boost function.
Definition: serial_port.h:277
int baud_
Baud rate.
Definition: serial_port.h:247
C++ serial port class for ROS.
Definition: serial_port.h:80
int baudRate()
Get the current baud rate.
Definition: serial_port.h:111


kvh_drivers
Author(s): Jeff Schmidt, Geoffrey Viola
autogenerated on Mon Jun 10 2019 13:45:24