macOS/net_serial.cpp
Go to the documentation of this file.
1 /*
2  * RPLIDAR SDK
3  *
4  * Copyright (c) 2009 - 2014 RoboPeak Team
5  * http://www.robopeak.com
6  * Copyright (c) 2014 - 2018 Shanghai Slamtec Co., Ltd.
7  * http://www.slamtec.com
8  *
9  */
10 /*
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions are met:
13  *
14  * 1. Redistributions of source code must retain the above copyright notice,
15  * this list of conditions and the following disclaimer.
16  *
17  * 2. Redistributions in binary form must reproduce the above copyright notice,
18  * this list of conditions and the following disclaimer in the documentation
19  * and/or other materials provided with the distribution.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
23  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
24  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
25  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
26  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
27  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
28  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
29  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
30  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
31  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *
33  */
34 
35 #include "arch/macOS/arch_macOS.h"
36 #include "arch/macOS/net_serial.h"
37 #include <termios.h>
38 #include <sys/select.h>
39 
40 namespace rp{ namespace arch{ namespace net{
41 
43  : rp::hal::serial_rxtx()
44  , _baudrate(0)
45  , _flags(0)
46  , serial_fd(-1)
47 {
48  _init();
49 }
50 
51 raw_serial::~raw_serial()
52 {
53  close();
54 
55 }
56 
57 bool raw_serial::open()
58 {
59  return open(_portName, _baudrate, _flags);
60 }
61 
62 bool raw_serial::bind(const char * portname, uint32_t baudrate, uint32_t flags)
63 {
64  strncpy(_portName, portname, sizeof(_portName));
65  _baudrate = baudrate;
66  _flags = flags;
67  return true;
68 }
69 
70 bool raw_serial::open(const char * portname, uint32_t baudrate, uint32_t flags)
71 {
72  if (isOpened()) close();
73 
74  serial_fd = ::open(portname, O_RDWR | O_NOCTTY | O_NDELAY);
75 
76  if (serial_fd == -1) return false;
77 
78  struct termios options, oldopt;
79  tcgetattr(serial_fd, &oldopt);
80  bzero(&options,sizeof(struct termios));
81 
82  _u32 termbaud = getTermBaudBitmap(baudrate);
83 
84  if (termbaud == (_u32)-1) {
85  fprintf(stderr, "Baudrate %d is not supported on macOS\r\n", baudrate);
86  close();
87  return false;
88  }
89  cfsetispeed(&options, termbaud);
90  cfsetospeed(&options, termbaud);
91 
92  // enable rx and tx
93  options.c_cflag |= (CLOCAL | CREAD);
94 
95 
96  options.c_cflag &= ~PARENB; //no checkbit
97  options.c_cflag &= ~CSTOPB; //1bit stop bit
98 
99  options.c_cflag &= ~CSIZE;
100  options.c_cflag |= CS8; /* Select 8 data bits */
101 
102 #ifdef CNEW_RTSCTS
103  options.c_cflag &= ~CNEW_RTSCTS; // no hw flow control
104 #endif
105 
106  options.c_iflag &= ~(IXON | IXOFF | IXANY); // no sw flow control
107 
108  // raw input mode
109  options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
110  // raw output mode
111  options.c_oflag &= ~OPOST;
112 
113  tcflush(serial_fd,TCIFLUSH);
114 /*
115  if (fcntl(serial_fd, F_SETFL, FNDELAY))
116  {
117  close();
118  return false;
119  }
120 */
121  if (tcsetattr(serial_fd, TCSANOW, &options))
122  {
123  close();
124  return false;
125  }
126 
127  _is_serial_opened = true;
128 
129  //Clear the DTR bit to let the motor spin
130  clearDTR();
131 
132  return true;
133 }
134 
135 void raw_serial::close()
136 {
137  if (serial_fd != -1)
138  ::close(serial_fd);
139  serial_fd = -1;
140 
141  _is_serial_opened = false;
142 }
143 
144 int raw_serial::senddata(const unsigned char * data, _word_size_t size)
145 {
146 // FIXME: non-block io should be used
147  if (!isOpened()) return 0;
148 
149  if (data == NULL || size ==0) return 0;
150 
151  size_t tx_len = 0;
152  required_tx_cnt = 0;
153  do {
154  int ans = ::write(serial_fd, data + tx_len, size-tx_len);
155 
156  if (ans == -1) return tx_len;
157 
158  tx_len += ans;
159  required_tx_cnt = tx_len;
160  }while (tx_len<size);
161 
162 
163  return tx_len;
164 }
165 
166 
167 
168 int raw_serial::recvdata(unsigned char * data, _word_size_t size)
169 {
170  if (!isOpened()) return 0;
171 
172  int ans = ::read(serial_fd, data, size);
173 
174  if (ans == -1) ans=0;
175  required_rx_cnt = ans;
176  return ans;
177 }
178 
179 
180 void raw_serial::flush( _u32 flags)
181 {
182  tcflush(serial_fd,TCIFLUSH);
183 }
184 
185 int raw_serial::waitforsent(_u32 timeout, _word_size_t * returned_size)
186 {
187  if (returned_size) *returned_size = required_tx_cnt;
188  return 0;
189 }
190 
191 int raw_serial::waitforrecv(_u32 timeout, _word_size_t * returned_size)
192 {
193  if (!isOpened() ) return -1;
194 
195  if (returned_size) *returned_size = required_rx_cnt;
196  return 0;
197 }
198 
199 int raw_serial::waitfordata(_word_size_t data_count, _u32 timeout, _word_size_t * returned_size)
200 {
201  _word_size_t length = 0;
202  if (returned_size==NULL) returned_size=(_word_size_t *)&length;
203  *returned_size = 0;
204 
205  int max_fd;
206  fd_set input_set;
207  struct timeval timeout_val;
208 
209  /* Initialize the input set */
210  FD_ZERO(&input_set);
211  FD_SET(serial_fd, &input_set);
212  max_fd = serial_fd + 1;
213 
214  /* Initialize the timeout structure */
215  timeout_val.tv_sec = timeout / 1000;
216  timeout_val.tv_usec = (timeout % 1000) * 1000;
217 
218  if ( isOpened() )
219  {
220  if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) return ANS_DEV_ERR;
221  if (*returned_size >= data_count)
222  {
223  return 0;
224  }
225  }
226 
227  while ( isOpened() )
228  {
229  /* Do the select */
230  int n = ::select(max_fd, &input_set, NULL, NULL, &timeout_val);
231 
232  if (n < 0)
233  {
234  // select error
235  return ANS_DEV_ERR;
236  }
237  else if (n == 0)
238  {
239  // time out
240  return ANS_TIMEOUT;
241  }
242  else
243  {
244  // data avaliable
245  assert (FD_ISSET(serial_fd, &input_set));
246 
247 
248  if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) return ANS_DEV_ERR;
249  if (*returned_size >= data_count)
250  {
251  return 0;
252  }
253  else
254  {
255  int remain_timeout = timeout_val.tv_sec*1000000 + timeout_val.tv_usec;
256  int expect_remain_time = (data_count - *returned_size)*1000000*8/_baudrate;
257  if (remain_timeout > expect_remain_time)
258  usleep(expect_remain_time);
259  }
260  }
261 
262  }
263  return ANS_DEV_ERR;
264 }
265 
266 size_t raw_serial::rxqueue_count()
267 {
268  if ( !isOpened() ) return 0;
269  size_t remaining;
270 
271  if (::ioctl(serial_fd, FIONREAD, &remaining) == -1) return 0;
272  return remaining;
273 }
274 
275 void raw_serial::setDTR()
276 {
277  if ( !isOpened() ) return;
278 
279  uint32_t dtr_bit = TIOCM_DTR;
280  ioctl(serial_fd, TIOCMBIS, &dtr_bit);
281 }
282 
283 void raw_serial::clearDTR()
284 {
285  if ( !isOpened() ) return;
286 
287  uint32_t dtr_bit = TIOCM_DTR;
288  ioctl(serial_fd, TIOCMBIC, &dtr_bit);
289 }
290 
291 void raw_serial::_init()
292 {
293  serial_fd = 0;
294  _portName[0] = 0;
295  required_tx_cnt = required_rx_cnt = 0;
296 }
297 
298 
299 
300 _u32 raw_serial::getTermBaudBitmap(_u32 baud)
301 {
302 #define BAUD_CONV(_baud_) case _baud_: return _baud_
303  switch (baud)
304  {
305  BAUD_CONV(1200);
306  BAUD_CONV(1800);
307  BAUD_CONV(2400);
308  BAUD_CONV(4800);
309  BAUD_CONV(9600);
310  BAUD_CONV(19200);
311  BAUD_CONV(38400);
312  BAUD_CONV(57600);
313  BAUD_CONV(115200);
314  BAUD_CONV(230400);
315  BAUD_CONV(460800);
316  BAUD_CONV(500000);
317  BAUD_CONV(576000);
318  BAUD_CONV(921600);
319  BAUD_CONV(1000000);
320  BAUD_CONV(1152000);
321  BAUD_CONV(1500000);
322  BAUD_CONV(2000000);
323  BAUD_CONV(2500000);
324  BAUD_CONV(3000000);
325  BAUD_CONV(3500000);
326  BAUD_CONV(4000000);
327  }
328  return -1;
329 }
330 
331 }}} //end rp::arch::net
332 
333 
334 
335 //begin rp::hal
336 namespace rp{ namespace hal{
337 
339  {
340  return new rp::arch::net::raw_serial();
341  }
342 
344  {
345  delete rxtx;
346  }
347 
348 }} //end rp::hal
virtual bool isOpened()
Definition: abs_rxtx.h:76
_u8 size
static serial_rxtx * CreateRxTx()
static void ReleaseRxTx(serial_rxtx *)
volatile bool _is_serial_opened
Definition: abs_rxtx.h:82
virtual bool open()=0
virtual void close()=0
virtual void clearDTR()=0
typedef _word_size_t(THREAD_PROC *thread_proc_t)(void *)
#define BAUD_CONV(_baud_)
uint32_t _u32
Definition: rptypes.h:69
_u8 data[0]


rplidar_ros
Author(s):
autogenerated on Wed Mar 20 2019 07:54:15