sbgInterfaceSerialUnix.c
Go to the documentation of this file.
1 #include "sbgInterfaceSerial.h"
2 #include <stdio.h>
3 #include <string.h>
4 #include <unistd.h>
5 #include <fcntl.h>
6 #include <errno.h>
7 #include <termios.h>
8 #include <sys/ioctl.h>
9 
10 //----------------------------------------------------------------------//
11 //- Private methods declarations -//
12 //----------------------------------------------------------------------//
13 
14 
21 {
22  uint32 baudRateConst;
23 
24  //
25  // Create the right baud rate value for unix platforms
26  //
27  switch (baudRate)
28  {
29  case 9600:
30  baudRateConst = B9600;
31  break;
32  case 19200:
33  baudRateConst = B19200;
34  break;
35 #ifdef B38400
36  case 38400:
37  baudRateConst = B38400;
38  break;
39 #endif
40 #ifdef B57600
41  case 57600:
42  baudRateConst = B57600;
43  break;
44 #endif
45 #ifdef B115200
46  case 115200:
47  baudRateConst = B115200;
48  break;
49 #endif
50 #ifdef B230400
51  case 230400:
52  baudRateConst = B230400;
53  break;
54 #endif
55 #ifdef B460800
56  case 460800:
57  baudRateConst = B460800;
58  break;
59 #endif
60 #ifdef B921600
61  case 921600:
62  baudRateConst = B921600;
63  break;
64 #endif
65  default:
66  baudRateConst = baudRate;
67  }
68 
69  return baudRateConst;
70 }
71 
72 //----------------------------------------------------------------------//
73 //- Operations methods declarations -//
74 //----------------------------------------------------------------------//
75 
83 SbgErrorCode sbgInterfaceSerialCreate(SbgInterface *pHandle, const char *deviceName, uint32 baudRate)
84 {
85  int *pSerialHandle;
86  struct termios options;
87  uint32 baudRateConst;
88 
89  //
90  // First check if we have a valid pHandle
91  //
92  if (pHandle)
93  {
94  //
95  // Check if the device name is valid
96  //
97  if (deviceName)
98  {
99  //
100  // Get our baud rate const for our Unix platform
101  //
102  baudRateConst = sbgInterfaceSerialGetBaudRateConst(baudRate);
103 
104  //
105  // Allocate the serial handle
106  //
107  pSerialHandle = (int*)malloc(sizeof(int));
108 
109  //
110  // Init the com port
111  //
112  (*pSerialHandle) = open(deviceName, O_RDWR | O_NOCTTY | O_NDELAY);
113 
114  //
115  // Test that the port has been initialized
116  //
117  if ((*pSerialHandle) != -1)
118  {
119  //
120  // Don't block on read call if no data are available
121  //
122  if (fcntl((*pSerialHandle), F_SETFL, O_NONBLOCK) != -1)
123  {
124  //
125  // Retreive current options
126  //
127  if (tcgetattr((*pSerialHandle), &options) != -1)
128  {
129  //
130  // Define com port options
131  //
132  options.c_cflag |= (CLOCAL | CREAD); // Enable the receiver and set local mode...
133  options.c_cflag &= ~(PARENB|CSTOPB|CSIZE); // No parity, 1 stop bit, mask character size bits
134  options.c_cflag |= CS8; // Select 8 data bits
135  options.c_cflag &= ~CRTSCTS; // Disable Hardware flow control
136 
137  //
138  // Disable software flow control
139  //
140  options.c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP|INLCR|IGNCR|ICRNL|IXON);
141 
142  //
143  // We would like raw input
144  //
145  options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG /*| IEXTEN | ECHONL*/);
146  options.c_oflag &= ~OPOST;
147 
148  //
149  // Set our timeout to 0
150  //
151  options.c_cc[VMIN] = 0;
152  options.c_cc[VTIME] = 1;
153 
154  //
155  // Set both input and output baud
156  //
157  if ( (cfsetispeed(&options, baudRateConst) != -1) && (cfsetospeed(&options, baudRateConst) != -1) )
158  {
159  //
160  // Define options
161  //
162  if (tcsetattr((*pSerialHandle), TCSANOW, &options) != -1)
163  {
164  //
165  // The serial port is ready so create a new serial interface
166  //
167  pHandle->handle = (void*)pSerialHandle;
168  pHandle->type = SBG_IF_TYPE_SERIAL;
171 
172  //
173  // Purge the communication
174  //
175  return sbgInterfaceSerialFlush(pHandle);
176  }
177  else
178  {
179  fprintf(stderr, "sbgInterfaceSerialCreate: tcsetattr fails.\n");
180  }
181  }
182  else
183  {
184  fprintf(stderr, "sbgInterfaceSerialCreate: Unable to set speed.\n");
185  }
186  }
187  else
188  {
189  fprintf(stderr, "sbgInterfaceSerialCreate: tcgetattr fails.\n");
190  }
191  }
192  else
193  {
194  fprintf(stderr, "sbgInterfaceSerialCreate: fcntl fails\n");
195  }
196  }
197  else
198  {
199  fprintf(stderr, "sbgInterfaceSerialCreate: Unable to open the com port: %s\n", deviceName);
200  }
201 
202  //
203  // Release the allocated serial handle
204  //
205  SBG_FREE(pSerialHandle);
206 
207  return SBG_ERROR;
208  }
209  else
210  {
211  //
212  // Invalid device name
213  //
214  return SBG_INVALID_PARAMETER;
215  }
216  }
217  else
218  {
219  return SBG_NULL_POINTER;
220  }
221 }
222 
229 {
230  int *pSerialHandle;
231 
232  //
233  // Test that we have a valid interface
234  //
235  if (pHandle)
236  {
237  //
238  // Get the internal serial handle
239  //
240  pSerialHandle = (int*)pHandle->handle;
241 
242  //
243  // Close the port com
244  //
245  close((*pSerialHandle));
246  SBG_FREE(pSerialHandle);
247  pHandle->handle = NULL;
248 
249  return SBG_NO_ERROR;
250  }
251  else
252  {
253  return SBG_NULL_POINTER;
254  }
255 }
256 
263 {
264  int hSerialHandle;
265 
266  //
267  // Test that we have a valid interface
268  //
269  if (pHandle)
270  {
271  //
272  // Get the internal serial handle
273  //
274  hSerialHandle = *((int*)pHandle->handle);
275 
276  //
277  // Flush our port
278  //
279  if (tcflush(hSerialHandle, TCIOFLUSH) == 0)
280  {
281  return SBG_NO_ERROR;
282  }
283  else
284  {
285  return SBG_ERROR;
286  }
287  }
288  else
289  {
290  return SBG_NULL_POINTER;
291  }
292 }
293 
301 {
302  int hSerialHandle;
303  struct termios options;
304  uint32 baudRateConst;
305 
306  //
307  // Test that we have a valid interface
308  //
309  if (pHandle)
310  {
311  //
312  // Get the internal serial handle
313  //
314  hSerialHandle = *((int*)pHandle->handle);
315 
316  //
317  // Get the baud rate const for our Unix platform
318  //
319  baudRateConst = sbgInterfaceSerialGetBaudRateConst(baudRate);
320 
321  //
322  // Retrieve current options
323  //
324  if (tcgetattr(hSerialHandle, &options) != -1)
325  {
326  //
327  // Set both input and output baud
328  //
329  if ( (cfsetispeed(&options, baudRateConst) == -1) || (cfsetospeed(&options, baudRateConst) == -1) )
330  {
331  fprintf(stderr, "sbgInterfaceSerialChangeBaudrate: Unable to set speed.\n");
332  return SBG_ERROR;
333  }
334 
335  //
336  // Define options
337  //
338  if (tcsetattr(hSerialHandle, TCSADRAIN, &options) != -1)
339  {
340  return SBG_NO_ERROR;
341  }
342  else
343  {
344  fprintf(stderr, "sbgInterfaceSerialChangeBaudrate: tcsetattr fails.\n");
345  return SBG_ERROR;
346  }
347  }
348  else
349  {
350  fprintf(stderr, "sbgInterfaceSerialChangeBaudrate: tcgetattr fails.\n");
351  return SBG_ERROR;
352  }
353  }
354  else
355  {
356  return SBG_NULL_POINTER;
357  }
358 }
359 
360 //----------------------------------------------------------------------//
361 //- Internal interfaces write/read implementations -//
362 //----------------------------------------------------------------------//
363 
371 SbgErrorCode sbgInterfaceSerialWrite(SbgInterface *pHandle, const void *pBuffer, size_t bytesToWrite)
372 {
373  size_t numBytesLeftToWrite = bytesToWrite;
374  uint8 *pCurrentBuffer = (uint8*)pBuffer;
375  ssize_t numBytesWritten;
376  int hSerialHandle;
377 
378  //
379  // Test input parameters
380  //
381  if ( (pHandle) && (pBuffer) )
382  {
383  //
384  // Get the internal serial handle
385  //
386  hSerialHandle = *((int*)pHandle->handle);
387 
388  //
389  // Write the whole buffer
390  //
391  while (numBytesLeftToWrite > 0)
392  {
393  //
394  // Write these bytes to the serial interface
395  //
396  numBytesWritten = write(hSerialHandle, pCurrentBuffer, numBytesLeftToWrite);
397 
398  //
399  // Test the there is no error
400  //
401  if (numBytesWritten == -1)
402  {
403  //
404  // An error has occured during the write
405  //
406  fprintf(stderr, "sbgDeviceWrite: Unable to write to our device: %s\n", strerror(errno));
407  return SBG_WRITE_ERROR;
408  }
409 
410  //
411  // Update the buffer pointer and the number of bytes to write
412  //
413  numBytesLeftToWrite -= (size_t)numBytesWritten;
414  pCurrentBuffer += (size_t)numBytesWritten;
415  }
416 
417  return SBG_NO_ERROR;
418  }
419  else
420  {
421  return SBG_NULL_POINTER;
422  }
423 }
424 
433 SbgErrorCode sbgInterfaceSerialRead(SbgInterface *pHandle, void *pBuffer, size_t *pReadBytes, size_t bytesToRead)
434 {
435  SbgErrorCode errorCode;
436  int hSerialHandle;
437  ssize_t numBytesRead;
438 
439  //
440  // Test input parameters
441  //
442  if ( (pHandle) && (pBuffer) && (pReadBytes) )
443  {
444  //
445  // Get the internal serial handle
446  //
447  hSerialHandle = *((int*)pHandle->handle);
448 
449  //
450  // Read our buffer
451  //
452  numBytesRead = read(hSerialHandle, pBuffer, bytesToRead);
453 
454  //
455  // Check if we have read at least one byte
456  //
457  if (numBytesRead > 0)
458  {
459  errorCode = SBG_NO_ERROR;
460  }
461  else
462  {
463  errorCode = SBG_READ_ERROR;
464  numBytesRead = 0;
465  }
466 
467  //
468  // If we can, returns the number of read bytes
469  //
470  if (pReadBytes)
471  {
472  *pReadBytes = (size_t)numBytesRead;
473  }
474  }
475  else
476  {
477  errorCode = SBG_NULL_POINTER;
478  }
479 
480  return errorCode;
481 }
#define SBG_FREE(p)
Definition: sbgDefines.h:79
unsigned int uint32
Definition: sbgTypes.h:58
SbgErrorCode sbgInterfaceSerialChangeBaudrate(SbgInterface *pHandle, uint32 baudRate)
SbgErrorCode sbgInterfaceSerialFlush(SbgInterface *pHandle)
SbgErrorCode sbgInterfaceSerialDestroy(SbgInterface *pHandle)
uint32 sbgInterfaceSerialGetBaudRateConst(uint32 baudRate)
SbgInterfaceHandle handle
Definition: sbgInterface.h:105
SbgErrorCode sbgInterfaceSerialRead(SbgInterface *pHandle, void *pBuffer, size_t *pReadBytes, size_t bytesToRead)
SbgInterfaceReadFunc pReadFunc
Definition: sbgInterface.h:109
This file implements a serial interface.
#define NULL
Definition: sbgDefines.h:43
unsigned char uint8
Definition: sbgTypes.h:56
SbgErrorCode sbgInterfaceSerialWrite(SbgInterface *pHandle, const void *pBuffer, size_t bytesToWrite)
SbgInterfaceType type
Definition: sbgInterface.h:106
SbgErrorCode sbgInterfaceSerialCreate(SbgInterface *pHandle, const char *deviceName, uint32 baudRate)
SbgInterfaceWriteFunc pWriteFunc
Definition: sbgInterface.h:108
enum _SbgErrorCode SbgErrorCode


sbg_driver
Author(s):
autogenerated on Sun Jan 27 2019 03:42:20