serial_pos.cpp
Go to the documentation of this file.
1 
9 /*****************************************************************************
10  ** Platform Check
11  *****************************************************************************/
12 
13 #include <ecl/config/ecl.hpp>
14 #ifdef ECL_IS_POSIX
15 
16 /*****************************************************************************
17  ** Includes
18  *****************************************************************************/
19 
20 #include <errno.h>
21 #include <fcntl.h>
22 #include <sys/ioctl.h>
23 #include <termios.h>
24 #include <cstdlib> // div
25 #include <unistd.h> // access
28 #include "../../include/ecl/devices/serial_pos.hpp"
29 #include "../../include/ecl/devices/detail/error_handler.hpp"
30 
31 /*****************************************************************************
32  ** Platform Checks
33  *****************************************************************************/
34 
35 #include <ecl/config.hpp>
36 // B921600 baud rate macro is not part of the posix specification (see
37 // http://digilander.libero.it/robang/rubrica/serial.htm#3_1_1). However
38 // FreeBSD has had it for at least four years and linux quite some time too.
39 // Apple Macs however do not currently have it, so we help it here.
40 #if defined(ECL_IS_APPLE)
41  #ifndef B460800
42  #define B460800 460800
43  #endif
44  #ifndef B921600
45  #define B921600 921600
46  #endif
47 #endif
48 
49 /*****************************************************************************
50  ** Namespaces
51  *****************************************************************************/
52 
53 namespace ecl
54 {
55 
56 /*****************************************************************************
57  ** Using
58  *****************************************************************************/
59 
60 using std::string;
62 using ecl::OpenError;
64 
65 /*****************************************************************************
66  ** Implementation [Serial][C&D]
67  *****************************************************************************/
68 
69 Serial::Serial(const std::string& port_name, const BaudRate &baud_rate, const DataBits &data_bits,
70  const StopBits &stop_bits, const Parity &parity) :
71  port(port_name), read_timeout_ms(5000), error_handler(NoError)
72 {
73  ecl_try
74  {
75  open(port_name, baud_rate, data_bits, stop_bits, parity);
76  } ecl_catch( const StandardException &e ) {
77  ecl_throw(StandardException(LOC,e));
78  }
79 }
80 
81 Serial::~Serial()
82 {
83  close();
84 }
85 
86 /*****************************************************************************
87  ** Implementation [Serial][Open]
88  *****************************************************************************/
89 
90 bool Serial::open(const std::string& port_name, const BaudRate &baud_rate, const DataBits &data_bits,
91  const StopBits &stop_bits, const Parity &parity)
92 {
93 
94  /*********************
95  ** Input Checks
96  **********************/
97  if (stop_bits == StopBits_15)
98  {
99  ecl_throw(
100  StandardException(LOC,ConfigurationError,"Standard serial device does not accept StopBits_15 as valid (used in ftdi)."));
101  error_handler = InvalidArgError;
102  is_open = false;
103  return false;
104  }
105 
106  if (open())
107  {
108  close();
109  }
110  port = port_name;
111  // One curious thing here is O_NONBLOCK. If you do not specify this, it will try
112  // and wait till the line has an 'other' end. Which it can't possibly know, so
113  // it will effectively block here forever.
114  file_descriptor = ::open(port_name.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
115  if (file_descriptor == -1)
116  {
117  ecl_throw(devices::open_exception(LOC,port_name));
118  error_handler = devices::open_error();
119  is_open = false;
120  return false;
121  }
122 
123  static const int baud_rate_flags[] = {B110, B300, B600, B1200, B2400, B4800, B9600, B19200, B38400, B57600, B115200,
124  B230400, B460800, B921600};
125  if (baud_rate >= (sizeof(baud_rate_flags) / sizeof(B110)))
126  {
127  ecl_throw(StandardException(LOC,ConfigurationError,"Selected baudrate is not supported."));
128  error_handler = InvalidArgError;
129  is_open = false;
130  return false;
131  }
132  static const int data_bits_flags[] = {CS5, CS6, CS7, CS8};
133 
134  /*********************
135  ** Current Settings
136  **********************/
137 // tcgetattr(file_descriptor,&options); // Need?
138  /******************************************
139  ** Flow Control
140  *******************************************/
141  // Turn off the O_NONBLOCK we set back when opening (we want by default
142  // blocking and timeouts etc to occur).
143  // Using 0 as the argument here resets the file status flags to defaults.
144  fcntl(file_descriptor, F_SETFL, 0);
145  // this came from ros' hokoyu node code for setting a lock on the device file descriptor
146  // useful if you want to make sure other devices dont mess with your device!
147  struct flock file_lock;
148  file_lock.l_type = F_WRLCK;
149  file_lock.l_whence = SEEK_SET;
150  file_lock.l_start = 0;
151  file_lock.l_len = 0;
152  file_lock.l_pid = getpid();
153  if (fcntl(file_descriptor, F_SETLK, &file_lock) != 0)
154  {
155  ecl_throw(
156  StandardException(LOC,OpenError,std::string("Device is already locked. Try 'lsof | grep ") + port + std::string("' to find other processes that currently have the port open (if the device is a symbolic link you may need to replace the device name with the device that it is pointing to) [posix error in case it is something else: " + std::to_string(errno))));
157  error_handler = IsLockedError;
158  is_open = false;
159  return false;
160  }
161 
162  /******************************************
163  ** Initialise flags
164  *******************************************/
165  options.c_cflag = 0;
166  options.c_iflag = 0;
167  options.c_lflag = 0;
168  options.c_oflag = 0;
169 
170  /*********************
171  ** Baud rates
172  **********************/
173  if (cfsetspeed(&options, baud_rate_flags[baud_rate]) < 0)
174  {
175  ecl_throw(StandardException(LOC,ConfigurationError,"Setting speed failed."));
176  error_handler = InvalidArgError;
177  is_open = false;
178  return false;
179  }
180 
181  /*********************
182  ** Ownership
183  **********************/
184  /*
185  * CLOCAL and CREAD should always be set.
186  * They make sure the owner of the port is
187  * not changed by the program.
188  */
189  options.c_cflag |= CLOCAL;
190  options.c_cflag |= CREAD;
191 
192  /*********************
193  ** Disable Flow control
194  **********************/
195 #if defined(CRTSCTS)
196  options.c_cflag &= ~CRTSCTS; // Disable hardware flow control (old)
197 #elif defined (CNEW_RTSCTS)
198  options.c_cflag &= ~CNEW_RTSCTS; // Disable hardware flow control (new)
199 #endif
200 
201  /*********************
202  ** StopBits
203  **********************/
204  if (stop_bits == StopBits_1)
205  {
206  options.c_cflag &= ~CSTOPB; // One stop bit only
207  }
208  else
209  {
210  options.c_cflag |= CSTOPB; // Two stop bits.
211  }
212 
213  /******************************************
214  ** DataBits
215  *******************************************/
216  options.c_cflag &= ~CSIZE; // Mask (i.e. reset) character size bits
217  options.c_cflag |= data_bits_flags[data_bits]; // Now set the # data bits
218 
219  /******************************************
220  ** Processing
221  *******************************************/
222  options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG); // raw, no echoing or waiting till a flush or signals
223  // options.c_lflag |= (ICANON | ECHO | ECHOE); // like a chat session
224 
225  /******************************************
226  ** Input Options
227  *******************************************/
228  options.c_iflag &= ~(IXON | IXOFF | IXANY); // Disable software flow control
229 
230  /******************************************
231  ** Output Options
232  *******************************************/
233 // options.c_oflag |= OPOST; // Perform a little post processing
234 // options.c_oflag |= ONLCR; // Man NL to NL-CR
235  /*********************
236  ** Parity
237  **********************/
238  if (parity == NoParity)
239  {
240  options.c_cflag &= ~PARENB; // No Parity
241  }
242  else if (parity == EvenParity)
243  {
244  options.c_iflag |= (INPCK | ISTRIP); // Enable parity check and strip parity bit
245  options.c_cflag |= PARENB;
246  options.c_cflag &= ~PARODD;
247  }
248  else
249  { // OddParity
250  options.c_iflag |= (INPCK | ISTRIP); // Enable parity check and strip parity bit
251  options.c_cflag |= PARENB;
252  options.c_cflag |= PARODD;
253  }
254 
255  /******************************************
256  ** Enable
257  *******************************************
258  * TCSANOW - make changes immediately
259  * TCSADRAIN - wait till everything is transmitted, don't do anything with unread data.
260  * TCSAFLUSH - wait till everything is transmitted, also clear unread data.
261  *******************************************/
262  tcsetattr(file_descriptor, TCSAFLUSH, &options);
263 
264  /******************************************
265  ** Reset Status
266  *******************************************/
267  if ( read_timeout_ms == NonBlocking ) {
268  unblock();
269  } else {
270  block(read_timeout_ms);
271  }
272  clear();
273 
274  is_open = true;
275  error_handler = NoError;
276  return true;
277 }
278 
279 void Serial::close()
280 {
281  if (is_open)
282  {
283  // should check return values here, it does have some, EBADF/EINTR/EIO
284  ::close(file_descriptor);
285  is_open = false;
286  }
287 }
288 
289 bool Serial::open()
290 {
291  if ( is_open ) {
292  if ( access(port.c_str(), F_OK ) == -1 ) {
293  close();
294  }
295  }
296  return is_open;
297 }
298 
299 /*****************************************************************************
300  ** Implementation [Serial][Reading Modes]
301  *****************************************************************************/
302 
303 void Serial::block(const unsigned long &timeout)
304 {
305  if (timeout < 100)
306  {
307  if (timeout < 5)
308  {
309  fake_snooze.period(ecl::Duration(0.001));
310  fake_loop_count = timeout;
311  }
312  else if (timeout < 20)
313  {
314  fake_snooze.period(ecl::Duration(0.002));
315  div_t d = div(timeout, 2);
316  if (d.rem == 0)
317  {
318  fake_loop_count = d.quot;
319  }
320  else
321  {
322  fake_loop_count = d.quot + 1;
323  }
324  }
325  else
326  {
327  fake_snooze.period(ecl::Duration(0.005));
328  div_t d = div(timeout, 5);
329  if (d.rem == 0)
330  {
331  fake_loop_count = d.quot;
332  }
333  else
334  {
335  fake_loop_count = d.quot + 1;
336  }
337  }
338  this->unblock();
339  }
340  else
341  {
342  options.c_cc[VMIN] = 0;
343  // VTIME is in tenths of a second
344  if (timeout < 100)
345  { // just in case we're not running in debug mode or exceptions are disabled.
346  options.c_cc[VTIME] = static_cast<unsigned char>(1); // 100/100
347  }
348  else
349  {
350  options.c_cc[VTIME] = static_cast<unsigned char>(timeout / 100);
351  }
352  tcsetattr(file_descriptor, TCSAFLUSH, &options);
353  }
354  read_timeout_ms = timeout;
355 }
356 
357 void Serial::unblock()
358 {
359  options.c_cc[VMIN] = 0;
360  options.c_cc[VTIME] = 0;
361  tcsetattr(file_descriptor, TCSAFLUSH, &options);
362  read_timeout_ms = NonBlocking;
363 }
364 
365 /*****************************************************************************
366  ** Implementation [Serial][Reading]
367  *****************************************************************************/
368 long Serial::remaining()
369 {
370  long bytes = 0;
371  ioctl(file_descriptor, FIONREAD, &bytes);
372  return bytes;
373 }
374 
375 } // namespace ecl
376 #endif /* ECL_IS_POSIX */
ecl::InvalidInputError
InvalidInputError
ecl::OpenError
OpenError
ecl_try
#define ecl_try
IsLockedError
IsLockedError
ecl::StopBits_15
@ StopBits_15
Definition: serial_parameters.hpp:74
ecl::Parity
Parity
Parity of the serial packet.
Definition: serial_parameters.hpp:83
ecl::NoParity
@ NoParity
Definition: serial_parameters.hpp:84
ecl::EvenParity
@ EvenParity
Definition: serial_parameters.hpp:86
d
void d()
ecl::StandardException
ecl::NoError
NoError
ecl::DataBits
DataBits
Data bits used in a serial packet.
Definition: serial_parameters.hpp:60
ecl::Duration
TimeStamp Duration
config.hpp
InvalidArgError
InvalidArgError
ecl::BaudRate
BaudRate
Serial connection baud rate.
Definition: serial_parameters.hpp:38
standard_exception.hpp
ecl_catch
#define ecl_catch(exception)
ecl_throw
#define ecl_throw(exception)
ecl::StopBits_1
@ StopBits_1
Definition: serial_parameters.hpp:73
ecl::devices::open_exception
StandardException open_exception(const char *loc, const std::string &file_name)
Definition: exception_handler_pos.cpp:56
macros.hpp
ecl
Embedded control libraries.
ecl::devices::open_error
ecl::Error open_error()
Definition: error_handler.cpp:46
ecl::StopBits
StopBits
Stop bits used in a serial packet.
Definition: serial_parameters.hpp:72


ecl_devices
Author(s): Daniel Stonier
autogenerated on Wed Mar 2 2022 00:16:45