Main MRPT website > C++ reference for MRPT 1.5.7
win32/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 - 2016 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 "sdkcommon.h"
36 #include "net_serial.h"
37 
38 namespace rp{ namespace arch{ namespace net{
39 
41  : rp::hal::serial_rxtx()
42  , _serial_handle(NULL)
43  , _baudrate(0)
44  , _flags(0)
45 {
46  _init();
47 }
48 
50 {
51  close();
52 
53  CloseHandle(_ro.hEvent);
54  CloseHandle(_wo.hEvent);
55  CloseHandle(_wait_o.hEvent);
56 }
57 
58 bool raw_serial::open()
59 {
60  return open(_portName, _baudrate, _flags);
61 }
62 
63 bool raw_serial::bind(const char * portname, _u32 baudrate, _u32 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, _u32 baudrate, _u32 flags)
72 {
73  if (isOpened()) close();
74 
75  _serial_handle = CreateFileA(
76  portname,
77  GENERIC_READ | GENERIC_WRITE,
78  0,
79  NULL,
80  OPEN_EXISTING,
81  FILE_ATTRIBUTE_NORMAL | FILE_FLAG_OVERLAPPED,
82  NULL
83  );
84 
85  if (_serial_handle == INVALID_HANDLE_VALUE) return false;
86 
88  {
89  close();
90  return false;
91  }
92 
93  _dcb.BaudRate = baudrate;
94  _dcb.ByteSize = 8;
95  _dcb.Parity = NOPARITY;
96  _dcb.StopBits = ONESTOPBIT;
97  _dcb.fDtrControl = DTR_CONTROL_ENABLE;
98 
99  if (!SetCommState(_serial_handle, &_dcb))
100  {
101  close();
102  return false;
103  }
104 
105  if (!SetCommTimeouts(_serial_handle, &_co))
106  {
107  close();
108  return false;
109  }
110 
111  if (!SetCommMask(_serial_handle, EV_RXCHAR | EV_ERR ))
112  {
113  close();
114  return false;
115  }
116 
117  if (!PurgeComm(_serial_handle, PURGE_TXABORT | PURGE_RXABORT | PURGE_TXCLEAR | PURGE_RXCLEAR ))
118  {
119  close();
120  return false;
121  }
122 
123  Sleep(30);
124  _is_serial_opened = true;
125 
126  //Clear the DTR bit set DTR=high
127  clearDTR();
128 
129  return true;
130 }
131 
132 void raw_serial::close()
133 {
134  SetCommMask(_serial_handle, 0);
135  ResetEvent(_wait_o.hEvent);
136 
137  CloseHandle(_serial_handle);
138  _serial_handle = INVALID_HANDLE_VALUE;
139 
140  _is_serial_opened = false;
141 }
142 
143 int raw_serial::senddata(const unsigned char * data, size_t size)
144 {
145  DWORD error;
146  DWORD w_len = 0, o_len = -1;
147  if (!isOpened()) return ANS_DEV_ERR;
148 
149  if (data == NULL || size ==0) return 0;
150 
151  if(ClearCommError(_serial_handle, &error, NULL) && error > 0)
152  PurgeComm(_serial_handle, PURGE_TXABORT | PURGE_TXCLEAR);
153 
154  if(!WriteFile(_serial_handle, data, size, &w_len, &_wo))
155  if(GetLastError() != ERROR_IO_PENDING)
156  w_len = ANS_DEV_ERR;
157 
158  return w_len;
159 }
160 
161 int raw_serial::recvdata(unsigned char * data, size_t size)
162 {
163  if (!isOpened()) return 0;
164  DWORD r_len = 0;
165 
166 
167  if(!ReadFile(_serial_handle, data, size, &r_len, &_ro))
168  {
169  if(GetLastError() == ERROR_IO_PENDING)
170  {
171  if(!GetOverlappedResult(_serial_handle, &_ro, &r_len, FALSE))
172  {
173  if(GetLastError() != ERROR_IO_INCOMPLETE)
174  r_len = 0;
175  }
176  }
177  else
178  r_len = 0;
179  }
180 
181  return r_len;
182 }
183 
184 void raw_serial::flush( _u32 flags)
185 {
186  PurgeComm(_serial_handle, PURGE_TXABORT | PURGE_RXABORT | PURGE_TXCLEAR | PURGE_RXCLEAR );
187 }
188 
189 int raw_serial::waitforsent(_u32 timeout, size_t * returned_size)
190 {
191  if (!isOpened() ) return ANS_DEV_ERR;
192  DWORD w_len = 0;
193  _word_size_t ans =0;
194 
195  if (WaitForSingleObject(_wo.hEvent, timeout) == WAIT_TIMEOUT)
196  {
197  ans = ANS_TIMEOUT;
198  goto _final;
199  }
200  if(!GetOverlappedResult(_serial_handle, &_wo, &w_len, FALSE))
201  {
202  ans = ANS_DEV_ERR;
203  }
204 _final:
205  if (returned_size) *returned_size = w_len;
206  return ans;
207 }
208 
209 int raw_serial::waitforrecv(_u32 timeout, size_t * returned_size)
210 {
211  if (!isOpened() ) return -1;
212  DWORD r_len = 0;
213  _word_size_t ans =0;
214 
215  if (WaitForSingleObject(_ro.hEvent, timeout) == WAIT_TIMEOUT)
216  {
217  ans = ANS_TIMEOUT;
218  }
219  if(!GetOverlappedResult(_serial_handle, &_ro, &r_len, FALSE))
220  {
221  ans = ANS_DEV_ERR;
222  }
223  if (returned_size) *returned_size = r_len;
224  return ans;
225 }
226 
227 int raw_serial::waitfordata(size_t data_count, _u32 timeout, size_t * returned_size)
228 {
229  COMSTAT stat;
230  DWORD error;
231  DWORD msk,length;
232  size_t dummy_length;
233 
234  if (returned_size==NULL) returned_size=(size_t *)&dummy_length;
235 
236 
237  if ( isOpened()) {
238  size_t rxqueue_remaining = rxqueue_count();
239  if (rxqueue_remaining >= data_count) {
240  *returned_size = rxqueue_remaining;
241  return 0;
242  }
243  }
244 
245  while ( isOpened() )
246  {
247  msk = 0;
248  SetCommMask(_serial_handle, EV_RXCHAR | EV_ERR );
249  if(!WaitCommEvent(_serial_handle, &msk, &_wait_o))
250  {
251  if(GetLastError() == ERROR_IO_PENDING)
252  {
253  if (WaitForSingleObject(_wait_o.hEvent, timeout) == WAIT_TIMEOUT)
254  {
255  *returned_size =0;
256  return ANS_TIMEOUT;
257  }
258 
259  GetOverlappedResult(_serial_handle, &_wait_o, &length, TRUE);
260 
261  ::ResetEvent(_wait_o.hEvent);
262  }else
263  {
264  ClearCommError(_serial_handle, &error, &stat);
265  *returned_size = stat.cbInQue;
266  return ANS_DEV_ERR;
267  }
268  }
269 
270  if(msk & EV_ERR){
271  // FIXME: may cause problem here
272  ClearCommError(_serial_handle, &error, &stat);
273  }
274 
275  if(msk & EV_RXCHAR){
276  ClearCommError(_serial_handle, &error, &stat);
277  if(stat.cbInQue >= data_count)
278  {
279  *returned_size = stat.cbInQue;
280  return 0;
281  }
282  }
283  }
284  *returned_size=0;
285  return ANS_DEV_ERR;
286 }
287 
289 {
290  if ( !isOpened() ) return 0;
291  COMSTAT com_stat;
292  DWORD error;
293  DWORD r_len = 0;
294 
295  if(ClearCommError(_serial_handle, &error, &com_stat) && error > 0)
296  {
297  PurgeComm(_serial_handle, PURGE_RXABORT | PURGE_RXCLEAR);
298  return 0;
299  }
300  return com_stat.cbInQue;
301 }
302 
303 void raw_serial::setDTR()
304 {
305  if ( !isOpened() ) return;
306 
307  EscapeCommFunction(_serial_handle, SETDTR);
308 }
309 
311 {
312  if ( !isOpened() ) return;
313 
314  EscapeCommFunction(_serial_handle, CLRDTR);
315 }
316 
317 
318 void raw_serial::_init()
319 {
320  memset(&_dcb, 0, sizeof(_dcb));
321  _dcb.DCBlength = sizeof(_dcb);
322  _serial_handle = INVALID_HANDLE_VALUE;
323  memset(&_co, 0, sizeof(_co));
324  _co.ReadIntervalTimeout = 0;
325  _co.ReadTotalTimeoutMultiplier = 0;
326  _co.ReadTotalTimeoutConstant = 0;
327  _co.WriteTotalTimeoutMultiplier = 0;
328  _co.WriteTotalTimeoutConstant = 0;
329 
330  memset(&_ro, 0, sizeof(_ro));
331  memset(&_wo, 0, sizeof(_wo));
332  memset(&_wait_o, 0, sizeof(_wait_o));
333 
334  _ro.hEvent = CreateEvent(NULL, TRUE, FALSE, NULL);
335  _wo.hEvent = CreateEvent(NULL, TRUE, FALSE, NULL);
336  _wait_o.hEvent = CreateEvent(NULL, TRUE, FALSE, NULL);
337 
338  _portName[0] = 0;
339 }
340 
341 }}} //end rp::arch::net
342 
343 
344 //begin rp::hal
345 namespace rp{ namespace hal{
346 
347 serial_rxtx * serial_rxtx::CreateRxTx()
348 {
349  return new rp::arch::net::raw_serial();
350 }
351 
352 void serial_rxtx::ReleaseRxTx( serial_rxtx * rxtx)
353 {
354  delete rxtx;
355 }
356 
357 
358 }} //end rp::hal
virtual void flush(_u32 flags)
virtual bool isOpened()
Definition: abs_rxtx.h:75
virtual int waitfordata(size_t data_count, _u32 timeout=-1, size_t *returned_size=NULL)
virtual int waitforsent(_u32 timeout=-1, size_t *returned_size=NULL)
static serial_rxtx * CreateRxTx()
static void ReleaseRxTx(serial_rxtx *)
volatile bool _is_serial_opened
Definition: abs_rxtx.h:81
virtual bool bind(const char *portname, uint32_t baudrate, uint32_t flags=0)
virtual int senddata(const unsigned char *data, size_t size)
#define FALSE
Definition: jmorecfg.h:227
virtual int recvdata(unsigned char *data, size_t size)
#define TRUE
Definition: jmorecfg.h:230
typedef _word_size_t(THREAD_PROC *thread_proc_t)(void *)
GLuint GLsizei GLsizei * length
Definition: glext.h:3900
uint32_t _u32
Definition: rptypes.h:69
volatile HANDLE _serial_handle
virtual int waitforrecv(_u32 timeout=-1, size_t *returned_size=NULL)
GLsizeiptr size
Definition: glext.h:3779
GLsizei GLsizei GLenum GLenum const GLvoid * data
Definition: glext.h:3520



Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019