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 #include <IOKit/serial/ioss.h>
40 
41 namespace rp{ namespace arch{ namespace net{
42 
44  : rp::hal::serial_rxtx()
45  , _baudrate(0)
46  , _flags(0)
47  , serial_fd(-1)
48 {
49  _init();
50 }
51 
52 raw_serial::~raw_serial()
53 {
54  close();
55 
56 }
57 
58 bool raw_serial::open()
59 {
60  return open(_portName, _baudrate, _flags);
61 }
62 
63 bool raw_serial::bind(const char * portname, uint32_t baudrate, uint32_t flags)
64 {
65  strncpy(_portName, portname, sizeof(_portName));
66  _baudrate = baudrate;
67  _flags = flags;
68  return true;
69 }
70 
71 bool raw_serial::open(const char * portname, uint32_t baudrate, uint32_t flags)
72 {
73  if (isOpened()) close();
74 
75  serial_fd = ::open(portname, O_RDWR | O_NOCTTY | O_NDELAY);
76 
77  if (serial_fd == -1) return false;
78 
79  struct termios options, oldopt;
80  tcgetattr(serial_fd, &oldopt);
81  bzero(&options,sizeof(struct termios));
82 
83  cfsetspeed(&options, B19200);
84 
85  // enable rx and tx
86  options.c_cflag |= (CLOCAL | CREAD);
87 
88 
89  options.c_cflag &= ~PARENB; //no checkbit
90  options.c_cflag &= ~CSTOPB; //1bit stop bit
91 
92  options.c_cflag &= ~CSIZE;
93  options.c_cflag |= CS8; /* Select 8 data bits */
94 
95 #ifdef CNEW_RTSCTS
96  options.c_cflag &= ~CNEW_RTSCTS; // no hw flow control
97 #endif
98 
99  options.c_iflag &= ~(IXON | IXOFF | IXANY); // no sw flow control
100 
101  // raw input mode
102  options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
103  // raw output mode
104  options.c_oflag &= ~OPOST;
105 
106  tcflush(serial_fd,TCIFLUSH);
107 
108  if (tcsetattr(serial_fd, TCSANOW, &options))
109  {
110  close();
111  return false;
112  }
113 
114  printf("Setting serial port baudrate...\n");
115 
116  speed_t speed = (speed_t)baudrate;
117  if (ioctl(serial_fd, IOSSIOSPEED, &speed)== -1) {
118  printf("Error calling ioctl(..., IOSSIOSPEED, ...) %s - %s(%d).\n",
119  portname, strerror(errno), errno);
120  close();
121  return false;
122  }
123 
124  _is_serial_opened = true;
125 
126  //Clear the DTR bit to let the motor spin
127  clearDTR();
128 
129  return true;
130 }
131 
132 void raw_serial::close()
133 {
134  if (serial_fd != -1)
135  ::close(serial_fd);
136  serial_fd = -1;
137 
138  _is_serial_opened = false;
139 }
140 
141 int raw_serial::senddata(const unsigned char * data, _word_size_t size)
142 {
143 // FIXME: non-block io should be used
144  if (!isOpened()) return 0;
145 
146  if (data == NULL || size ==0) return 0;
147 
148  size_t tx_len = 0;
149  required_tx_cnt = 0;
150  do {
151  int ans = ::write(serial_fd, data + tx_len, size-tx_len);
152 
153  if (ans == -1) return tx_len;
154 
155  tx_len += ans;
156  required_tx_cnt = tx_len;
157  }while (tx_len<size);
158 
159 
160  return tx_len;
161 }
162 
163 
164 
165 int raw_serial::recvdata(unsigned char * data, _word_size_t size)
166 {
167  if (!isOpened()) return 0;
168 
169  int ans = ::read(serial_fd, data, size);
170 
171  if (ans == -1) ans=0;
172  required_rx_cnt = ans;
173  return ans;
174 }
175 
176 
177 void raw_serial::flush( _u32 flags)
178 {
179  tcflush(serial_fd,TCIFLUSH);
180 }
181 
182 int raw_serial::waitforsent(_u32 timeout, _word_size_t * returned_size)
183 {
184  if (returned_size) *returned_size = required_tx_cnt;
185  return 0;
186 }
187 
188 int raw_serial::waitforrecv(_u32 timeout, _word_size_t * returned_size)
189 {
190  if (!isOpened() ) return -1;
191 
192  if (returned_size) *returned_size = required_rx_cnt;
193  return 0;
194 }
195 
196 int raw_serial::waitfordata(_word_size_t data_count, _u32 timeout, _word_size_t * returned_size)
197 {
198  _word_size_t length = 0;
199  if (returned_size==NULL) returned_size=(_word_size_t *)&length;
200  *returned_size = 0;
201 
202  int max_fd;
203  fd_set input_set;
204  struct timeval timeout_val;
205 
206  /* Initialize the input set */
207  FD_ZERO(&input_set);
208  FD_SET(serial_fd, &input_set);
209  max_fd = serial_fd + 1;
210 
211  /* Initialize the timeout structure */
212  timeout_val.tv_sec = timeout / 1000;
213  timeout_val.tv_usec = (timeout % 1000) * 1000;
214 
215  if ( isOpened() )
216  {
217  if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) return ANS_DEV_ERR;
218  if (*returned_size >= data_count)
219  {
220  return 0;
221  }
222  }
223 
224  while ( isOpened() )
225  {
226  /* Do the select */
227  int n = ::select(max_fd, &input_set, NULL, NULL, &timeout_val);
228 
229  if (n < 0)
230  {
231  // select error
232  return ANS_DEV_ERR;
233  }
234  else if (n == 0)
235  {
236  // time out
237  return ANS_TIMEOUT;
238  }
239  else
240  {
241  // data avaliable
242  assert (FD_ISSET(serial_fd, &input_set));
243 
244 
245  if ( ioctl(serial_fd, FIONREAD, returned_size) == -1) return ANS_DEV_ERR;
246  if (*returned_size >= data_count)
247  {
248  return 0;
249  }
250  else
251  {
252  int remain_timeout = timeout_val.tv_sec*1000000 + timeout_val.tv_usec;
253  int expect_remain_time = (data_count - *returned_size)*1000000*8/_baudrate;
254  if (remain_timeout > expect_remain_time)
255  usleep(expect_remain_time);
256  }
257  }
258 
259  }
260  return ANS_DEV_ERR;
261 }
262 
263 size_t raw_serial::rxqueue_count()
264 {
265  if ( !isOpened() ) return 0;
266  size_t remaining;
267 
268  if (::ioctl(serial_fd, FIONREAD, &remaining) == -1) return 0;
269  return remaining;
270 }
271 
272 void raw_serial::setDTR()
273 {
274  if ( !isOpened() ) return;
275 
276  uint32_t dtr_bit = TIOCM_DTR;
277  ioctl(serial_fd, TIOCMBIS, &dtr_bit);
278 }
279 
280 void raw_serial::clearDTR()
281 {
282  if ( !isOpened() ) return;
283 
284  uint32_t dtr_bit = TIOCM_DTR;
285  ioctl(serial_fd, TIOCMBIC, &dtr_bit);
286 }
287 
288 void raw_serial::_init()
289 {
290  serial_fd = 0;
291  _portName[0] = 0;
292  required_tx_cnt = required_rx_cnt = 0;
293 }
294 
295 
296 
297 _u32 raw_serial::getTermBaudBitmap(_u32 baud)
298 {
299 #define BAUD_CONV(_baud_) case _baud_: return _baud_
300  switch (baud)
301  {
302  BAUD_CONV(1200);
303  BAUD_CONV(1800);
304  BAUD_CONV(2400);
305  BAUD_CONV(4800);
306  BAUD_CONV(9600);
307  BAUD_CONV(19200);
308  BAUD_CONV(38400);
309  BAUD_CONV(57600);
310  BAUD_CONV(115200);
311  BAUD_CONV(230400);
312  BAUD_CONV(460800);
313  BAUD_CONV(500000);
314  BAUD_CONV(576000);
315  BAUD_CONV(921600);
316  BAUD_CONV(1000000);
317  BAUD_CONV(1152000);
318  BAUD_CONV(1500000);
319  BAUD_CONV(2000000);
320  BAUD_CONV(2500000);
321  BAUD_CONV(3000000);
322  BAUD_CONV(3500000);
323  BAUD_CONV(4000000);
324  }
325  return -1;
326 }
327 
328 }}} //end rp::arch::net
329 
330 
331 
332 //begin rp::hal
333 namespace rp{ namespace hal{
334 
336  {
337  return new rp::arch::net::raw_serial();
338  }
339 
341  {
342  delete rxtx;
343  }
344 
345 }} //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 Jan 1 2020 04:01:40