13 #include <ecl/config/ecl.hpp>
22 #include <sys/ioctl.h>
28 #include "../../include/ecl/devices/serial_pos.hpp"
29 #include "../../include/ecl/devices/detail/error_handler.hpp"
40 #if defined(ECL_IS_APPLE)
42 #define B460800 460800
45 #define B921600 921600
69 Serial::Serial(
const std::string& port_name,
const BaudRate &baud_rate,
const DataBits &data_bits,
71 port(port_name), read_timeout_ms(5000), error_handler(
NoError)
75 open(port_name, baud_rate, data_bits, stop_bits, parity);
76 }
ecl_catch(
const StandardException &e ) {
90 bool Serial::open(
const std::string& port_name,
const BaudRate &baud_rate,
const DataBits &data_bits,
100 StandardException(LOC,ConfigurationError,
"Standard serial device does not accept StopBits_15 as valid (used in ftdi)."));
114 file_descriptor = ::open(port_name.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
115 if (file_descriptor == -1)
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)))
127 ecl_throw(StandardException(LOC,ConfigurationError,
"Selected baudrate is not supported."));
132 static const int data_bits_flags[] = {CS5, CS6, CS7, CS8};
144 fcntl(file_descriptor, F_SETFL, 0);
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;
152 file_lock.l_pid = getpid();
153 if (fcntl(file_descriptor, F_SETLK, &file_lock) != 0)
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))));
173 if (cfsetspeed(&options, baud_rate_flags[baud_rate]) < 0)
175 ecl_throw(StandardException(LOC,ConfigurationError,
"Setting speed failed."));
189 options.c_cflag |= CLOCAL;
190 options.c_cflag |= CREAD;
196 options.c_cflag &= ~CRTSCTS;
197 #elif defined (CNEW_RTSCTS)
198 options.c_cflag &= ~CNEW_RTSCTS;
206 options.c_cflag &= ~CSTOPB;
210 options.c_cflag |= CSTOPB;
216 options.c_cflag &= ~CSIZE;
217 options.c_cflag |= data_bits_flags[data_bits];
222 options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
228 options.c_iflag &= ~(IXON | IXOFF | IXANY);
240 options.c_cflag &= ~PARENB;
244 options.c_iflag |= (INPCK | ISTRIP);
245 options.c_cflag |= PARENB;
246 options.c_cflag &= ~PARODD;
250 options.c_iflag |= (INPCK | ISTRIP);
251 options.c_cflag |= PARENB;
252 options.c_cflag |= PARODD;
262 tcsetattr(file_descriptor, TCSAFLUSH, &options);
267 if ( read_timeout_ms == NonBlocking ) {
270 block(read_timeout_ms);
284 ::close(file_descriptor);
292 if ( access(port.c_str(), F_OK ) == -1 ) {
303 void Serial::block(
const unsigned long &timeout)
310 fake_loop_count = timeout;
312 else if (timeout < 20)
315 div_t
d = div(timeout, 2);
318 fake_loop_count =
d.quot;
322 fake_loop_count =
d.quot + 1;
328 div_t
d = div(timeout, 5);
331 fake_loop_count =
d.quot;
335 fake_loop_count =
d.quot + 1;
342 options.c_cc[VMIN] = 0;
346 options.c_cc[VTIME] =
static_cast<unsigned char>(1);
350 options.c_cc[VTIME] =
static_cast<unsigned char>(timeout / 100);
352 tcsetattr(file_descriptor, TCSAFLUSH, &options);
354 read_timeout_ms = timeout;
357 void Serial::unblock()
359 options.c_cc[VMIN] = 0;
360 options.c_cc[VTIME] = 0;
361 tcsetattr(file_descriptor, TCSAFLUSH, &options);
362 read_timeout_ms = NonBlocking;
368 long Serial::remaining()
371 ioctl(file_descriptor, FIONREAD, &bytes);