serial_transport_posix.c
Go to the documentation of this file.
00001 
00009 /*
00010  * Copyright (c) 2009 ThingMagic, Inc.
00011  *
00012  * Permission is hereby granted, free of charge, to any person obtaining a copy
00013  * of this software and associated documentation files (the "Software"), to deal
00014  * in the Software without restriction, including without limitation the rights
00015  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00016  * copies of the Software, and to permit persons to whom the Software is
00017  * furnished to do so, subject to the following conditions:
00018  *
00019  * The above copyright notice and this permission notice shall be included in
00020  * all copies or substantial portions of the Software.
00021  * 
00022  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00023  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00024  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00025  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00026  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00027  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00028  * THE SOFTWARE.
00029  */
00030 #include <sys/types.h>
00031 #include <sys/stat.h>
00032 #include <sys/select.h>
00033 #include <fcntl.h>
00034 #include <termios.h>
00035 #include <unistd.h>
00036 #include <errno.h>
00037 #include <string.h>
00038 #include <sys/ioctl.h>
00039 #include "tm_reader.h"
00040 
00041 #ifdef __APPLE__
00042 #include <sys/ioctl.h>
00043 #include <IOKit/serial/ioss.h>
00044 #endif
00045 
00046 #ifdef TMR_ENABLE_SERIAL_TRANSPORT_NATIVE
00047 
00048 static TMR_Status
00049 s_open(TMR_SR_SerialTransport *this)
00050 {
00051   int ret;
00052   struct termios t;
00053 #if TMR_MAX_READER_NAME_LENGTH > 0
00054   TMR_SR_SerialPortNativeContext *c;
00055 
00056   c = this->cookie;
00057 
00058   c->handle = open(c->devicename, O_RDWR);
00059   if (c->handle == -1)
00060     return TMR_ERROR_COMM_ERRNO(errno);
00061 #endif
00062 
00063   /*
00064    * Set 8N1, disable high-bit stripping, soft flow control, and hard
00065    * flow control (modem lines).
00066    */
00067   ret = tcgetattr(c->handle, &t);
00068   if (-1 == ret)
00069     return TMR_ERROR_COMM_ERRNO(errno);
00070   t.c_iflag &= ~(ICRNL | IGNCR | INLCR | INPCK | ISTRIP | IXANY 
00071                  | IXON | IXOFF | PARMRK);
00072   t.c_oflag &= ~OPOST;
00073   t.c_cflag &= ~(CRTSCTS | CSIZE | CSTOPB | PARENB);
00074   t.c_cflag |= CS8 | CLOCAL | CREAD | HUPCL;
00075   t.c_lflag &= ~(ECHO | ICANON | IEXTEN | ISIG);
00076   t.c_cc[VMIN] = 0;
00077   t.c_cc[VTIME] = 1;
00078   ret = tcsetattr(c->handle, TCSANOW, &t);
00079   if (-1 == ret)
00080     return TMR_ERROR_COMM_ERRNO(errno);
00081 
00082   return TMR_SUCCESS;
00083 }
00084 
00085 static TMR_Status
00086 s_sendBytes(TMR_SR_SerialTransport *this, uint32_t length, 
00087             uint8_t* message, const uint32_t timeoutMs)
00088 {
00089   TMR_SR_SerialPortNativeContext *c;
00090   int ret;
00091 
00092   c = this->cookie;
00093   do 
00094   {
00095     ret = write(c->handle, message, length);
00096     if (ret == -1)
00097     {
00098       if (ENXIO == errno)
00099       {
00100         return TMR_ERROR_TIMEOUT; 
00101       }
00102       else
00103       {
00104         return TMR_ERROR_COMM_ERRNO(errno);
00105       }
00106     }
00107     length -= ret;
00108     message += ret;
00109   }
00110   while (length > 0);
00111 
00112   return TMR_SUCCESS;
00113 }
00114 
00115 static TMR_Status
00116 s_receiveBytes(TMR_SR_SerialTransport *this, uint32_t length, 
00117                uint32_t *messageLength, uint8_t* message, const uint32_t timeoutMs)
00118 {
00119   TMR_SR_SerialPortNativeContext *c;
00120   int ret;
00121   struct timeval tv;
00122   fd_set set;
00123   int status = 0;
00124 
00125   *messageLength = 0;
00126   c = this->cookie;
00127 
00128   do
00129   {
00130     FD_ZERO(&set);
00131     FD_SET(c->handle, &set);
00132     tv.tv_sec = timeoutMs / 1000;
00133     tv.tv_usec = (timeoutMs % 1000) * 1000;
00134     /* Ideally should reset this timeout value every time through */
00135     ret = select(c->handle + 1, &set, NULL, NULL, &tv);
00136     if (ret < 1)
00137     {
00138       return TMR_ERROR_TIMEOUT;
00139     }
00140     ret = read(c->handle, message, length);
00141     if (ret == -1)
00142     {
00143       if (ENXIO == errno)
00144       {
00145         return TMR_ERROR_TIMEOUT; 
00146       }
00147       else
00148       {
00149         return TMR_ERROR_COMM_ERRNO(errno);
00150       }
00151     }
00152 
00153     if (0 == ret)
00154     {
00160       ret = ioctl(c->handle, TIOCMGET, &status);
00161       if (-1 == ret)
00162       {
00163         /* not success. check for errno */
00164         if (EIO == errno)
00165         {
00170           return TMR_ERROR_TIMEOUT;
00171         }
00172       }
00173     }
00174 
00175     length -= ret;
00176     *messageLength += ret;
00177     message += ret;
00178   }
00179   while (length > 0);
00180 
00181   return TMR_SUCCESS;
00182 }
00183 
00184 static TMR_Status
00185 s_setBaudRate(TMR_SR_SerialTransport *this, uint32_t rate)
00186 {
00187   TMR_SR_SerialPortNativeContext *c;
00188   
00189   c = this->cookie;
00190 
00191 #if defined(__APPLE__)
00192   {
00193     speed_t speed = rate;
00194 
00195     if (ioctl(c->handle, IOSSIOSPEED, &speed) == -1)
00196       return TMR_ERROR_COMM_ERRNO(errno);
00197   }
00198 #else
00199   {
00200     struct termios t;
00201 
00202     tcgetattr(c->handle, &t);
00203 
00204 #define BCASE(t,n) case n: cfsetispeed((t),B##n); cfsetospeed((t),B##n); break;
00205     switch (rate)
00206     {
00207       BCASE(&t, 9600);
00208       BCASE(&t, 19200);
00209       BCASE(&t, 38400);
00210       // Believe it or not, speeds beyond 38400 aren't required by POSIX.
00211 #ifdef B57600
00212       BCASE(&t, 57600);
00213 #endif
00214 #ifdef B115200
00215       BCASE(&t, 115200);
00216 #endif
00217 #ifdef B230400
00218       BCASE(&t, 230400);
00219 #endif
00220 #ifdef B460800
00221       BCASE(&t, 460800);
00222 #endif
00223 #ifdef B921600
00224       BCASE(&t, 921600);
00225 #endif
00226     default:
00227       return TMR_ERROR_INVALID;
00228     }
00229 #undef BCASE
00230     if (tcsetattr(c->handle, TCSANOW, &t) != 0)
00231     {
00232       return TMR_ERROR_COMM_ERRNO(errno);
00233     }
00234   }
00235 #endif /* __APPLE__ */
00236 
00237   return TMR_SUCCESS;
00238 }
00239 
00240 static TMR_Status
00241 s_shutdown(TMR_SR_SerialTransport *this)
00242 {
00243   TMR_SR_SerialPortNativeContext *c;
00244 
00245   c = this->cookie;
00246 
00247   close(c->handle);
00248   /* What, exactly, would be the point of checking for an error here? */
00249 
00250   return TMR_SUCCESS;
00251 }
00252 
00253 static TMR_Status
00254 s_flush(TMR_SR_SerialTransport *this)
00255 {
00256   TMR_SR_SerialPortNativeContext *c;
00257 
00258   c = this->cookie;
00259 
00260   if (tcflush(c->handle, TCOFLUSH) == -1)
00261   {
00262     return TMR_ERROR_COMM_ERRNO(errno);
00263   }
00264 
00265   return TMR_SUCCESS;
00266 }
00267 
00268 TMR_Status
00269 TMR_SR_SerialTransportNativeInit(TMR_SR_SerialTransport *transport,
00270                                  TMR_SR_SerialPortNativeContext *context,
00271                                  const char *device)
00272 {
00273 
00274 #if TMR_MAX_READER_NAME_LENGTH > 0
00275   if (strlen(device) + 1 > TMR_MAX_READER_NAME_LENGTH)
00276   {
00277     return TMR_ERROR_INVALID;
00278   }
00279   strcpy(context->devicename, device);
00280 #else
00281   /* No space to store the device name, so open it now */
00282   context->handle = open(device, O_RDWR);
00283   if (context->handle == -1)
00284   {
00285     return TMR_ERROR_COMM_ERRNO(errno);
00286   }
00287 #endif
00288 
00289   transport->cookie = context;
00290   transport->open = s_open;
00291   transport->sendBytes = s_sendBytes;
00292   transport->receiveBytes = s_receiveBytes;
00293   transport->setBaudRate = s_setBaudRate;
00294   transport->shutdown = s_shutdown;
00295   transport->flush = s_flush;
00296 
00297   return TMR_SUCCESS;
00298 }
00299 
00300 #endif


thingmagic_rfid
Author(s): Brian Bingham
autogenerated on Thu May 16 2019 03:01:24