tmr_llrp_reader.h
Go to the documentation of this file.
00001 #ifndef _TMR_LLRP_READER_H
00002 #define _TMR_LLRP_READER_H
00003 
00010 /*
00011  * Copyright (c) 2011 ThingMagic, Inc.
00012  *
00013  * Permission is hereby granted, free of charge, to any person obtaining a copy
00014  * of this software and associated documentation files (the "Software"), to deal
00015  * in the Software without restriction, including without limitation the rights
00016  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00017  * copies of the Software, and to permit persons to whom the Software is
00018  * furnished to do so, subject to the following conditions:
00019  *
00020  * The above copyright notice and this permission notice shall be included in
00021  * all copies or substantial portions of the Software.
00022  * 
00023  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00024  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00025  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00026  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00027  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00028  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00029  * THE SOFTWARE.
00030  */
00031 
00032 #include <pthread.h>
00033 #include <semaphore.h>
00034 #include "tmr_region.h"
00035 #include "tmr_tag_protocol.h"
00036 #include "tmr_serial_transport.h"
00037 #include "tmr_params.h"
00038 #include "ltkc.h"
00039 #include "tm_ltkc.h"
00040 
00041 #ifdef __cplusplus
00042 extern "C" {
00043 #endif
00044  
00045 #define TM_MANUFACTURER_ID  26554
00046 #define TMR_LLRP_SYNC_MAX_ROSPECS 256  
00047 #define TMR_LLRP_MAX_RFMODE_ENTRIES 7
00048 #define TMR_LLRP_READER_DEFAULT_PORT 5084
00049 
00053 typedef struct TMR_LLRP_RFControl
00054 {
00055   /* RFMode index */
00056   llrp_u16_t index;
00057 
00058   /* Tari */
00059   TMR_GEN2_Tari tari;
00060 
00061 } TMR_LLRP_RFControl;
00062 
00068 typedef struct TMR_LLRP_C1G2RFModeTable
00069 {
00070   /* Gen2 BLF */
00071   TMR_GEN2_LinkFrequency blf;
00072 
00073   /* Gen2 Tag encoding */
00074   TMR_GEN2_TagEncoding m;
00075 
00076   /* Min Tari Value*/
00077   TMR_GEN2_Tari minTari;
00078 
00079   /* Max Tari Value*/
00080   TMR_GEN2_Tari maxTari;
00081 
00082 } TMR_LLRP_C1G2RFModeTable;
00083 
00087 typedef struct TMR_LLRP_ReaderCapabilities
00088 {
00090   llrp_u16_t countryCode;
00091 
00093   uint32_t model;
00094 
00096   char softwareVersion[128];
00097 
00099   TMR_uint16List powerTable;
00100   uint16_t powerList[255];
00101 
00103   TMR_uint32List freqTable;
00104   uint32_t freqList[64];
00105 
00106   union
00107   {
00113     TMR_LLRP_C1G2RFModeTable gen2Modes[TMR_LLRP_MAX_RFMODE_ENTRIES];
00118   } u;
00119 
00120 } TMR_LLRP_ReaderCapabilities;
00121 
00127 typedef struct ROSpecProtocolTable
00128 {
00129   /* rospecid */
00130   uint8_t rospecID;
00131   /*protocol */
00132   TMR_TagProtocol rospecProtocol;
00133 }ROSpecProtocolTable;
00134 
00139 typedef struct TMR_LLRP_UnhandledAsyncResponse
00140 {
00142   LLRP_tSMessage *lMsg;
00143 }TMR_LLRP_UnhandledAsyncResponse;
00144 
00148 typedef struct TMR_LLRP_LlrpReader
00149 {
00150   /* @privatesection */
00151   LLRP_tSTypeRegistry *       pTypeRegistry;
00152   LLRP_tSConnection *         pConn;
00153   int                         portNum;
00154   llrp_u32_t                  msgId;
00155   llrp_u32_t                  roSpecId, accessSpecId;
00156   llrp_u16_t                  opSpecId;
00157 
00158   TMR_AntennaMapList *txRxMap;
00159   uint32_t transportTimeout;
00160   uint32_t commandTimeout;
00161   TMR_Region  regionId;
00162   TMR_GEN2_Password gen2AccessPassword;
00163 
00164   /* Static storage for the default map */
00165   TMR_AntennaMap staticTxRxMapData[TMR_SR_MAX_ANTENNA_PORTS];
00166   TMR_AntennaMapList staticTxRxMap;
00167 
00168   uint32_t portMask;
00169   /* Bit mask of supported protocol list */
00170   uint32_t supportedProtocols;
00171 
00172   TMR_TagProtocol currentProtocol;
00173 
00174   /* Buffer to store additional error message */
00175   /* TODO: Change TMR_SR_MAX_PACKET_SIZE to appropriate value */
00176   char errMsg[TMR_SR_MAX_PACKET_SIZE];
00177 
00178   /* Large bitmask that stores whether each parameter's presence
00179    * is known or not.
00180    */
00181   uint32_t paramConfirmed[TMR_PARAMWORDS];
00182 
00183   /* Large bitmask that, if the corresponding bit in paramConfirmed is set,
00184    * stores whether each parameter is present or not.
00185    */
00186   uint32_t paramPresent[TMR_PARAMWORDS];
00187   
00188   /* Number of tags reported by reader */
00189   int tagsRemaining;
00190 
00191   /* Array of LLRP_tSMessage pointers holding the tag read responses */
00192   LLRP_tSMessage **bufResponse;
00193 
00194   /* bufResponse read index */
00195   uint8_t bufPointer;
00196   uint8_t bufIndex;
00197 
00198   /* Pointer to buffer holding the tag read data */
00199   LLRP_tSTagReportData *pTagReportData;
00200 
00201   int searchTimeoutMs;
00202 
00203   /* Cache LLRP Reader Capabilities */
00204   TMR_LLRP_ReaderCapabilities capabilities;
00205 
00210   pthread_t llrpReceiver;
00211   bool receiverSetup, receiverRunning, receiverEnabled;
00212   pthread_cond_t receiverCond;
00213   int numOfROSpecEvents;
00215   pthread_mutex_t receiverLock;
00216 
00221   uint64_t ka_start, ka_now;
00222   bool get_report, reportReceived;
00227   ROSpecProtocolTable readPlanProtocol[TMR_SR_MAX_PACKET_SIZE];
00228 
00233   TMR_LLRP_UnhandledAsyncResponse unhandledAsyncResponse;
00235   bool isResponsePending;
00237   bool threadCancel;
00238 }TMR_LLRP_LlrpReader;
00239 
00240 
00241 TMR_Status TMR_LLRP_connect(TMR_Reader *reader);
00242 TMR_Status TMR_LLRP_destroy(TMR_Reader *reader);
00243 TMR_Status TMR_LLRP_hasMoreTags(TMR_Reader *reader); 
00244 TMR_Status TMR_LLRP_getNextTag(TMR_Reader *reader, TMR_TagReadData *trd);
00245 TMR_Status TMR_LLRP_executeTagOp(TMR_Reader *reader, TMR_TagOp *tagop, TMR_TagFilter *filter, TMR_uint8List *data);
00246 TMR_Status TMR_LLRP_gpiGet(struct TMR_Reader *reader,uint8_t *count, TMR_GpioPin state[]);
00247 TMR_Status TMR_LLRP_gpoSet(struct TMR_Reader *reader,uint8_t count, const TMR_GpioPin state[]);
00248 TMR_Status TMR_LLRP_readTagMemBytes(struct TMR_Reader *reader, const TMR_TagFilter *filter,
00249                                     uint32_t bank, uint32_t addreass,
00250                                     uint16_t count,uint8_t data[]);
00251 TMR_Status TMR_LLRP_readTagMemWords(struct TMR_Reader *reader, const TMR_TagFilter *filter,
00252                                     uint32_t bank, uint32_t address,
00253                                     uint16_t count, uint16_t *data);
00254 TMR_Status TMR_LLRP_writeTagMemBytes(struct TMR_Reader *reader, const TMR_TagFilter *filter,
00255                                     uint32_t bank, uint32_t addreass,
00256                                     uint16_t count,const uint8_t data[]);
00257 TMR_Status TMR_LLRP_writeTagMemWords(struct TMR_Reader *reader, const TMR_TagFilter *filter,
00258                                     uint32_t bank, uint32_t address,
00259                                     uint16_t count, const uint16_t *data);
00260 TMR_Status TMR_LLRP_firmwareLoad( TMR_Reader *reader, void *cookie, TMR_FirmwareDataProvider provider);
00261 TMR_Status TMR_LLRP_writeTag(TMR_Reader *reader, const TMR_TagFilter *filter, const TMR_TagData *data);
00262 TMR_Status TMR_LLRP_killTag(struct TMR_Reader *reader, const TMR_TagFilter *filter,
00263                              const TMR_TagAuthentication *auth);
00264 TMR_Status TMR_LLRP_lockTag(struct TMR_Reader *reader,const TMR_TagFilter *filter, TMR_TagLockAction *action);
00265 TMR_Status TMR_LLRP_reboot(struct TMR_Reader *reader);
00269 TMR_Status TMR_LLRP_LlrpReader_init(TMR_Reader *reader);
00270 
00271 TMR_Status TMR_LLRP_read(struct TMR_Reader *reader, uint32_t timeoutMs, int32_t *tagCount);
00272 #ifdef __cplusplus
00273 }
00274 #endif
00275 
00276 #endif /* _TMR_LLRP_READER_H */


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