serial_transport_arduino.c
Go to the documentation of this file.
00001 
00009 /*
00010  * Copyright (c) 2010 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 
00031 #if defined(ARDUINO) && ARDUINO >= 100
00032 #include "Arduino.h"
00033 #else
00034 #include "WProgram.h"
00035 #endif
00036 #include "tm_reader.h"
00037 
00038 static TMR_Status
00039 s_open(TMR_SR_SerialTransport *transport, const char *deviceName)
00040 {
00041   /* This routine should open the serial connection */
00042   TMR_SR_SerialPortNativeContext *context;
00043   HardwareSerial *dev;
00044 
00045   dev = &Serial1;
00046   if (0==strcmp(deviceName,"/Serial"))
00047   {
00048     dev = &Serial;
00049   }
00050   else if (0==strcmp(deviceName,"/Serial1"))
00051   {
00052     dev = &Serial1;
00053   }
00054   else if (0==strcmp(deviceName,"/Serial2"))
00055   {
00056     dev = &Serial2;
00057   }
00058   else if (0==strcmp(deviceName,"/Serial3"))
00059   {
00060     dev = &Serial3;
00061   }
00062 
00063   context = (TMR_SR_SerialPortNativeContext*)transport->cookie;
00064   context->handle = dev;
00065   dev->begin(9600);
00066   return TMR_SUCCESS;
00067 }
00068 
00069 static TMR_Status
00070 s_open(TMR_SR_SerialTransport *transport)
00071 {
00072   /* This routine should open the serial connection */
00073   TMR_SR_SerialPortNativeContext *context;
00074 
00075   context = (TMR_SR_SerialPortNativeContext*)transport->cookie,
00076           s_open(transport,context->devicename);
00077   return TMR_SUCCESS;
00078 }
00079 
00080 static TMR_Status
00081 s_sendBytes(TMR_SR_SerialTransport *transport, uint32_t length, 
00082                 uint8_t* message, const uint32_t timeoutMs)
00083 {
00084   /* This routine should send length bytes, pointed to by message on
00085    * the serial connection. If the transmission does not complete in
00086    * timeoutMs milliseconds, it should return TMR_ERROR_TIMEOUT.
00087    */
00088   TMR_SR_SerialPortNativeContext *context;
00089   HardwareSerial *dev;
00090 
00091   context = (TMR_SR_SerialPortNativeContext*)transport->cookie,
00092           dev = (HardwareSerial*)context->handle;
00093   dev->write(message, length);
00094   return TMR_SUCCESS;
00095 }
00096 
00097 static TMR_Status
00098 s_receiveBytes(TMR_SR_SerialTransport *transport, uint32_t length, 
00099                    uint32_t* messageLength, uint8_t* message, const uint32_t timeoutMs)
00100 {
00101   /* This routine should receive exactly length bytes on the serial
00102    * connection and store them into the memory pointed to by
00103    * message. If the required number of bytes are note received in
00104    * timeoutMs milliseconds, it should return TMR_ERROR_TIMEOUT.
00105    */
00106   unsigned long currentMillis,initialMillis;
00107   TMR_SR_SerialPortNativeContext *context;
00108   HardwareSerial *dev;
00109 
00110   context = (TMR_SR_SerialPortNativeContext*)transport->cookie,
00111           dev = (HardwareSerial*)context->handle;
00112   initialMillis = millis();
00113   currentMillis = initialMillis;
00114   *messageLength = 0;
00115 
00116   while((length > 0)
00117       && ((currentMillis - initialMillis) < timeoutMs)
00118       )
00119   {
00120     if (dev->available() > 0)
00121     {
00122       int inByte;
00123       // read the incoming byte:
00124       inByte = dev->read();
00125       if (inByte != -1)
00126       {
00127         message[*messageLength] = inByte;
00128         ++(*messageLength);
00129         --length;
00130       }
00131     }
00132     currentMillis  = millis();
00133   }
00134 
00135   if (0 != length)
00136   {
00137     return TMR_ERROR_TIMEOUT;
00138   }
00139   return TMR_SUCCESS;
00140 }
00141 
00142 static TMR_Status
00143 s_setBaudRate(TMR_SR_SerialTransport *transport, uint32_t rate)
00144 {
00145   /* This routine should change the baud rate of the serial connection
00146    * to the specified rate, or return TMR_ERROR_INVALID if the rate is
00147    * not supported.
00148    */
00149   TMR_SR_SerialPortNativeContext *context;
00150   HardwareSerial *dev;
00151 
00152   context = (TMR_SR_SerialPortNativeContext*)transport->cookie,
00153           dev = (HardwareSerial*)context->handle;
00154   dev->end();
00155   dev->begin(rate);
00156   return TMR_SUCCESS;
00157 }
00158 
00159 static TMR_Status
00160 s_shutdown(TMR_SR_SerialTransport *transport)
00161 {
00162   /* This routine should close the serial connection and release any
00163    * acquired resources.
00164    */
00165   TMR_SR_SerialPortNativeContext *context;
00166   HardwareSerial *dev;
00167 
00168   context = (TMR_SR_SerialPortNativeContext*)transport->cookie,
00169           dev = (HardwareSerial*)context->handle;
00170   dev->end();
00171   return TMR_SUCCESS;
00172 }
00173 
00174 static TMR_Status
00175 s_flush(TMR_SR_SerialTransport *transport)
00176 {
00177   /* This routine should empty any input or output buffers in the
00178    * communication channel. If there are no such buffers, it may do
00179    * nothing.
00180    */
00181   TMR_SR_SerialPortNativeContext *context;
00182   HardwareSerial *dev;
00183 
00184   context = (TMR_SR_SerialPortNativeContext*)transport->cookie,
00185           dev = (HardwareSerial*)context->handle;
00186 
00187   dev->flush();
00188   return TMR_SUCCESS;
00189 }
00190 
00191 /* This function is not part of the API as such. This is for
00192  * application code to call to fill in the transport object before
00193  * initializing the reader object itself, as in the following code:
00194  * 
00195  * TMR_Reader reader;
00196  *
00197  * TMR_SerialTransportDummyInit(&reader.u.serialReader.transport, myArgs);
00198  * TMR_SR_SerialReader_init(&reader);
00199  *
00200  * The initialization should not actually open a communication channel
00201  * or acquire other communication resources at this time.
00202  */
00203 TMR_Status
00204 TMR_SR_SerialTransportNativeInit(TMR_SR_SerialTransport *transport,
00205                                  TMR_SR_SerialPortNativeContext *context,
00206                                  const char *device)
00207 
00208 {
00209   /* Each of the callback functions will be passed the transport
00210    * pointer, and they can use the "cookie" member of the transport
00211    * structure to store the information specific to the transport,
00212    * such as a file handle or the memory address of the FIFO.
00213    */
00214   transport->cookie = context;
00215   transport->open = s_open;
00216   transport->sendBytes = s_sendBytes;
00217   transport->receiveBytes = s_receiveBytes;
00218   transport->setBaudRate = s_setBaudRate;
00219   transport->shutdown = s_shutdown;
00220   transport->flush = s_flush;
00221 
00222 #if TMR_MAX_SERIAL_DEVICE_NAME_LENGTH > 0
00223   if (strlen(device) + 1 > TMR_MAX_SERIAL_DEVICE_NAME_LENGTH)
00224   {
00225     return TMR_ERROR_INVALID;
00226   }
00227   strcpy(context->devicename, device);
00228   return TMR_SUCCESS;
00229 #else
00230   /* No space to store the device name, so open it now */
00231   return s_open(transport,device);
00232 #endif
00233 }


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