llrp_reader_l3.c
Go to the documentation of this file.
00001 
00008 /*
00009  * Copyright (c) 2011 ThingMagic, Inc.
00010  *
00011  * Permission is hereby granted, free of charge, to any person obtaining a copy
00012  * of this software and associated documentation files (the "Software"), to deal
00013  * in the Software without restriction, including without limitation the rights
00014  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00015  * copies of the Software, and to permit persons to whom the Software is
00016  * furnished to do so, subject to the following conditions:
00017  *
00018  * The above copyright notice and this permission notice shall be included in
00019  * all copies or substantial portions of the Software.
00020  * 
00021  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00022  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00023  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00024  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00025  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00026  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00027  * THE SOFTWARE.
00028  */
00029 
00034 #define _XOPEN_SOURCE
00035 
00036 
00037 #include "tm_reader.h"
00038 #include "osdep.h"
00039 #ifdef TMR_ENABLE_LLRP_READER
00040 
00041 #include <inttypes.h>
00042 #include <stdio.h>
00043 #include <stdlib.h>
00044 #include <string.h>
00045 #include <sys/select.h>
00046 #include <time.h>
00047 #include "llrp_reader_imp.h"
00048 #include "tmr_utils.h"
00049 
00050 #define BACKGROUND_RECEIVER_LOOP_PERIOD 100
00051 
00052 uint8_t TMR_LLRP_gpiListSargas[] = {0,1};
00053 uint8_t TMR_LLRP_gpoListSargas[] = {2,3};
00054 uint8_t sizeGpiListSargas = sizeof(TMR_LLRP_gpiListSargas)/sizeof(TMR_LLRP_gpiListSargas[0]);
00055 uint8_t sizeGpoListSargas = sizeof(TMR_LLRP_gpoListSargas)/sizeof(TMR_LLRP_gpoListSargas[0]);
00056 uint8_t TMR_LLRP_gpiListM6Astra[] = {3,4,6,7};
00057 uint8_t TMR_LLRP_gpoListM6Astra[] = {0,1,2,5};
00058 uint8_t sizeGpiListM6Astra = sizeof(TMR_LLRP_gpiListM6Astra)/sizeof(TMR_LLRP_gpiListM6Astra[0]);
00059 uint8_t sizeGpoListM6Astra = sizeof(TMR_LLRP_gpoListM6Astra)/sizeof(TMR_LLRP_gpoListM6Astra[0]);
00060 
00061 static TMR_Status
00062 TMR_LLRP_llrpToTmGpi(uint32_t model, llrp_u16_t llrpNum, uint8_t* tmNum)
00063 {
00064   int index = llrpNum - 1;
00065   int gpiCount;
00066 
00067   if (TMR_LLRP_MODEL_SARGAS == model)
00068   {
00069           gpiCount = sizeGpiListSargas;
00070   }
00071   else
00072   {
00073           gpiCount = sizeGpiListM6Astra;
00074   }
00075   if ((index < 0) || (gpiCount <= index))
00076   {
00077     return TMR_ERROR_LLRP_UNDEFINED_VALUE;
00078   }
00079 
00080   if (TMR_LLRP_MODEL_SARGAS == model)
00081   {
00082           *tmNum = TMR_LLRP_gpiListSargas[index];
00083   }
00084   else
00085   {
00086           *tmNum = TMR_LLRP_gpiListM6Astra[index];
00087   }
00088   return TMR_SUCCESS;
00089 }
00090 
00091 static TMR_Status
00092 TMR_LLRP_tmToLlrpGpo(uint32_t model, uint8_t tmNum, llrp_u16_t *llrpNum)
00093 {
00094   int gpoCount;
00095   int i;
00096 
00097   if (TMR_LLRP_MODEL_SARGAS == model)
00098   {
00099           gpoCount = sizeGpoListSargas;
00100   }
00101   else
00102   {
00103           gpoCount = sizeGpoListM6Astra;
00104   }
00105   for (i = 0; i < gpoCount; i++)
00106   {
00107           if (TMR_LLRP_MODEL_SARGAS == model)
00108           {
00109             if (TMR_LLRP_gpoListSargas[i] == tmNum) break;
00110           }
00111           else
00112           {
00113             if (TMR_LLRP_gpoListM6Astra[i] == tmNum) break;
00114           }
00115   }
00116   if (i == gpoCount)
00117   {
00118           return TMR_ERROR_INVALID;
00119   }
00120   else
00121   {
00122           *llrpNum = i + 1;
00123           return TMR_SUCCESS;
00124   }
00125 }
00126 
00136 TMR_Status
00137 TMR_LLRP_notifyTransportListener(TMR_Reader *reader, LLRP_tSMessage *pMsg, bool tx, int timeout)
00138 {
00139   char buf[100*1024];
00140 
00141   if (LLRP_RC_OK != LLRP_toXMLString(&pMsg->elementHdr, buf, sizeof(buf)))
00142   {
00143     TMR__notifyTransportListeners(reader, tx, 0, (uint8_t *)buf, timeout);
00144     return TMR_ERROR_LLRP_MSG_PARSE_ERROR; 
00145   }
00146 
00147   TMR__notifyTransportListeners(reader, tx, 0, (uint8_t *)buf, timeout);
00148 
00149   return TMR_SUCCESS;
00150 }
00151 
00159 TMR_Status
00160 TMR_LLRP_sendMessage(TMR_Reader *reader, LLRP_tSMessage *pMsg, int timeoutMs)
00161 {
00162   LLRP_tSConnection *pConn = reader->u.llrpReader.pConn;
00163   timeoutMs += reader->u.llrpReader.transportTimeout;
00164 
00165   if (NULL == pConn)
00166   {
00167     return TMR_ERROR_LLRP_SENDIO_ERROR;
00168   }
00169 
00170   pMsg->MessageID = reader->u.llrpReader.msgId ++;
00171 
00172   if (NULL != reader->transportListeners)
00173   {
00174     TMR_LLRP_notifyTransportListener(reader, pMsg, true, timeoutMs);
00175   }
00176   /*
00177    * If LLRP_Conn_sendMessage() returns other than LLRP_RC_OK
00178    * then there was an error.
00179    */
00180   if (LLRP_RC_OK != LLRP_Conn_sendMessage(pConn, pMsg))
00181   {
00182     const LLRP_tSErrorDetails *pError = LLRP_Conn_getSendError(pConn);
00183     sprintf(reader->u.llrpReader.errMsg, "ERROR: %s sendMessage failed, %s",
00184                 pMsg->elementHdr.pType->pName,
00185                 pError->pWhatStr ? pError->pWhatStr : "no reason given");
00186 
00187     return TMR_ERROR_LLRP_SENDIO_ERROR;
00188   }
00189 
00190   return TMR_SUCCESS;
00191 }
00192 
00200 TMR_Status
00201 TMR_LLRP_receiveMessage(TMR_Reader *reader, LLRP_tSMessage **pMsg, int timeoutMs)
00202 {
00203   LLRP_tSConnection *pConn = reader->u.llrpReader.pConn;
00204   timeoutMs += reader->u.llrpReader.transportTimeout;
00205 
00206   if (NULL == pConn)
00207   {
00208     return TMR_ERROR_LLRP_RECEIVEIO_ERROR;
00209   }
00210 
00211   /*
00212    * Receive the message subject to a time limit
00213    */
00214   *pMsg = LLRP_Conn_recvMessage(pConn, timeoutMs);
00215   /*
00216    * If LLRP_Conn_recvMessage() returns NULL then there was
00217    * an error.
00218    */
00219   if(NULL == *pMsg)
00220   {
00221     const LLRP_tSErrorDetails *pError = LLRP_Conn_getRecvError(pConn);
00222     
00223     sprintf(reader->u.llrpReader.errMsg,
00224             "ERROR: recvMessage failed, %s",
00225             pError->pWhatStr ? pError->pWhatStr : "no reason given");
00226     
00227     return TMR_ERROR_LLRP_RECEIVEIO_ERROR;
00228   }
00229 
00230   TMR_LLRP_notifyTransportListener(reader, *pMsg, false, timeoutMs);
00231   return TMR_SUCCESS;
00232 }
00233 
00242 TMR_Status
00243 TMR_LLRP_sendTimeout(TMR_Reader *reader, LLRP_tSMessage *pMsg, LLRP_tSMessage **pRsp, int timeoutMs)
00244 {
00245   TMR_Status ret;
00246 
00247   if (false == reader->continuousReading)
00248   {
00252     TMR_LLRP_setBackgroundReceiverState(reader, false);
00253   }
00254 
00255   ret = TMR_LLRP_sendMessage(reader, pMsg, timeoutMs);
00256   if (TMR_SUCCESS != ret)
00257   {
00258     goto out;
00259   }
00260 
00261 repeat:
00262   ret = TMR_LLRP_receiveMessage(reader, pRsp, timeoutMs);
00263   if (TMR_SUCCESS != ret)
00264   {
00265     goto out;
00266   }
00267 
00268   if (pMsg->elementHdr.pType->pResponseType != (*pRsp)->elementHdr.pType)
00269   {
00277     TMR_LLRP_processReceivedMessage(reader, *pRsp);
00278     goto repeat;
00279   }
00280 
00281 out:
00282   if (false == reader->continuousReading)
00283   {
00287     TMR_LLRP_setBackgroundReceiverState(reader, true);
00288   }
00289   return ret;
00290 }
00291 
00299 TMR_Status
00300 TMR_LLRP_send(TMR_Reader *reader, LLRP_tSMessage *pMsg, LLRP_tSMessage **pRsp)
00301 {
00302   return TMR_LLRP_sendTimeout(reader, pMsg, pRsp,
00303                               reader->u.llrpReader.commandTimeout
00304                               + reader->u.llrpReader.transportTimeout);
00305 }
00306 
00312 void
00313 TMR_LLRP_freeMessage(LLRP_tSMessage *pMsg)
00314 {
00315   /* Free only if the message is not null */
00316   if (NULL != pMsg)
00317   {
00318   LLRP_Element_destruct(&pMsg->elementHdr);
00319     pMsg = NULL;
00320   }
00321 }
00322 
00330 TMR_Status
00331 TMR_LLRP_checkLLRPStatus(LLRP_tSLLRPStatus *pLLRPStatus)
00332 {
00333   if (LLRP_StatusCode_M_Success != pLLRPStatus->eStatusCode)
00334   {
00335     return TMR_ERROR_LLRP;
00336   }
00337   else
00338   {
00339     return TMR_SUCCESS;
00340   }
00341 }
00342 
00349 TMR_Status
00350 TMR_LLRP_cmdGetRegion(TMR_Reader *reader, TMR_Region *region)
00351 {
00352   TMR_Status ret;
00353   LLRP_tSGET_READER_CONFIG              *pCmd;
00354   LLRP_tSMessage                        *pCmdMsg;
00355   LLRP_tSMessage                        *pRspMsg;
00356   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
00357   LLRP_tSThingMagicDeviceControlConfiguration  *pTMRegionConfig;
00358   LLRP_tSParameter                      *pCustParam;
00359 
00360   ret = TMR_SUCCESS;
00364   pCmd = LLRP_GET_READER_CONFIG_construct();
00365   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_Identification);
00366 
00372   pTMRegionConfig = LLRP_ThingMagicDeviceControlConfiguration_construct();
00373   if (NULL == pTMRegionConfig)
00374   {
00375     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
00376     return TMR_ERROR_LLRP;
00377   }
00378 
00383   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMRegionConfig, LLRP_ThingMagicControlConfiguration_ThingMagicRegionConfiguration);
00384   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMRegionConfig->hdr))
00385   {
00386     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMRegionConfig);
00387     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
00388     return TMR_ERROR_LLRP;
00389   }
00390 
00391   pCmdMsg       = &pCmd->hdr;
00395   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
00400   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
00401   if (TMR_SUCCESS != ret)
00402   {
00403     return ret;
00404   }
00405 
00409   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
00410   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
00411   {
00412     TMR_LLRP_freeMessage(pRspMsg);
00413     return TMR_ERROR_LLRP; 
00414   }
00415 
00419   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
00420   if (NULL != pCustParam)
00421   {
00422     *region = LLRP_ThingMagicRegionConfiguration_getRegionID((LLRP_tSThingMagicRegionConfiguration *) pCustParam);
00423   }
00424   else
00425   {
00426     TMR_LLRP_freeMessage(pRspMsg);
00427     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
00428   }
00429   
00433   TMR_LLRP_freeMessage(pRspMsg);
00434 
00435   return ret;
00436 }
00443 TMR_Status
00444 TMR_LLRP_cmdGetTMAsyncOffTime(TMR_Reader *reader, uint32_t *offtime)
00445 {
00446   TMR_Status ret;
00447   LLRP_tSGET_READER_CONFIG              *pCmd;
00448   LLRP_tSMessage                        *pCmdMsg;
00449   LLRP_tSMessage                        *pRspMsg;
00450   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
00451   LLRP_tSThingMagicDeviceControlConfiguration  *pTMAsyncOffTime;
00452   LLRP_tSParameter                      *pCustParam;
00453 
00454   ret = TMR_SUCCESS;
00458   pCmd = LLRP_GET_READER_CONFIG_construct();
00459   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_Identification);
00460 
00466   pTMAsyncOffTime = LLRP_ThingMagicDeviceControlConfiguration_construct();
00467   if (NULL == pTMAsyncOffTime)
00468   {
00469     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
00470     return TMR_ERROR_LLRP;
00471   }
00472 
00477   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMAsyncOffTime, LLRP_ThingMagicControlConfiguration_ThingMagicAsyncOFFTime);
00478   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMAsyncOffTime->hdr))
00479   {
00480     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMAsyncOffTime);
00481     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
00482     return TMR_ERROR_LLRP;
00483   }
00484 
00485   pCmdMsg       = &pCmd->hdr;
00489   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
00494   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
00495   if (TMR_SUCCESS != ret)
00496   {
00497     return ret;
00498   }
00499 
00503   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
00504   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
00505   {
00506     TMR_LLRP_freeMessage(pRspMsg);
00507     return TMR_ERROR_LLRP; 
00508   }
00509 
00513   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
00514   if (NULL != pCustParam)
00515   {
00516     *offtime = LLRP_ThingMagicAsyncOFFTime_getAsyncOFFTime((LLRP_tSThingMagicAsyncOFFTime *) pCustParam);
00517   }
00518   else
00519   {
00520     TMR_LLRP_freeMessage(pRspMsg);
00521     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
00522   }
00523 
00527   TMR_LLRP_freeMessage(pRspMsg);
00528 
00529   return ret;
00530 }
00531 
00539 TMR_Status
00540 TMR_LLRP_cmdAntennaDetect(TMR_Reader *reader, uint8_t *count, TMR_LLRP_PortDetect *ports)
00541 {
00542   TMR_Status ret;
00543   LLRP_tSGET_READER_CONFIG              *pCmd;
00544   LLRP_tSMessage                        *pCmdMsg;
00545   LLRP_tSMessage                        *pRspMsg;
00546   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
00547   LLRP_tSAntennaProperties              *pAntProps;
00548   uint8_t                               i;
00549 
00550   ret = TMR_SUCCESS;
00551   i = 0;
00557   pCmd = LLRP_GET_READER_CONFIG_construct();
00558   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_AntennaProperties);
00559   LLRP_GET_READER_CONFIG_setAntennaID(pCmd, 0);
00560 
00561   pCmdMsg       = &pCmd->hdr;
00565   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
00570   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
00571   if (TMR_SUCCESS != ret)
00572   {
00573     return ret;
00574   }
00575 
00579   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
00580   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
00581   {
00582     TMR_LLRP_freeMessage(pRspMsg);
00583     return TMR_ERROR_LLRP; 
00584   }
00585 
00589   for (pAntProps = LLRP_GET_READER_CONFIG_RESPONSE_beginAntennaProperties(pRsp),
00590       i = 0;
00591       (pAntProps != NULL) && (i < *count);
00592       pAntProps = LLRP_GET_READER_CONFIG_RESPONSE_nextAntennaProperties(pAntProps),
00593       i ++)
00594   {
00595     ports[i].port       = pAntProps->AntennaID;
00596     ports[i].connected  = pAntProps->AntennaConnected;
00597     ports[i].gain       = pAntProps->AntennaGain;
00598   }
00599   *count = i;
00600 
00604   TMR_LLRP_freeMessage(pRspMsg);
00605 
00606   return ret;
00607 }
00608 
00615 TMR_Status
00616 TMR_LLRP_cmdGetTMDeviceInformationCapabilities(TMR_Reader *reader, int param, TMR_String *version)
00617 {
00618   TMR_Status ret;
00619   LLRP_tSGET_READER_CAPABILITIES              *pCmd;
00620   LLRP_tSMessage                              *pCmdMsg;
00621   LLRP_tSMessage                              *pRspMsg;
00622   LLRP_tSGET_READER_CAPABILITIES_RESPONSE     *pRsp;
00623   LLRP_tSThingMagicDeviceControlCapabilities  *pTMCaps;
00624   LLRP_tSParameter                            *pCustParam;
00625   llrp_utf8v_t                                 hardwareVersion;
00626   llrp_utf8v_t                                 serialNumber;
00627 
00628   ret = TMR_SUCCESS;
00629 
00633   pCmd = LLRP_GET_READER_CAPABILITIES_construct();
00634   LLRP_GET_READER_CAPABILITIES_setRequestedData(pCmd, LLRP_GetReaderCapabilitiesRequestedData_General_Device_Capabilities);
00635 
00640   pTMCaps = LLRP_ThingMagicDeviceControlCapabilities_construct();
00641   if (NULL == pTMCaps)
00642   {
00643     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
00644     return TMR_ERROR_LLRP;
00645   }
00646 
00651   LLRP_ThingMagicDeviceControlCapabilities_setRequestedData(pTMCaps, LLRP_ThingMagicControlCapabilities_DeviceInformationCapabilities);
00652   if (LLRP_RC_OK != LLRP_GET_READER_CAPABILITIES_addCustom(pCmd, &pTMCaps->hdr))
00653   {
00654     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMCaps);
00655     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
00656     return TMR_ERROR_LLRP;
00657   }
00658   pCmdMsg       = &pCmd->hdr;
00659 
00663   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
00668   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
00669   if (TMR_SUCCESS != ret)
00670   {
00671     return ret;
00672   }
00673 
00677   pRsp = (LLRP_tSGET_READER_CAPABILITIES_RESPONSE *) pRspMsg;
00678   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
00679   {
00680     TMR_LLRP_freeMessage(pRspMsg);
00681     return TMR_ERROR_LLRP;
00682   }
00687   pCustParam = LLRP_GET_READER_CAPABILITIES_RESPONSE_beginCustom(pRsp);
00688   if (NULL != pCustParam)
00689   {
00690     if(param == TMR_PARAM_VERSION_HARDWARE)
00691     {
00692       hardwareVersion = ((LLRP_tSDeviceInformationCapabilities *)pCustParam)->HardwareVersion;
00693       TMR_stringCopy(version, (char *)hardwareVersion.pValue, (int)hardwareVersion.nValue);
00694     }
00695     else if(param == TMR_PARAM_VERSION_SERIAL)
00696     {
00697       serialNumber = ((LLRP_tSDeviceInformationCapabilities *)pCustParam)->ReaderSerialNumber;
00698       TMR_stringCopy(version, (char *)serialNumber.pValue, (int)serialNumber.nValue);
00699     }
00700   }
00704   TMR_LLRP_freeMessage(pRspMsg);
00705 
00706   return ret;
00707 
00708 }
00709 
00710 TMR_GEN2_Tari
00711 TMR_convertTari(uint16_t tari)
00712 {
00713   switch(tari) {
00714   case 6250:
00715     return TMR_GEN2_TARI_6_25US;
00716     break;
00717   case 12500:
00718     return TMR_GEN2_TARI_12_5US;
00719     break;
00720   case 25000:
00721     return TMR_GEN2_TARI_25US;
00722     break;
00723   default:
00724     return TMR_GEN2_TARI_25US;
00725     break;
00726   }
00727 }
00734 TMR_Status
00735 TMR_LLRP_cmdGetReaderCapabilities(TMR_Reader *reader, TMR_LLRP_ReaderCapabilities *capabilities)
00736 {
00737   TMR_Status ret;
00738   LLRP_tSGET_READER_CAPABILITIES          *pCmd;
00739   LLRP_tSMessage                          *pCmdMsg;
00740   LLRP_tSMessage                          *pRspMsg;
00741   LLRP_tSGET_READER_CAPABILITIES_RESPONSE *pRsp;
00742   TMR_GEN2_Tari minTari, maxTari;
00743 
00744   ret = TMR_SUCCESS;
00745 
00750   pCmd = LLRP_GET_READER_CAPABILITIES_construct();
00751   LLRP_GET_READER_CAPABILITIES_setRequestedData(pCmd, LLRP_GetReaderCapabilitiesRequestedData_All);
00752 
00753   pCmdMsg = &pCmd->hdr;
00757   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
00762   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
00763   if (TMR_SUCCESS != ret)
00764   {
00765     return ret;
00766   }
00767 
00771   pRsp = (LLRP_tSGET_READER_CAPABILITIES_RESPONSE *) pRspMsg;
00772   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
00773   {
00774     TMR_LLRP_freeMessage(pRspMsg);
00775     return TMR_ERROR_LLRP; 
00776   }
00777 
00787   {
00791     LLRP_tSGeneralDeviceCapabilities        *pReaderCap;
00792     pReaderCap = LLRP_GET_READER_CAPABILITIES_RESPONSE_getGeneralDeviceCapabilities(pRsp);
00793 
00794     if (TM_MANUFACTURER_ID == pReaderCap->DeviceManufacturerName)
00795     {
00796       capabilities->model = pReaderCap->ModelName;
00797     }
00798 
00802     memcpy(capabilities->softwareVersion, pReaderCap->ReaderFirmwareVersion.pValue, 
00803                                                   pReaderCap->ReaderFirmwareVersion.nValue );
00804     capabilities->softwareVersion[pReaderCap->ReaderFirmwareVersion.nValue] = '\0';
00805   }
00806 
00810   {
00811     LLRP_tSRegulatoryCapabilities *pRegCaps;
00812     pRegCaps = LLRP_GET_READER_CAPABILITIES_RESPONSE_getRegulatoryCapabilities(pRsp);
00813 
00814     {
00818       LLRP_tSTransmitPowerLevelTableEntry     *pTableEntry;
00819 
00820       /*Initialize cached powerTable */
00821       TMR_uint16List *table = &capabilities->powerTable;
00822       table->max = 255;
00823       table->len = 0;
00824       table->list = capabilities->powerList;
00825 
00826       /* Before extracting the power level initialize the powerList table to zero*/
00827       memset(table->list, 0, table->max*(sizeof(uint16_t)));
00828 
00829 
00830       for (pTableEntry = LLRP_UHFBandCapabilities_beginTransmitPowerLevelTableEntry(
00831                                                               pRegCaps->pUHFBandCapabilities);
00832           (pTableEntry != NULL);
00833           pTableEntry = LLRP_UHFBandCapabilities_nextTransmitPowerLevelTableEntry(pTableEntry))
00834       {
00835         table->list[pTableEntry->Index] = pTableEntry->TransmitPowerValue;
00836         table->len ++;
00837       }
00838     }
00839 
00840     {
00844       LLRP_tSFrequencyHopTable  *pFreqHopTable;
00845       llrp_u16_t count;
00846 
00847       /*Initialize cached frequency table */
00848       TMR_uint32List *table = &capabilities->freqTable;
00849       table->max = 64;
00850       table->len = 0;
00851       table->list = capabilities->freqList;
00852 
00853       /* Before extracting the frequency  initialize the freqList table to zero*/
00854       memset(table->list, 0, table->max*(sizeof(uint32_t)));
00855 
00856       pFreqHopTable = LLRP_FrequencyInformation_beginFrequencyHopTable(
00857                                 pRegCaps->pUHFBandCapabilities->pFrequencyInformation);
00858 
00859       for (count = 0; count < pFreqHopTable->Frequency.nValue; count ++)
00860       {
00861         table->list[count] = pFreqHopTable->Frequency.pValue[count];
00862         table->len ++;
00863       }
00864     }
00865     {
00869       LLRP_tSParameter *pRFModeTable;
00870 
00871       for (pRFModeTable = LLRP_UHFBandCapabilities_beginAirProtocolUHFRFModeTable(pRegCaps->pUHFBandCapabilities);
00872           (pRFModeTable != NULL);
00873           pRFModeTable = LLRP_UHFBandCapabilities_nextAirProtocolUHFRFModeTable(pRFModeTable))
00874       {
00875         /* Check for Mode table protocol */
00876         if (&LLRP_tdC1G2UHFRFModeTable == pRFModeTable->elementHdr.pType)
00877         {
00882           LLRP_tSC1G2UHFRFModeTableEntry *pModeEntry;
00883 
00884           /* Iterate through list of entries in table */
00885           for (pModeEntry = LLRP_C1G2UHFRFModeTable_beginC1G2UHFRFModeTableEntry(
00886                                                 (LLRP_tSC1G2UHFRFModeTable *)pRFModeTable);
00887               (pModeEntry != NULL);
00888               pModeEntry = LLRP_C1G2UHFRFModeTable_nextC1G2UHFRFModeTableEntry(pModeEntry))
00889           {
00890             TMR_GEN2_LinkFrequency blf;
00891             llrp_u32_t index        = pModeEntry->ModeIdentifier;
00892             llrp_u32_t bdr          = pModeEntry->BDRValue;
00893             llrp_u32_t minTariValue = pModeEntry->MinTariValue;
00894             llrp_u32_t maxTariValue = pModeEntry->MaxTariValue;
00895 
00896             switch (bdr)
00897             {
00898               case 250000:
00899                 blf = TMR_GEN2_LINKFREQUENCY_250KHZ;
00900                 break;
00901 
00902               case 640000:
00903                 blf = TMR_GEN2_LINKFREQUENCY_640KHZ;
00904                 break;
00905 
00906               case 320000:
00907                 blf = TMR_GEN2_LINKFREQUENCY_320KHZ;
00908                 break;
00909 
00910               default:
00911                 blf = TMR_GEN2_LINKFREQUENCY_250KHZ;
00912                 break;
00913             }
00914             /* In the tari enum smaller enum values = higher
00915              * tari values. i.e. tari25us=enum 0 and tari6.25= enum 2.
00916              * Hence, swapping the values
00917              */ 
00918             maxTari = TMR_convertTari(minTariValue);
00919             minTari = TMR_convertTari(maxTariValue);
00920 
00922             capabilities->u.gen2Modes[index].blf = blf;
00924             capabilities->u.gen2Modes[index].m = pModeEntry->eMValue;
00926             capabilities->u.gen2Modes[index].minTari = minTari;
00928             capabilities->u.gen2Modes[index].maxTari = maxTari;
00929           }
00930         }
00931         else
00932         {
00936           TMR_LLRP_freeMessage(pRspMsg);
00937           return TMR_ERROR_UNIMPLEMENTED_FEATURE;
00938         }
00939       }
00940     } /* End of iterating through listAirProtocolUHFRFModeTable */
00941   } /* End of extracting Regulatory capabilities */
00942 
00946   TMR_LLRP_freeMessage(pRspMsg);
00947 
00948   return ret;
00949 }
00950 
00957 TMR_Status
00958 TMR_LLRP_cmdSetGPOState(TMR_Reader *reader, uint8_t count,
00959                         const TMR_GpioPin state[])
00960 {
00961   TMR_Status ret;
00962   LLRP_tSSET_READER_CONFIG              *pCmd;
00963   LLRP_tSMessage                        *pCmdMsg;
00964   LLRP_tSMessage                        *pRspMsg;
00965   LLRP_tSSET_READER_CONFIG_RESPONSE     *pRsp;
00966   uint8_t i;
00967 
00968   ret = TMR_SUCCESS;
00969 
00974   pCmd = LLRP_SET_READER_CONFIG_construct();
00975 
00976   /* Set GPO state as per the list supplied */
00977   for (i=0; i<count; i++)
00978   {
00979     uint8_t id;
00980     bool high;
00981     llrp_u16_t llrpId;
00982     LLRP_tSGPOWriteData *pParam;
00983 
00984     id = state[i].id;
00985     high = state[i].high;
00986 
00987     /* Construct LLRP parameter */
00988     pParam = LLRP_GPOWriteData_construct();
00989     ret = TMR_LLRP_tmToLlrpGpo(reader->u.llrpReader.capabilities.model, id, &llrpId);
00990     if (TMR_SUCCESS != ret) { return ret; }
00991     LLRP_GPOWriteData_setGPOPortNumber(pParam, llrpId);
00992     LLRP_GPOWriteData_setGPOData(pParam, high);
00993 
00994     /* Add param */
00995     LLRP_SET_READER_CONFIG_addGPOWriteData(pCmd, pParam);
00996   }
00997 
01001   pCmdMsg = &pCmd->hdr;
01002 
01003   if (reader->continuousReading)
01004   {
01005     ret = TMR_LLRP_sendMessage(reader, pCmdMsg, reader->u.llrpReader.transportTimeout);
01006     if (TMR_SUCCESS != ret)
01007     {
01008       TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01009       return ret;
01010     }
01011 
01012     while (false == reader->u.llrpReader.isResponsePending)
01013     {
01014       tmr_sleep(10);
01015     }
01016 
01017     if (NULL != reader->u.llrpReader.unhandledAsyncResponse.lMsg)
01018     {
01019       if (pCmdMsg->elementHdr.pType->pResponseType == reader->u.llrpReader.unhandledAsyncResponse.lMsg->elementHdr.pType)
01020       {
01021         TMR_LLRP_freeMessage((LLRP_tSMessage *)reader->u.llrpReader.unhandledAsyncResponse.lMsg);
01022         reader->u.llrpReader.isResponsePending = false;
01023         TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01024 
01025         return TMR_SUCCESS;
01026       }
01027     }
01028     else
01029     {
01030       TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01031       return TMR_ERROR_LLRP;
01032     }
01033   }
01034   else
01035   {
01036     ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
01041     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01042     if (TMR_SUCCESS != ret)
01043     {
01044       return ret;
01045     }
01046 
01050     pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
01051     if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
01052     {
01053       TMR_LLRP_freeMessage(pRspMsg);
01054       return TMR_ERROR_LLRP; 
01055     }
01056 
01060     TMR_LLRP_freeMessage(pRspMsg);
01061   }
01062 
01063   return ret;
01064 }
01065 
01066 
01073 TMR_Status
01074 TMR_LLRP_cmdSetReadTransmitPowerList(TMR_Reader *reader, TMR_PortValueList *pPortValueList)
01075 {
01076   TMR_Status ret;
01077   LLRP_tSSET_READER_CONFIG              *pCmd;
01078   LLRP_tSMessage                        *pCmdMsg;
01079   LLRP_tSMessage                        *pRspMsg;
01080   LLRP_tSSET_READER_CONFIG_RESPONSE     *pRsp;
01081   uint8_t                               i;
01082 
01083   ret = TMR_SUCCESS;
01084   i = 0;
01090   pCmd = LLRP_SET_READER_CONFIG_construct();
01091 
01092   /* Set antenna configuration as per the list supplied */
01093   for (i = 0; i < pPortValueList->len; i ++)
01094   {
01095     LLRP_tSAntennaConfiguration   *pAntConfig;
01096     LLRP_tSRFTransmitter          *pRfTransmitter;
01097     uint16_t                       index, power = 0;
01098 
01099     /* Construct RFTransmitter */
01100     pRfTransmitter = LLRP_RFTransmitter_construct();
01101     if (NULL == pRfTransmitter)
01102     {
01103       TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01104       return TMR_ERROR_LLRP;
01105     }
01106 
01107     /* Get the index of corresponding power from powerTable  */
01108     for (index = 1; index <= reader->u.llrpReader.capabilities.powerTable.len; 
01109                                                                   index ++)
01110     {
01111       power = reader->u.llrpReader.capabilities.powerTable.list[index];
01112       if (pPortValueList->list[i].value == power)
01113       {
01114         break;
01115       }
01116       else
01117       {
01118         /*
01119          * we are cacheing the power level in 0.2db resolution.
01120          * if the value provided by the user is within the range
01121          * but not in the powertable always down grade the value
01122          * to the nearest available lower power value
01123          */
01124         if((pPortValueList->list[i].value > power)&&
01125             (pPortValueList->list[i].value < reader->u.llrpReader.capabilities.powerTable.list[index+1]))
01126         {
01127           power = reader->u.llrpReader.capabilities.powerTable.list[index];
01128           break;
01129         }
01130       }
01131     }
01132 
01133     if (index > reader->u.llrpReader.capabilities.powerTable.len)
01134     {
01135       /* power value specified is unknown or out of range */
01136       TMR_LLRP_freeMessage((LLRP_tSMessage *)pRfTransmitter);
01137       TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01138       return TMR_ERROR_ILLEGAL_VALUE;
01139     }
01140 
01141     if ((TMR_LLRP_MODEL_ASTRA_EX == reader->u.llrpReader.capabilities.model)
01142         && (1 == pPortValueList->list[i].port)
01143         && (TMR_REGION_NA == reader->u.llrpReader.regionId))
01144     {
01145       if (3000 < power)
01146       {
01147         TMR_LLRP_freeMessage((LLRP_tSMessage *)pRfTransmitter);
01148         TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01149         return TMR_ERROR_MSG_POWER_TOO_HIGH;
01150       }
01151     }
01152 
01153     LLRP_RFTransmitter_setTransmitPower(pRfTransmitter, index);
01154 
01155     /* Construct AntennaConfiguration */
01156     pAntConfig = LLRP_AntennaConfiguration_construct();
01157     LLRP_AntennaConfiguration_setAntennaID(pAntConfig, pPortValueList->list[i].port);
01158     LLRP_AntennaConfiguration_setRFTransmitter(pAntConfig, pRfTransmitter);
01159 
01160     /* Add AntennaConfiguration */
01161     LLRP_SET_READER_CONFIG_addAntennaConfiguration(pCmd, pAntConfig);
01162   }
01163 
01164   pCmdMsg = &pCmd->hdr;
01168   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
01173   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01174   if (TMR_SUCCESS != ret)
01175   {
01176     return ret;
01177   }
01178 
01182   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
01183   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
01184   {
01185     TMR_LLRP_freeMessage(pRspMsg);
01186     return TMR_ERROR_LLRP; 
01187   }
01188 
01192   TMR_LLRP_freeMessage(pRspMsg);
01193 
01194   return ret;
01195 }
01196 
01203 TMR_Status
01204 TMR_LLRP_cmdGetLicensedFeatures(TMR_Reader *reader, TMR_uint8List *features)
01205 {
01206   TMR_Status ret;
01207   LLRP_tSGET_READER_CONFIG              *pCmd;
01208   LLRP_tSMessage                        *pCmdMsg;
01209   LLRP_tSMessage                        *pRspMsg;
01210   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
01211   LLRP_tSThingMagicDeviceControlConfiguration  *pTMLicensedFeatures;
01212   LLRP_tSParameter                      *pCustParam;
01213   llrp_u8v_t                            licensedFeatures;
01214 
01215   ret = TMR_SUCCESS;
01216 
01217   pCmd = LLRP_GET_READER_CONFIG_construct();
01218   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_Identification);
01219 
01225   pTMLicensedFeatures = LLRP_ThingMagicDeviceControlConfiguration_construct();
01226   if (NULL == pTMLicensedFeatures)
01227   {
01228     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01229     return TMR_ERROR_LLRP;
01230   }
01231   
01232   
01237   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMLicensedFeatures, LLRP_ThingMagicControlConfiguration_ThingMagicLicensedFeatures);
01238   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMLicensedFeatures->hdr))
01239   {
01240     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMLicensedFeatures);
01241     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01242     return TMR_ERROR_LLRP;
01243   }
01244   
01245   pCmdMsg       = &pCmd->hdr;
01249   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
01254   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01255   if (TMR_SUCCESS != ret)
01256   {
01257     return ret;
01258   }
01259 
01263   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
01264   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
01265   {
01266     TMR_LLRP_freeMessage(pRspMsg);
01267     return TMR_ERROR_LLRP; 
01268   }
01272   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
01273   if (NULL != pCustParam)
01274   {
01275     licensedFeatures = LLRP_ThingMagicLicensedFeatures_getLicensedFeatures((LLRP_tSThingMagicLicensedFeatures *) pCustParam);
01276   }
01277   else
01278   {
01279     TMR_LLRP_freeMessage(pRspMsg);
01280     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
01281   }
01282 
01283   memcpy(features->list, licensedFeatures.pValue, licensedFeatures.nValue);
01284 
01285   TMR_LLRP_freeMessage(pRspMsg);
01286 
01287   return ret;
01288 
01289 }
01296 TMR_Status
01297 TMR_LLRP_cmdGetVersionSerial(TMR_Reader *reader, TMR_String *version)
01298 {
01299   TMR_Status ret;
01300   LLRP_tSGET_READER_CONFIG              *pCmd;
01301   LLRP_tSMessage                        *pCmdMsg;
01302   LLRP_tSMessage                        *pRspMsg;
01303   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
01304 
01305   ret = TMR_SUCCESS;
01306 
01312   pCmd = LLRP_GET_READER_CONFIG_construct();
01313   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_Identification);
01314 
01315   pCmdMsg       = &pCmd->hdr;
01319   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
01324   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01325   if (TMR_SUCCESS != ret)
01326   {
01327     return ret;
01328   }
01329 
01333   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
01334   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
01335   {
01336     TMR_LLRP_freeMessage(pRspMsg);
01337     return TMR_ERROR_LLRP; 
01338   }
01342   TMR_bytesToHex(pRsp->pIdentification->ReaderID.pValue, pRsp->pIdentification->ReaderID.nValue, version->value);
01346   TMR_LLRP_freeMessage(pRspMsg);
01347 
01348   return ret;
01349 
01350 }
01351 
01359 TMR_Status
01360 TMR_LLRP_cmdGetGPIState(TMR_Reader *reader, uint8_t *count, TMR_GpioPin state[])
01361 {
01362   TMR_Status ret;
01363   LLRP_tSGET_READER_CONFIG              *pCmd;
01364   LLRP_tSMessage                        *pCmdMsg;
01365   LLRP_tSMessage                        *pRspMsg;
01366   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
01367 
01368   *count = 0;
01369   ret = TMR_SUCCESS;
01370 
01376   pCmd = LLRP_GET_READER_CONFIG_construct();
01377   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_GPIPortCurrentState);
01378 
01382   pCmdMsg       = &pCmd->hdr;
01386   if (reader->continuousReading)
01387   {
01388     ret = TMR_LLRP_sendMessage(reader, pCmdMsg, reader->u.llrpReader.transportTimeout);
01389     if (TMR_SUCCESS != ret)
01390     {
01391       TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01392       return ret;
01393     }
01394 
01395     while (false == reader->u.llrpReader.isResponsePending)
01396     {
01397       tmr_sleep(10);
01398     }
01399 
01400     if (NULL != reader->u.llrpReader.unhandledAsyncResponse.lMsg)
01401     {
01402       if (pCmdMsg->elementHdr.pType->pResponseType == reader->u.llrpReader.unhandledAsyncResponse.lMsg->elementHdr.pType)
01403       {
01404         pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *)reader->u.llrpReader.unhandledAsyncResponse.lMsg;
01405         if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
01406         {
01407           TMR_LLRP_freeMessage(pRspMsg);
01408           return TMR_ERROR_LLRP; 
01409         }
01413         {
01414           LLRP_tSGPIPortCurrentState* list = pRsp->listGPIPortCurrentState;
01415           while (NULL != list)
01416           {
01417             TMR_GpioPin* pin = &state[*count];
01418             ret = TMR_LLRP_llrpToTmGpi(reader->u.llrpReader.capabilities.model, list->GPIPortNum, &pin->id);
01419             if (TMR_SUCCESS != ret) { return ret; }
01420             pin->high = (LLRP_GPIPortState_High == list->eState);
01421             pin->output = false;
01422             (*count)++;
01423             list = (LLRP_tSGPIPortCurrentState*)list->hdr.pNextSubParameter;
01424           }
01425         }
01426 
01427         TMR_LLRP_freeMessage((LLRP_tSMessage *)reader->u.llrpReader.unhandledAsyncResponse.lMsg);
01428         reader->u.llrpReader.isResponsePending = false;
01429         TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01430 
01431         return TMR_SUCCESS;
01432       }
01433     }    
01434     else
01435     {
01436       TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01437       return TMR_ERROR_LLRP;
01438     }
01439   }
01440   else
01441   {
01442 
01443     ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
01448     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01449     if (TMR_SUCCESS != ret)
01450     {
01451       return ret;
01452     }
01453 
01457     pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
01458     if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
01459     {
01460       TMR_LLRP_freeMessage(pRspMsg);
01461       return TMR_ERROR_LLRP; 
01462     }
01466     {
01467       LLRP_tSGPIPortCurrentState* list = pRsp->listGPIPortCurrentState;
01468       while (NULL != list)
01469       {
01470         TMR_GpioPin* pin = &state[*count];
01471         ret = TMR_LLRP_llrpToTmGpi(reader->u.llrpReader.capabilities.model, list->GPIPortNum, &pin->id);
01472         if (TMR_SUCCESS != ret) { return ret; }
01473         pin->high = (LLRP_GPIPortState_High == list->eState);
01474         pin->output = false;
01475         (*count)++;
01476         list = (LLRP_tSGPIPortCurrentState*)list->hdr.pNextSubParameter;
01477       }
01478     }
01479 
01483     TMR_LLRP_freeMessage(pRspMsg);
01484   }
01485   return ret;
01486 
01487 }
01488 
01495 TMR_Status 
01496 TMR_LLRP_cmdGetReadTransmitPowerList(TMR_Reader *reader, TMR_PortValueList *pPortValueList)
01497 {
01498   TMR_Status ret;
01499   LLRP_tSGET_READER_CONFIG              *pCmd;
01500   LLRP_tSMessage                        *pCmdMsg;
01501   LLRP_tSMessage                        *pRspMsg;
01502   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
01503   LLRP_tSAntennaConfiguration           *pAntConfig;
01504   uint8_t                               i;
01505 
01506   ret = TMR_SUCCESS;
01507   i = 0;
01513   pCmd = LLRP_GET_READER_CONFIG_construct();
01514   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_AntennaConfiguration);
01515 
01516   /* Get antenna configuration for all antennas*/
01517   LLRP_GET_READER_CONFIG_setAntennaID(pCmd, 0);
01518 
01519   pCmdMsg       = &pCmd->hdr;
01523   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
01528   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01529   if (TMR_SUCCESS != ret)
01530   {
01531     return ret;
01532   }
01533 
01537   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
01538   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
01539   {
01540     TMR_LLRP_freeMessage(pRspMsg);
01541     return TMR_ERROR_LLRP; 
01542   }
01543 
01547   pPortValueList->len = 0;
01548   for (pAntConfig = LLRP_GET_READER_CONFIG_RESPONSE_beginAntennaConfiguration(pRsp),
01549           i = 0;
01550           (pAntConfig != NULL);
01551           pAntConfig = LLRP_GET_READER_CONFIG_RESPONSE_nextAntennaConfiguration(pAntConfig),
01552           i ++)
01553   {
01554     uint16_t index;
01555 
01556     if (i > pPortValueList->max)
01557     {
01558       break;
01559     }
01560     pPortValueList->list[i].port  = pAntConfig->AntennaID;
01561     index = pAntConfig->pRFTransmitter->TransmitPower;
01562     if (NULL != reader->u.llrpReader.capabilities.powerTable.list)
01563     {
01564     pPortValueList->list[i].value = (int32_t)reader->u.llrpReader.capabilities.powerTable.list[index];
01565     pPortValueList->len ++;
01566   }
01567   }
01568   
01572   TMR_LLRP_freeMessage(pRspMsg);
01573 
01574   return ret;
01575 }
01576 
01583 TMR_Status
01584 TMR_LLRP_cmdSetWriteTransmitPowerList(TMR_Reader *reader, TMR_PortValueList *pPortValueList)
01585 {
01586   TMR_Status ret;
01587   LLRP_tSSET_READER_CONFIG              *pCmd;
01588   LLRP_tSMessage                        *pCmdMsg;
01589   LLRP_tSMessage                        *pRspMsg;
01590   LLRP_tSSET_READER_CONFIG_RESPONSE     *pRsp;
01591   uint8_t                               i;
01592 
01593   ret = TMR_SUCCESS;
01594   i = 0;
01600   pCmd = LLRP_SET_READER_CONFIG_construct();
01601 
01602   /* Set antenna configuration as per the list supplied */
01603   for (i = 0; i < pPortValueList->len; i ++)
01604   {
01605     LLRP_tSThingMagicAntennaConfiguration   *pAntConfig;
01606     LLRP_tSWriteTransmitPower               *pWriteTransmitPower;
01607     uint16_t                                index, power = 0;
01608 
01609     /* Construct AntennaConfiguration */
01610     pAntConfig = LLRP_ThingMagicAntennaConfiguration_construct();
01611     if (NULL == pAntConfig)
01612     {
01613       TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01614       return TMR_ERROR_LLRP;
01615     }
01616     LLRP_ThingMagicAntennaConfiguration_setAntennaID(pAntConfig, pPortValueList->list[i].port);
01617     pWriteTransmitPower = LLRP_WriteTransmitPower_construct();
01618     if (NULL == pWriteTransmitPower)
01619     {
01620       TMR_LLRP_freeMessage((LLRP_tSMessage *)pAntConfig);
01621       TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01622       return TMR_ERROR_LLRP;
01623     }
01624  
01625     /* Get the index of corresponding power from powerTable  */
01626     for (index = 1; index <= reader->u.llrpReader.capabilities.powerTable.len; 
01627                                                                   index ++)
01628     {
01629       power = reader->u.llrpReader.capabilities.powerTable.list[index];
01630       if (pPortValueList->list[i].value == power)
01631       {
01632         break;
01633       }
01634       else
01635       {
01636         /*
01637          * we are cacheing the power level in 0.2db resolution.
01638          * if the value provided by the user is within the range
01639          * but not in the powertable always down grade the value
01640          * to the nearest available lower power value
01641          */
01642         if((pPortValueList->list[i].value > power)&&
01643             (pPortValueList->list[i].value < reader->u.llrpReader.capabilities.powerTable.list[index+1]))
01644         {
01645           power = reader->u.llrpReader.capabilities.powerTable.list[index];
01646           break;
01647         }
01648       }
01649     }
01650 
01651     if (index > reader->u.llrpReader.capabilities.powerTable.len)
01652     {
01653       /* power value specified is unknown or out of range */
01654       TMR_LLRP_freeMessage((LLRP_tSMessage *)pWriteTransmitPower);
01655       TMR_LLRP_freeMessage((LLRP_tSMessage *)pAntConfig);
01656       TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01657       return TMR_ERROR_ILLEGAL_VALUE;
01658     }
01659 
01660     if ((TMR_LLRP_MODEL_ASTRA_EX == reader->u.llrpReader.capabilities.model)
01661         && (1 == pPortValueList->list[i].port)
01662         && (TMR_REGION_NA == reader->u.llrpReader.regionId))
01663     {
01664       if (3000 < power)
01665       {
01666         TMR_LLRP_freeMessage((LLRP_tSMessage *)pWriteTransmitPower);
01667         TMR_LLRP_freeMessage((LLRP_tSMessage *)pAntConfig);
01668         TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01669         return TMR_ERROR_MSG_POWER_TOO_HIGH;
01670       }
01671     }
01672 
01673     LLRP_WriteTransmitPower_setWriteTransmitPower(pWriteTransmitPower, index);
01674     LLRP_ThingMagicAntennaConfiguration_setWriteTransmitPower(pAntConfig, pWriteTransmitPower);
01675 
01676     /* Add AntennaConfiguration as a custom parameter*/
01677     LLRP_SET_READER_CONFIG_addCustom(pCmd, (LLRP_tSParameter *)pAntConfig);
01678   }
01679 
01680   pCmdMsg = &pCmd->hdr;
01684   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
01689   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01690   if (TMR_SUCCESS != ret)
01691   {
01692     return ret;
01693   }
01694 
01698   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
01699   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
01700   {
01701     TMR_LLRP_freeMessage(pRspMsg);
01702     return TMR_ERROR_LLRP; 
01703   }
01704 
01708   TMR_LLRP_freeMessage(pRspMsg);
01709 
01710   return ret;
01711 }
01712 
01719 TMR_Status
01720 TMR_LLRP_cmdGetWriteTransmitPowerList(TMR_Reader *reader, TMR_PortValueList *pPortValueList)
01721 {
01722   TMR_Status ret;
01723   LLRP_tSGET_READER_CONFIG                      *pCmd;
01724   LLRP_tSMessage                                *pCmdMsg;
01725   LLRP_tSMessage                                *pRspMsg;
01726   LLRP_tSGET_READER_CONFIG_RESPONSE             *pRsp;
01727   LLRP_tSThingMagicDeviceControlConfiguration   *pTMConfig;
01728   LLRP_tSWriteTransmitPower                     *pWriteTransmitPower;
01729   LLRP_tSParameter                              *pCustParam;
01730   uint8_t                                       i;
01731 
01732   ret = TMR_SUCCESS;
01733   i = 0;
01734 
01738   pCmd = LLRP_GET_READER_CONFIG_construct();
01739   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_Identification);
01740 
01746   pTMConfig = LLRP_ThingMagicDeviceControlConfiguration_construct();
01747   if (NULL == pTMConfig)
01748   {
01749     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01750     return TMR_ERROR_LLRP;
01751   }
01752 
01757   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMConfig, LLRP_ThingMagicControlConfiguration_ThingMagicAntennaConfiguration);
01758   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMConfig->hdr))
01759   {
01760     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMConfig);
01761     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01762     return TMR_ERROR_LLRP;
01763   }
01764 
01765   pCmdMsg = &pCmd->hdr;
01769   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
01774   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01775   if (TMR_SUCCESS != ret)
01776   {
01777     return ret;
01778   }
01779 
01783   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
01784   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
01785   {
01786     TMR_LLRP_freeMessage(pRspMsg);
01787     return TMR_ERROR_LLRP; 
01788   }
01789 
01793   pPortValueList->len = 0;
01794   for (pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp),
01795           i = 0;
01796           (pCustParam != NULL);
01797           pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_nextCustom(pCustParam),
01798           i ++)
01799   {
01800     uint16_t index;
01801 
01802     if (i > pPortValueList->max)
01803     {
01804       break;
01805     }
01806     pPortValueList->list[i].port
01807       = ((LLRP_tSThingMagicAntennaConfiguration *) pCustParam)->AntennaID;
01808     pWriteTransmitPower =
01809       LLRP_ThingMagicAntennaConfiguration_getWriteTransmitPower((LLRP_tSThingMagicAntennaConfiguration *) pCustParam);
01810     index = LLRP_WriteTransmitPower_getWriteTransmitPower(pWriteTransmitPower);
01811     if (NULL != reader->u.llrpReader.capabilities.powerTable.list)
01812     {
01813     pPortValueList->list[i].value = (int32_t)reader->u.llrpReader.capabilities.powerTable.list[index];
01814     pPortValueList->len ++;
01815   }
01816   }
01817  
01821   TMR_LLRP_freeMessage(pRspMsg);
01822 
01823   return ret;
01824 }
01825 
01831 TMR_Status
01832 TMR_LLRP_cmdDeleteAllROSpecs(TMR_Reader *reader, bool receiveResponse)
01833 {
01834   TMR_Status ret;
01835   LLRP_tSDELETE_ROSPEC          *pCmd;
01836   LLRP_tSMessage                *pCmdMsg;
01837   LLRP_tSMessage                *pRspMsg;
01838   LLRP_tSDELETE_ROSPEC_RESPONSE *pRsp;
01839 
01840   ret = TMR_SUCCESS;
01841 
01845   pCmd = LLRP_DELETE_ROSPEC_construct();
01846   LLRP_DELETE_ROSPEC_setROSpecID(pCmd, 0);        /* All */
01847 
01848   pCmdMsg = &pCmd->hdr;
01852   if (false == receiveResponse)
01853   {
01854     ret = TMR_LLRP_sendMessage(reader, pCmdMsg, reader->u.llrpReader.transportTimeout);
01855     /*
01856      * done with the command, free it
01857      */
01858     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01859   }
01860   else
01861   {
01862     ret = TMR_LLRP_sendTimeout(reader, pCmdMsg, &pRspMsg,
01863                                TMR_LLRP_STOP_TIMEOUT
01864                                + reader->u.llrpReader.commandTimeout
01865                                + reader->u.llrpReader.transportTimeout);
01870     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
01871   if (TMR_SUCCESS != ret)
01872   {
01873     return ret;
01874   }
01875 
01879   pRsp = (LLRP_tSDELETE_ROSPEC_RESPONSE *) pRspMsg;
01880   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
01881   {
01882     TMR_LLRP_freeMessage(pRspMsg);
01883     return TMR_ERROR_LLRP; 
01884   }
01885 
01889   TMR_LLRP_freeMessage(pRspMsg);
01890   }
01891 
01892   return ret;
01893 }
01894 
01899 static TMR_Status
01900 TMR_LLRP_prepareTagFilter(LLRP_tSInventoryParameterSpec *ipSpec, 
01901                           TMR_TagProtocol protocol, const TMR_TagFilter *filter)
01902 {
01903   TMR_Status ret;
01904   LLRP_tSAntennaConfiguration   *pAntConfig;
01905 
01906   ret = TMR_SUCCESS;
01907 
01908   /* Initialize antenna configuration */
01909   pAntConfig     = LLRP_AntennaConfiguration_construct();
01910 
01911   /* Add C1G2Filter */
01912   if (TMR_TAG_PROTOCOL_GEN2 == protocol)
01913   { 
01914     LLRP_tSC1G2Filter             *pFilter;
01915     LLRP_tSC1G2TagInventoryMask   *pMask;
01916     LLRP_tSC1G2InventoryCommand   *pInvCommand;
01917     LLRP_tSC1G2TagInventoryStateUnawareFilterAction
01918                                   *pUnawareAction;
01919 
01920     /* Initialize */
01921     pFilter        = LLRP_C1G2Filter_construct();
01922     pMask          = LLRP_C1G2TagInventoryMask_construct();
01923     pInvCommand    = LLRP_C1G2InventoryCommand_construct();
01924     pUnawareAction = LLRP_C1G2TagInventoryStateUnawareFilterAction_construct();
01925 
01926     /* Set antenna id to antConfig (all antennas) */
01927     pAntConfig->AntennaID = 0;
01928 
01929     /* Set TagInventoryStateAwareAction to false */
01930     pInvCommand->TagInventoryStateAware = false;
01931 
01932     /* Set TagInventory StateUnaware Action */
01933     LLRP_C1G2TagInventoryStateUnawareFilterAction_setAction(pUnawareAction,
01934                                 LLRP_C1G2StateUnawareAction_Select_Unselect);
01935 
01939     if (TMR_FILTER_TYPE_GEN2_SELECT == filter->type)
01940     {
01941       const TMR_GEN2_Select *fp;
01942       llrp_u1v_t  tmpMask;
01943       fp = &filter->u.gen2Select;
01944 
01948       /* Set Memory bank */
01949       LLRP_C1G2TagInventoryMask_setMB(pMask, fp->bank);
01950 
01951       /* Set tag mask */
01952       tmpMask = LLRP_u1v_construct(fp->maskBitLength);
01953       memcpy(tmpMask.pValue, fp->mask, fp->maskBitLength / 8);
01954       LLRP_C1G2TagInventoryMask_setTagMask(pMask, tmpMask);
01955 
01956       /* Set bit Pointer */
01957       LLRP_C1G2TagInventoryMask_setPointer(pMask, fp->bitPointer);
01958 
01959       if(fp->invert)
01960       {
01961         /* If invert is set true, Unselect matched and select unmatched */
01962         LLRP_C1G2TagInventoryStateUnawareFilterAction_setAction(pUnawareAction, 
01963                                 LLRP_C1G2StateUnawareAction_Unselect_Select);
01964       }
01965     }
01969     else if (TMR_FILTER_TYPE_TAG_DATA == filter->type)
01970     {
01971       const TMR_TagData *fp;
01972       llrp_u1v_t  tmpMask;
01973       fp = &filter->u.tagData;
01974 
01978       /* Set Memory bank to EPC always, in case of TagData */
01979       LLRP_C1G2TagInventoryMask_setMB(pMask, TMR_GEN2_BANK_EPC);
01980 
01981       /* Set tag mask */
01982       tmpMask = LLRP_u1v_construct(fp->epcByteCount * 8);
01983       memcpy(tmpMask.pValue, fp->epc, fp->epcByteCount);
01984       LLRP_C1G2TagInventoryMask_setTagMask(pMask, tmpMask);
01985 
01990       LLRP_C1G2TagInventoryMask_setPointer(pMask, 32);
01991     }
01995     else
01996     {
01997       return TMR_ERROR_INVALID;
01998     }
01999 
02000     /* Set mask to filter */
02001     LLRP_C1G2Filter_setC1G2TagInventoryMask(pFilter, pMask);
02002 
02003     /* Set InventoryStateUnawareFilter Action to filter */
02004     LLRP_C1G2Filter_setC1G2TagInventoryStateUnawareFilterAction(pFilter, pUnawareAction);
02005 
02006     /* Add filter to InventoryCommand */
02007     LLRP_C1G2InventoryCommand_addC1G2Filter(pInvCommand, pFilter);
02008 
02009     /* Add InvCommand to antenna configuration */
02010     LLRP_AntennaConfiguration_addAirProtocolInventoryCommandSettings(pAntConfig,
02011                                             (LLRP_tSParameter *)pInvCommand);
02012   }
02013   else
02014   {
02015     if (TMR_TAG_PROTOCOL_ISO180006B == protocol)
02016     {
02017 
02018 #ifdef TMR_ENABLE_ISO180006B
02019 
02020       LLRP_tSThingMagicISO180006BInventoryCommand   *pTMISOInventory;
02021       LLRP_tSThingMagicISO180006BTagPattern         *pTMISOTagPattern;
02022 
02023       /* initialize  the TM inventory commmand */
02024       pTMISOInventory = LLRP_ThingMagicISO180006BInventoryCommand_construct();
02025 
02026       /* initialize  the  TM tagpattern */
02027       pTMISOTagPattern = LLRP_ThingMagicISO180006BTagPattern_construct();
02028 
02032       if (TMR_FILTER_TYPE_ISO180006B_SELECT == filter->type)
02033       {
02034         const TMR_ISO180006B_Select *fp;
02035         llrp_u2_t   selectOp;
02036         llrp_u8v_t  tmpMask;
02037 
02038         fp = &filter->u.iso180006bSelect;
02039 
02040         /* Initialize the filter type */
02041         LLRP_ThingMagicISO180006BTagPattern_setFilterType(pTMISOTagPattern,
02042             LLRP_ThingMagicISO180006BFilterType_ISO180006BSelect);
02043 
02044         /* Initialize the select tag op */
02045         selectOp = fp->op;
02046         LLRP_ThingMagicISO180006BTagPattern_setSelectOp(pTMISOTagPattern, selectOp);
02047 
02048         /* set address of tag memory */
02049         LLRP_ThingMagicISO180006BTagPattern_setAddress(pTMISOTagPattern, fp->address);
02050 
02051         /* set the tag mask */
02052         LLRP_ThingMagicISO180006BTagPattern_setMask(pTMISOTagPattern, fp->mask);
02053 
02054         /* set the data to compare */
02055         /* In case of iso the data length must be eight */ 
02056         tmpMask = LLRP_u8v_construct((llrp_u16_t)(sizeof(fp->data))/(sizeof(fp->data[0])));
02057         memcpy(tmpMask.pValue, fp->data, tmpMask.nValue);
02058         LLRP_ThingMagicISO180006BTagPattern_setTagData(pTMISOTagPattern, tmpMask);
02059 
02060         /* set the selct action */
02061         LLRP_ThingMagicISO180006BTagPattern_setInvert(pTMISOTagPattern, (llrp_u1_t)fp->invert);
02062 
02063         /* Add TagPattern to the TM ISOInventory */
02064         LLRP_ThingMagicISO180006BInventoryCommand_setThingMagicISO180006BTagPattern(pTMISOInventory, pTMISOTagPattern);
02065 
02066         /* Add InvCommand to antenna configuration */
02067         LLRP_AntennaConfiguration_addAirProtocolInventoryCommandSettings(pAntConfig,
02068             (LLRP_tSParameter *)pTMISOInventory);
02069 
02070       }
02074       else if(TMR_FILTER_TYPE_TAG_DATA == filter->type)
02075       {
02076         const TMR_TagData *fp;
02077         llrp_u8v_t  tmpMask;
02078 
02079         /* Initialize the filter type */
02080         LLRP_ThingMagicISO180006BTagPattern_setFilterType(pTMISOTagPattern,
02081             LLRP_ThingMagicISO180006BFilterType_ISO180006BTagData);
02082 
02083         fp = &filter->u.tagData;
02084         /* Initialize the select tag op */
02085         /* Set the Select op as TMR_ISO180006B_SELECT_OP_EQUALS 
02086          * in case of TagData
02087          */
02088         LLRP_ThingMagicISO180006BTagPattern_setSelectOp(pTMISOTagPattern, (llrp_u2_t) TMR_ISO180006B_SELECT_OP_EQUALS);
02089         /* Set the tag memory address to Zero , in case of TagData */
02090         LLRP_ThingMagicISO180006BTagPattern_setAddress(pTMISOTagPattern, (llrp_u8_t)0);
02091         /* Set the mask to 0xff, in case TagData */
02092         LLRP_ThingMagicISO180006BTagPattern_setMask(pTMISOTagPattern, (llrp_u8_t)0xFF);
02093 
02094         /* set the data to compare */
02095         /* In case of iso the data length must be eight */
02096         tmpMask = LLRP_u8v_construct((llrp_u16_t)fp->epcByteCount);
02097         memcpy(tmpMask.pValue, fp->epc, tmpMask.nValue);
02098         LLRP_ThingMagicISO180006BTagPattern_setTagData(pTMISOTagPattern, tmpMask);
02099 
02100         /* Set the select action false, in case of TagData */
02101         LLRP_ThingMagicISO180006BTagPattern_setInvert(pTMISOTagPattern, (llrp_u1_t)false);
02102 
02103         /* Add TagPattern to the TM ISOInventory */
02104         LLRP_ThingMagicISO180006BInventoryCommand_setThingMagicISO180006BTagPattern(pTMISOInventory, pTMISOTagPattern);
02105 
02106         /* Add InvCommand to antenna configuration */
02107         LLRP_AntennaConfiguration_addAirProtocolInventoryCommandSettings(pAntConfig,
02108             (LLRP_tSParameter *)pTMISOInventory);
02109 
02110       }
02111       else
02112       {
02113     return TMR_ERROR_INVALID;
02114   }
02115 #endif /* TMR_ENABLE_ISO180006B */
02116     }
02117     else
02118     {
02119       /* Unsuppoerd Protocol */
02120       return TMR_ERROR_INVALID;
02121     }
02122   }
02123 
02124   /* Finally, Add antenna configuration to InventoryParameterSpec */
02125   LLRP_InventoryParameterSpec_addAntennaConfiguration(ipSpec, pAntConfig);
02126   return ret;
02127 }
02128 
02133 TMR_Status
02134 TMR_LLRP_addFastSearch(LLRP_tSInventoryParameterSpec *ipSpec, bool fastSearch)
02135 {
02136   TMR_Status ret;
02137   LLRP_tSThingMagicFastSearchMode *pFastSearch;
02138   LLRP_tSC1G2InventoryCommand     *pInvCommand;
02139   LLRP_tSAntennaConfiguration     *pAntConfig;
02140 
02141   ret = TMR_SUCCESS;
02142 
02143   /* Initialize antenna configuration */
02144   pAntConfig     = LLRP_AntennaConfiguration_construct();
02145   pFastSearch = LLRP_ThingMagicFastSearchMode_construct();
02146   pInvCommand    = LLRP_C1G2InventoryCommand_construct();
02147 
02148   LLRP_ThingMagicFastSearchMode_setThingMagicFastSearch(pFastSearch,
02149       (LLRP_tEThingMagicFastSearchValue)fastSearch);
02150 
02151   /* Add FastSearch to InventoryCommand */
02152   LLRP_C1G2InventoryCommand_addCustom (pInvCommand,
02153       (LLRP_tSParameter *)pFastSearch); 
02154 
02155   /* Add InvCommand to antenna configuration */
02156   LLRP_AntennaConfiguration_addAirProtocolInventoryCommandSettings(pAntConfig,
02157       (LLRP_tSParameter *)pInvCommand);
02158 
02159   /* Finally, Add antenna configuration to InventoryParameterSpec */
02160   LLRP_InventoryParameterSpec_addAntennaConfiguration(ipSpec, pAntConfig);
02161 
02162   return ret;
02163 }
02164 
02174 TMR_Status
02175 TMR_LLRP_cmdAddROSpec(TMR_Reader *reader, uint16_t readDuration,
02176                                   TMR_uint8List *antennaList,
02177                                   const TMR_TagFilter *filter,
02178                                   TMR_TagProtocol protocol)
02179 {
02180   TMR_Status ret;
02181   LLRP_tSADD_ROSPEC               *pCmd;
02182   LLRP_tSMessage                  *pCmdMsg;
02183   LLRP_tSMessage                  *pRspMsg;
02184   LLRP_tSADD_ROSPEC_RESPONSE      *pRsp;
02185 
02186   LLRP_tSROSpec                   *pROSpec;
02187   LLRP_tSROSpecStartTrigger       *pROSpecStartTrigger;
02188   LLRP_tSROSpecStopTrigger        *pROSpecStopTrigger;
02189   LLRP_tSROBoundarySpec           *pROBoundarySpec;
02190   LLRP_tSAISpecStopTrigger        *pAISpecStopTrigger;
02191   LLRP_tSInventoryParameterSpec   *pInventoryParameterSpec;
02192   LLRP_tSAISpec                   *pAISpec;
02193   LLRP_tSTagReportContentSelector *pTagReportContentSelector;
02194   LLRP_tSROReportSpec             *pROReportSpec;
02195 
02196   llrp_u16v_t                     AntennaIDs;
02197   int                             i;
02198 
02199   ret = TMR_SUCCESS;
02200 
02204   pCmd = LLRP_ADD_ROSPEC_construct();
02220   /* Construct ROSpec message */
02221   pROSpec = LLRP_ROSpec_construct();
02222   {
02223     /* 1. Set ROSpec id */
02224     LLRP_ROSpec_setROSpecID(pROSpec, reader->u.llrpReader.roSpecId);
02225 
02226     /* 2. Set priority  */
02227     LLRP_ROSpec_setPriority(pROSpec, 0);
02228 
02229     /* 3. Set current State */
02230     LLRP_ROSpec_setCurrentState(pROSpec, LLRP_ROSpecState_Disabled);
02231 
02232 
02236     {
02237       pROBoundarySpec = LLRP_ROBoundarySpec_construct();
02238 
02239       /* Initialize ROSpec start trigger */
02240       pROSpecStartTrigger = LLRP_ROSpecStartTrigger_construct();
02241  
02242       if ((true == reader->continuousReading) &&
02243            (TMR_READ_PLAN_TYPE_MULTI == reader->readParams.readPlan->type))
02244       {
02245 #ifdef TMR_ENABLE_BACKGROUND_READS
02246 
02255         LLRP_tSPeriodicTriggerValue *pPeriod;
02256 
02257         LLRP_ROSpecStartTrigger_setROSpecStartTriggerType(pROSpecStartTrigger,
02258                                         LLRP_ROSpecStartTriggerType_Periodic);
02259 
02263         pPeriod = LLRP_PeriodicTriggerValue_construct();
02269         pPeriod->Period = reader->readParams.asyncOnTime;
02270         LLRP_ROSpecStartTrigger_setPeriodicTriggerValue(pROSpecStartTrigger, pPeriod);
02271 #endif
02272       }
02273       else
02274       {
02278         LLRP_ROSpecStartTrigger_setROSpecStartTriggerType(pROSpecStartTrigger, 
02279                                               LLRP_ROSpecStartTriggerType_Null);
02280       }
02281 
02282       /* Initialize ROSpec stop trigger */
02283       pROSpecStopTrigger = LLRP_ROSpecStopTrigger_construct();
02284       LLRP_ROSpecStopTrigger_setROSpecStopTriggerType(pROSpecStopTrigger, LLRP_ROSpecStopTriggerType_Null);
02285 
02286       /* Set start and stop triggers to BoundarySpec */
02287       LLRP_ROBoundarySpec_setROSpecStartTrigger(pROBoundarySpec, pROSpecStartTrigger);
02288       LLRP_ROBoundarySpec_setROSpecStopTrigger(pROBoundarySpec, pROSpecStopTrigger);
02289 
02290       /* Set ROBoundarySpec to ROSpec  */
02291       LLRP_ROSpec_setROBoundarySpec(pROSpec, pROBoundarySpec);
02292     }
02293 
02294 
02298     {
02299       pAISpec = LLRP_AISpec_construct();
02300 
02301       /* Initialize AISpec stop trigger  */
02302       pAISpecStopTrigger = LLRP_AISpecStopTrigger_construct();
02303 
02304       if ((true == reader->continuousReading) &&
02305           (TMR_READ_PLAN_TYPE_SIMPLE == reader->readParams.readPlan->type))
02306       {
02312         LLRP_AISpecStopTrigger_setAISpecStopTriggerType(pAISpecStopTrigger, LLRP_AISpecStopTriggerType_Null);
02313         LLRP_AISpecStopTrigger_setDurationTrigger(pAISpecStopTrigger, 0);
02314       }
02315       else
02316       {
02321         LLRP_AISpecStopTrigger_setAISpecStopTriggerType(pAISpecStopTrigger, LLRP_AISpecStopTriggerType_Duration);
02322         LLRP_AISpecStopTrigger_setDurationTrigger(pAISpecStopTrigger, readDuration);
02323       }
02324 
02325       /* Set AISpec stop trigger */
02326       LLRP_AISpec_setAISpecStopTrigger(pAISpec, pAISpecStopTrigger);
02327 
02328       /* set antenna ids to aispec */
02329       {
02330         AntennaIDs = LLRP_u16v_construct(TMR_SR_MAX_ANTENNA_PORTS);
02331         AntennaIDs.nValue = 0;
02332 
02333         if (NULL != antennaList->list)
02334         {
02339           if (TMR_SR_MAX_ANTENNA_PORTS < antennaList->len)
02340           {
02341             antennaList->len = TMR_SR_MAX_ANTENNA_PORTS;
02342           }
02343 
02344           for (i = 0; i < antennaList->len; i++)
02345           {
02346             AntennaIDs.pValue[i] = antennaList->list[i];
02347             AntennaIDs.nValue ++;
02348           }
02349         }
02350         else
02351         {
02356           AntennaIDs.pValue[0] = 0;
02357           AntennaIDs.nValue    = 1;
02358         }
02359 
02360         LLRP_AISpec_setAntennaIDs(pAISpec, AntennaIDs);
02361       }
02362 
02367       pInventoryParameterSpec = LLRP_InventoryParameterSpec_construct();
02368 
02369       /* Set protocol */
02370       if (TMR_TAG_PROTOCOL_GEN2 == protocol)
02371       {
02372         LLRP_InventoryParameterSpec_setProtocolID(pInventoryParameterSpec, LLRP_AirProtocols_EPCGlobalClass1Gen2);
02373       }
02374 #ifdef TMR_ENABLE_ISO180006B
02375       else if (TMR_TAG_PROTOCOL_ISO180006B == protocol)
02376         {
02377           /* For other protocol specify the Inventory Parameter protocol ID as unspecified */
02378           LLRP_InventoryParameterSpec_setProtocolID(pInventoryParameterSpec, LLRP_AirProtocols_Unspecified);
02379           LLRP_tSThingMagicCustomAirProtocols *pInventoryParameterCustom;
02380           pInventoryParameterCustom = LLRP_ThingMagicCustomAirProtocols_construct();
02381           LLRP_ThingMagicCustomAirProtocols_setcustomProtocolId(pInventoryParameterCustom,
02382               LLRP_ThingMagicCustomAirProtocolList_Iso180006b);
02383 
02384           /* add this as a custom parameter to InventoryParameterSpec */
02385           LLRP_InventoryParameterSpec_addCustom(pInventoryParameterSpec, (LLRP_tSParameter *)pInventoryParameterCustom);
02386         }
02387 #endif /* TMR_ENABLE_ISO180006B */
02388       else if(TMR_TAG_PROTOCOL_ATA == protocol)
02389       {
02390         /* For other protocol specify the Inventory Parameter protocol ID as unspecified */
02391         LLRP_InventoryParameterSpec_setProtocolID(pInventoryParameterSpec, LLRP_AirProtocols_Unspecified);
02392         LLRP_tSThingMagicCustomAirProtocols *pInventoryParameterCustom;
02393         pInventoryParameterCustom = LLRP_ThingMagicCustomAirProtocols_construct();
02394         LLRP_ThingMagicCustomAirProtocols_setcustomProtocolId(pInventoryParameterCustom,
02395             LLRP_ThingMagicCustomAirProtocolList_Ata);
02396 
02397         /* add this as a custom parameter to InventoryParameterSpec */
02398         LLRP_InventoryParameterSpec_addCustom(pInventoryParameterSpec, (LLRP_tSParameter *)pInventoryParameterCustom);
02399       }
02400       else if(TMR_TAG_PROTOCOL_IPX64 == protocol)
02401       {
02402         /* For other protocol specify the Inventory Parameter protocol ID as unspecified */
02403         LLRP_InventoryParameterSpec_setProtocolID(pInventoryParameterSpec, LLRP_AirProtocols_Unspecified);
02404         LLRP_tSThingMagicCustomAirProtocols *pInventoryParameterCustom;
02405         pInventoryParameterCustom = LLRP_ThingMagicCustomAirProtocols_construct();
02406         LLRP_ThingMagicCustomAirProtocols_setcustomProtocolId(pInventoryParameterCustom,
02407             LLRP_ThingMagicCustomAirProtocolList_IPX64);
02408 
02409         /* add this as a custom parameter to InventoryParameterSpec */
02410         LLRP_InventoryParameterSpec_addCustom(pInventoryParameterSpec, (LLRP_tSParameter *)pInventoryParameterCustom);
02411       }
02412       else if(TMR_TAG_PROTOCOL_IPX256 == protocol)
02413       {
02414         /* For other protocol specify the Inventory Parameter protocol ID as unspecified */
02415         LLRP_InventoryParameterSpec_setProtocolID(pInventoryParameterSpec, LLRP_AirProtocols_Unspecified);
02416         LLRP_tSThingMagicCustomAirProtocols *pInventoryParameterCustom;
02417         pInventoryParameterCustom = LLRP_ThingMagicCustomAirProtocols_construct();
02418         LLRP_ThingMagicCustomAirProtocols_setcustomProtocolId(pInventoryParameterCustom,
02419             LLRP_ThingMagicCustomAirProtocolList_IPX256);
02420 
02421         /* add this as a custom parameter to InventoryParameterSpec */
02422         LLRP_InventoryParameterSpec_addCustom(pInventoryParameterSpec, (LLRP_tSParameter *)pInventoryParameterCustom);
02423       }
02424       else
02425       {
02426         return TMR_ERROR_UNIMPLEMENTED_FEATURE;
02427       }
02428 
02429       /* Set InventoryParameterSpec id */
02430       LLRP_InventoryParameterSpec_setInventoryParameterSpecID(pInventoryParameterSpec, 1);
02431 
02435       if (NULL != filter)
02436       {
02437         ret = TMR_LLRP_prepareTagFilter(pInventoryParameterSpec, protocol, filter);
02438         if (TMR_SUCCESS != ret)
02439         {
02440           return ret;
02441         }
02442       }
02443 
02448       if (reader->fastSearch)
02449       {
02450         ret = TMR_LLRP_addFastSearch(pInventoryParameterSpec, reader->fastSearch);
02451         if (TMR_SUCCESS != ret)
02452         {
02453           return ret;
02454         }
02455       }
02456 
02457       /* Add InventoryParameterSpec to AISpec */
02458       LLRP_AISpec_addInventoryParameterSpec(pAISpec, pInventoryParameterSpec);
02459 
02460       /* Now AISpec is fully framed and add it to ROSpec Parameter list */
02461       LLRP_ROSpec_addSpecParameter(pROSpec, (LLRP_tSParameter *)pAISpec);
02462     }
02463 
02467     {
02468       pROReportSpec = LLRP_ROReportSpec_construct();
02469 
02470       /* Set ROReportSpecTrigger type  */
02471       LLRP_ROReportSpec_setROReportTrigger(pROReportSpec, LLRP_ROReportTriggerType_Upon_N_Tags_Or_End_Of_ROSpec);
02472       
02473       if (reader->continuousReading)
02474       {
02481         LLRP_ROReportSpec_setN(pROReportSpec, 1);
02482       }
02483       else
02484       {
02489         LLRP_ROReportSpec_setN(pROReportSpec, 0);
02490       }
02491 
02492       /* Initialize and Set ReportContent selection */
02493       pTagReportContentSelector = LLRP_TagReportContentSelector_construct();
02494 
02495       pTagReportContentSelector->EnableROSpecID                 = 1;
02496       pTagReportContentSelector->EnableSpecIndex                = 1;
02497       pTagReportContentSelector->EnableInventoryParameterSpecID = 1;
02498       pTagReportContentSelector->EnableAntennaID                = 1;
02499       pTagReportContentSelector->EnableChannelIndex             = 1;
02500       pTagReportContentSelector->EnablePeakRSSI                 = 1;
02501       pTagReportContentSelector->EnableFirstSeenTimestamp       = 1;
02502       pTagReportContentSelector->EnableLastSeenTimestamp        = 1;
02503       pTagReportContentSelector->EnableTagSeenCount             = 1;
02504       pTagReportContentSelector->EnableAccessSpecID             = 1;
02505 
02506       if (TMR_TAG_PROTOCOL_GEN2 == protocol)
02507       {
02511         LLRP_tSC1G2EPCMemorySelector *pGen2MemSelector;
02512 
02513         pGen2MemSelector = LLRP_C1G2EPCMemorySelector_construct();
02514         LLRP_C1G2EPCMemorySelector_setEnableCRC(pGen2MemSelector, 1);
02515         LLRP_C1G2EPCMemorySelector_setEnablePCBits(pGen2MemSelector, 1);
02516 
02517         /* Add C1G2MemorySelector to ReportContentSelector  */
02518         LLRP_TagReportContentSelector_addAirProtocolEPCMemorySelector(
02519             pTagReportContentSelector, (LLRP_tSParameter *)pGen2MemSelector);
02520 
02521       }
02522 
02523       LLRP_ROReportSpec_setTagReportContentSelector(pROReportSpec, pTagReportContentSelector);
02528       if (((atoi(&reader->u.llrpReader.capabilities.softwareVersion[0]) == 4) 
02529             && (atoi(&reader->u.llrpReader.capabilities.softwareVersion[2]) >= 17))
02530           || (atoi(&reader->u.llrpReader.capabilities.softwareVersion[0]) > 4))
02531       {
02532         LLRP_tSThingMagicTagReportContentSelector *pTMTagReportContentSelector;
02533 
02534         /* Initialize and Set the ThingMagicReportContentSelector */
02535         pTMTagReportContentSelector = LLRP_ThingMagicTagReportContentSelector_construct();
02536 
02537         /* Set the phase angel mode */
02538         LLRP_ThingMagicTagReportContentSelector_setPhaseMode(
02539             pTMTagReportContentSelector, (LLRP_tEThingMagicPhaseMode)
02540             LLRP_ThingMagicPhaseMode_Enabled);
02541 
02546         LLRP_ROReportSpec_addCustom(pROReportSpec, (LLRP_tSParameter *)pTMTagReportContentSelector);
02547       }
02548 
02549       /* Now ROReportSpec is fully framed and set it to ROSpec */
02550       LLRP_ROSpec_setROReportSpec(pROSpec, pROReportSpec);
02551     }
02552   }
02553 
02554   /* Now ROSpec is fully framed, add to AddROSpec */
02555   LLRP_ADD_ROSPEC_setROSpec(pCmd, pROSpec);
02556 
02557   pCmdMsg = &pCmd->hdr;
02561   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
02566   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
02567   if (TMR_SUCCESS != ret)
02568   {
02569     return ret;
02570   }
02571 
02575   pRsp = (LLRP_tSADD_ROSPEC_RESPONSE *) pRspMsg;
02576   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
02577   {
02578     TMR_LLRP_freeMessage(pRspMsg);
02579     return TMR_ERROR_LLRP; 
02580   }
02581 
02585   TMR_LLRP_freeMessage(pRspMsg);
02586 
02587   return ret;
02588 }
02589 
02595 TMR_Status
02596 TMR_LLRP_cmdEnableROSpec(TMR_Reader *reader)
02597 {
02598   TMR_Status ret;
02599   LLRP_tSENABLE_ROSPEC          *pCmd;
02600   LLRP_tSMessage                *pCmdMsg;
02601   LLRP_tSMessage                *pRspMsg;
02602   LLRP_tSENABLE_ROSPEC_RESPONSE *pRsp;
02603   
02604   ret = TMR_SUCCESS;
02605 
02609   pCmd = LLRP_ENABLE_ROSPEC_construct();
02610   LLRP_ENABLE_ROSPEC_setROSpecID(pCmd, reader->u.llrpReader.roSpecId);
02611 
02612   pCmdMsg = &pCmd->hdr;
02616   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
02621   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
02622   if (TMR_SUCCESS != ret)
02623   {
02624     return ret;
02625   }
02626 
02630   pRsp = (LLRP_tSENABLE_ROSPEC_RESPONSE *) pRspMsg;
02631   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
02632   {
02633     TMR_LLRP_freeMessage(pRspMsg);
02634     return TMR_ERROR_LLRP; 
02635   }
02636 
02640   TMR_LLRP_freeMessage(pRspMsg);
02641 
02642   return ret;
02643 }
02644 TMR_Status
02645 TMR_LLRP_cmdDisableROSpec(TMR_Reader *reader)
02646 {
02647   TMR_Status ret;
02648   LLRP_tSDISABLE_ROSPEC          *pCmd;
02649   LLRP_tSMessage                *pCmdMsg;
02650   LLRP_tSMessage                *pRspMsg;
02651   LLRP_tSDISABLE_ROSPEC_RESPONSE *pRsp;
02652   
02653   ret = TMR_SUCCESS;
02654 
02658   pCmd = LLRP_DISABLE_ROSPEC_construct();
02659   LLRP_DISABLE_ROSPEC_setROSpecID(pCmd, reader->u.llrpReader.roSpecId);
02660 
02661   pCmdMsg = &pCmd->hdr;
02665   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
02670   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
02671   if (TMR_SUCCESS != ret)
02672   {
02673     return ret;
02674   }
02675 
02679   pRsp = (LLRP_tSDISABLE_ROSPEC_RESPONSE *) pRspMsg;
02680   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
02681   {
02682     TMR_LLRP_freeMessage(pRspMsg);
02683     return TMR_ERROR_LLRP; 
02684   }
02685 
02689   TMR_LLRP_freeMessage(pRspMsg);
02690 
02691   return ret;
02692 }
02693 
02699 TMR_Status
02700 TMR_LLRP_cmdStartROSpec(TMR_Reader *reader, llrp_u32_t roSpecId)
02701 {
02702   TMR_Status ret;
02703   LLRP_tSSTART_ROSPEC           *pCmd;
02704   LLRP_tSMessage                *pCmdMsg;
02705   LLRP_tSMessage                *pRspMsg;
02706   LLRP_tSSTART_ROSPEC_RESPONSE  *pRsp;
02707   
02708   ret = TMR_SUCCESS;
02709 
02713   pCmd = LLRP_START_ROSPEC_construct();
02714   LLRP_START_ROSPEC_setROSpecID(pCmd, roSpecId);
02715 
02716   pCmdMsg = &pCmd->hdr;
02720   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
02725   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
02726   if (TMR_SUCCESS != ret)
02727   {
02728     return ret;
02729   }
02730 
02734   pRsp = (LLRP_tSSTART_ROSPEC_RESPONSE *) pRspMsg;
02735   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
02736   {
02737     TMR_LLRP_freeMessage(pRspMsg);
02738     return TMR_ERROR_LLRP; 
02739   }
02740 
02744   TMR_LLRP_freeMessage(pRspMsg);
02745 
02746   return ret;
02747 }
02748 
02757 TMR_Status
02758 TMR_LLRP_cmdStopROSpec(TMR_Reader *reader, bool receiveResponse)
02759 {
02760   TMR_Status ret;
02761   LLRP_tSSTOP_ROSPEC            *pCmd;
02762   LLRP_tSMessage                *pCmdMsg;
02763   LLRP_tSMessage                *pRspMsg;
02764   LLRP_tSSTOP_ROSPEC_RESPONSE   *pRsp;
02765 
02766   ret = TMR_SUCCESS;
02767 
02771   pCmd = LLRP_STOP_ROSPEC_construct();
02772   LLRP_STOP_ROSPEC_setROSpecID(pCmd, reader->u.llrpReader.roSpecId);
02773 
02774   pCmdMsg = &pCmd->hdr;
02778   if (false == receiveResponse)
02779   {
02780     ret = TMR_LLRP_sendMessage(reader, pCmdMsg, reader->u.llrpReader.transportTimeout);
02784     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
02785   }
02786   else
02787   {
02788     ret = TMR_LLRP_sendTimeout(reader, pCmdMsg, &pRspMsg,
02789                                TMR_LLRP_STOP_TIMEOUT
02790                                + reader->u.llrpReader.commandTimeout
02791                                + reader->u.llrpReader.transportTimeout);
02792 
02797     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
02798   if (TMR_SUCCESS != ret)
02799   {
02800     return ret;
02801   }
02802 
02806   pRsp = (LLRP_tSSTOP_ROSPEC_RESPONSE *) pRspMsg;
02807     if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
02808   {
02809     TMR_LLRP_freeMessage(pRspMsg);
02810       return TMR_ERROR_LLRP;
02811   }
02812 
02816   TMR_LLRP_freeMessage(pRspMsg);
02817   }
02818 
02819   return ret;
02820 }
02821 
02835 TMR_Status 
02836 TMR_LLRP_cmdPrepareROSpec(TMR_Reader *reader, uint16_t timeout,
02837                             TMR_uint8List *antennaList,
02838                             const TMR_TagFilter *filter, 
02839                             TMR_TagProtocol protocol)
02840 {
02841   TMR_Status ret;
02842   
02843   ret = TMR_SUCCESS;
02844 
02853   ret = TMR_LLRP_cmdAddROSpec(reader, timeout, antennaList, filter, protocol);
02854   if (TMR_SUCCESS != ret)
02855   {
02856     return ret;
02857   }
02858 
02862   return TMR_LLRP_cmdEnableROSpec(reader);
02863 }
02864 
02865 TMR_Status
02866 TMR_LLRP_verifyReadOperation(TMR_Reader *reader, int32_t *tagCount)
02867 {
02868   LLRP_tSTagReportData    *pTagReportData;
02869   LLRP_tSRO_ACCESS_REPORT *pReport;
02870   TMR_LLRP_LlrpReader *lr;
02871   uint32_t count, i;
02872 
02873   lr = &reader->u.llrpReader;
02878   while (true)
02879   {
02880     pthread_mutex_lock(&lr->receiverLock);
02881     while(lr->numOfROSpecEvents > 0 ) {
02882       pthread_cond_wait(&lr->receiverCond, &lr->receiverLock);
02883     }
02884     if (0 >= lr->numOfROSpecEvents)
02885   {
02886       /* We have received all ROSpec events */
02887       if (-1 == lr->numOfROSpecEvents)
02888     {
02889       pthread_mutex_unlock(&lr->receiverLock);
02890         return TMR_ERROR_LLRP_READER_CONNECTION_LOST;
02891     }
02892       pthread_mutex_unlock(&lr->receiverLock);
02893       break;
02894   }
02895     pthread_mutex_unlock(&lr->receiverLock);
02896 
02897     /* Wait until all rospec events arrive */
02898   }
02899 
02900   for (i = 0; i < lr->bufPointer; i ++)
02901   {
02902     pReport = (LLRP_tSRO_ACCESS_REPORT *)lr->bufResponse[i];
02903     if (NULL == pReport)
02904     {
02909       continue;
02910     }
02911 
02912     count = 0;
02916       for(pTagReportData = pReport->listTagReportData;
02917           NULL != pTagReportData;
02918           pTagReportData = (LLRP_tSTagReportData *)pTagReportData->hdr.pNextSubParameter)
02919       {
02920         count ++;
02921       }
02922 
02923     lr->tagsRemaining += count;
02924       if (NULL != tagCount)
02925       {
02926         *tagCount += count;
02927       }
02928     }
02929 
02930   return TMR_SUCCESS;
02931 }
02932 
02942 TMR_Status
02943 TMR_LLRP_parseMetadataFromMessage(TMR_Reader *reader, TMR_TagReadData *data, LLRP_tSTagReportData *pTagReportData)
02944 {
02945   TMR_Status ret;
02946   LLRP_tSParameter *pEPC;
02947   llrp_u16_t        ChannelIndex;
02948 
02949   ret = TMR_SUCCESS;
02950 
02951   if (NULL != pTagReportData)
02952   {
02953     if(NULL != pTagReportData->pEPCParameter)
02954     {
02959       pEPC = pTagReportData->pEPCParameter;
02960       if (&LLRP_tdEPCData == pEPC->elementHdr.pType)
02961       {
02965         LLRP_tSEPCData *pEPCData = (LLRP_tSEPCData *)pEPC;
02966       data->tag.epcByteCount = (pEPCData->EPC.nBit + 7u) / 8u;
02967       memcpy(data->tag.epc, pEPCData->EPC.pValue, data->tag.epcByteCount);
02968     }
02969       else
02970       {
02975         LLRP_tSEPC_96 *pEPC_96 = (LLRP_tSEPC_96 *)pEPC;
02976         data->tag.epcByteCount = 12;
02977         memcpy(data->tag.epc, pEPC_96->EPC.aValue, data->tag.epcByteCount);
02978       }
02979     }
02980 
02984     llrp_u64_t msSinceEpoch = (pTagReportData->pLastSeenTimestampUTC->Microseconds)/1000;
02985     data->dspMicros = (msSinceEpoch % 1000);
02986     data->timestampHigh = (msSinceEpoch>>32) & 0xFFFFFFFF;
02987     data->timestampLow  = (msSinceEpoch>> 0) & 0xFFFFFFFF;
02988     data->metadataFlags |= TMR_TRD_METADATA_FLAG_TIMESTAMP;
02989 
02995     data->antenna = pTagReportData->pAntennaID->AntennaID;
02996     data->metadataFlags |= TMR_TRD_METADATA_FLAG_ANTENNAID;
02997     data->readCount = pTagReportData->pTagSeenCount->TagCount;
02998     data->metadataFlags |= TMR_TRD_METADATA_FLAG_READCOUNT;
02999     data->rssi = pTagReportData->pPeakRSSI->PeakRSSI;
03000     data->metadataFlags |= TMR_TRD_METADATA_FLAG_RSSI;
03001 
03006     ChannelIndex = pTagReportData->pChannelIndex->ChannelIndex;
03007     /* as for llrp the indexing always starts with one
03008      * but in api indexing always starts with zero
03009      * so, decrementing the index
03010      */
03011     if (NULL != reader->u.llrpReader.capabilities.freqTable.list)
03012     {
03013     data->frequency = reader->u.llrpReader.capabilities.freqTable.list[ChannelIndex - 1];
03014     data->metadataFlags |= TMR_TRD_METADATA_FLAG_FREQUENCY;
03015     }
03016 
03022     {
03027       int protocolindex;
03028       for (protocolindex = 0; protocolindex <= pTagReportData->pROSpecID->ROSpecID; protocolindex++)
03029       {
03030         if (protocolindex == pTagReportData->pROSpecID->ROSpecID)
03031           data->tag.protocol = reader->u.llrpReader.readPlanProtocol[protocolindex].rospecProtocol;
03032       }
03033     }
03034     data->metadataFlags |= TMR_TRD_METADATA_FLAG_PROTOCOL;
03035 
03036     if (TMR_TAG_PROTOCOL_GEN2 == data->tag.protocol)
03037     {
03038       LLRP_tSParameter *pParameter;
03039 
03043       for(pParameter = pTagReportData->listAirProtocolTagData;
03044           NULL != pParameter;
03045           pParameter = (LLRP_tSParameter *)pParameter->pNextSubParameter)
03046       {
03047         if (&LLRP_tdC1G2_PC == pParameter->elementHdr.pType)
03048         {
03049           llrp_u16_t pc;
03050 
03051           pc = LLRP_C1G2_PC_getPC_Bits((LLRP_tSC1G2_PC *)pParameter);
03052           data->tag.u.gen2.pc[0] = pc & 0xFF;
03053           data->tag.u.gen2.pc[1] = (pc & 0xFF00) >> 8;
03054 
03055           data->tag.u.gen2.pcByteCount = 2;
03056 
03058         }
03059         else if (&LLRP_tdC1G2_CRC == pParameter->elementHdr.pType)
03060         {
03061           data->tag.crc = LLRP_C1G2_CRC_getCRC((LLRP_tSC1G2_CRC *)pParameter);
03062         }
03063       } /* End of for loop */
03064     }
03069     if (((atoi(&reader->u.llrpReader.capabilities.softwareVersion[0]) == 4) 
03070           && (atoi(&reader->u.llrpReader.capabilities.softwareVersion[2]) >= 17))
03071           || (atoi(&reader->u.llrpReader.capabilities.softwareVersion[0]) > 4))
03072     {
03073       LLRP_tSParameter *pParameter;
03074       llrp_u16_t        phase;
03075 
03076       for (pParameter = pTagReportData->listCustom;
03077           NULL != pParameter;
03078           pParameter = (LLRP_tSParameter *)pParameter->pNextSubParameter)
03079       {
03083         phase = LLRP_ThingMagicRFPhase_getPhase(
03084             (LLRP_tSThingMagicRFPhase *)pParameter);
03085 
03086         /* Copy the value to tagReport */
03087         data->phase = phase;
03088   }
03089     }
03090 
03094     {
03095       LLRP_tSParameter *pParameter;
03096 
03097       for (pParameter = pTagReportData->listAccessCommandOpSpecResult;
03098            NULL != pParameter;
03099            pParameter = (LLRP_tSParameter *)pParameter->pNextSubParameter)
03100       {
03106         TMR_Status retVal;
03107 
03108         retVal = TMR_LLRP_verifyOpSpecResultStatus(reader, pParameter);
03109         if (TMR_SUCCESS != retVal)
03110         {
03119 #ifdef TMR_ENABLE_BACKGROUND_READS
03120           notify_exception_listeners(reader, retVal);
03121 #endif
03122 
03126           continue;
03127         }
03128 
03137         if (NULL != &data->data)
03138         {
03139           TMR_LLRP_parseTagOpSpecData(pParameter, &data->data);
03140           data->metadataFlags |= TMR_TRD_METADATA_FLAG_DATA;
03141         }
03142       } /* End of for loop */
03143     } /* End of parsing OpSpecResults */
03144   }
03145   else
03146   {
03147     return TMR_ERROR_LLRP;
03148   }
03149 
03150   return ret;
03151 }
03152 
03161 void
03162 TMR_LLRP_parseTagOpSpecData(LLRP_tSParameter *pParameter, TMR_uint8List *data)
03163 {
03164   switch (pParameter->elementHdr.pType->TypeNum)
03165   {
03169     case TMR_LLRP_C1G2READOPSPECRESULT:
03170       {
03171         LLRP_tSC1G2ReadOpSpecResult *pReadOpSpecResult;
03172         int copyLen;
03173 
03177         pReadOpSpecResult = (LLRP_tSC1G2ReadOpSpecResult *)pParameter;
03178 
03179         /* nValue is the length in 16-bit words */
03180         data->len = pReadOpSpecResult->ReadData.nValue * 2;
03181         copyLen = data->len;
03182 
03183         /* couple of validations and error checks */
03184         if (copyLen > data->max)
03185         {
03186           copyLen = data->max;
03187         }
03188 
03189         if (NULL != data->list)
03190         {
03191           /* Copy the data  */
03192           int i, j;
03193 
03194           for (i = 0, j = 0; i < copyLen; i += 2, j ++)
03195           {
03196             /* Hi byte */
03197             data->list[i] = pReadOpSpecResult->ReadData.pValue[j] >> 8;
03198             /* Lo byte */
03199             data->list[i + 1] = pReadOpSpecResult->ReadData.pValue[j] & 0xff;
03200           }
03201         }
03202         break;
03203       }
03204 
03209     case TMR_LLRP_CUSTOM_G2IEASALARMOPSPECRESULT:
03210       {
03211         LLRP_tSThingMagicNXPG2IEASAlarmOpSpecResult *pResult;
03212         int copyLen;
03213 
03214         pResult = (LLRP_tSThingMagicNXPG2IEASAlarmOpSpecResult *)pParameter;
03215         
03219         data->len = pResult->EASAlarmCode.nValue;
03220         copyLen = data->len;
03221 
03222         /* couple of validations and error checks */
03223         if (copyLen > data->max)
03224         {
03225           copyLen = data->max;
03226         }
03227 
03228         if (NULL != data->list)
03229         {
03230           memcpy(data->list, pResult->EASAlarmCode.pValue, copyLen);
03231         }
03232         break;
03233       }
03234 
03239     case TMR_LLRP_CUSTOM_G2XEASALARMOPSPECRESULT:
03240       {
03241         LLRP_tSThingMagicNXPG2XEASAlarmOpSpecResult *pResult;
03242         int copyLen;
03243 
03244         pResult = (LLRP_tSThingMagicNXPG2XEASAlarmOpSpecResult *)pParameter;
03245         
03249         data->len = pResult->EASAlarmCode.nValue;
03250         copyLen = data->len;
03251 
03252         /* couple of validations and error checks */
03253         if (copyLen > data->max)
03254         {
03255           copyLen = data->max;
03256         }
03257 
03258         if (NULL != data->list)
03259         {
03260           memcpy(data->list, pResult->EASAlarmCode.pValue, copyLen);
03261         }
03262         break;
03263       }
03264 
03270     case TMR_LLRP_CUSTOM_G2ICALIBRATEOPSPECRESULT:
03271       {
03272         LLRP_tSThingMagicNXPG2ICalibrateOpSpecResult *pResult;
03273         int copyLen;
03274 
03275         pResult = (LLRP_tSThingMagicNXPG2ICalibrateOpSpecResult *)pParameter;
03276 
03280         data->len = pResult->CalibrateData.nValue;
03281         copyLen = data->len;
03282         /* couple of validations and error checks */
03283         if (copyLen > data->max)
03284         {
03285           copyLen = data->max;
03286         }
03287 
03288         if (NULL != data->list)
03289         {
03290           memcpy(data->list, pResult->CalibrateData.pValue, copyLen);
03291         }
03292         break;
03293       }
03294 
03300     case TMR_LLRP_CUSTOM_G2XCALIBRATEOPSPECRESULT:
03301       {
03302         LLRP_tSThingMagicNXPG2XCalibrateOpSpecResult *pResult;
03303         int copyLen;
03304 
03305         pResult = (LLRP_tSThingMagicNXPG2XCalibrateOpSpecResult *)pParameter;
03306 
03310         data->len = pResult->CalibrateData.nValue;
03311         copyLen = data->len;
03312         /* couple of validations and error checks */
03313         if (copyLen > data->max)
03314         {
03315           copyLen = data->max;
03316         }
03317 
03318         if (NULL != data->list)
03319         {
03320           memcpy(data->list, pResult->CalibrateData.pValue, copyLen);
03321         }
03322         break;
03323       }
03324 
03330     case TMR_LLRP_CUSTOM_G2ICHANGECONFIGOPSPECRESULT:
03331       {
03332         LLRP_tSThingMagicNXPG2IChangeConfigOpSpecResult *pResult;
03333 
03334         pResult = (LLRP_tSThingMagicNXPG2IChangeConfigOpSpecResult *)pParameter;
03335 
03340         data->len = 2;
03341         /* couple of validations and error checks */
03342         if ((data->len < data->max) &&
03343             (NULL != data->list))
03344         {
03345           /* Hi byte */
03346           data->list[0] = pResult->ConfigData >> 8;
03347           /* Lo byte */
03348           data->list[1] = pResult->ConfigData & 0xff;
03349         }
03350         break;
03351       }
03352 
03357     case TMR_LLRP_CUSTOM_IDS_GETBATTERYLEVELOPSPECRESULT:
03358       {
03359         LLRP_tSThingMagicIDSSL900AGetBatteryLevelOpSpecResult *pResult;
03360 
03361         pResult = (LLRP_tSThingMagicIDSSL900AGetBatteryLevelOpSpecResult *)pParameter;
03362 
03367         data->len = pResult->pThingMagicIDSBatteryLevel->batteryValueByteStream.nValue;
03368         /* couple of validations and error checks */
03369         if (data->len > data->max)
03370         {
03371           data->len = data->max;
03372         }
03373         if (NULL != data->list)
03374         {
03375           memcpy (data->list, pResult->pThingMagicIDSBatteryLevel->batteryValueByteStream.pValue,
03376               (size_t)(pResult->pThingMagicIDSBatteryLevel->batteryValueByteStream.nValue * sizeof(uint8_t)));
03377         }
03378         break;
03379       }
03380 
03385     case TMR_LLRP_CUSTOM_IDS_GETMEASUREMENTSETUPOPSPECRESULT:
03386       {
03387         LLRP_tSThingMagicIDSSL900AGetMeasurementSetupOpSpecResult *pResult;
03388 
03389         pResult = (LLRP_tSThingMagicIDSSL900AGetMeasurementSetupOpSpecResult *)pParameter;
03390 
03395         data->len = pResult->measurementByteStream.nValue;
03396         /* couple of validations and error checks */
03397         if (data->len > data->max)
03398         {
03399           data->len = data->max;
03400         }
03401         if (NULL != data->list)
03402         {
03403           memcpy (data->list, pResult->measurementByteStream.pValue,
03404               (size_t)(pResult->measurementByteStream.nValue * sizeof(uint8_t)));
03405         }
03406         break;
03407       }
03408 
03413     case TMR_LLRP_CUSTOM_MONZA4QTREADWRITEOPSPECRESULT:
03414       {
03415         LLRP_tSThingMagicImpinjMonza4QTReadWriteOpSpecResult *pResult;
03416 
03417         pResult = (LLRP_tSThingMagicImpinjMonza4QTReadWriteOpSpecResult *)pParameter;
03418 
03423         data->len = 2;
03424         /* couple of validations and error checks */
03425         if ((data->len < data->max) &&
03426             (NULL != data->list))
03427         {
03428           /* Hi byte */
03429           data->list[0] = pResult->Payload >> 8;
03430           /* Lo byte */
03431           data->list[1] = pResult->Payload & 0xff;
03432         }
03433         break;
03434       }
03435 
03440     case TMR_LLRP_CUSTOM_IDS_GETSENSORVALUEOPSPECRESULT:
03441       {
03442         LLRP_tSThingMagicIDSSL900ASensorValueOpSpecResult  *pResult;
03443 
03444         pResult = (LLRP_tSThingMagicIDSSL900ASensorValueOpSpecResult *)pParameter;
03445 
03450         data->len = 2;
03451         /* couple of validations and error checks */
03452         if (data->len > data->max)
03453         {
03454           data->len = data->max;
03455         }
03456 
03457         if (NULL != data->list)
03458         {
03459           /* Hi byte */
03460           data->list[0] = pResult->raw >> 8;
03461           /* Lo byte */
03462           data->list[1] = pResult->raw & 0xff;
03463         }
03464         break;
03465       }
03466 
03471     case TMR_LLRP_CUSTOM_IDS_GETLOGSTATEOPSPECRESULT:
03472       {
03473         LLRP_tSThingMagicIDSSL900ALogStateOpSpecResult  *pResult;
03474 
03475         pResult = (LLRP_tSThingMagicIDSSL900ALogStateOpSpecResult *)pParameter;
03476 
03481         data->len = pResult->LogStateByteStream.nValue;
03482         /* couple of validations and error checks */
03483         if (data->len > data->max)
03484         {
03485           data->len = data->max;
03486         }
03487 
03488         if (NULL != data->list)
03489         {
03490           memcpy (data->list, pResult->LogStateByteStream.pValue, (llrp_u16_t)data->len); 
03491         }
03492         break;
03493       }
03494 
03499     case TMR_LLRP_CUSTOM_IDS_ACCESSFIFOSTATUSOPSPECRESULT:
03500       {
03501         LLRP_tSThingMagicIDSSL900AAccessFIFOStatusOpSpecResult  *pResult;
03502 
03503         pResult = (LLRP_tSThingMagicIDSSL900AAccessFIFOStatusOpSpecResult *)pParameter;
03504 
03509         data->len = 1;
03510         /* couple of validations and error checks */
03511         if (data->len > data->max)
03512         {
03513           data->len = data->max;
03514         }
03515 
03516         if (NULL != data->list)
03517         {
03518           memcpy (data->list, &(pResult->FIFOStatusRawByte), (size_t)((data->len) * sizeof(uint8_t)));
03519         }
03520         break;
03521       }
03522 
03527     case TMR_LLRP_CUSTOM_IDS_ACCESSFIFOREADOPSPECRESULT:
03528       {
03529         LLRP_tSThingMagicIDSSL900AAccessFIFOReadOpSpecResult  *pResult;
03530 
03531         pResult = (LLRP_tSThingMagicIDSSL900AAccessFIFOReadOpSpecResult *)pParameter;
03532 
03537         data->len = pResult->readPayLoad.nValue;
03538         /* couple of validations and error checks */
03539         if (data->len > data->max)
03540         {
03541           data->len = data->max;
03542         }
03543 
03544         if (NULL != data->list)
03545         {
03546           memcpy (data->list, pResult->readPayLoad.pValue, (size_t)(pResult->readPayLoad.nValue * sizeof(uint8_t)));
03547         }
03548 
03549         break;
03550       }
03551 
03556     case TMR_LLRP_CUSTOM_IDS_GETCALIBRATIONDATAOPSPECRESULT:
03557     {
03558         LLRP_tSThingMagicIDSSL900AGetCalibrationDataOpSpecResult  *pResult;
03559 
03560       pResult = (LLRP_tSThingMagicIDSSL900AGetCalibrationDataOpSpecResult *)pParameter;
03561 
03566       data->len = pResult->pThingMagicIDSCalibrationData->calibrationValueByteStream.nValue;
03567       /* couple of validations and error checks */
03568       if (data->len > data->max)
03569       {
03570         data->len = data->max;
03571       }
03572 
03573       if (NULL != data->list)
03574       {
03575         memcpy (data->list, pResult->pThingMagicIDSCalibrationData->calibrationValueByteStream.pValue,
03576                         (size_t)(pResult->pThingMagicIDSCalibrationData->calibrationValueByteStream.nValue * sizeof(uint8_t)));
03577       }
03578 
03579       break;
03580     }
03581 
03586     case TMR_LLRP_CUSTOM_DENATRAN_IAV_ACTIVATESECUREMODEOPSPECRESULT:
03587     {
03588       LLRP_tSThingMagicDenatranIAVActivateSecureModeOpSpecResult *pResult;
03589 
03590       pResult = (LLRP_tSThingMagicDenatranIAVActivateSecureModeOpSpecResult *)pParameter;
03591 
03596       data->len = pResult->ActivateSecureModeByteStream.nValue;
03597       /* couple of validations and error checks */
03598       if (data->len > data->max)
03599       {
03600         data->len = data->max;
03601       }
03602 
03603       if (NULL != data->list)
03604       {
03605         memcpy (data->list, pResult->ActivateSecureModeByteStream.pValue,
03606             (size_t)(pResult->ActivateSecureModeByteStream.nValue * sizeof(uint8_t)));
03607       }
03608 
03609       break;
03610     }
03611 
03616     case TMR_LLRP_CUSTOM_DENATRAN_IAV_AUTHENTICATEOBUOPSPECRESULT:
03617     {
03618       LLRP_tSThingMagicDenatranIAVAuthenticateOBUOpSpecResult *pResult;
03619 
03620       pResult = (LLRP_tSThingMagicDenatranIAVAuthenticateOBUOpSpecResult *)pParameter;
03621 
03626       data->len = pResult->AuthenitcateOBUByteStream.nValue;
03627       /* couple of validations and error checks */
03628       if (data->len > data->max)
03629       {
03630         data->len = data->max;
03631       }
03632 
03633       if (NULL != data->list)
03634       {
03635         memcpy (data->list, pResult->AuthenitcateOBUByteStream.pValue,
03636             (size_t)(pResult->AuthenitcateOBUByteStream.nValue * sizeof(uint8_t)));
03637       }
03638 
03639       break;
03640     }
03641 
03646     case TMR_LLRP_CUSTOM_DENATRAN_IAV_ACTIVATESINIAVMODEOPSPECRESULT:
03647     {
03648       LLRP_tSThingMagicDenatranIAVActivateSiniavModeOpSpecResult *pResult;
03649 
03650       pResult = (LLRP_tSThingMagicDenatranIAVActivateSiniavModeOpSpecResult *)pParameter;
03651 
03656       data->len = pResult->ActivateSiniavModeByteStream.nValue;
03657       /* couple of validations and error checks */
03658       if (data->len > data->max)
03659       {
03660         data->len = data->max;
03661       }
03662 
03663       if (NULL != data->list)
03664       {
03665         memcpy (data->list, pResult->ActivateSiniavModeByteStream.pValue,
03666             (size_t)(pResult->ActivateSiniavModeByteStream.nValue * sizeof(uint8_t)));
03667       }
03668 
03669       break;
03670     }
03671 
03676     case TMR_LLRP_CUSTOM_DENATRAN_IAV_AUTHENTICATEIDOPSPECRESULT:
03677     {
03678       LLRP_tSThingMagicDenatranIAVOBUAuthenticateIDOpSpecResult *pResult;
03679 
03680       pResult = (LLRP_tSThingMagicDenatranIAVOBUAuthenticateIDOpSpecResult *)pParameter;
03681 
03686       data->len = pResult->OBUAuthenticateIDByteStream.nValue;
03687       /* couple of validations and error checks */
03688       if (data->len > data->max)
03689       {
03690         data->len = data->max;
03691       }
03692 
03693       if (NULL != data->list)
03694       {
03695         memcpy (data->list, pResult->OBUAuthenticateIDByteStream.pValue,
03696             (size_t)(pResult->OBUAuthenticateIDByteStream.nValue * sizeof(uint8_t)));
03697       }
03698 
03699       break;
03700     }
03701 
03706     case TMR_LLRP_CUSTOM_DENATRAN_IAV_AUTHENTICATEFULLPASS1OPSPECRESULT:
03707     {
03708       LLRP_tSThingMagicDenatranIAVOBUAuthenticateFullPass1OpSpecResult *pResult;
03709 
03710       pResult = (LLRP_tSThingMagicDenatranIAVOBUAuthenticateFullPass1OpSpecResult *)pParameter;
03711 
03716       data->len = pResult->OBUAuthenticateFullPass1ByteStream.nValue;
03717       /* couple of validations and error checks */
03718       if (data->len > data->max)
03719       {
03720         data->len = data->max;
03721       }
03722 
03723       if (NULL != data->list)
03724       {
03725         memcpy (data->list, pResult->OBUAuthenticateFullPass1ByteStream.pValue,
03726             (size_t)(pResult->OBUAuthenticateFullPass1ByteStream.nValue * sizeof(uint8_t)));
03727       }
03728 
03729       break;
03730     }
03731 
03736     case TMR_LLRP_CUSTOM_DENATRAN_IAV_AUTHENTICATEFULLPASS2OPSPECRESULT:
03737     {
03738       LLRP_tSThingMagicDenatranIAVOBUAuthenticateFullPass2OpSpecResult *pResult;
03739 
03740       pResult = (LLRP_tSThingMagicDenatranIAVOBUAuthenticateFullPass2OpSpecResult *)pParameter;
03741 
03746       data->len = pResult->OBUAuthenticateFullPass2ByteStream.nValue;
03747       /* couple of validations and error checks */
03748       if (data->len > data->max)
03749       {
03750         data->len = data->max;
03751       }
03752 
03753       if (NULL != data->list)
03754       {
03755         memcpy (data->list, pResult->OBUAuthenticateFullPass2ByteStream.pValue,
03756             (size_t)(pResult->OBUAuthenticateFullPass2ByteStream.nValue * sizeof(uint8_t)));
03757       }
03758 
03759       break;
03760     }
03761 
03766     case TMR_LLRP_CUSTOM_DENATRAN_IAV_OBUREADFROMMEMMAPOPSPECRESULT:
03767     {
03768       LLRP_tSThingMagicDenatranIAVOBUReadFromMemMapOpSpecResult *pResult;
03769 
03770       pResult = (LLRP_tSThingMagicDenatranIAVOBUReadFromMemMapOpSpecResult *)pParameter;
03771 
03776       data->len = pResult->OBUReadMemoryMapByteStream.nValue;
03777       /* couple of validations and error checks */
03778       if (data->len > data->max)
03779       {
03780         data->len = data->max;
03781       }
03782 
03783       if (NULL != data->list)
03784       {
03785         memcpy (data->list, pResult->OBUReadMemoryMapByteStream.pValue,
03786             (size_t)(pResult->OBUReadMemoryMapByteStream.nValue * sizeof(uint8_t)));
03787       }
03788 
03789       break;
03790     }
03791 
03796     case TMR_LLRP_CUSTOM_DENATRAN_IAV_OBUWRITETOMEMMAPOPSPECRESULT:
03797     {
03798       LLRP_tSThingMagicDenatranIAVOBUWriteToMemMapOpSpecResult *pResult;
03799 
03800       pResult = (LLRP_tSThingMagicDenatranIAVOBUWriteToMemMapOpSpecResult *)pParameter;
03801 
03806       data->len = pResult->OBUWriteMemoryMapByteStream.nValue;
03807       /* couple of validations and error checks */
03808       if (data->len > data->max)
03809       {
03810         data->len = data->max;
03811       }
03812 
03813       if (NULL != data->list)
03814       {
03815         memcpy (data->list, pResult->OBUWriteMemoryMapByteStream.pValue,
03816             (size_t)(pResult->OBUWriteMemoryMapByteStream.nValue * sizeof(uint8_t)));
03817       }
03818 
03819       break;
03820     }
03821 
03822 #ifdef TMR_ENABLE_ISO180006B
03823     case TMR_LLRP_CUSTOM_ISO_READDATAOPSPECRESULT:
03824       {
03825         LLRP_tSThingMagicISO180006BReadOpSpecResult *pResult;
03826         pResult = (LLRP_tSThingMagicISO180006BReadOpSpecResult *)pParameter;
03827         memcpy(data->list, pResult->ReadData.pValue, (pResult->ReadData.nValue * sizeof(uint8_t)));
03828 
03829         break; 
03830       }
03831 #endif /* TMR_ENABLE_ISO180006B */
03832 
03833     default:
03834       {
03839       }
03840   }
03841 }
03842 
03849 TMR_Status
03850 TMR_LLRP_cmdGetThingMagicDeDuplication(TMR_Reader *reader, TMR_LLRP_TMDeDuplication *duplication)
03851 {
03852   TMR_Status ret;
03853   LLRP_tSGET_READER_CONFIG              *pCmd;
03854   LLRP_tSMessage                        *pCmdMsg;
03855   LLRP_tSMessage                        *pRspMsg;
03856   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
03857   LLRP_tSThingMagicDeviceControlConfiguration  *pTMDeDuplication;
03858   LLRP_tSParameter                      *pCustParam;
03859 
03860   ret = TMR_SUCCESS;
03864   pCmd = LLRP_GET_READER_CONFIG_construct();
03865   LLRP_GET_READER_CONFIG_setRequestedData(pCmd,
03866       LLRP_GetReaderConfigRequestedData_Identification);
03867 
03873   pTMDeDuplication = LLRP_ThingMagicDeviceControlConfiguration_construct();
03874   if (NULL == pTMDeDuplication)
03875   {
03876     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
03877     return TMR_ERROR_LLRP;
03878   }
03879 
03884   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMDeDuplication,
03885       LLRP_ThingMagicControlConfiguration_ThingMagicDeDuplication);
03886   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMDeDuplication->hdr))
03887   {
03888     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMDeDuplication);
03889     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
03890     return TMR_ERROR_LLRP;
03891   }
03892 
03893   pCmdMsg       = &pCmd->hdr;
03897   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
03902   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
03903   if (TMR_SUCCESS != ret)
03904   {
03905     return ret;
03906   }
03907 
03911   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
03912   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
03913   {
03914     TMR_LLRP_freeMessage(pRspMsg);
03915     return TMR_ERROR_LLRP;
03916   }
03917 
03921   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
03922   if (NULL != pCustParam)
03923   {
03924     /* Get the Record Highest RSSI */
03925     duplication->highestRSSI = LLRP_ThingMagicDeDuplication_getRecordHighestRSSI((LLRP_tSThingMagicDeDuplication*)pCustParam);
03926 
03927     /* Get the Unique By antenna */
03928     duplication->uniquebyAntenna = LLRP_ThingMagicDeDuplication_getUniqueByAntenna((LLRP_tSThingMagicDeDuplication*)pCustParam);
03929 
03930     /* Get the Unique By data */
03931     duplication->uniquebyData = LLRP_ThingMagicDeDuplication_getUniqueByData((LLRP_tSThingMagicDeDuplication*)pCustParam);
03932   }
03933   else
03934   {
03935     TMR_LLRP_freeMessage(pRspMsg);
03936     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
03937   }
03938 
03942   TMR_LLRP_freeMessage(pRspMsg);
03943 
03944   return ret;
03945 }
03946 
03953 TMR_Status
03954 TMR_LLRP_cmdSetThingMagicDeDuplication(TMR_Reader *reader, TMR_LLRP_TMDeDuplication *duplication)
03955 {
03956   TMR_Status ret;
03957   LLRP_tSSET_READER_CONFIG              *pCmd;
03958   LLRP_tSMessage                        *pCmdMsg;
03959   LLRP_tSMessage                        *pRspMsg;
03960   LLRP_tSSET_READER_CONFIG_RESPONSE     *pRsp;
03961   LLRP_tSThingMagicDeDuplication        *pTMDeDuplication;
03962 
03963   ret = TMR_SUCCESS;
03969   pCmd = LLRP_SET_READER_CONFIG_construct();
03970 
03971   /* Initialize DeDuplication */
03972   pTMDeDuplication = LLRP_ThingMagicDeDuplication_construct();
03973 
03974   /* set the highestRSSI to DeDuplication */
03975   pTMDeDuplication->RecordHighestRSSI = duplication->highestRSSI;
03976 
03977   /* set the unique by antenna to DeDuplication */
03978   pTMDeDuplication->UniqueByAntenna = duplication->uniquebyAntenna;
03979 
03980   /* set the unique by data to DeDuplication */
03981   pTMDeDuplication->UniqueByData = duplication->uniquebyData;
03982 
03983   /* Add DeDuplication as a custom parameter*/
03984   LLRP_SET_READER_CONFIG_addCustom(pCmd, (LLRP_tSParameter *)pTMDeDuplication);
03985 
03986   pCmdMsg = &pCmd->hdr;
03990   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
03995   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
03996   if (TMR_SUCCESS != ret)
03997   {
03998     return ret;
03999   }
04000 
04004   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
04005   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
04006   {
04007     TMR_LLRP_freeMessage(pRspMsg);
04008     return TMR_ERROR_LLRP; 
04009   }
04010 
04014   TMR_LLRP_freeMessage(pRspMsg);
04015 
04016   return ret;
04017 
04018 }
04019 
04020 void 
04021 TMR_LLRP_freeTMReaderConfiguration(TMR_LLRP_TMReaderConfiguration *config)
04022 {
04023   if (NULL != config->description.pValue)
04024   {
04025     free(config->description.pValue);
04026   }
04027 
04028   if (NULL != config->role.pValue)
04029   {
04030     free(config->role.pValue);
04031   }
04032 }
04033 
04034 
04043 TMR_Status
04044 TMR_LLRP_cmdGetThingmagicReaderConfiguration(TMR_Reader *reader, 
04045                        TMR_LLRP_TMReaderConfiguration *config)
04046 {
04047   TMR_Status ret;
04048   LLRP_tSGET_READER_CONFIG              *pCmd;
04049   LLRP_tSMessage                        *pCmdMsg;
04050   LLRP_tSMessage                        *pRspMsg;
04051   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
04052   LLRP_tSThingMagicDeviceControlConfiguration  *pTMReaderConfig;
04053   LLRP_tSParameter                      *pCustParam;
04054 
04055   ret = TMR_SUCCESS;
04059   pCmd = LLRP_GET_READER_CONFIG_construct();
04060   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, 
04061                         LLRP_GetReaderConfigRequestedData_Identification);
04062 
04068   pTMReaderConfig = LLRP_ThingMagicDeviceControlConfiguration_construct();
04069   if (NULL == pTMReaderConfig)
04070   {
04071     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04072     return TMR_ERROR_LLRP;
04073   }
04074 
04079   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMReaderConfig, 
04080             LLRP_ThingMagicControlConfiguration_ThingMagicReaderConfiguration);
04081   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMReaderConfig->hdr))
04082   {
04083     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMReaderConfig);
04084     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04085     return TMR_ERROR_LLRP;
04086   }
04087 
04088   pCmdMsg       = &pCmd->hdr;
04092   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
04097   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04098   if (TMR_SUCCESS != ret)
04099   {
04100     return ret;
04101   }
04102 
04106   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
04107   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
04108   {
04109     TMR_LLRP_freeMessage(pRspMsg);
04110     return TMR_ERROR_LLRP; 
04111   }
04112 
04116   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
04117   if (NULL != pCustParam)
04118   {
04119     /* Get description */
04120     {
04121       llrp_utf8v_t description;
04122       description = LLRP_ThingMagicReaderConfiguration_getReaderDescription((LLRP_tSThingMagicReaderConfiguration*) pCustParam);
04123       config->description = LLRP_utf8v_copy(description);
04124 
04125     }
04126     /* Get Role */
04127     {
04128       llrp_utf8v_t role;
04129       role = LLRP_ThingMagicReaderConfiguration_getReaderRole((LLRP_tSThingMagicReaderConfiguration*) pCustParam);
04130       config->role = LLRP_utf8v_copy(role);
04131     }
04132     /* Get host name */
04133     {
04134       llrp_utf8v_t hostname;
04135       hostname = LLRP_ThingMagicReaderConfiguration_getReaderHostName((LLRP_tSThingMagicReaderConfiguration*) pCustParam);
04136       config->hostName = LLRP_utf8v_copy(hostname);
04137     }
04138   }
04139   else
04140   {
04141     TMR_LLRP_freeMessage(pRspMsg);
04142     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
04143   }
04144   
04148   TMR_LLRP_freeMessage(pRspMsg);
04149 
04150   return ret;
04151 }
04152 
04159 TMR_Status
04160 TMR_LLRP_cmdSetThingmagicReaderConfiguration(TMR_Reader *reader, 
04161                                   TMR_LLRP_TMReaderConfiguration *config)
04162 {
04163   TMR_Status ret;
04164   LLRP_tSSET_READER_CONFIG              *pCmd;
04165   LLRP_tSMessage                        *pCmdMsg;
04166   LLRP_tSMessage                        *pRspMsg;
04167   LLRP_tSSET_READER_CONFIG_RESPONSE     *pRsp;
04168   LLRP_tSThingMagicReaderConfiguration  *pReaderConfig;
04169   
04170   ret = TMR_SUCCESS;
04176   pCmd = LLRP_SET_READER_CONFIG_construct();
04177 
04178   /* Initialize Reader configuration */
04179   pReaderConfig = LLRP_ThingMagicReaderConfiguration_construct();
04180 
04181   /* Set description to reader config */
04182   pReaderConfig->ReaderDescription = LLRP_utf8v_copy(config->description);
04183   /* Set Reader role */
04184   pReaderConfig->ReaderRole = LLRP_utf8v_copy(config->role);
04185   /* Set reader host name */
04186   pReaderConfig->ReaderHostName = LLRP_utf8v_copy(config->hostName);
04187 
04188   /* Add ThingMagic reader configuration as a custom parameter*/
04189   LLRP_SET_READER_CONFIG_addCustom(pCmd, (LLRP_tSParameter *)pReaderConfig);
04190 
04191   pCmdMsg = &pCmd->hdr;
04195   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
04200   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04201   if (TMR_SUCCESS != ret)
04202   {
04203     return ret;
04204   }
04205 
04209   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
04210   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
04211   {
04212     TMR_LLRP_freeMessage(pRspMsg);
04213     return TMR_ERROR_LLRP; 
04214   }
04215 
04219   TMR_LLRP_freeMessage(pRspMsg);
04220 
04221   return ret;
04222 }
04223 
04231 TMR_Status
04232 TMR_LLRP_cmdGetThingMagicCurrentTime(TMR_Reader *reader, struct tm *curTime)
04233 {
04234   TMR_Status ret;
04235   LLRP_tSGET_READER_CONFIG              *pCmd;
04236   LLRP_tSMessage                        *pCmdMsg;
04237   LLRP_tSMessage                        *pRspMsg;
04238   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
04239   LLRP_tSThingMagicDeviceControlConfiguration  *pTMCurrentTime;
04240   LLRP_tSParameter                      *pCustParam;
04241   
04242   ret = TMR_SUCCESS;
04246   pCmd = LLRP_GET_READER_CONFIG_construct();
04247   LLRP_GET_READER_CONFIG_setRequestedData(pCmd,
04248       LLRP_GetReaderConfigRequestedData_Identification);
04249 
04255   pTMCurrentTime = LLRP_ThingMagicDeviceControlConfiguration_construct();
04256   if (NULL == pTMCurrentTime)
04257   {
04258     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04259     return TMR_ERROR_LLRP;
04260   }
04261 
04266   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMCurrentTime,
04267       LLRP_ThingMagicControlConfiguration_ThingMagicCurrentTime);
04268   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMCurrentTime->hdr))
04269   {
04270     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMCurrentTime);
04271     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04272     return TMR_ERROR_LLRP;
04273   }
04274 
04275   pCmdMsg       = &pCmd->hdr;
04279   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
04284   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04285   if (TMR_SUCCESS != ret)
04286   {
04287     return ret;
04288   }
04289 
04293   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
04294   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
04295   {
04296     TMR_LLRP_freeMessage(pRspMsg);
04297     return TMR_ERROR_LLRP;
04298   }
04299 
04303   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
04304   if (NULL != pCustParam)
04305   {
04306     /* Get the reader current time */
04307     {
04308       llrp_utf8v_t readerCT;
04309       readerCT = LLRP_ThingMagicCurrentTime_getReaderCurrentTime ((LLRP_tSThingMagicCurrentTime *) pCustParam);
04310       if (!strptime((const char *)readerCT.pValue, "%Y-%m-%dT%H:%M:%S", curTime))
04311       {
04312         return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
04313       }
04314     }
04315   }
04316   else
04317   {
04318     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
04319   }
04320 
04324   TMR_LLRP_freeMessage(pRspMsg);
04325 
04326   return ret;
04327 }
04328 
04329 
04337 TMR_Status
04338 TMR_LLRP_cmdGetThingMagicReaderModuleTemperature(TMR_Reader *reader, uint8_t *readerTemp)
04339 {
04340   TMR_Status ret;
04341   LLRP_tSGET_READER_CONFIG              *pCmd;
04342   LLRP_tSMessage                        *pCmdMsg;
04343   LLRP_tSMessage                        *pRspMsg;
04344   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
04345   LLRP_tSThingMagicDeviceControlConfiguration  *pTMReaderTemp;
04346   LLRP_tSParameter                      *pCustParam;
04347 
04348   ret = TMR_SUCCESS;
04352   pCmd = LLRP_GET_READER_CONFIG_construct();
04353   LLRP_GET_READER_CONFIG_setRequestedData(pCmd,
04354       LLRP_GetReaderConfigRequestedData_Identification);
04355 
04362   pTMReaderTemp = LLRP_ThingMagicDeviceControlConfiguration_construct();
04363   if (NULL == pTMReaderTemp)
04364   {
04365     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04366     return TMR_ERROR_LLRP;
04367   }
04368 
04373   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMReaderTemp,
04374       LLRP_ThingMagicControlConfiguration_ThingMagicReaderModuleTemperature);
04375   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMReaderTemp->hdr))
04376   {
04377     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMReaderTemp);
04378     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04379     return TMR_ERROR_LLRP;
04380   }
04381 
04382   pCmdMsg       = &pCmd->hdr;
04386   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
04391   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04392   if (TMR_SUCCESS != ret)
04393   {
04394     return ret;
04395   }
04396 
04400   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
04401   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
04402   {
04403     TMR_LLRP_freeMessage(pRspMsg);
04404     return TMR_ERROR_LLRP;
04405   }
04406 
04410   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
04411   if (NULL != pCustParam)
04412   {
04413     /* get the reader module temperature */
04414     llrp_u8_t temp;
04415     temp = LLRP_ThingMagicReaderModuleTemperature_getReaderModuleTemperature ((
04416          LLRP_tSThingMagicReaderModuleTemperature *) pCustParam);
04417 
04418    *(uint8_t *)readerTemp = (uint8_t)temp;
04419   }
04420   else
04421   {
04422     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
04423   }
04424 
04428   TMR_LLRP_freeMessage(pRspMsg);
04429 
04430   return ret;
04431 }
04432 
04440 TMR_Status
04441 TMR_LLRP_cmdGetThingMagicAntennaDetection(TMR_Reader *reader, bool *antennaport)
04442 {
04443   TMR_Status ret;
04444   LLRP_tSGET_READER_CONFIG              *pCmd;
04445   LLRP_tSMessage                        *pCmdMsg;
04446   LLRP_tSMessage                        *pRspMsg;
04447   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
04448   LLRP_tSThingMagicDeviceControlConfiguration  *pTMAntennaDetection;
04449   LLRP_tSParameter                      *pCustParam;
04450 
04451   ret = TMR_SUCCESS;
04455   pCmd = LLRP_GET_READER_CONFIG_construct();
04456   LLRP_GET_READER_CONFIG_setRequestedData(pCmd,
04457       LLRP_GetReaderConfigRequestedData_Identification);
04458 
04465   pTMAntennaDetection = LLRP_ThingMagicDeviceControlConfiguration_construct();
04466   if (NULL == pTMAntennaDetection)
04467   {
04468     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04469     return TMR_ERROR_LLRP;
04470   }
04471 
04476   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMAntennaDetection,
04477       LLRP_ThingMagicControlConfiguration_ThingMagicAntennaDetection);
04478   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMAntennaDetection->hdr))
04479   {
04480     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMAntennaDetection);
04481     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04482     return TMR_ERROR_LLRP;
04483   }
04484 
04485   pCmdMsg       = &pCmd->hdr;
04489   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
04494   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04495   if (TMR_SUCCESS != ret)
04496   {
04497     return ret;
04498   }
04499 
04503   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
04504   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
04505   {
04506     TMR_LLRP_freeMessage(pRspMsg);
04507     return TMR_ERROR_LLRP;
04508   }
04509 
04513   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
04514   if (NULL != pCustParam)
04515   {
04516     /* get the antenna checkport */
04517     llrp_u1_t temp;
04518     temp = LLRP_ThingMagicAntennaDetection_getAntennaDetection ((
04519           LLRP_tSThingMagicAntennaDetection *) pCustParam);
04520 
04521     *(bool*)antennaport = (bool)temp;
04522   }
04523   else
04524   {
04525     TMR_LLRP_freeMessage(pRspMsg);
04526     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
04527   }
04528 
04532   TMR_LLRP_freeMessage(pRspMsg);
04533 
04534   return ret;
04535 
04536 }
04537 
04545 TMR_Status
04546 TMR_LLRP_cmdSetThingMagicAntennaDetection(TMR_Reader *reader, bool *antennaport)
04547 {
04548   TMR_Status ret;
04549   LLRP_tSSET_READER_CONFIG              *pCmd;
04550   LLRP_tSMessage                        *pCmdMsg;
04551   LLRP_tSMessage                        *pRspMsg;
04552   LLRP_tSSET_READER_CONFIG_RESPONSE     *pRsp;
04553   LLRP_tSThingMagicAntennaDetection        *pTMAntennaDetection;
04554 
04555   ret = TMR_SUCCESS;
04561   pCmd = LLRP_SET_READER_CONFIG_construct();
04562 
04563   /* Initialize Antenna Detection */
04564   pTMAntennaDetection = LLRP_ThingMagicAntennaDetection_construct();
04565 
04566   /* set  Antenna Detction */
04567   pTMAntennaDetection->AntennaDetection = *(bool*)antennaport;
04568 
04569   /* Add Antenna Detection as a custom parameter*/
04570   LLRP_SET_READER_CONFIG_addCustom(pCmd, (LLRP_tSParameter *)pTMAntennaDetection);
04571 
04572   pCmdMsg = &pCmd->hdr;
04576   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
04581   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04582   if (TMR_SUCCESS != ret)
04583   {
04584     return ret;
04585   }
04586 
04590   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
04591   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
04592   {
04593     TMR_LLRP_freeMessage(pRspMsg);
04594     return TMR_ERROR_LLRP; 
04595   }
04596 
04600   TMR_LLRP_freeMessage(pRspMsg);
04601 
04602   return ret;
04603 
04604 }
04605 
04613 TMR_Status
04614 TMR_LLRP_cmdGetTMDeviceProtocolCapabilities(TMR_Reader *reader, TMR_TagProtocolList *protocolList)
04615 {
04616   TMR_Status ret;
04617   LLRP_tSGET_READER_CAPABILITIES              *pCmd;
04618   LLRP_tSMessage                              *pCmdMsg;
04619   LLRP_tSMessage                              *pRspMsg;
04620   LLRP_tSGET_READER_CAPABILITIES_RESPONSE     *pRsp;
04621   LLRP_tSThingMagicDeviceControlCapabilities  *pTMCaps;
04622   LLRP_tSParameter                            *pCustParam;
04623   LLRP_tSSupportedProtocols                   *pSupportedProtocols;
04624   uint8_t                                     i;
04625 
04626   ret = TMR_SUCCESS;
04627 
04631   pCmd = LLRP_GET_READER_CAPABILITIES_construct();
04632   LLRP_GET_READER_CAPABILITIES_setRequestedData(pCmd, LLRP_GetReaderCapabilitiesRequestedData_General_Device_Capabilities);
04633 
04638   pTMCaps = LLRP_ThingMagicDeviceControlCapabilities_construct();
04639   if (NULL == pTMCaps)
04640   {
04641     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04642     return TMR_ERROR_LLRP;
04643   }
04644 
04649   LLRP_ThingMagicDeviceControlCapabilities_setRequestedData(pTMCaps, LLRP_ThingMagicControlCapabilities_DeviceProtocolCapabilities);
04650   if (LLRP_RC_OK != LLRP_GET_READER_CAPABILITIES_addCustom(pCmd, &pTMCaps->hdr))
04651   {
04652     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMCaps);
04653     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04654     return TMR_ERROR_LLRP;
04655   }
04656   pCmdMsg       = &pCmd->hdr;
04657 
04661   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
04666   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04667   if (TMR_SUCCESS != ret)
04668   {
04669     return ret;
04670   }
04671 
04675   pRsp = (LLRP_tSGET_READER_CAPABILITIES_RESPONSE *) pRspMsg;
04676   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
04677   {
04678     TMR_LLRP_freeMessage(pRspMsg);
04679     return TMR_ERROR_LLRP;
04680   }
04685   pCustParam = LLRP_GET_READER_CAPABILITIES_RESPONSE_beginCustom(pRsp);
04686   if (NULL != pCustParam)
04687   {
04688     protocolList->len = 0;
04689 
04690     for (pSupportedProtocols = LLRP_DeviceProtocolCapabilities_beginSupportedProtocols(
04691           (LLRP_tSDeviceProtocolCapabilities *) pCustParam), i = 0;
04692         (NULL != pSupportedProtocols);
04693         pSupportedProtocols = LLRP_DeviceProtocolCapabilities_nextSupportedProtocols(
04694           pSupportedProtocols), i ++)
04695     {
04696       protocolList->list[i] = LLRP_SupportedProtocols_getProtocol(pSupportedProtocols);
04700       if (TMR_TAG_PROTOCOL_GEN2 == protocolList->list[i] || 
04701           TMR_TAG_PROTOCOL_ISO180006B == protocolList->list[i] || 
04702           TMR_TAG_PROTOCOL_ATA == protocolList->list[i] ||
04703           TMR_TAG_PROTOCOL_IPX64 == protocolList->list[i] ||
04704           TMR_TAG_PROTOCOL_IPX256 == protocolList->list[i]) 
04705         reader->u.llrpReader.supportedProtocols |= (1 << (protocolList->list[i] -1 ));
04706       protocolList->len ++;
04707     }
04708 
04709   }
04710 
04714   TMR_LLRP_freeMessage(pRspMsg);
04715 
04716   return ret;
04717 
04718 }
04719 
04726 TMR_Status 
04727 TMR_LLRP_cmdGetActiveRFControl(TMR_Reader *reader, TMR_LLRP_RFControl *rfControl)
04728 {
04729   TMR_Status ret;
04730   LLRP_tSGET_READER_CONFIG              *pCmd;
04731   LLRP_tSMessage                        *pCmdMsg;
04732   LLRP_tSMessage                        *pRspMsg;
04733   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
04734   LLRP_tSAntennaConfiguration           *pAntConfig;
04735 
04736   ret = TMR_SUCCESS;
04743   pCmd = LLRP_GET_READER_CONFIG_construct();
04744   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_AntennaConfiguration);
04745 
04746   /* Get antenna configuration for all antennas*/
04747   LLRP_GET_READER_CONFIG_setAntennaID(pCmd, 0);
04748 
04749   pCmdMsg       = &pCmd->hdr;
04753   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
04758   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04759   if (TMR_SUCCESS != ret)
04760   {
04761     return ret;
04762   }
04763 
04767   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
04768   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
04769   {
04770     TMR_LLRP_freeMessage(pRspMsg);
04771     return TMR_ERROR_LLRP; 
04772   }
04773 
04777   for (pAntConfig = LLRP_GET_READER_CONFIG_RESPONSE_beginAntennaConfiguration(pRsp);
04778       (pAntConfig != NULL);
04779       pAntConfig = LLRP_GET_READER_CONFIG_RESPONSE_nextAntennaConfiguration(pAntConfig))
04780   {
04781     LLRP_tSParameter *pInventoryCommand;
04782 
04783     for (pInventoryCommand = LLRP_AntennaConfiguration_beginAirProtocolInventoryCommandSettings(pAntConfig);
04784         (pInventoryCommand != NULL);
04785         pInventoryCommand = LLRP_AntennaConfiguration_nextAirProtocolInventoryCommandSettings(pInventoryCommand))
04786     {
04787       LLRP_tSC1G2RFControl *pRFControl;
04788       pRFControl = LLRP_C1G2InventoryCommand_getC1G2RFControl(
04789           (LLRP_tSC1G2InventoryCommand *)pInventoryCommand);
04790       rfControl->index = pRFControl->ModeIndex;
04791 
04792       /* Convert Tari value */
04793       switch (pRFControl->Tari)
04794       {
04795         case 25000:
04796           rfControl->tari = TMR_GEN2_TARI_25US;
04797           break;
04798 
04799         case 12500:
04800           rfControl->tari = TMR_GEN2_TARI_12_5US;
04801           break;
04802 
04803         case 6250:
04804           rfControl->tari = TMR_GEN2_TARI_6_25US;
04805           break;
04806 
04807         default:
04808           rfControl->tari = TMR_GEN2_TARI_INVALID;
04809       }
04810     }
04811   }
04812 
04816   TMR_LLRP_freeMessage(pRspMsg);
04817 
04818   return ret;
04819 }
04820 
04827 TMR_Status 
04828 TMR_LLRP_cmdSetActiveRFControl(TMR_Reader *reader, TMR_LLRP_RFControl *rfControl)
04829 {
04830   TMR_Status ret;
04831   LLRP_tSSET_READER_CONFIG              *pCmd;
04832   LLRP_tSMessage                        *pCmdMsg;
04833   LLRP_tSMessage                        *pRspMsg;
04834   LLRP_tSSET_READER_CONFIG_RESPONSE     *pRsp;
04835   LLRP_tSAntennaConfiguration           *pAntConfig;
04836   LLRP_tSC1G2RFControl                  *pRFControl;
04837   LLRP_tSC1G2InventoryCommand           *pInventoryCommand;
04838 
04839 
04840   ret = TMR_SUCCESS;
04847   pCmd = LLRP_SET_READER_CONFIG_construct();
04848 
04849   /* Initialize antenna configuration */
04850   pAntConfig = LLRP_AntennaConfiguration_construct();
04851   LLRP_AntennaConfiguration_setAntennaID(pAntConfig, 0); /* For all antennas */
04852 
04853   /* Initialize Inventory Command */
04854   pInventoryCommand = LLRP_C1G2InventoryCommand_construct();
04855 
04856   /* Initialize RFControl */
04857   pRFControl = LLRP_C1G2RFControl_construct();
04858   pRFControl->ModeIndex = rfControl->index;
04859 
04860   /* Convert Tari into nano seconds */
04861   switch (rfControl->tari)
04862   {
04863     case TMR_GEN2_TARI_25US:
04864       pRFControl->Tari = 25000;
04865       break;
04866 
04867     case TMR_GEN2_TARI_12_5US:
04868       pRFControl->Tari = 12500;
04869       break;
04870 
04871     case TMR_GEN2_TARI_6_25US:
04872       pRFControl->Tari = 6250;
04873       break;
04874 
04875     default:
04880       pRFControl->Tari = 0;
04881   }
04882 
04883   /* Set RFControl to inventoryCommand */
04884   LLRP_C1G2InventoryCommand_setC1G2RFControl(pInventoryCommand, pRFControl);
04885 
04886   /* Set InventoryCommand to antenna configuration */
04887   LLRP_AntennaConfiguration_addAirProtocolInventoryCommandSettings(
04888       pAntConfig, (LLRP_tSParameter *)pInventoryCommand);
04889 
04890   /* Set antenna configuration to SET_READER_CONFIG */
04891   LLRP_SET_READER_CONFIG_addAntennaConfiguration(pCmd, pAntConfig);
04892 
04893   pCmdMsg       = &pCmd->hdr;
04894 
04898   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
04903   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04904   if (TMR_SUCCESS != ret)
04905   {
04906     return ret;
04907   }
04908 
04912   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
04913   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
04914   {
04915     TMR_LLRP_freeMessage(pRspMsg);
04916     return TMR_ERROR_LLRP; 
04917   }
04918 
04922   TMR_LLRP_freeMessage(pRspMsg);
04923   return ret;
04924 }
04925 
04932 TMR_Status
04933 TMR_LLRP_cmdGetGen2Q(TMR_Reader *reader, TMR_GEN2_Q *q)
04934 {
04935   TMR_Status ret;
04936   LLRP_tSGET_READER_CONFIG                    *pCmd;
04937   LLRP_tSMessage                              *pCmdMsg;
04938   LLRP_tSMessage                              *pRspMsg;
04939   LLRP_tSGET_READER_CONFIG_RESPONSE           *pRsp;
04940   LLRP_tSThingMagicDeviceControlConfiguration *pTMProtoConfig;
04941   LLRP_tSParameter                            *pCustParam;
04942 
04943   ret = TMR_SUCCESS;
04947   pCmd = LLRP_GET_READER_CONFIG_construct();
04948   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_Identification);
04949 
04955   pTMProtoConfig = LLRP_ThingMagicDeviceControlConfiguration_construct();
04956   if (NULL == pTMProtoConfig)
04957   {
04958     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04959     return TMR_ERROR_LLRP;
04960   }
04961 
04966   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMProtoConfig, 
04967         LLRP_ThingMagicControlConfiguration_ThingMagicProtocolConfiguration);
04968   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMProtoConfig->hdr))
04969   {
04970     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMProtoConfig);
04971     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04972     return TMR_ERROR_LLRP;
04973   }
04974 
04975   pCmdMsg       = &pCmd->hdr;
04979   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
04984   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
04985   if (TMR_SUCCESS != ret)
04986   {
04987     return ret;
04988   }
04989 
04993   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
04994   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
04995   {
04996     TMR_LLRP_freeMessage(pRspMsg);
04997     return TMR_ERROR_LLRP; 
04998   }
04999 
05003   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
05004   if (NULL != pCustParam)
05005   {
05006     LLRP_tSGen2CustomParameters *gen2Custom;
05007     LLRP_tSGen2Q *gen2Q;
05008 
05009     gen2Custom = LLRP_ThingMagicProtocolConfiguration_getGen2CustomParameters(
05010                         (LLRP_tSThingMagicProtocolConfiguration *)pCustParam);
05011     gen2Q = LLRP_Gen2CustomParameters_getGen2Q(gen2Custom);
05012 
05013     if(gen2Q->eGen2QType)
05014     {
05015       /* If static Q, then get the q value */
05016       q->type = TMR_SR_GEN2_Q_STATIC;
05017       q->u.staticQ.initialQ = gen2Q->InitQValue;
05018     }
05019     else
05020     {
05021       q->type = TMR_SR_GEN2_Q_DYNAMIC;
05022     }
05023   }
05024   else
05025   {
05026     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
05027   }
05028   
05032   TMR_LLRP_freeMessage(pRspMsg);
05033 
05034   return ret;
05035 }
05036 
05043 TMR_Status
05044 TMR_LLRP_cmdSetGen2Q(TMR_Reader *reader, TMR_GEN2_Q *q)
05045 {
05046   TMR_Status ret;
05047   LLRP_tSSET_READER_CONFIG                *pCmd;
05048   LLRP_tSMessage                          *pCmdMsg;
05049   LLRP_tSMessage                          *pRspMsg;
05050   LLRP_tSSET_READER_CONFIG_RESPONSE       *pRsp;
05051   LLRP_tSThingMagicProtocolConfiguration  *pProtoConfig;
05052   LLRP_tSGen2CustomParameters             *pGen2Custom;
05053   LLRP_tSGen2Q                            *pGen2Q;
05054   
05055   ret = TMR_SUCCESS;
05061   pCmd = LLRP_SET_READER_CONFIG_construct();
05062 
05063   /* Initialize Protocol configuration */
05064   pProtoConfig = LLRP_ThingMagicProtocolConfiguration_construct();
05065 
05066   /* Initialize gen2 Q */
05067   pGen2Q = LLRP_Gen2Q_construct();
05068   pGen2Q->eGen2QType = q->type;
05069 
05070   if (TMR_SR_GEN2_Q_STATIC == q->type)
05071   {
05072     /* If static q, set the value */
05073     pGen2Q->InitQValue = q->u.staticQ.initialQ;
05074   }
05075   else
05076   {
05077     /* If dynamic, set initQ value to 0 */
05078     pGen2Q->InitQValue = 0;
05079   }
05080 
05081   /* Initialize gen2 custom parameter */
05082   pGen2Custom = LLRP_Gen2CustomParameters_construct();
05083   LLRP_Gen2CustomParameters_setGen2Q(pGen2Custom, pGen2Q);
05084 
05085   /* Set Gen2 Custom parameter to protocol configuration */
05086   LLRP_ThingMagicProtocolConfiguration_setGen2CustomParameters(pProtoConfig,
05087                                                                 pGen2Custom);
05088     
05089   /* Add ThingMagic Protocol configuration as a custom parameter*/
05090   LLRP_SET_READER_CONFIG_addCustom(pCmd, (LLRP_tSParameter *)pProtoConfig);
05091 
05092   pCmdMsg = &pCmd->hdr;
05096   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
05101   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05102   if (TMR_SUCCESS != ret)
05103   {
05104     return ret;
05105   }
05106 
05110   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
05111   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
05112   {
05113     TMR_LLRP_freeMessage(pRspMsg);
05114     return TMR_ERROR_LLRP; 
05115   }
05116 
05120   TMR_LLRP_freeMessage(pRspMsg);
05121 
05122   return ret;
05123 }
05124 
05125 
05132 TMR_Status
05133 TMR_LLRP_cmdGetGen2Session(TMR_Reader *reader, TMR_GEN2_Session *session)
05134 {
05135   TMR_Status ret;
05136   LLRP_tSGET_READER_CONFIG              *pCmd;
05137   LLRP_tSMessage                        *pCmdMsg;
05138   LLRP_tSMessage                        *pRspMsg;
05139   LLRP_tSGET_READER_CONFIG_RESPONSE     *pRsp;
05140   LLRP_tSAntennaConfiguration           *pAntConfig;
05141 
05142   ret = TMR_SUCCESS;
05149   pCmd = LLRP_GET_READER_CONFIG_construct();
05150   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_AntennaConfiguration);
05151 
05152   /* Get antenna configuration for all antennas*/
05153   LLRP_GET_READER_CONFIG_setAntennaID(pCmd, 0);
05154 
05155   pCmdMsg       = &pCmd->hdr;
05159   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
05164   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05165   if (TMR_SUCCESS != ret)
05166   {
05167     return ret;
05168   }
05169 
05173   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
05174   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
05175   {
05176     TMR_LLRP_freeMessage(pRspMsg);
05177     return TMR_ERROR_LLRP;
05178   }
05179 
05183   for (pAntConfig = LLRP_GET_READER_CONFIG_RESPONSE_beginAntennaConfiguration(pRsp);
05184       (pAntConfig != NULL);
05185       pAntConfig = LLRP_GET_READER_CONFIG_RESPONSE_nextAntennaConfiguration(pAntConfig))
05186   {
05187     LLRP_tSParameter *pInventoryCommand;
05188     llrp_u2_t        temp;
05189 
05190     for (pInventoryCommand = LLRP_AntennaConfiguration_beginAirProtocolInventoryCommandSettings(pAntConfig);
05191         (pInventoryCommand != NULL);
05192         pInventoryCommand = LLRP_AntennaConfiguration_nextAirProtocolInventoryCommandSettings(pInventoryCommand))
05193     {
05194       LLRP_tSC1G2SingulationControl *pSingulationControl;
05195 
05196       pSingulationControl = LLRP_C1G2InventoryCommand_getC1G2SingulationControl(
05197           (LLRP_tSC1G2InventoryCommand *)pInventoryCommand);
05198 
05199       /* get the session */
05200       temp = LLRP_C1G2SingulationControl_getSession(pSingulationControl);
05201 
05202       /* convert the session value */
05203       switch (temp)
05204       {
05205         case 0:
05206           {
05207             *session = TMR_GEN2_SESSION_S0;
05208             break;
05209           }
05210         case 1:
05211           {
05212             *session = TMR_GEN2_SESSION_S1;
05213             break;
05214           }
05215         case 2:
05216           {
05217             *session = TMR_GEN2_SESSION_S2;
05218             break;
05219           }
05220         case 3:
05221           {
05222             *session = TMR_GEN2_SESSION_S3;
05223             break;
05224           }
05225         default:
05226           {
05227             *session = TMR_GEN2_SESSION_INVALID;
05228             break;
05229           }
05230       }
05231     }
05232   }
05233 
05237   TMR_LLRP_freeMessage(pRspMsg);
05238   return ret;
05239 }
05240 
05247 TMR_Status
05248 TMR_LLRP_cmdSetGen2Session(TMR_Reader *reader, TMR_GEN2_Session *session)
05249 {
05250   TMR_Status ret;
05251   LLRP_tSSET_READER_CONFIG              *pCmd;
05252   LLRP_tSMessage                        *pCmdMsg;
05253   LLRP_tSMessage                        *pRspMsg;
05254   LLRP_tSSET_READER_CONFIG_RESPONSE     *pRsp;
05255   LLRP_tSAntennaConfiguration           *pAntConfig;
05256   LLRP_tSC1G2SingulationControl         *pSingulationControl;
05257   LLRP_tSC1G2InventoryCommand           *pInventoryCommand;
05258 
05259   ret = TMR_SUCCESS;
05266   pCmd = LLRP_SET_READER_CONFIG_construct();
05267 
05268   /* Initialize antenna configuration */
05269   pAntConfig = LLRP_AntennaConfiguration_construct();
05270   if (NULL == pAntConfig)
05271   {
05272     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05273     return TMR_ERROR_LLRP;
05274   }
05275 
05276   LLRP_AntennaConfiguration_setAntennaID(pAntConfig, 0); /* For all antennas */
05277 
05278   /* Initialize Inventory Command */
05279   pInventoryCommand = LLRP_C1G2InventoryCommand_construct();
05280   if (NULL == pInventoryCommand)
05281   {
05282     TMR_LLRP_freeMessage((LLRP_tSMessage *)pAntConfig);
05283     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05284     return TMR_ERROR_LLRP;
05285   }
05286 
05287   /* Initialize SingulationControl */
05288   pSingulationControl = LLRP_C1G2SingulationControl_construct();
05289   if (NULL == pSingulationControl)
05290   {
05291     TMR_LLRP_freeMessage((LLRP_tSMessage *)pInventoryCommand);
05292     TMR_LLRP_freeMessage((LLRP_tSMessage *)pAntConfig);
05293     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05294     return TMR_ERROR_LLRP;
05295   }
05296 
05297 
05298   /* convert the session value */
05299   switch (*session)
05300   {
05301     case TMR_GEN2_SESSION_S0:
05302       {
05303         pSingulationControl->Session = 0;
05304         break;
05305       }
05306     case TMR_GEN2_SESSION_S1:
05307       {
05308         pSingulationControl->Session = 1;
05309         break;
05310       }
05311     case TMR_GEN2_SESSION_S2:
05312       {
05313         pSingulationControl->Session = 2;
05314         break;
05315       }
05316     case TMR_GEN2_SESSION_S3:
05317       {
05318         pSingulationControl->Session = 3;
05319         break;
05320       }
05321     default:
05322       {
05323         TMR_LLRP_freeMessage((LLRP_tSMessage *)pSingulationControl);
05324         TMR_LLRP_freeMessage((LLRP_tSMessage *)pInventoryCommand);
05325         TMR_LLRP_freeMessage((LLRP_tSMessage *)pAntConfig);
05326         TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05327         return TMR_ERROR_INVALID;
05328       }
05329   }
05330 
05331   /* Set Singulation Control to inventoryCommand */
05332   LLRP_C1G2InventoryCommand_setC1G2SingulationControl(pInventoryCommand, pSingulationControl);
05333 
05334   /* Set InventoryCommand to antenna configuration */
05335   LLRP_AntennaConfiguration_addAirProtocolInventoryCommandSettings(
05336       pAntConfig, (LLRP_tSParameter *)pInventoryCommand);
05337 
05338   /* Set antenna configuration to SET_READER_CONFIG */
05339   LLRP_SET_READER_CONFIG_addAntennaConfiguration(pCmd, pAntConfig);
05340 
05341   pCmdMsg       = &pCmd->hdr;
05342 
05346   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
05351   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05352   if (TMR_SUCCESS != ret)
05353   {
05354     return ret;
05355   }
05356 
05360   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
05361   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
05362   {
05363     TMR_LLRP_freeMessage(pRspMsg);
05364     return TMR_ERROR_LLRP; 
05365   }
05366 
05370   TMR_LLRP_freeMessage(pRspMsg);
05371   return ret;
05372 }
05373 
05380 TMR_Status
05381 TMR_LLRP_cmdGetGen2Target(TMR_Reader *reader, TMR_GEN2_Target *target)
05382 {
05383   TMR_Status ret;
05384   LLRP_tSGET_READER_CONFIG                    *pCmd;
05385   LLRP_tSMessage                              *pCmdMsg;
05386   LLRP_tSMessage                              *pRspMsg;
05387   LLRP_tSGET_READER_CONFIG_RESPONSE           *pRsp;
05388   LLRP_tSThingMagicDeviceControlConfiguration *pTMProtoConfig;
05389   LLRP_tSParameter                            *pCustParam;
05390 
05391   ret = TMR_SUCCESS;
05395   pCmd = LLRP_GET_READER_CONFIG_construct();
05396   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_Identification);
05397 
05403   pTMProtoConfig = LLRP_ThingMagicDeviceControlConfiguration_construct();
05404   if (NULL == pTMProtoConfig)
05405   {
05406     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05407     return TMR_ERROR_LLRP;
05408   }
05409 
05414   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMProtoConfig, 
05415       LLRP_ThingMagicControlConfiguration_ThingMagicProtocolConfiguration);
05416   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMProtoConfig->hdr))
05417   {
05418     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMProtoConfig);
05419     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05420     return TMR_ERROR_LLRP;
05421   }
05422 
05423   pCmdMsg       = &pCmd->hdr;
05427   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
05432   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05433   if (TMR_SUCCESS != ret)
05434   {
05435     return ret;
05436   }
05437 
05441   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
05442   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
05443   {
05444     TMR_LLRP_freeMessage(pRspMsg);
05445     return TMR_ERROR_LLRP; 
05446   }
05447 
05451   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
05452   if (NULL != pCustParam)
05453   {
05454     LLRP_tSGen2CustomParameters *gen2Custom;
05455     LLRP_tSThingMagicTargetStrategy  *gen2target;
05456 
05457     gen2Custom = LLRP_ThingMagicProtocolConfiguration_getGen2CustomParameters(
05458         (LLRP_tSThingMagicProtocolConfiguration *)pCustParam);
05459 
05460     gen2target = LLRP_Gen2CustomParameters_getThingMagicTargetStrategy(gen2Custom);
05461     *target = (TMR_GEN2_Target)gen2target->eThingMagicTargetStrategyValue;
05462   }
05463   else
05464   {
05465     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
05466   }
05467 
05471   TMR_LLRP_freeMessage(pRspMsg);
05472   return ret;
05473 }
05474 
05481 TMR_Status
05482 TMR_LLRP_cmdSetGen2Target(TMR_Reader *reader, TMR_GEN2_Target *target)
05483 {
05484   TMR_Status ret;
05485   LLRP_tSSET_READER_CONFIG                *pCmd;
05486   LLRP_tSMessage                          *pCmdMsg;
05487   LLRP_tSMessage                          *pRspMsg;
05488   LLRP_tSSET_READER_CONFIG_RESPONSE       *pRsp;
05489   LLRP_tSThingMagicProtocolConfiguration  *pProtoConfig;
05490   LLRP_tSGen2CustomParameters             *pGen2Custom;
05491   LLRP_tSThingMagicTargetStrategy         *gen2target;
05492 
05493   ret = TMR_SUCCESS;
05499   pCmd = LLRP_SET_READER_CONFIG_construct();
05500 
05501   /* Initialize Protocol configuration */
05502   pProtoConfig = LLRP_ThingMagicProtocolConfiguration_construct();
05503 
05504   /* Initialize gen2 Target */
05505   gen2target = LLRP_ThingMagicTargetStrategy_construct();
05506   gen2target->eThingMagicTargetStrategyValue = (LLRP_tEThingMagicC1G2TargetStrategy)*target;
05507 
05508   /* Initialize gen2 custom parameter */
05509   pGen2Custom = LLRP_Gen2CustomParameters_construct();
05510   LLRP_Gen2CustomParameters_setThingMagicTargetStrategy(pGen2Custom, gen2target);
05511 
05512   /* Set Gen2 Custom parameter to protocol configuration */
05513   LLRP_ThingMagicProtocolConfiguration_setGen2CustomParameters(pProtoConfig,
05514       pGen2Custom);
05515 
05516   /* Add ThingMagic Protocol configuration as a custom parameter*/
05517   LLRP_SET_READER_CONFIG_addCustom(pCmd, (LLRP_tSParameter *)pProtoConfig);
05518 
05519   pCmdMsg = &pCmd->hdr;
05523   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
05528   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05529   if (TMR_SUCCESS != ret)
05530   {
05531     return ret;
05532   }
05533 
05537   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
05538   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
05539   {
05540     TMR_LLRP_freeMessage(pRspMsg);
05541     return TMR_ERROR_LLRP; 
05542   }
05543 
05547   TMR_LLRP_freeMessage(pRspMsg);
05548   return ret;
05549 }
05550 
05557 TMR_Status
05558 TMR_LLRP_cmdSetTMLicenseKey(TMR_Reader *reader, TMR_uint8List *license)
05559 {
05560   TMR_Status ret;
05561   LLRP_tSSET_READER_CONFIG                *pCmd;
05562   LLRP_tSMessage                          *pCmdMsg;
05563   LLRP_tSMessage                          *pRspMsg;
05564   LLRP_tSSET_READER_CONFIG_RESPONSE       *pRsp;
05565   LLRP_tSThingMagicLicenseKey             *pTMLicense;
05566 
05567   ret = TMR_SUCCESS;
05573   pCmd = LLRP_SET_READER_CONFIG_construct();
05574 
05575   /* Initialize ThingMagic LicenseKey  */
05576   pTMLicense = LLRP_ThingMagicLicenseKey_construct();
05577 
05578   /* Set the License key */
05579   llrp_u8v_t key;
05580   key = LLRP_u8v_construct(license->len);
05581   key.nValue = license->len;
05582   memcpy(key.pValue, license->list, license->len);
05583 
05584   LLRP_ThingMagicLicenseKey_setLicenseKey(pTMLicense, key);
05585 
05586   /* Add ThingMagic License key  as a custom parameter*/
05587   LLRP_SET_READER_CONFIG_addCustom(pCmd, (LLRP_tSParameter *)pTMLicense);
05588 
05589   pCmdMsg = &pCmd->hdr;
05593   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
05598   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05599   if (TMR_SUCCESS != ret)
05600   {
05601     return ret;
05602   }
05603 
05607   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
05608   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
05609   {
05610     TMR_LLRP_freeMessage(pRspMsg);
05611     return TMR_ERROR_LLRP; 
05612   }
05613 
05617   TMR_LLRP_freeMessage(pRspMsg);
05618   return ret;
05619 }
05620 
05627 TMR_Status
05628 TMR_LLRP_cmdSetTMAsyncOffTime(TMR_Reader *reader, uint32_t offtime)
05629 {
05630   TMR_Status ret;
05631   LLRP_tSSET_READER_CONFIG                *pCmd;
05632   LLRP_tSMessage                          *pCmdMsg;
05633   LLRP_tSMessage                          *pRspMsg;
05634   LLRP_tSSET_READER_CONFIG_RESPONSE       *pRsp;
05635   LLRP_tSThingMagicAsyncOFFTime           *pTMAsyncOffTime;
05636 
05637   ret = TMR_SUCCESS;
05643   pCmd = LLRP_SET_READER_CONFIG_construct();
05644 
05645   /* Initialize ThingMagic LicenseKey  */
05646   pTMAsyncOffTime = LLRP_ThingMagicAsyncOFFTime_construct();
05647 
05648   /* Set the License key */
05649 
05650   LLRP_ThingMagicAsyncOFFTime_setAsyncOFFTime(pTMAsyncOffTime, (llrp_u32_t)offtime);
05651 
05652   /* Add ThingMagic License key  as a custom parameter*/
05653   LLRP_SET_READER_CONFIG_addCustom(pCmd, (LLRP_tSParameter *)pTMAsyncOffTime);
05654 
05655   pCmdMsg = &pCmd->hdr;
05659   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
05664   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05665   if (TMR_SUCCESS != ret)
05666   {
05667     return ret;
05668   }
05669 
05673   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
05674   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
05675   {
05676     TMR_LLRP_freeMessage(pRspMsg);
05677     return TMR_ERROR_LLRP; 
05678   }
05679 
05683   TMR_LLRP_freeMessage(pRspMsg);
05684   return ret;
05685 }
05686 
05687 #ifdef TMR_ENABLE_ISO180006B
05688 
05694 TMR_Status
05695 TMR_LLRP_cmdGetISO18K6BDelimiter(TMR_Reader *reader, TMR_ISO180006B_Delimiter *delimiter)
05696 {
05697   TMR_Status ret;
05698   LLRP_tSGET_READER_CONFIG                    *pCmd;
05699   LLRP_tSMessage                              *pCmdMsg;
05700   LLRP_tSMessage                              *pRspMsg;
05701   LLRP_tSGET_READER_CONFIG_RESPONSE           *pRsp;
05702   LLRP_tSThingMagicDeviceControlConfiguration *pTMProtoConfig;
05703   LLRP_tSParameter                            *pCustParam;
05704 
05705   ret = TMR_SUCCESS;
05709   pCmd = LLRP_GET_READER_CONFIG_construct();
05710   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_Identification);
05711 
05717   pTMProtoConfig = LLRP_ThingMagicDeviceControlConfiguration_construct();
05718   if (NULL == pTMProtoConfig)
05719   {
05720     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05721     return TMR_ERROR_LLRP;
05722   }
05723 
05728   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMProtoConfig, 
05729       LLRP_ThingMagicControlConfiguration_ThingMagicProtocolConfiguration);
05730   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMProtoConfig->hdr))
05731   {
05732     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMProtoConfig);
05733     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05734     return TMR_ERROR_LLRP;
05735   }
05736 
05737   pCmdMsg       = &pCmd->hdr;
05741   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
05746   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05747   if (TMR_SUCCESS != ret)
05748   {
05749     return ret;
05750   }
05751 
05755   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
05756   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
05757   {
05758     TMR_LLRP_freeMessage(pRspMsg);
05759     return TMR_ERROR_LLRP; 
05760   }
05761 
05765   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
05766   if (NULL != pCustParam)
05767   {
05768     LLRP_tSISO18K6BCustomParameters *iso18k6bCustParam;
05769     LLRP_tSThingMagicISO180006BDelimiter  *iso18k6bDelimiter;
05770 
05771     iso18k6bCustParam = LLRP_ThingMagicProtocolConfiguration_getISO18K6BCustomParameters(
05772         (LLRP_tSThingMagicProtocolConfiguration *)pCustParam);
05773 
05774     if (NULL != iso18k6bCustParam) 
05775     {
05776       iso18k6bDelimiter = LLRP_ISO18K6BCustomParameters_getThingMagicISO180006BDelimiter(iso18k6bCustParam);
05777       *delimiter = (TMR_ISO180006B_Delimiter)iso18k6bDelimiter->eISO18K6BDelimiter;
05778     }
05779     else
05780     {
05781       return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
05782     }
05783   }
05784   else
05785   {
05786     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
05787   }
05788 
05792   TMR_LLRP_freeMessage(pRspMsg);
05793   return ret;
05794 }
05795 
05802 TMR_Status
05803 TMR_LLRP_cmdSetISO18K6BDelimiter(TMR_Reader *reader, TMR_ISO180006B_Delimiter *delimiter)
05804 {
05805   TMR_Status ret;
05806   LLRP_tSSET_READER_CONFIG                *pCmd;
05807   LLRP_tSMessage                          *pCmdMsg;
05808   LLRP_tSMessage                          *pRspMsg;
05809   LLRP_tSSET_READER_CONFIG_RESPONSE       *pRsp;
05810   LLRP_tSThingMagicProtocolConfiguration  *pProtoConfig;
05811   LLRP_tSISO18K6BCustomParameters         *pISO18k6bCustParam;
05812   LLRP_tSThingMagicISO180006BDelimiter    *pISO18k6bDelimiter;
05813 
05814   ret = TMR_SUCCESS;
05820   pCmd = LLRP_SET_READER_CONFIG_construct();
05821 
05822   /* Initialize Protocol configuration */
05823   pProtoConfig = LLRP_ThingMagicProtocolConfiguration_construct();
05824 
05825   /* Initialize ISO 18K6B dedlimiter */
05826   pISO18k6bDelimiter = LLRP_ThingMagicISO180006BDelimiter_construct();
05827   pISO18k6bDelimiter->eISO18K6BDelimiter = (LLRP_tEThingMagicCustom18K6BDelimiter)*delimiter;
05828 
05829   /* Initialize ISO 18K6B custom parameter */
05830   pISO18k6bCustParam = LLRP_ISO18K6BCustomParameters_construct();
05831   LLRP_ISO18K6BCustomParameters_setThingMagicISO180006BDelimiter(pISO18k6bCustParam, pISO18k6bDelimiter);
05832 
05833   /* Set ISO 18K6B Custom parameter to protocol configuration */
05834   LLRP_ThingMagicProtocolConfiguration_setISO18K6BCustomParameters(pProtoConfig,
05835       pISO18k6bCustParam);
05836 
05837   /* Add ThingMagic Protocol configuration as a custom parameter*/
05838   LLRP_SET_READER_CONFIG_addCustom(pCmd, (LLRP_tSParameter *)pProtoConfig);
05839 
05840   pCmdMsg = &pCmd->hdr;
05844   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
05849   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05850   if (TMR_SUCCESS != ret)
05851   {
05852     return ret;
05853   }
05854 
05858   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
05859   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
05860   {
05861     TMR_LLRP_freeMessage(pRspMsg);
05862     return TMR_ERROR_LLRP; 
05863   }
05864 
05868   TMR_LLRP_freeMessage(pRspMsg);
05869   return ret;
05870 }
05871 
05878 TMR_Status
05879 TMR_LLRP_cmdGetISO18K6BModDepth(TMR_Reader *reader, TMR_ISO180006B_ModulationDepth *modDepth)
05880 {
05881   TMR_Status ret;
05882   LLRP_tSGET_READER_CONFIG                    *pCmd;
05883   LLRP_tSMessage                              *pCmdMsg;
05884   LLRP_tSMessage                              *pRspMsg;
05885   LLRP_tSGET_READER_CONFIG_RESPONSE           *pRsp;
05886   LLRP_tSThingMagicDeviceControlConfiguration *pTMProtoConfig;
05887   LLRP_tSParameter                            *pCustParam;
05888 
05889   ret = TMR_SUCCESS;
05893   pCmd = LLRP_GET_READER_CONFIG_construct();
05894   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_Identification);
05895 
05901   pTMProtoConfig = LLRP_ThingMagicDeviceControlConfiguration_construct();
05902   if (NULL == pTMProtoConfig)
05903   {
05904     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05905     return TMR_ERROR_LLRP;
05906   }
05907 
05912   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMProtoConfig, 
05913       LLRP_ThingMagicControlConfiguration_ThingMagicProtocolConfiguration);
05914   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMProtoConfig->hdr))
05915   {
05916     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMProtoConfig);
05917     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05918     return TMR_ERROR_LLRP;
05919   }
05920 
05921   pCmdMsg       = &pCmd->hdr;
05925   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
05930   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
05931   if (TMR_SUCCESS != ret)
05932   {
05933     return ret;
05934   }
05935 
05939   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
05940   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
05941   {
05942     TMR_LLRP_freeMessage(pRspMsg);
05943     return TMR_ERROR_LLRP; 
05944   }
05945 
05949   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
05950   if (NULL != pCustParam)
05951   {
05952     LLRP_tSISO18K6BCustomParameters          *pISO18k6bCustParam;
05953     LLRP_tSThingMagicISO18K6BModulationDepth *pISO18k6bModDepth;
05954 
05955     pISO18k6bCustParam = LLRP_ThingMagicProtocolConfiguration_getISO18K6BCustomParameters(
05956         (LLRP_tSThingMagicProtocolConfiguration *)pCustParam);
05957 
05958     if (NULL != pISO18k6bCustParam) 
05959     {
05960       pISO18k6bModDepth = LLRP_ISO18K6BCustomParameters_getThingMagicISO18K6BModulationDepth(pISO18k6bCustParam);
05961       *modDepth = (TMR_ISO180006B_ModulationDepth)pISO18k6bModDepth->eISO18K6BModulationDepth;
05962     }
05963     else {
05964       return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
05965     }
05966   }
05967   else
05968   {
05969     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
05970   }
05971 
05975   TMR_LLRP_freeMessage(pRspMsg);
05976   return ret;
05977 }
05978 
05985 TMR_Status
05986 TMR_LLRP_cmdSetISO18K6BModDepth(TMR_Reader *reader, TMR_ISO180006B_ModulationDepth *modDepth)
05987 {
05988   TMR_Status ret;
05989   LLRP_tSSET_READER_CONFIG                *pCmd;
05990   LLRP_tSMessage                          *pCmdMsg;
05991   LLRP_tSMessage                          *pRspMsg;
05992   LLRP_tSSET_READER_CONFIG_RESPONSE       *pRsp;
05993   LLRP_tSThingMagicProtocolConfiguration  *pProtoConfig;
05994   LLRP_tSISO18K6BCustomParameters         *pISO18k6bCustParam;
05995   LLRP_tSThingMagicISO18K6BModulationDepth *pISO18k6bModDepth;
05996 
05997   ret = TMR_SUCCESS;
06003   pCmd = LLRP_SET_READER_CONFIG_construct();
06004 
06005   /* Initialize Protocol configuration */
06006   pProtoConfig = LLRP_ThingMagicProtocolConfiguration_construct();
06007 
06008   /* Initialize ISO 18K6B modulation Depth */
06009   pISO18k6bModDepth = LLRP_ThingMagicISO18K6BModulationDepth_construct();
06010   pISO18k6bModDepth->eISO18K6BModulationDepth = (LLRP_tEThingMagicCustom18K6BModulationDepth)*modDepth;
06011 
06012   /* Initialize ISO 18K6B custom parameter */
06013   pISO18k6bCustParam = LLRP_ISO18K6BCustomParameters_construct();
06014   LLRP_ISO18K6BCustomParameters_setThingMagicISO18K6BModulationDepth(pISO18k6bCustParam, pISO18k6bModDepth);
06015 
06016   /* Set ISO 18K6B Custom parameter to protocol configuration */
06017   LLRP_ThingMagicProtocolConfiguration_setISO18K6BCustomParameters(pProtoConfig,
06018       pISO18k6bCustParam);
06019 
06020   /* Add ThingMagic Protocol configuration as a custom parameter*/
06021   LLRP_SET_READER_CONFIG_addCustom(pCmd, (LLRP_tSParameter *)pProtoConfig);
06022 
06023   pCmdMsg = &pCmd->hdr;
06027   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
06032   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
06033   if (TMR_SUCCESS != ret)
06034   {
06035     return ret;
06036   }
06037 
06041   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
06042   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
06043   {
06044     TMR_LLRP_freeMessage(pRspMsg);
06045     return TMR_ERROR_LLRP; 
06046   }
06047 
06051   TMR_LLRP_freeMessage(pRspMsg);
06052   return ret;
06053 }
06054 
06061 TMR_Status
06062 TMR_LLRP_cmdGetISO18K6BLinkFrequency(TMR_Reader *reader, TMR_ISO180006B_LinkFrequency *linkFreq)
06063 {
06064   TMR_Status ret;
06065   LLRP_tSGET_READER_CONFIG                    *pCmd;
06066   LLRP_tSMessage                              *pCmdMsg;
06067   LLRP_tSMessage                              *pRspMsg;
06068   LLRP_tSGET_READER_CONFIG_RESPONSE           *pRsp;
06069   LLRP_tSThingMagicDeviceControlConfiguration *pTMProtoConfig;
06070   LLRP_tSParameter                            *pCustParam;
06071 
06072   ret = TMR_SUCCESS;
06076   pCmd = LLRP_GET_READER_CONFIG_construct();
06077   LLRP_GET_READER_CONFIG_setRequestedData(pCmd, LLRP_GetReaderConfigRequestedData_Identification);
06078 
06084   pTMProtoConfig = LLRP_ThingMagicDeviceControlConfiguration_construct();
06085   if (NULL == pTMProtoConfig)
06086   {
06087     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
06088     return TMR_ERROR_LLRP;
06089   }
06090 
06095   LLRP_ThingMagicDeviceControlConfiguration_setRequestedData(pTMProtoConfig, 
06096       LLRP_ThingMagicControlConfiguration_ThingMagicProtocolConfiguration);
06097   if (LLRP_RC_OK != LLRP_GET_READER_CONFIG_addCustom(pCmd, &pTMProtoConfig->hdr))
06098   {
06099     TMR_LLRP_freeMessage((LLRP_tSMessage *)pTMProtoConfig);
06100     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
06101     return TMR_ERROR_LLRP;
06102   }
06103 
06104   pCmdMsg       = &pCmd->hdr;
06108   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
06113   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
06114   if (TMR_SUCCESS != ret)
06115   {
06116     return ret;
06117   }
06118 
06122   pRsp = (LLRP_tSGET_READER_CONFIG_RESPONSE *) pRspMsg;
06123   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
06124   {
06125     TMR_LLRP_freeMessage(pRspMsg);
06126     return TMR_ERROR_LLRP; 
06127   }
06128 
06132   pCustParam = LLRP_GET_READER_CONFIG_RESPONSE_beginCustom(pRsp);
06133   if (NULL != pCustParam)
06134   {
06135     LLRP_tSISO18K6BCustomParameters *iso18k6bCustParam;
06136     LLRP_tSThingMagicISO18K6BLinkFrequency  *iso18k6blinkFreq;
06137 
06138     iso18k6bCustParam = LLRP_ThingMagicProtocolConfiguration_getISO18K6BCustomParameters(
06139         (LLRP_tSThingMagicProtocolConfiguration *)pCustParam);
06140 
06141     if (NULL != iso18k6bCustParam) 
06142     {
06143       iso18k6blinkFreq =  LLRP_ISO18K6BCustomParameters_getThingMagicISO18K6BLinkFrequency(iso18k6bCustParam);
06144       *linkFreq = (TMR_ISO180006B_LinkFrequency)iso18k6blinkFreq->eISO18K6BLinkFrequency;
06145     }
06146     else
06147     {
06148       return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
06149     }
06150   }
06151   else
06152   {
06153     return TMR_ERROR_LLRP_MSG_PARSE_ERROR;
06154   }
06155 
06159   TMR_LLRP_freeMessage(pRspMsg);
06160   return ret;
06161 }
06162 
06169 TMR_Status
06170 TMR_LLRP_cmdSetISO18K6BLinkFrequency(TMR_Reader *reader, TMR_ISO180006B_LinkFrequency *linkFreq)
06171 {
06172   TMR_Status ret;
06173   LLRP_tSSET_READER_CONFIG                *pCmd;
06174   LLRP_tSMessage                          *pCmdMsg;
06175   LLRP_tSMessage                          *pRspMsg;
06176   LLRP_tSSET_READER_CONFIG_RESPONSE       *pRsp;
06177   LLRP_tSThingMagicProtocolConfiguration  *pProtoConfig;
06178   LLRP_tSISO18K6BCustomParameters         *pISO18k6bCustParam;
06179   LLRP_tSThingMagicISO18K6BLinkFrequency  *pISO18k6blinkFreq;
06180 
06181   ret = TMR_SUCCESS;
06187   pCmd = LLRP_SET_READER_CONFIG_construct();
06188 
06189   /* Initialize Protocol configuration */
06190   pProtoConfig = LLRP_ThingMagicProtocolConfiguration_construct();
06191 
06192   /* Initialize ISO 18K6B linkFrequency */
06193   pISO18k6blinkFreq = LLRP_ThingMagicISO18K6BLinkFrequency_construct();
06194   pISO18k6blinkFreq->eISO18K6BLinkFrequency = (LLRP_tEThingMagicCustom18K6BLinkFrequency)*linkFreq;
06195 
06196   /* Initialize ISO 18K6B custom parameter */
06197   pISO18k6bCustParam = LLRP_ISO18K6BCustomParameters_construct();
06198   LLRP_ISO18K6BCustomParameters_setThingMagicISO18K6BLinkFrequency(pISO18k6bCustParam, pISO18k6blinkFreq);
06199 
06200   /* Set ISO 18K6B Custom parameter to protocol configuration */
06201   LLRP_ThingMagicProtocolConfiguration_setISO18K6BCustomParameters(pProtoConfig,
06202       pISO18k6bCustParam);
06203 
06204   /* Add ThingMagic Protocol configuration as a custom parameter*/
06205   LLRP_SET_READER_CONFIG_addCustom(pCmd, (LLRP_tSParameter *)pProtoConfig);
06206 
06207   pCmdMsg = &pCmd->hdr;
06211   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
06216   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
06217   if (TMR_SUCCESS != ret)
06218   {
06219     return ret;
06220   }
06221 
06225   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
06226   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
06227   {
06228     TMR_LLRP_freeMessage(pRspMsg);
06229     return TMR_ERROR_LLRP; 
06230   }
06231 
06235   TMR_LLRP_freeMessage(pRspMsg);
06236   return ret;
06237 }
06238 #endif /* TMR_ENABLE_ISO180006B */
06239 
06240 TMR_Status
06241 TMR_LLRP_stopActiveROSpecs(TMR_Reader *reader)
06242 {
06243   TMR_Status ret;
06244   LLRP_tSGET_ROSPECS                    *pCmd;
06245   LLRP_tSMessage                        *pCmdMsg;
06246   LLRP_tSMessage                        *pRspMsg;
06247   LLRP_tSGET_ROSPECS_RESPONSE           *pRsp;
06248   LLRP_tSROSpec                         *pROSpec;
06249 
06250   ret = TMR_SUCCESS;
06254   pCmd = LLRP_GET_ROSPECS_construct();
06255   pCmdMsg = &pCmd->hdr;
06256   
06260   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
06265   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
06266   if (TMR_SUCCESS != ret)
06267   {
06268     return ret;
06269   }
06270 
06274   pRsp = (LLRP_tSGET_ROSPECS_RESPONSE *) pRspMsg;
06275   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus)) 
06276   {
06277     TMR_LLRP_freeMessage(pRspMsg);
06278     return TMR_ERROR_LLRP;
06279   }
06280 
06284   for (pROSpec = LLRP_GET_ROSPECS_RESPONSE_beginROSpec(pRsp);
06285         NULL != pROSpec;
06286         pROSpec = LLRP_GET_ROSPECS_RESPONSE_nextROSpec(pROSpec))
06287   {
06288     /* If this ROSpec is actively running, then stop it */
06289     if (LLRP_ROSpecState_Active == pROSpec->eCurrentState)
06290     {
06291       reader->u.llrpReader.roSpecId = pROSpec->ROSpecID;
06292       ret = TMR_LLRP_cmdStopROSpec(reader, true);
06293     }
06294     if (LLRP_ROSpecStartTriggerType_Periodic ==
06295         pROSpec->pROBoundarySpec->pROSpecStartTrigger->eROSpecStartTriggerType)
06296     {
06297       reader->u.llrpReader.roSpecId = pROSpec->ROSpecID;
06298       ret = TMR_LLRP_cmdDisableROSpec(reader);
06299     }
06300   }
06301 
06302   /* Revert back to default value */
06303   reader->u.llrpReader.roSpecId = 0;
06307   TMR_LLRP_freeMessage(pRspMsg);
06308   return ret;
06309 }
06310 
06311 TMR_Status
06312 TMR_LLRP_enableEventsAndReports(TMR_Reader *reader)
06313 {
06314   TMR_Status ret;
06315   LLRP_tSENABLE_EVENTS_AND_REPORTS *pCmd;
06316   LLRP_tSMessage                   *pCmdMsg;
06317 
06318   ret = TMR_SUCCESS;
06319 
06323   pCmd = LLRP_ENABLE_EVENTS_AND_REPORTS_construct();
06324   pCmdMsg = &pCmd->hdr;
06325  
06330   ret = TMR_LLRP_sendMessage(reader, pCmdMsg, 
06331           reader->u.llrpReader.transportTimeout);
06336   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
06337   if (TMR_SUCCESS != ret)
06338   {
06339     return ret;
06340   }
06341 
06342   return ret;
06343 }
06344 
06345 TMR_Status
06346 TMR_LLRP_setHoldEventsAndReportsStatus(TMR_Reader *reader, llrp_u1_t status)
06347 {
06348   TMR_Status ret;
06349   LLRP_tSSET_READER_CONFIG                *pCmd;
06350   LLRP_tSMessage                          *pCmdMsg;
06351   LLRP_tSMessage                          *pRspMsg;
06352   LLRP_tSSET_READER_CONFIG_RESPONSE       *pRsp;
06353   LLRP_tSEventsAndReports                 *pEvents;
06354 
06355   ret = TMR_SUCCESS;
06360   pCmd = LLRP_SET_READER_CONFIG_construct();
06361 
06362   /* Initialize EventsAndReports  */
06363   pEvents = LLRP_EventsAndReports_construct();
06364   LLRP_EventsAndReports_setHoldEventsAndReportsUponReconnect(pEvents, status); 
06365 
06366 
06367   /* Add EventsAndReports to SET_READER_CONFIG*/
06368   LLRP_SET_READER_CONFIG_setEventsAndReports(pCmd, pEvents);
06369 
06370   pCmdMsg = &pCmd->hdr;
06374   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
06379   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
06380   if (TMR_SUCCESS != ret)
06381   {
06382     return ret;
06383   }
06384 
06388   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
06389   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus)) 
06390   {
06391     TMR_LLRP_freeMessage(pRspMsg);
06392     return TMR_ERROR_LLRP;
06393   }
06394 
06398   TMR_LLRP_freeMessage(pRspMsg);
06399 
06400   return ret;
06401 }
06402 
06403 
06404 TMR_Status
06405 TMR_LLRP_setKeepAlive(TMR_Reader *reader)
06406 {
06407   TMR_Status ret;
06408   LLRP_tSSET_READER_CONFIG                *pCmd;
06409   LLRP_tSMessage                          *pCmdMsg;
06410   LLRP_tSMessage                          *pRspMsg;
06411   LLRP_tSSET_READER_CONFIG_RESPONSE       *pRsp;
06412   LLRP_tSKeepaliveSpec                    *pKeepAlive;
06413 
06414   ret = TMR_SUCCESS;
06419   pCmd = LLRP_SET_READER_CONFIG_construct();
06420 
06421   /* Initialize Keep Alive Spec  */
06422   pKeepAlive = LLRP_KeepaliveSpec_construct();
06423   LLRP_KeepaliveSpec_setKeepaliveTriggerType(pKeepAlive, LLRP_KeepaliveTriggerType_Periodic);
06424   LLRP_KeepaliveSpec_setPeriodicTriggerValue(pKeepAlive, TMR_LLRP_KEEP_ALIVE_TIMEOUT);
06425 
06426 
06427   /* Add KeepaliveSpec to SET_READER_CONFIG*/
06428   LLRP_SET_READER_CONFIG_setKeepaliveSpec(pCmd, pKeepAlive);
06429 
06430   pCmdMsg = &pCmd->hdr;
06434   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
06439   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
06440   if (TMR_SUCCESS != ret)
06441   {
06442     return ret;
06443   }
06444 
06448   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
06449   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus)) 
06450   {
06451     TMR_LLRP_freeMessage(pRspMsg);
06452     return TMR_ERROR_LLRP;
06453   }
06454 
06458   TMR_LLRP_freeMessage(pRspMsg);
06459 
06463   return TMR_LLRP_startBackgroundReceiver(reader);
06464 }
06465 
06466 TMR_Status
06467 TMR_LLRP_handleReaderEvents(TMR_Reader *reader, LLRP_tSMessage *pMsg)
06468 {
06469   TMR_Status ret;
06470   LLRP_tSReaderEventNotificationData *pEventData;
06471   
06472   ret = TMR_SUCCESS;
06473   pEventData = ((LLRP_tSREADER_EVENT_NOTIFICATION *)pMsg)->pReaderEventNotificationData;
06474 
06478   if (NULL != pEventData->pROSpecEvent)
06479   {
06484     if ((LLRP_ROSpecEventType_End_Of_ROSpec ==
06485         pEventData->pROSpecEvent->eEventType) &&
06486         (false == reader->continuousReading))
06487     {
06492       pthread_mutex_lock(&reader->u.llrpReader.receiverLock);
06493       reader->u.llrpReader.numOfROSpecEvents --;
06494       if(reader->u.llrpReader.numOfROSpecEvents <= 0 ) {
06495         pthread_cond_broadcast(&reader->u.llrpReader.receiverCond);
06496       }
06497       pthread_mutex_unlock(&reader->u.llrpReader.receiverLock);
06498     }
06499   }
06500 
06510   TMR_LLRP_freeMessage(pMsg);
06511   return ret;
06512 }
06513 
06514 TMR_Status
06515 TMR_LLRP_handleKeepAlive(TMR_Reader *reader, LLRP_tSMessage *pMsg)
06516 {
06517   TMR_Status ret;
06518   LLRP_tSMessage                          *pCmdMsg;
06519   LLRP_tSKEEPALIVE_ACK                    *pAck;
06520 
06521   ret = TMR_SUCCESS;
06522 
06527   TMR_LLRP_freeMessage(pMsg);
06528 
06532   pAck = LLRP_KEEPALIVE_ACK_construct();
06533   pCmdMsg = &pAck->hdr;
06537   ret = TMR_LLRP_sendMessage(reader, pCmdMsg,
06538                 reader->u.llrpReader.transportTimeout);
06539   if (TMR_SUCCESS != ret)
06540   {
06541     return ret;
06542   }
06543 
06544   /*
06545    * Response is success, and done with the command
06546    */
06547   TMR_LLRP_freeMessage((LLRP_tSMessage *)pAck);
06548 
06549   return TMR_SUCCESS;
06550 }
06551 
06552 static void *
06553 llrp_receiver_thread(void *arg)
06554 {
06555   TMR_Status ret;
06556   TMR_Reader *reader;
06557   TMR_LLRP_LlrpReader *lr;
06558   LLRP_tSMessage *pMsg;
06559   LLRP_tSConnection *pConn;
06560   struct timeval tv;
06561   fd_set set;
06562   bool ka_start_flag = true;
06563   bool receive_failed = false;
06564 
06565   ret = TMR_SUCCESS;
06566   reader = arg;
06567   lr = &reader->u.llrpReader;
06568 
06573   while (true)
06574   {
06575     pConn = reader->u.llrpReader.pConn;
06576     if (NULL != pConn)
06577     {
06578       pthread_mutex_lock(&lr->receiverLock);
06579       lr->receiverRunning = false;
06580       pthread_cond_broadcast(&lr->receiverCond);
06581       while (false == lr->receiverEnabled)
06582       {
06583         pthread_cond_wait(&lr->receiverCond, &lr->receiverLock);
06584       }
06585     
06586       lr->receiverRunning = true;
06587       pthread_mutex_unlock(&lr->receiverLock);
06588 
06589       FD_ZERO(&set);
06590       FD_SET(pConn->fd, &set);
06591       tv.tv_sec = 0;
06592       tv.tv_usec = BACKGROUND_RECEIVER_LOOP_PERIOD * 1000;
06593       ret = select(pConn->fd + 1, &set, NULL, NULL, &tv);
06594       if (0 < ret)
06595       {
06596         /* check for new message in Inbox */
06597         ret = TMR_LLRP_receiveMessage(reader, &pMsg, lr->transportTimeout);
06598         if (TMR_SUCCESS != ret)
06599         {
06605           receive_failed = true;
06606         }
06607         else
06608         {
06613           ret = TMR_LLRP_processReceivedMessage(reader, pMsg);
06614           ka_start_flag = true;
06615           receive_failed = false;
06616         }
06617       }
06618     }
06619     else
06620     {
06621       receive_failed = true;
06622       /* We shouldn't be in here if pConn is NULL, but if it is sleep for a little bit and hopefully things will get better */
06623       tmr_sleep(1000);
06624     }
06625 
06626     if(true == receive_failed)
06627     {
06633       uint64_t diffTime;
06634 
06635       if (ka_start_flag)
06636       {
06637         reader->u.llrpReader.ka_start = tmr_gettime();
06638         ka_start_flag = false;
06639       }
06640       reader->u.llrpReader.ka_now = tmr_gettime();
06641       diffTime = reader->u.llrpReader.ka_now - reader->u.llrpReader.ka_start;
06642       if ((TMR_LLRP_KEEP_ALIVE_TIMEOUT * 4) < diffTime)
06643       {
06655         pthread_mutex_lock(&lr->receiverLock);
06656         lr->numOfROSpecEvents = -1;
06657         pthread_cond_broadcast(&lr->receiverCond);
06658         pthread_mutex_unlock(&lr->receiverLock);
06659         ka_start_flag = true;
06660       }
06661     }
06662 
06663     if (true == reader->u.llrpReader.threadCancel)
06664     {
06666       pthread_exit(NULL);
06667     }
06668   } /* End of while */
06669   return NULL;
06670 }
06671 
06672 TMR_Status
06673 TMR_LLRP_processReceivedMessage(TMR_Reader *reader, LLRP_tSMessage *pMsg)
06674 {
06675   TMR_Status ret;
06676   TMR_LLRP_LlrpReader *lr;
06677 
06678   ret = TMR_SUCCESS;
06679   lr = &reader->u.llrpReader;
06680 
06681   /* Check if it is a keepalive */
06682   if (&LLRP_tdKEEPALIVE == pMsg->elementHdr.pType)
06683   {
06688     ret = TMR_LLRP_handleKeepAlive(reader, pMsg);
06689   }
06690 
06694   else if (&LLRP_tdRO_ACCESS_REPORT == pMsg->elementHdr.pType)
06695   {
06701     if (NULL == lr->bufResponse)
06702     {
06703       /* We haven't had opportunity to allocate the buffer yet, so allocate the
06704        * first
06705        */
06706       lr->bufResponse = (LLRP_tSMessage **) malloc( 1 * sizeof(LLRP_tSMessage *));
06707       lr->bufPointer = 0;
06708     }
06709     lr->bufResponse[lr->bufPointer ] = pMsg;
06710 
06715     {
06716       LLRP_tSMessage **newResponse;
06717 
06718       newResponse = realloc(lr->bufResponse, (lr->bufPointer + 2) * sizeof(lr->bufResponse[0]));
06719       if (NULL == newResponse)
06720       {
06726       }
06727       lr->bufResponse = newResponse;
06728     }
06729 
06734     lr->bufPointer += 1;
06735   }
06736 
06740   else if (&LLRP_tdREADER_EVENT_NOTIFICATION  == pMsg->elementHdr.pType)
06741   {
06745     ret = TMR_LLRP_handleReaderEvents(reader, pMsg);
06746   }
06747 
06748   else
06749   {
06755     TMR_LLRP_freeMessage(pMsg);
06756   }
06757 
06758   return ret;
06759 }
06760 
06761 void
06762 TMR_LLRP_setBackgroundReceiverState(TMR_Reader *reader, bool state)
06763 {
06764   if (true == reader->u.llrpReader.receiverSetup)
06765   {
06766     if (false == state)
06767     {
06771       pthread_mutex_lock(&reader->u.llrpReader.receiverLock);
06772       reader->u.llrpReader.receiverEnabled = false;
06773       while (true == reader->u.llrpReader.receiverRunning)
06774       {
06775         pthread_cond_wait(&reader->u.llrpReader.receiverCond, &reader->u.llrpReader.receiverLock);
06776       }
06777       pthread_mutex_unlock(&reader->u.llrpReader.receiverLock);
06778     }
06779     else
06780     {
06784       pthread_mutex_lock(&reader->u.llrpReader.receiverLock);
06785       reader->u.llrpReader.receiverEnabled = true;
06786       pthread_cond_broadcast(&reader->u.llrpReader.receiverCond);
06787       pthread_mutex_unlock(&reader->u.llrpReader.receiverLock);
06788     }
06789   }
06790 }
06791 
06792 TMR_Status
06793 TMR_LLRP_startBackgroundReceiver(TMR_Reader *reader)
06794 {
06795   TMR_Status ret;
06796   TMR_LLRP_LlrpReader *lr = &reader->u.llrpReader;
06797 
06798   ret = TMR_SUCCESS;
06799 
06800   /* Initialize background llrp receiver */
06801   pthread_mutex_lock(&lr->receiverLock);
06802 
06803   ret = pthread_create(&lr->llrpReceiver, NULL,
06804                       llrp_receiver_thread, reader);
06805   if (0 != ret)
06806   {
06807     pthread_mutex_unlock(&lr->receiverLock);
06808     return TMR_ERROR_NO_THREADS;
06809   }
06810   
06811   pthread_setcanceltype(PTHREAD_CANCEL_ASYNCHRONOUS, NULL);
06812   pthread_setcancelstate(PTHREAD_CANCEL_ENABLE, NULL);
06813   
06814   lr->receiverSetup = true;
06815   lr->receiverEnabled = true;
06816   pthread_mutex_unlock(&lr->receiverLock);
06817 
06818   return TMR_SUCCESS;
06819 }
06820 
06821 TMR_Status
06822 TMR_LLRP_cmdSetEventNotificationSpec(TMR_Reader *reader, bool state)
06823 {
06824   TMR_Status ret;
06825   LLRP_tSSET_READER_CONFIG                *pCmd;
06826   LLRP_tSMessage                          *pCmdMsg;
06827   LLRP_tSMessage                          *pRspMsg;
06828   LLRP_tSSET_READER_CONFIG_RESPONSE       *pRsp;
06829   LLRP_tSReaderEventNotificationSpec      *pEventNotificationSpec;
06830   LLRP_tSEventNotificationState           *pEventNotificationState;
06831 
06832   ret = TMR_SUCCESS;
06837   pCmd = LLRP_SET_READER_CONFIG_construct();
06838 
06839   /* Initialize Reader Event Notification spec */
06840   pEventNotificationSpec = LLRP_ReaderEventNotificationSpec_construct();
06841 
06846   pEventNotificationState = LLRP_EventNotificationState_construct();
06847   LLRP_EventNotificationState_setEventType(pEventNotificationState,
06848                                    LLRP_NotificationEventType_ROSpec_Event);
06849   LLRP_EventNotificationState_setNotificationState(pEventNotificationState, (uint8_t)state);
06850 
06851   /* Set Event to EventNotificationSpec */
06852   LLRP_ReaderEventNotificationSpec_addEventNotificationState(pEventNotificationSpec,
06853                                                     pEventNotificationState);
06854 
06855 
06856   /* Add EventNotificationSpec to SET_READER_CONFIG*/
06857   LLRP_SET_READER_CONFIG_setReaderEventNotificationSpec(pCmd, pEventNotificationSpec);
06858 
06859   pCmdMsg = &pCmd->hdr;
06863   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
06868   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
06869   if (TMR_SUCCESS != ret)
06870   {
06871     return ret;
06872   }
06873 
06877   pRsp = (LLRP_tSSET_READER_CONFIG_RESPONSE *) pRspMsg;
06878   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))
06879   {
06880     TMR_LLRP_freeMessage(pRspMsg);
06881     return TMR_ERROR_LLRP;
06882   }
06883 
06887   TMR_LLRP_freeMessage(pRspMsg);
06888   return ret;
06889 }
06890 
06897 TMR_Status
06898 TMR_LLRP_cmdEnableAccessSpec(TMR_Reader *reader, llrp_u32_t accessSpecId)
06899 {
06900   TMR_Status ret;
06901   LLRP_tSENABLE_ACCESSSPEC          *pCmd;
06902   LLRP_tSMessage                    *pCmdMsg;
06903   LLRP_tSMessage                    *pRspMsg;
06904   LLRP_tSENABLE_ACCESSSPEC_RESPONSE *pRsp;
06905   
06906   ret = TMR_SUCCESS;
06907 
06911   pCmd = LLRP_ENABLE_ACCESSSPEC_construct();
06912   LLRP_ENABLE_ACCESSSPEC_setAccessSpecID(pCmd, accessSpecId);
06913 
06914   pCmdMsg = &pCmd->hdr;
06918   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
06923   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
06924   if (TMR_SUCCESS != ret)
06925   {
06926     return ret;
06927   }
06928 
06932   pRsp = (LLRP_tSENABLE_ACCESSSPEC_RESPONSE *) pRspMsg;
06933   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
06934   {
06935     TMR_LLRP_freeMessage(pRspMsg);
06936     return TMR_ERROR_LLRP; 
06937   }
06938 
06942   TMR_LLRP_freeMessage(pRspMsg);
06943 
06944   return ret;
06945 }
06946 
06955 TMR_Status
06956 TMR_LLRP_msgPrepareAccessCommand(TMR_Reader *reader,
06957                                   LLRP_tSAccessCommand *pAccessCommand, 
06958                                   TMR_TagFilter *filter, 
06959                                   TMR_TagOp *tagop)
06960 {
06961   TMR_Status ret;
06962 
06963   ret = TMR_SUCCESS;
06964 
06968   {
06969     LLRP_tSC1G2TagSpec *pTagSpec;
06970     LLRP_tSC1G2TargetTag *pTargetTag;
06971 
06972     /* Initialize TagSpec */
06973     pTagSpec = LLRP_C1G2TagSpec_construct();
06974     pTargetTag = LLRP_C1G2TargetTag_construct();
06975   
06983     /* Add TargetTag to TagSpec */
06984     LLRP_C1G2TagSpec_addC1G2TargetTag(pTagSpec, pTargetTag);
06985 
06989     LLRP_AccessCommand_setAirProtocolTagSpec(pAccessCommand,
06990                                               (LLRP_tSParameter *)pTagSpec);
06991   }
06992 
06996   {
06997     reader->u.llrpReader.opSpecId ++;
06998 
07003     switch (tagop->type)
07004     {
07005       case TMR_TAGOP_GEN2_READDATA:
07006         {
07007           TMR_TagOp_GEN2_ReadData *args;
07008           LLRP_tSC1G2Read         *pC1G2Read;
07009 
07010           args = &tagop->u.gen2.u.readData;
07011           
07012           /* Construct and initialize C1G2Read */
07013           pC1G2Read = LLRP_C1G2Read_construct();
07014           /* Set OpSpec Id */
07015           LLRP_C1G2Read_setOpSpecID(pC1G2Read, reader->u.llrpReader.opSpecId);
07016           /* Set access password */
07017           LLRP_C1G2Read_setAccessPassword(pC1G2Read, reader->u.llrpReader.gen2AccessPassword);
07018           /* Set Memory Bank */
07019           LLRP_C1G2Read_setMB(pC1G2Read, (llrp_u2_t)args->bank);
07020           /* Set word pointer */
07021           LLRP_C1G2Read_setWordPointer(pC1G2Read, args->wordAddress);
07022           /* Set word length to read */
07023           LLRP_C1G2Read_setWordCount(pC1G2Read, args->len);
07024 
07028           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand, 
07029                                           (LLRP_tSParameter *)pC1G2Read); 
07030           break;
07031         }
07032 
07033       case TMR_TAGOP_GEN2_BLOCKERASE:
07034         {
07035           TMR_TagOp_GEN2_BlockErase *args;
07036           LLRP_tSC1G2BlockErase     *pC1G2BlockErase;
07037 
07038           args = &tagop->u.gen2.u.blockErase;
07039 
07040           /* Construct and initialize C1G2BlockErase */
07041           pC1G2BlockErase = LLRP_C1G2BlockErase_construct();
07042           /* Set OpSpec Id */
07043           LLRP_C1G2BlockErase_setOpSpecID(pC1G2BlockErase, reader->u.llrpReader.opSpecId);
07044           /* Set access password */
07045           LLRP_C1G2BlockErase_setAccessPassword(pC1G2BlockErase, reader->u.llrpReader.gen2AccessPassword);
07046           /* Set Memory Bank */
07047           LLRP_C1G2BlockErase_setMB(pC1G2BlockErase, (llrp_u2_t)args->bank);
07048           /* Set word pointer */
07049           LLRP_C1G2BlockErase_setWordPointer(pC1G2BlockErase, args->wordPtr);
07050           /* Set word count to erase */
07051           LLRP_C1G2BlockErase_setWordCount(pC1G2BlockErase, (llrp_u16_t)args->wordCount);
07052 
07056           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07057                                       (LLRP_tSParameter *)pC1G2BlockErase);
07058           break;
07059         }
07060 
07061       case TMR_TAGOP_GEN2_WRITETAG:
07062         {
07063           TMR_TagOp_GEN2_WriteTag     *args;
07064           LLRP_tSThingMagicWriteTag   *pC1G2WriteTag;
07065           llrp_u16v_t                  data;
07066           int                          i,j;
07067 
07068           args = &tagop->u.gen2.u.writeTag;
07069 
07070           /* Construct and initialize ThingMagicWriteTag */
07071           pC1G2WriteTag = LLRP_ThingMagicWriteTag_construct();
07072           /* Set OpSpec Id */
07073           LLRP_ThingMagicWriteTag_setOpSpecID(pC1G2WriteTag, reader->u.llrpReader.opSpecId);
07074           /* Set access password */
07075           LLRP_ThingMagicWriteTag_setAccessPassword(pC1G2WriteTag, reader->u.llrpReader.gen2AccessPassword);
07076           /* Set the data to be written */
07077           /* As API epc datatype is uint8_t but
07078            * llrp takes epc of type uint16_t
07079            * so, mapping the uint8_t data into uint16_t
07080            */
07081           data = LLRP_u16v_construct((llrp_u16_t) (args->epcptr->epcByteCount / 2));
07082           for(i = 0, j = 0;i < data.nValue; i++, j+=2)
07083           {
07084             data.pValue[i] = (args->epcptr->epc[j] << 8) | args->epcptr->epc[j + 1];
07085           }
07086 
07087           LLRP_ThingMagicWriteTag_setWriteData (pC1G2WriteTag, data);
07088 
07092           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07093               (LLRP_tSParameter *)pC1G2WriteTag);
07094          
07095           break;
07096         }
07097 
07098       case TMR_TAGOP_GEN2_WRITEDATA:
07099         {
07100           TMR_TagOp_GEN2_WriteData *args;
07101           LLRP_tSC1G2Write         *pC1G2WriteData;
07102           llrp_u16v_t               data;
07103 
07104           args = &tagop->u.gen2.u.writeData;
07105 
07106           /* Construct and initialize C1GWrite */
07107           pC1G2WriteData = LLRP_C1G2Write_construct();
07108           /* Set OpSpec Id */
07109           LLRP_C1G2Write_setOpSpecID(pC1G2WriteData, reader->u.llrpReader.opSpecId);
07110           /* Set access password */
07111           LLRP_C1G2Write_setAccessPassword(pC1G2WriteData, reader->u.llrpReader.gen2AccessPassword);
07112           /* Set Memory Bank */
07113           LLRP_C1G2Write_setMB(pC1G2WriteData, (llrp_u2_t)args->bank);
07114           /* Set word pointer */
07115           LLRP_C1G2Write_setWordPointer(pC1G2WriteData, args->wordAddress);
07116           /* Set the data to be written */
07117           data = LLRP_u16v_construct (args->data.len);
07118           memcpy (data.pValue, args->data.list, data.nValue * sizeof(uint16_t));
07119           LLRP_C1G2Write_setWriteData (pC1G2WriteData, data);
07120 
07125           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07126               (LLRP_tSParameter *)pC1G2WriteData);
07127          
07128           break;
07129         }
07130 
07131       case TMR_TAGOP_GEN2_BLOCKPERMALOCK:
07132         {
07133           TMR_TagOp_GEN2_BlockPermaLock      *args;
07134           LLRP_tSThingMagicBlockPermalock    *pC1G2BlockPermaLock;
07135           llrp_u16v_t                        mask;
07136 
07137           args = &tagop->u.gen2.u.blockPermaLock;
07138 
07139           /* Construct and initialize BlockPermaLock */
07140           pC1G2BlockPermaLock = LLRP_ThingMagicBlockPermalock_construct();
07141           /* Set OpSpec Id */
07142           LLRP_ThingMagicBlockPermalock_setOpSpecID(pC1G2BlockPermaLock, 
07143                                             reader->u.llrpReader.opSpecId);
07144           /* Set access password */
07145           LLRP_ThingMagicBlockPermalock_setAccessPassword(pC1G2BlockPermaLock,
07146                                       reader->u.llrpReader.gen2AccessPassword);
07147           /* Set ReadLock */
07148           LLRP_ThingMagicBlockPermalock_setReadLock(pC1G2BlockPermaLock, args->readLock);
07149           /* Set Memory Bank */
07150           LLRP_ThingMagicBlockPermalock_setMB(pC1G2BlockPermaLock, (llrp_u2_t)args->bank);
07151           /* Set block pointer */
07152           LLRP_ThingMagicBlockPermalock_setBlockPointer(pC1G2BlockPermaLock, 
07153                                                             args->blockPtr);
07154           /* Set block range mask */
07155           mask = LLRP_u16v_construct(args->mask.len);
07156           memcpy(mask.pValue, args->mask.list, mask.nValue * sizeof(uint16_t));
07157           LLRP_ThingMagicBlockPermalock_setBlockMask(pC1G2BlockPermaLock, mask);
07158 
07162           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07163                                       (LLRP_tSParameter *)pC1G2BlockPermaLock);
07164  
07165           break;
07166         }
07167 
07168       case TMR_TAGOP_GEN2_ALIEN_HIGGS2_PARTIALLOADIMAGE:
07169         {
07170           TMR_TagOp_GEN2_Alien_Higgs2_PartialLoadImage *args;
07171           LLRP_tSThingMagicHiggs2PartialLoadImage      *pHiggs2PartialLoadImage;
07172           llrp_u8v_t                                    epc;
07173 
07174           args = &tagop->u.gen2.u.custom.u.alien.u.higgs2.u.partialLoadImage;
07175 
07179           if ((args->epcptr->epcByteCount > 12) || 
07180               (args->epcptr->epcByteCount <=0))
07181           { 
07182             /* Only 96 bit epc */
07183             return TMR_ERROR_PROTOCOL_INVALID_EPC;
07184           }    
07185 
07186           /* Construct and initialize Higgs2PartialLoadImage */
07187           pHiggs2PartialLoadImage = LLRP_ThingMagicHiggs2PartialLoadImage_construct();
07188           /* Set OpSpec Id */
07189           LLRP_ThingMagicHiggs2PartialLoadImage_setOpSpecID(pHiggs2PartialLoadImage, 
07190                                                       reader->u.llrpReader.opSpecId);
07191           /* Set access password to use to write on tag */
07192           LLRP_ThingMagicHiggs2PartialLoadImage_setCurrentAccessPassword(
07193               pHiggs2PartialLoadImage, reader->u.llrpReader.gen2AccessPassword);
07194           /* Set Kill Password to be written on tag */
07195           LLRP_ThingMagicHiggs2PartialLoadImage_setKillPassword(pHiggs2PartialLoadImage,
07196                                                                     args->killPassword);
07197           /* Set access password to be written on tag */
07198           LLRP_ThingMagicHiggs2PartialLoadImage_setAccessPassword(pHiggs2PartialLoadImage,
07199                                                                     args->accessPassword);
07200           /* Set EPC to be written */
07201           epc = LLRP_u8v_construct (args->epcptr->epcByteCount * sizeof(uint8_t));
07202           memcpy (epc.pValue, args->epcptr->epc, epc.nValue);
07203           LLRP_ThingMagicHiggs2PartialLoadImage_setEPCData(pHiggs2PartialLoadImage, epc);
07204 
07208           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07209               (LLRP_tSParameter *)pHiggs2PartialLoadImage);
07210  
07211           break;
07212         }
07213 
07214       case TMR_TAGOP_GEN2_ALIEN_HIGGS2_FULLLOADIMAGE:
07215         {
07216           TMR_TagOp_GEN2_Alien_Higgs2_FullLoadImage *args;
07217           LLRP_tSThingMagicHiggs2FullLoadImage      *pOpSpec;
07218           llrp_u8v_t                                epc;
07219 
07220           args = &tagop->u.gen2.u.custom.u.alien.u.higgs2.u.fullLoadImage;
07221 
07225           if ((args->epcptr->epcByteCount > 12) || 
07226               (args->epcptr->epcByteCount <=0))
07227           { 
07228             /* Only 96 bit epc */
07229             return TMR_ERROR_PROTOCOL_INVALID_EPC;
07230           }    
07231 
07232           /* Construct and initialize Higgs2FullLoadImage */
07233           pOpSpec = LLRP_ThingMagicHiggs2FullLoadImage_construct();
07234           /* Set OpSpec Id */
07235           LLRP_ThingMagicHiggs2FullLoadImage_setOpSpecID(pOpSpec, 
07236                                   reader->u.llrpReader.opSpecId);
07237           /* Set access password to use to write on tag */
07238           LLRP_ThingMagicHiggs2FullLoadImage_setCurrentAccessPassword(
07239                       pOpSpec, reader->u.llrpReader.gen2AccessPassword);
07240           /* Set Kill Password to be written on tag */
07241           LLRP_ThingMagicHiggs2FullLoadImage_setKillPassword(pOpSpec, args->killPassword);
07242           /* Set access password to be written on tag */
07243           LLRP_ThingMagicHiggs2FullLoadImage_setAccessPassword(pOpSpec, args->accessPassword);
07244           /* Set LockBits */
07245           LLRP_ThingMagicHiggs2FullLoadImage_setLockBits(pOpSpec, args->lockBits);
07246           /* Set PCWord */
07247           LLRP_ThingMagicHiggs2FullLoadImage_setPCWord(pOpSpec, args->pcWord);
07248           /* Set EPC to be written */
07249           epc = LLRP_u8v_construct (args->epcptr->epcByteCount * sizeof(uint8_t));
07250           memcpy (epc.pValue, args->epcptr->epc, epc.nValue);
07251           LLRP_ThingMagicHiggs2FullLoadImage_setEPCData(pOpSpec, epc);
07252 
07256           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07257                                       (LLRP_tSParameter *)pOpSpec);
07258  
07259           break;
07260         }
07261 
07262       case TMR_TAGOP_GEN2_ALIEN_HIGGS3_FASTLOADIMAGE:
07263         {
07264           TMR_TagOp_GEN2_Alien_Higgs3_FastLoadImage *args;
07265           LLRP_tSThingMagicHiggs3FastLoadImage      *pOpSpec;
07266           llrp_u8v_t                                epc;
07267 
07268           args = &tagop->u.gen2.u.custom.u.alien.u.higgs3.u.fastLoadImage;
07269 
07273           if ((args->epcptr->epcByteCount > 12) || 
07274               (args->epcptr->epcByteCount <=0))
07275           { 
07276             /* Only 96 bit epc */
07277             return TMR_ERROR_PROTOCOL_INVALID_EPC;
07278           }    
07279 
07280           /* Construct and initialize Higgs3FastLoadImage */
07281           pOpSpec = LLRP_ThingMagicHiggs3FastLoadImage_construct();
07282           /* Set OpSpec Id */
07283           LLRP_ThingMagicHiggs3FastLoadImage_setOpSpecID(pOpSpec, 
07284                                   reader->u.llrpReader.opSpecId);
07285           /* Set access password to use to write on tag */
07286           LLRP_ThingMagicHiggs3FastLoadImage_setCurrentAccessPassword(
07287                                   pOpSpec, args->currentAccessPassword);
07288           /* Set Kill Password to be written on tag */
07289           LLRP_ThingMagicHiggs3FastLoadImage_setKillPassword(pOpSpec, args->killPassword);
07290           /* Set access password to be written on tag */
07291           LLRP_ThingMagicHiggs3FastLoadImage_setAccessPassword(pOpSpec, args->accessPassword);
07292           /* Set PCWord */
07293           LLRP_ThingMagicHiggs3FastLoadImage_setPCWord(pOpSpec, args->pcWord);
07294           /* Set EPC to be written */
07295           epc = LLRP_u8v_construct (args->epcptr->epcByteCount * sizeof(uint8_t));
07296           memcpy (epc.pValue, args->epcptr->epc, epc.nValue);
07297           LLRP_ThingMagicHiggs3FastLoadImage_setEPCData(pOpSpec, epc);
07298 
07302           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07303                                       (LLRP_tSParameter *)pOpSpec);
07304  
07305           break;
07306         }
07307 
07308       case TMR_TAGOP_GEN2_ALIEN_HIGGS3_LOADIMAGE:
07309         {
07310           TMR_TagOp_GEN2_Alien_Higgs3_LoadImage *args;
07311           LLRP_tSThingMagicHiggs3LoadImage      *pOpSpec;
07312           llrp_u8v_t                            epcAndUserData;
07313 
07314           args = &tagop->u.gen2.u.custom.u.alien.u.higgs3.u.loadImage;
07315 
07319           if ((args->epcAndUserData->len > 76) || 
07320               (args->epcAndUserData->len <= 0))                                                                                                 
07321           { 
07322             /* Only 76 byte epcAndUserData */
07323             return TMR_ERROR_MSG_INVALID_PARAMETER_VALUE;
07324           }
07325 
07326           /* Construct and initialize Higgs3LoadImage */
07327           pOpSpec = LLRP_ThingMagicHiggs3LoadImage_construct();
07328           /* Set OpSpec Id */
07329           LLRP_ThingMagicHiggs3LoadImage_setOpSpecID(pOpSpec, 
07330                                reader->u.llrpReader.opSpecId);
07331           /* Set access password to use to write on tag */
07332           LLRP_ThingMagicHiggs3LoadImage_setCurrentAccessPassword(
07333                               pOpSpec, args->currentAccessPassword);
07334           /* Set Kill Password to be written on tag */
07335           LLRP_ThingMagicHiggs3LoadImage_setKillPassword(pOpSpec, args->killPassword);
07336           /* Set access password to be written on tag */
07337           LLRP_ThingMagicHiggs3LoadImage_setAccessPassword(pOpSpec, args->accessPassword);
07338           /* Set PCWord */
07339           LLRP_ThingMagicHiggs3LoadImage_setPCWord(pOpSpec, args->pcWord);
07340           /* Set EPC And User data to be written */
07341           epcAndUserData = LLRP_u8v_construct (args->epcAndUserData->len);
07342           memcpy (epcAndUserData.pValue, args->epcAndUserData->list,
07343                                  epcAndUserData.nValue);
07344           LLRP_ThingMagicHiggs3LoadImage_setEPCAndUserData(pOpSpec, epcAndUserData);
07345 
07349           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07350                                       (LLRP_tSParameter *)pOpSpec);
07351  
07352           break;
07353         }
07354 
07355       case TMR_TAGOP_GEN2_ALIEN_HIGGS3_BLOCKREADLOCK:
07356         {
07357           TMR_TagOp_GEN2_Alien_Higgs3_BlockReadLock *args;
07358           LLRP_tSThingMagicHiggs3BlockReadLock      *pOpSpec;
07359 
07360           args = &tagop->u.gen2.u.custom.u.alien.u.higgs3.u.blockReadLock;
07361 
07362           /* Construct and initialize Higgs3BlockReadLock */
07363           pOpSpec = LLRP_ThingMagicHiggs3BlockReadLock_construct();
07364           /* Set OpSpec Id */
07365           LLRP_ThingMagicHiggs3BlockReadLock_setOpSpecID(pOpSpec, 
07366                                   reader->u.llrpReader.opSpecId);
07367           /* Set AccessPassword */
07368           LLRP_ThingMagicHiggs3BlockReadLock_setAccessPassword(
07369                                   pOpSpec, args->accessPassword);
07370           /* Set LockBits */
07371           LLRP_ThingMagicHiggs3BlockReadLock_setLockBits(
07372                                   pOpSpec, args->lockBits);
07373 
07377           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07378                                       (LLRP_tSParameter *)pOpSpec);
07379  
07380           break;
07381         }
07382 
07383       case TMR_TAGOP_GEN2_LOCK:
07384         {
07385           TMR_TagOp_GEN2_Lock        *args;
07386           LLRP_tSC1G2Lock            *pC1G2Lock;
07387           LLRP_tSC1G2LockPayload     *pC1G2LockPayload;
07388           int                         index;
07389 
07390           args = &tagop->u.gen2.u.lock;
07391           /* Construct and initialize C1G2Lock */
07392           pC1G2Lock = LLRP_C1G2Lock_construct();
07393           /* Set OpSpec Id */
07394           LLRP_C1G2Lock_setOpSpecID(pC1G2Lock, reader->u.llrpReader.opSpecId);
07395           /* Set access password */
07396           LLRP_C1G2Lock_setAccessPassword(pC1G2Lock, args->accessPassword);
07397           /* Construct and initialize C1G2LockPayload */
07398           pC1G2LockPayload = LLRP_C1G2LockPayload_construct();
07399           /* Set the LockPrivilege  */
07400           switch (args->mask)
07401           {
07402             case TMR_GEN2_LOCK_BITS_USER_PERM:
07403               {
07404                 index = 0;
07405                 pC1G2LockPayload->eDataField = LLRP_C1G2LockDataField_User_Memory;
07406                 if (1 == (args->action >> index))
07407                 {
07408                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Perma_Lock;
07409                 }
07410                 else
07411                 {
07412                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Perma_Unlock;
07413                 }
07414                 break;
07415               }
07416             case TMR_GEN2_LOCK_BITS_USER:
07417               {
07418                 index = 1;
07419                 pC1G2LockPayload->eDataField = LLRP_C1G2LockDataField_User_Memory;
07420                 if (1 == (args->action >> index))
07421                 {
07422                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Read_Write;
07423                 }
07424                 else
07425                 {
07426                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Unlock;
07427                 }
07428                 break;
07429               }
07430             case TMR_GEN2_LOCK_BITS_TID_PERM:
07431               {
07432                 index = 2;
07433                 pC1G2LockPayload->eDataField = LLRP_C1G2LockDataField_TID_Memory;
07434                 if (1 == (args->action >> index))
07435                 {
07436                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Perma_Lock;
07437                 }
07438                 else
07439                 {
07440                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Perma_Unlock;
07441                 }
07442                 break;
07443               }
07444             case TMR_GEN2_LOCK_BITS_TID:
07445               {
07446                 index = 3;
07447                 pC1G2LockPayload->eDataField = LLRP_C1G2LockDataField_TID_Memory;
07448                 if (1 == (args->action >> index))
07449                 {
07450                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Read_Write;
07451                 }
07452                 else
07453                 {
07454                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Unlock;
07455                 }
07456                 break;
07457               }
07458             case TMR_GEN2_LOCK_BITS_EPC_PERM:
07459               {
07460                 index = 4;
07461                 pC1G2LockPayload->eDataField = LLRP_C1G2LockDataField_EPC_Memory;
07462                 if (1 == (args->action >> index))
07463                 {
07464                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Perma_Lock;
07465                 }
07466                 else
07467                 {
07468                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Perma_Unlock;
07469                 }
07470                 break;
07471               }
07472             case TMR_GEN2_LOCK_BITS_EPC:
07473               {
07474                 index = 5;
07475                 pC1G2LockPayload->eDataField = LLRP_C1G2LockDataField_EPC_Memory;
07476                 if (1 == (args->action >> index))
07477                 {
07478                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Read_Write;
07479                 }
07480                 else
07481                 {
07482                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Unlock;
07483                 }
07484                 break;
07485               }
07486             case TMR_GEN2_LOCK_BITS_ACCESS_PERM:
07487               {
07488                 index = 6;
07489                 pC1G2LockPayload->eDataField = LLRP_C1G2LockDataField_Access_Password;
07490                 if (1 == (args->action >> index))
07491                 {
07492                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Perma_Lock;
07493                 }
07494                 else
07495                 {
07496                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Perma_Unlock;
07497                 }
07498                 break;
07499               }
07500             case TMR_GEN2_LOCK_BITS_ACCESS:
07501               {
07502                 index = 7;
07503                 pC1G2LockPayload->eDataField = LLRP_C1G2LockDataField_Access_Password;
07504                 if (1 == (args->action >> index))
07505                 {
07506                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Read_Write;
07507                 }
07508                 else
07509                 {
07510                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Unlock;
07511                 }
07512                 break;
07513               }
07514             case TMR_GEN2_LOCK_BITS_KILL_PERM:
07515               {
07516                 index = 8;
07517                 pC1G2LockPayload->eDataField = LLRP_C1G2LockDataField_Kill_Password;
07518                 if (1 == (args->action >> index))
07519                 {
07520                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Perma_Lock;
07521                 }
07522                 else
07523                 {
07524                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Perma_Unlock;
07525                 }
07526                 break;
07527               }
07528             case TMR_GEN2_LOCK_BITS_KILL:
07529               {
07530                 index = 9;
07531                 pC1G2LockPayload->eDataField = LLRP_C1G2LockDataField_Kill_Password;
07532                 if (1 == (args->action >> index))
07533                 {
07534                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Read_Write;
07535                 }
07536                 else
07537                 {
07538                   pC1G2LockPayload->ePrivilege = LLRP_C1G2LockPrivilege_Unlock;
07539                 }
07540                 break;
07541               }
07542 
07543             default:
07544               {
07545                 /* Unknown lockaction  return invalid error */
07546                 return TMR_ERROR_INVALID; 
07547 
07548               }
07549           }
07550 
07554           LLRP_C1G2Lock_addC1G2LockPayload (pC1G2Lock, pC1G2LockPayload);
07558           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07559               (LLRP_tSParameter *)pC1G2Lock);
07560 
07561           break;
07562         }
07563 
07564       case TMR_TAGOP_GEN2_KILL:
07565         {
07566           TMR_TagOp_GEN2_Kill   *args;
07567           LLRP_tSC1G2Kill       *pC1G2Kill;
07568 
07569           args = &tagop->u.gen2.u.kill;
07570           /* Construct and initialize C1G2Kill */
07571           pC1G2Kill = LLRP_C1G2Kill_construct();
07572           /* Set OpSpec Id */
07573           LLRP_C1G2Kill_setOpSpecID(pC1G2Kill, reader->u.llrpReader.opSpecId);
07574           /* Set the kill password */
07575           LLRP_C1G2Kill_setKillPassword(pC1G2Kill, args->password);
07576 
07580           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07581                                       (LLRP_tSParameter *)pC1G2Kill);
07582           break;
07583         }
07584 
07585       case TMR_TAGOP_GEN2_BLOCKWRITE:
07586         {
07587           TMR_TagOp_GEN2_BlockWrite  *args;
07588           LLRP_tSC1G2BlockWrite      *pC1G2BlockWrite;
07589           llrp_u16v_t                 data;
07590 
07591           args = &tagop->u.gen2.u.blockWrite;
07592           /* Construct and initialize C1G2BlockWrite */
07593           pC1G2BlockWrite = LLRP_C1G2BlockWrite_construct();
07594           /* Set OpSpec Id */
07595           LLRP_C1G2BlockWrite_setOpSpecID(pC1G2BlockWrite, reader->u.llrpReader.opSpecId);
07596           /* Set access password */
07597           LLRP_C1G2BlockWrite_setAccessPassword(pC1G2BlockWrite, reader->u.llrpReader.gen2AccessPassword);
07598           /* Set Memory Bank */
07599           LLRP_C1G2BlockWrite_setMB(pC1G2BlockWrite, (llrp_u2_t)args->bank);
07600           /* Set word pointer */
07601           LLRP_C1G2BlockWrite_setWordPointer(pC1G2BlockWrite, args->wordPtr);
07602           /* Set the data to be written */
07603           data = LLRP_u16v_construct (args->data.len);
07604           memcpy (data.pValue, args->data.list, data.nValue * sizeof(uint16_t));
07605           LLRP_C1G2BlockWrite_setWriteData(pC1G2BlockWrite, data);
07606 
07611           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07612               (LLRP_tSParameter *)pC1G2BlockWrite);
07613 
07614           break;
07615         }
07616 
07617       case TMR_TAGOP_GEN2_NXP_SETREADPROTECT:
07618         {
07619           TMR_TagOp_GEN2_NXP_SetReadProtect *args;
07620           LLRP_tSThingMagicNXPG2ISetReadProtect *pG2I;
07621           LLRP_tSThingMagicNXPG2XSetReadProtect *pG2X;
07622 
07623           args = &tagop->u.gen2.u.custom.u.nxp.u.setReadProtect;
07624 
07625           if (TMR_SR_GEN2_NXP_G2I_SILICON == tagop->u.gen2.u.custom.chipType)
07626           {
07627             /* Construct and initialize G2I setReadProtect */
07628             pG2I = LLRP_ThingMagicNXPG2ISetReadProtect_construct();
07629             /* Set OpSpec Id */
07630             LLRP_ThingMagicNXPG2ISetReadProtect_setOpSpecID(
07631                     pG2I, reader->u.llrpReader.opSpecId);
07632             /* Set access password */
07633             LLRP_ThingMagicNXPG2ISetReadProtect_setAccessPassword(
07634                                       pG2I, args->accessPassword);
07638             LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07639                                           (LLRP_tSParameter *)pG2I);
07640           }
07641           else
07642           {
07643             /* Construct and initialize G2X setReadProtect */
07644             pG2X = LLRP_ThingMagicNXPG2XSetReadProtect_construct();
07645             /* Set OpSpec Id */
07646             LLRP_ThingMagicNXPG2XSetReadProtect_setOpSpecID(
07647                         pG2X, reader->u.llrpReader.opSpecId);
07648             /* Set access password */
07649             LLRP_ThingMagicNXPG2XSetReadProtect_setAccessPassword(
07650                                       pG2X, args->accessPassword);
07654             LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07655                                             (LLRP_tSParameter *)pG2X);
07656           }
07657           break;
07658         }
07659 
07660       case TMR_TAGOP_GEN2_NXP_RESETREADPROTECT:
07661         {
07662           TMR_TagOp_GEN2_NXP_ResetReadProtect   *args;
07663           LLRP_tSThingMagicNXPG2IResetReadProtect *pG2I;
07664           LLRP_tSThingMagicNXPG2XResetReadProtect *pG2X;
07665 
07666           args = &tagop->u.gen2.u.custom.u.nxp.u.resetReadProtect;
07667 
07668           if (TMR_SR_GEN2_NXP_G2I_SILICON == tagop->u.gen2.u.custom.chipType)
07669           {
07670             /* Construct and initialize G2I resetReadProtect */
07671             pG2I = LLRP_ThingMagicNXPG2IResetReadProtect_construct();
07672             /* Set OpSpec Id */
07673             LLRP_ThingMagicNXPG2IResetReadProtect_setOpSpecID(
07674                     pG2I, reader->u.llrpReader.opSpecId);
07675             /* Set access password */
07676             LLRP_ThingMagicNXPG2IResetReadProtect_setAccessPassword(
07677                                       pG2I, args->accessPassword);
07681             LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07682                                           (LLRP_tSParameter *)pG2I);
07683           }
07684           else
07685           {
07686             /* Construct and initialize G2X resetReadProtect */
07687             pG2X = LLRP_ThingMagicNXPG2XResetReadProtect_construct();
07688             /* Set OpSpec Id */
07689             LLRP_ThingMagicNXPG2XResetReadProtect_setOpSpecID(
07690                         pG2X, reader->u.llrpReader.opSpecId);
07691             /* Set access password */
07692             LLRP_ThingMagicNXPG2XResetReadProtect_setAccessPassword(
07693                                       pG2X, args->accessPassword);
07697             LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07698                                             (LLRP_tSParameter *)pG2X);
07699           }
07700           break;
07701         }
07702 
07703       case TMR_TAGOP_GEN2_NXP_CHANGEEAS:
07704         {
07705           TMR_TagOp_GEN2_NXP_ChangeEAS     *args;
07706           LLRP_tSThingMagicNXPG2IChangeEAS *pG2I;
07707           LLRP_tSThingMagicNXPG2XChangeEAS *pG2X;
07708 
07709           args = &tagop->u.gen2.u.custom.u.nxp.u.changeEAS;
07710 
07711           if (TMR_SR_GEN2_NXP_G2I_SILICON == tagop->u.gen2.u.custom.chipType)
07712           {
07713             /* Construct and initialize G2I changeEAS */
07714             pG2I = LLRP_ThingMagicNXPG2IChangeEAS_construct();
07715             /* Set OpSpec Id */
07716             LLRP_ThingMagicNXPG2IChangeEAS_setOpSpecID(
07717                     pG2I, reader->u.llrpReader.opSpecId);
07718             /* Set access password */
07719             LLRP_ThingMagicNXPG2IChangeEAS_setAccessPassword(
07720                                       pG2I, args->accessPassword);
07721             /* Set EASStatus */
07722             LLRP_ThingMagicNXPG2IChangeEAS_setReset(
07723                                       pG2I, args->reset);
07727             LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07728                                           (LLRP_tSParameter *)pG2I);
07729           }
07730           else
07731           {
07732             /* Construct and initialize G2X ChangeEAS */
07733             pG2X = LLRP_ThingMagicNXPG2XChangeEAS_construct();
07734             /* Set OpSpec Id */
07735             LLRP_ThingMagicNXPG2XChangeEAS_setOpSpecID(
07736                         pG2X, reader->u.llrpReader.opSpecId);
07737             /* Set access password */
07738             LLRP_ThingMagicNXPG2XChangeEAS_setAccessPassword(
07739                                       pG2X, args->accessPassword);
07740             /* Set EASStatus */
07741             LLRP_ThingMagicNXPG2XChangeEAS_setReset(
07742                                       pG2X, args->reset);
07746             LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07747                                             (LLRP_tSParameter *)pG2X);
07748           }
07749           break;
07750         }
07751 
07752       case TMR_TAGOP_GEN2_NXP_EASALARM:
07753         {
07754           TMR_TagOp_GEN2_NXP_EASAlarm     *args;
07755           LLRP_tSThingMagicNXPG2IEASAlarm *pG2I;
07756           LLRP_tSThingMagicNXPG2XEASAlarm *pG2X;
07757 
07758           args = &tagop->u.gen2.u.custom.u.nxp.u.EASAlarm;
07759 
07760           if (TMR_SR_GEN2_NXP_G2I_SILICON == tagop->u.gen2.u.custom.chipType)
07761           {
07762             /* Construct and initialize G2I EASAlarm */
07763             pG2I = LLRP_ThingMagicNXPG2IEASAlarm_construct();
07764             /* Set OpSpec Id */
07765             LLRP_ThingMagicNXPG2IEASAlarm_setOpSpecID(
07766                     pG2I, reader->u.llrpReader.opSpecId);
07767             /* Set access password */
07768             LLRP_ThingMagicNXPG2IEASAlarm_setAccessPassword(
07769                 pG2I, reader->u.llrpReader.gen2AccessPassword);
07770             /* Set DivideRatio */
07771             LLRP_ThingMagicNXPG2IEASAlarm_setDivideRatio(pG2I, args->dr);
07772             /* Set TagEncoding */
07773             LLRP_ThingMagicNXPG2IEASAlarm_setTagEncoding(pG2I, args->m);
07774             /* Set TrExt */
07775             LLRP_ThingMagicNXPG2IEASAlarm_setPilotTone(pG2I, args->trExt);
07776 
07780             LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07781                                           (LLRP_tSParameter *)pG2I);
07782           }
07783           else
07784           {
07785             /* Construct and initialize G2X EASAlarm */
07786             pG2X = LLRP_ThingMagicNXPG2XEASAlarm_construct();
07787             /* Set OpSpec Id */
07788             LLRP_ThingMagicNXPG2XEASAlarm_setOpSpecID(
07789                     pG2X, reader->u.llrpReader.opSpecId);
07790             /* Set access password */
07791             LLRP_ThingMagicNXPG2XEASAlarm_setAccessPassword(
07792                 pG2X, reader->u.llrpReader.gen2AccessPassword);
07793             /* Set DivideRatio */
07794             LLRP_ThingMagicNXPG2XEASAlarm_setDivideRatio(pG2X, args->dr);
07795             /* Set TagEncoding */
07796             LLRP_ThingMagicNXPG2XEASAlarm_setTagEncoding(pG2X, args->m);
07797             /* Set TrExt */
07798             LLRP_ThingMagicNXPG2XEASAlarm_setPilotTone(pG2X, args->trExt);
07799 
07803             LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07804                                             (LLRP_tSParameter *)pG2X);
07805           }
07806           break;
07807         }
07808 
07809       case TMR_TAGOP_GEN2_NXP_CALIBRATE:
07810         {
07811           TMR_TagOp_GEN2_NXP_Calibrate     *args;
07812           LLRP_tSThingMagicNXPG2ICalibrate *pG2I;
07813           LLRP_tSThingMagicNXPG2XCalibrate *pG2X;
07814 
07815           args = &tagop->u.gen2.u.custom.u.nxp.u.calibrate;
07816 
07817           if (TMR_SR_GEN2_NXP_G2I_SILICON == tagop->u.gen2.u.custom.chipType)
07818           {
07819             /* Construct and initialize G2I calibrate */
07820             pG2I = LLRP_ThingMagicNXPG2ICalibrate_construct();
07821             /* Set OpSpec Id */
07822             LLRP_ThingMagicNXPG2ICalibrate_setOpSpecID(
07823                     pG2I, reader->u.llrpReader.opSpecId);
07824             /* Set access password */
07825             LLRP_ThingMagicNXPG2ICalibrate_setAccessPassword(
07826                                       pG2I, args->accessPassword);
07830             LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07831                                           (LLRP_tSParameter *)pG2I);
07832           }
07833           else
07834           {
07835             /* Construct and initialize G2X Calibrate */
07836             pG2X = LLRP_ThingMagicNXPG2XCalibrate_construct();
07837             /* Set OpSpec Id */
07838             LLRP_ThingMagicNXPG2XCalibrate_setOpSpecID(
07839                         pG2X, reader->u.llrpReader.opSpecId);
07840             /* Set access password */
07841             LLRP_ThingMagicNXPG2XCalibrate_setAccessPassword(
07842                                       pG2X, args->accessPassword);
07846             LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07847                                             (LLRP_tSParameter *)pG2X);
07848           }
07849           break;
07850         }
07851 
07852       case TMR_TAGOP_GEN2_NXP_CHANGECONFIG:
07853         {
07854           TMR_TagOp_GEN2_NXP_ChangeConfig     *args;
07855           LLRP_tSThingMagicNXPG2IChangeConfig *pG2I;
07856           LLRP_tSThingMagicNXPConfigWord      *pConfigWord;
07857 
07858           args = &tagop->u.gen2.u.custom.u.nxp.u.changeConfig;
07859 
07860           if (TMR_SR_GEN2_NXP_G2I_SILICON == tagop->u.gen2.u.custom.chipType)
07861           {
07862             /* Construct and initialize G2I changeconfig */
07863             pG2I = LLRP_ThingMagicNXPG2IChangeConfig_construct();
07864             /* Set OpSpec Id */
07865             LLRP_ThingMagicNXPG2IChangeConfig_setOpSpecID(
07866                     pG2I, reader->u.llrpReader.opSpecId);
07867             /* Set access password */
07868             LLRP_ThingMagicNXPG2IChangeConfig_setAccessPassword(
07869                                       pG2I, args->accessPassword);
07870 
07871             /* Construct and initialize configword */
07872             pConfigWord = LLRP_ThingMagicNXPConfigWord_construct();
07873             
07874             pConfigWord->PSFAlarm = args->configWord.bits.psfAlarm;
07875             pConfigWord->ReadProtectTID = args->configWord.bits.readProtectTID;
07876             pConfigWord->ReadProtectEPC = args->configWord.bits.readProtectEPC;
07877             pConfigWord->ReadProtectUser = args->configWord.bits.readProtectUser;
07878             pConfigWord->PrivacyMode = args->configWord.bits.privacyMode;
07879             pConfigWord->DigitalOutput = args->configWord.bits.digitalOutput;
07880             pConfigWord->MaxBackscatterStrength = args->configWord.bits.maxBackscatterStrength;
07881             pConfigWord->ConditionalReadRangeReduction_OpenShort =
07882                   args->configWord.bits.conditionalReadRangeReduction_openShort;
07883             pConfigWord->ConditionalReadRangeReduction_OnOff =
07884                   args->configWord.bits.conditionalReadRangeReduction_onOff;
07885             pConfigWord->DataMode = args->configWord.bits.dataMode;
07886             pConfigWord->TransparentMode = args->configWord.bits.transparentMode;
07887             pConfigWord->InvertDigitalOutput = args->configWord.bits.invertDigitalOutput;
07888             pConfigWord->ExternalSupply = args->configWord.bits.externalSupply;
07889             pConfigWord->TamperAlarm = args->configWord.bits.tamperAlarm;
07890 
07891             /* Set configword to opSpec */
07892             LLRP_ThingMagicNXPG2IChangeConfig_setThingMagicNXPConfigWord(
07893                                                         pG2I, pConfigWord);
07897             LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07898                                           (LLRP_tSParameter *)pG2I);
07899           }
07900           else
07901           {
07905             return TMR_ERROR_UNSUPPORTED;
07906           }
07907           break;
07908         }
07909 
07910       case TMR_TAGOP_GEN2_IDS_SL900A_SETSFEPARAMETERS:
07911         {
07912           TMR_TagOp_GEN2_IDS_SL900A_SetSfeParameters *args;
07913           LLRP_tSThingMagicIDSSL900ASetSFEParams     *pTMIdsSetSfeParameters;
07914           LLRP_tSThingMagicIDSSFEParam               *pTMIdsSfeParam;
07915           LLRP_tSThingMagicIDSSL900ACommandRequest   *pTMIdsCommandRequest;
07916 
07917           args = &tagop->u.gen2.u.custom.u.ids.u.setSfeParameters;
07918 
07919           /* Construct and initialize TMIDS SetSfeParameters opspec */
07920           pTMIdsSetSfeParameters = LLRP_ThingMagicIDSSL900ASetSFEParams_construct();
07921           /* Construct and initialize TMIDS Command Request */
07922           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
07923           /* Set OpSpecId to TMIDS Command Request */
07924           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
07925               reader->u.llrpReader.opSpecId);
07926           /* Set access password to TMIDS Command Request */
07927           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
07928               (llrp_u32_t) args->AccessPassword);
07929           /* Set the IDS password level to TMIDS Command Request */
07930           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
07931               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
07932           /* Set the Command code for IDS SetSfeParameters operation to TMIDS Command Request */
07933           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
07934               (llrp_u8_t)args->CommandCode);
07935           /* Set the IDS Password to TMIDS Command Request */
07936           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
07937               (llrp_u32_t)args->Password);
07938           /* Set the IDS Command Request to TMIDS SetSfeParameters opspec */
07939           LLRP_ThingMagicIDSSL900ASetSFEParams_setThingMagicIDSSL900ACommandRequest(pTMIdsSetSfeParameters,
07940               pTMIdsCommandRequest);
07941           /* Construct and initialize the TMIDS SetSfeParams */
07942           {
07943             pTMIdsSfeParam = LLRP_ThingMagicIDSSFEParam_construct();
07944             /* Raw 16-bit SFE parameters value */
07945             LLRP_ThingMagicIDSSFEParam_setraw(pTMIdsSfeParam, (llrp_u16_t)args->sfe->raw);
07946             /* External sensor 2 range */
07947             LLRP_ThingMagicIDSSFEParam_setrange(pTMIdsSfeParam, (llrp_u8_t)args->sfe->Rang);
07948             /* External sensor 1 range */
07949             LLRP_ThingMagicIDSSFEParam_setseti(pTMIdsSfeParam, (llrp_u8_t)args->sfe->Seti);
07950             /* External sensor 1 type */
07951             LLRP_ThingMagicIDSSFEParam_setExt1(pTMIdsSfeParam, (llrp_u8_t)args->sfe->Ext1);
07952             /* External sensor 2 type */
07953             LLRP_ThingMagicIDSSFEParam_setExt2(pTMIdsSfeParam, (llrp_u8_t)args->sfe->Ext2);
07954             /* Use preset range */
07955             LLRP_ThingMagicIDSSFEParam_setAutoRangeDisable(pTMIdsSfeParam, (llrp_u1_t)args->sfe->AutorangeDisable);
07956             /* Sensor used in limit check */
07957             LLRP_ThingMagicIDSSFEParam_setVerifySensorID(pTMIdsSfeParam, (llrp_u8_t)args->sfe->VerifySensorID);
07958             /* specifies the type of field user want to modify */
07959             LLRP_ThingMagicIDSSFEParam_setSFEType(pTMIdsSfeParam, (LLRP_tEThingMagicCustomIDSSFEType)args->sfe->type);
07960 
07961             LLRP_ThingMagicIDSSL900ASetSFEParams_setThingMagicIDSSFEParam(pTMIdsSetSfeParameters,
07962                 (LLRP_tSThingMagicIDSSFEParam *)pTMIdsSfeParam);
07963           }
07964 
07968           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
07969               (LLRP_tSParameter *)pTMIdsSetSfeParameters);
07970           break;
07971         }
07972 
07973       case TMR_TAGOP_GEN2_IDS_SL900A_GETMEASUREMENTSETUP:
07974         {
07975           TMR_TagOp_GEN2_IDS_SL900A_GetMeasurementSetup *args;
07976           LLRP_tSThingMagicIDSSL900AGetMeasurementSetup *pTMIdsGetMeasurementSetup;
07977           LLRP_tSThingMagicIDSSL900ACommandRequest      *pTMIdsCommandRequest;
07978 
07979           args = &tagop->u.gen2.u.custom.u.ids.u.measurementSetup;
07980 
07981           /* Construct and initialize TMIDS GetMeasurementSetUp opspec */
07982           pTMIdsGetMeasurementSetup = LLRP_ThingMagicIDSSL900AGetMeasurementSetup_construct();
07983           /* Construct and initialize TMIDS Command Request */
07984           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
07985           /* Set OpSpecId to TMIDS Command Request */
07986           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
07987               reader->u.llrpReader.opSpecId);
07988           /* Set access password to TMIDS Command Request */
07989           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
07990               (llrp_u32_t) args->AccessPassword);
07991           /* Set the IDS password level to TMIDS Command Request */
07992           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
07993               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
07994           /* Set the Command code for IDS GetMeasurementSetup operation to TMIDS Command Request */
07995           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
07996               (llrp_u8_t)args->CommandCode);
07997           /* Set the IDS Password to TMIDS Command Request */
07998           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
07999               (llrp_u32_t)args->Password);
08000           /* Set the IDS Command Request to TMIDS GetMeasurementSetup opspec */
08001           LLRP_ThingMagicIDSSL900AGetMeasurementSetup_setThingMagicIDSSL900ACommandRequest(pTMIdsGetMeasurementSetup,
08002               pTMIdsCommandRequest);
08003 
08007           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08008               (LLRP_tSParameter *)pTMIdsGetMeasurementSetup);
08009           break;
08010         }
08011 
08012       case TMR_TAGOP_GEN2_IDS_SL900A_GETBATTERYLEVEL:
08013         {
08014           TMR_TagOp_GEN2_IDS_SL900A_GetBatteryLevel *args;
08015           LLRP_tSThingMagicIDSSL900AGetBatteryLevel *pTMIdsGetBatteryLevel;
08016           LLRP_tSThingMagicIDSSL900ACommandRequest  *pTMIdsCommandRequest;
08017 
08018           args = &tagop->u.gen2.u.custom.u.ids.u.batteryLevel;
08019 
08020           /* Construct and initialize TMIDS GetBatteryLevel opspec */
08021           pTMIdsGetBatteryLevel = LLRP_ThingMagicIDSSL900AGetBatteryLevel_construct();
08022           /* Construct and initialize TMIDS Command Request */
08023           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08024           /* Set OpSpecId to TMIDS Command Request */
08025           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08026               reader->u.llrpReader.opSpecId);
08027           /* Set access password to TMIDS Command Request */
08028           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08029               (llrp_u32_t) args->AccessPassword);
08030           /* Set the IDS password level to TMIDS Command Request */
08031           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08032               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08033           /* Set the Command code for IDS GetBatteryLevel operation to TMIDS Command Request */
08034           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08035               (llrp_u8_t)args->CommandCode);
08036           /* Set the IDS Password to TMIDS Command Request */
08037           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08038               (llrp_u32_t)args->Password);
08039           /* Set the IDS Command Request to TMIDS GetBatteryLevel opspec */
08040           LLRP_ThingMagicIDSSL900AGetBatteryLevel_setThingMagicIDSSL900ACommandRequest(pTMIdsGetBatteryLevel,
08041               pTMIdsCommandRequest);
08042 
08046           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08047               (LLRP_tSParameter *)pTMIdsGetBatteryLevel);
08048           break;
08049         }
08050 
08051       case TMR_TAGOP_GEN2_IDS_SL900A_SETLOGLIMITS:
08052         {
08053           TMR_TagOp_GEN2_IDS_SL900A_SetLogLimits    *args;
08054           LLRP_tSThingMagicIDSSL900ASetLogLimits    *pTMIdsSetLogLimits;
08055           LLRP_tSThingMagicIDSLogLimits             *pTMIdsLogLimits;
08056           LLRP_tSThingMagicIDSSL900ACommandRequest  *pTMIdsCommandRequest;
08057 
08058           args = &tagop->u.gen2.u.custom.u.ids.u.setLogLimit;
08059 
08060           /* Construct and initialize TMIDS SetLogLimits opspec */
08061           pTMIdsSetLogLimits = LLRP_ThingMagicIDSSL900ASetLogLimits_construct();
08062           /* Construct and initialize TMIDS Command Request */
08063           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08064           /* Set OpSpecId to TMIDS Command Request */
08065           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08066               reader->u.llrpReader.opSpecId);
08067           /* Set access password to TMIDS Command Request */
08068           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08069               (llrp_u32_t) args->AccessPassword);
08070           /* Set the IDS password level to TMIDS Command Request */
08071           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08072               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08073           /* Set the Command code for IDS SetLogLimits operation to TMIDS Command Request */
08074           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08075               (llrp_u8_t)args->CommandCode);
08076           /* Set the IDS Password to TMIDS Command Request */
08077           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08078               (llrp_u32_t)args->Password);
08079           /* Set the IDS Command Request to TMIDS SetLogLimits opspec */
08080           LLRP_ThingMagicIDSSL900ASetLogLimits_setThingMagicIDSSL900ACommandRequest(pTMIdsSetLogLimits,
08081               pTMIdsCommandRequest);
08082           /* Construct and initialize the TMIDS LogLimits */
08083           {
08084             pTMIdsLogLimits = LLRP_ThingMagicIDSLogLimits_construct();
08085             /* Specifying the extreme lower limit */
08086             LLRP_ThingMagicIDSLogLimits_setextremeLower(pTMIdsLogLimits, (llrp_u16_t)args->limit.extremeLower);
08087             /* Specifying the lower limit */
08088             LLRP_ThingMagicIDSLogLimits_setlower(pTMIdsLogLimits, (llrp_u16_t)args->limit.lower);
08089             /* Specifying the upper limit */
08090             LLRP_ThingMagicIDSLogLimits_setupper(pTMIdsLogLimits, (llrp_u16_t)args->limit.upper);
08091             /* Specifying the extreme upper limit */
08092             LLRP_ThingMagicIDSLogLimits_setextremeUpper(pTMIdsLogLimits, (llrp_u16_t)args->limit.extremeUpper);
08093 
08094             LLRP_ThingMagicIDSSL900ASetLogLimits_setThingMagicIDSLogLimits(pTMIdsSetLogLimits,
08095                 (LLRP_tSThingMagicIDSLogLimits *)pTMIdsLogLimits);
08096           }
08097 
08101           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08102               (LLRP_tSParameter *)pTMIdsSetLogLimits);
08103           break;
08104         }
08105 
08106       case TMR_TAGOP_GEN2_IDS_SL900A_SETSHELFLIFE:
08107         {
08108           TMR_TagOp_GEN2_IDS_SL900A_SetShelfLife    *args;
08109           LLRP_tSThingMagicIDSSetShelfLife          *pTMIdsSetShelfLife;
08110           LLRP_tSThingMagicIDSSLBlock0              *pTMIdsBlock0;
08111           LLRP_tSThingMagicIDSSLBlock1              *pTMIdsBlock1;
08112           LLRP_tSThingMagicIDSSL900ACommandRequest  *pTMIdsCommandRequest;
08113 
08114           args = &tagop->u.gen2.u.custom.u.ids.u.setShelfLife;
08115 
08116           /* Construct and initialize TMIDS SetShelfLife opspec */
08117           pTMIdsSetShelfLife = LLRP_ThingMagicIDSSetShelfLife_construct();
08118           /* Construct and initialize TMIDS Command Request */
08119           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08120           /* Set OpSpecId to TMIDS Command Request */
08121           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08122               reader->u.llrpReader.opSpecId);
08123           /* Set access password to TMIDS Command Request */
08124           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08125               (llrp_u32_t) args->AccessPassword);
08126           /* Set the IDS password level to TMIDS Command Request */
08127           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08128               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08129           /* Set the Command code for IDS SetShelfLife operation to TMIDS Command Request */
08130           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08131               (llrp_u8_t)args->CommandCode);
08132           /* Set the IDS Password to TMIDS Command Request */
08133           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08134               (llrp_u32_t)args->Password);
08135           /* Set the IDS Command Request to TMIDS SetShelfLife opspec */
08136           LLRP_ThingMagicIDSSetShelfLife_setThingMagicIDSSL900ACommandRequest(pTMIdsSetShelfLife,
08137               pTMIdsCommandRequest);
08138           /* Construct and Initialize the TMIDS Block0 Data */
08139           {
08140             pTMIdsBlock0 = LLRP_ThingMagicIDSSLBlock0_construct();
08141             /* raw value of block0 */
08142             LLRP_ThingMagicIDSSLBlock0_setraw(pTMIdsBlock0, (llrp_u32_t)args->shelfLifeBlock0->raw);
08143             /* Tmax */
08144             LLRP_ThingMagicIDSSLBlock0_setTimeMax(pTMIdsBlock0, (llrp_u8_t)args->shelfLifeBlock0->Tmax);
08145             /* Tmin */
08146             LLRP_ThingMagicIDSSLBlock0_setTimeMin(pTMIdsBlock0, (llrp_u8_t)args->shelfLifeBlock0->Tmin);
08147             /* Tstd */
08148             LLRP_ThingMagicIDSSLBlock0_setTimeStd(pTMIdsBlock0, (llrp_u8_t)args->shelfLifeBlock0->Tstd);
08149             /* Ea */
08150             LLRP_ThingMagicIDSSLBlock0_setEa(pTMIdsBlock0, (llrp_u8_t)args->shelfLifeBlock0->Ea);
08151 
08152             LLRP_ThingMagicIDSSetShelfLife_setThingMagicIDSSLBlock0(pTMIdsSetShelfLife,
08153                 (LLRP_tSThingMagicIDSSLBlock0 *)pTMIdsBlock0);
08154           }
08155           /* Construct and Initialize the TMIDS Block1 Data */
08156           {
08157             pTMIdsBlock1 = LLRP_ThingMagicIDSSLBlock1_construct();
08158             /* raw value for block 1 */
08159             LLRP_ThingMagicIDSSLBlock1_setraw(pTMIdsBlock1, (llrp_u32_t)args->shelfLifeBlock1->raw);
08160             /* SLinit */
08161             LLRP_ThingMagicIDSSLBlock1_setSLInit(pTMIdsBlock1, (llrp_u16_t)args->shelfLifeBlock1->SLinit);
08162             /* Tint */
08163             LLRP_ThingMagicIDSSLBlock1_setTInit(pTMIdsBlock1, (llrp_u16_t)args->shelfLifeBlock1->Tint);
08164             /* SensorID */
08165             LLRP_ThingMagicIDSSLBlock1_setSensorID(pTMIdsBlock1, (llrp_u8_t)args->shelfLifeBlock1->sensorID);
08166             /* Enable negative shelf life */
08167             LLRP_ThingMagicIDSSLBlock1_setenableNegative(pTMIdsBlock1, (llrp_u1_t)args->shelfLifeBlock1->enableNegative);
08168             /* Shelf life algorithem enable */
08169             LLRP_ThingMagicIDSSLBlock1_setalgorithmEnable(pTMIdsBlock1, (llrp_u1_t)args->shelfLifeBlock1->algorithmEnable);
08170             /* RFU Bytes */
08171             LLRP_ThingMagicIDSSLBlock1_setRFU(pTMIdsBlock1, (llrp_u8_t)args->shelfLifeBlock1->rfu);
08172 
08173             LLRP_ThingMagicIDSSetShelfLife_setThingMagicIDSSLBlock1(pTMIdsSetShelfLife,
08174                 (LLRP_tSThingMagicIDSSLBlock1 *)pTMIdsBlock1);
08175           }
08176 
08180           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08181               (LLRP_tSParameter *)pTMIdsSetShelfLife);
08182           break;
08183         }
08184 
08185       case TMR_TAGOP_GEN2_IDS_SL900A_SETPASSWORD:
08186         {
08187           TMR_TagOp_GEN2_IDS_SL900A_SetPassword     *args;
08188           LLRP_tSThingMagicIDSSL900ASetIDSPassword  *pTMIdsSetPassword;
08189           LLRP_tSThingMagicIDSSL900ACommandRequest  *pTMIdsCommandRequest;
08190 
08191           args = &tagop->u.gen2.u.custom.u.ids.u.setPassword;
08192           /* Construct and initialize TMIDS SetPassword opspec */
08193           pTMIdsSetPassword = LLRP_ThingMagicIDSSL900ASetIDSPassword_construct();
08194           /* Construct and initialize TMIDS Command Request */
08195           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08196           /* Set OpSpecId to TMIDS Command Request */
08197           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08198               reader->u.llrpReader.opSpecId);
08199           /* Set access password to TMIDS Command Request */
08200           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08201               (llrp_u32_t) args->AccessPassword);
08202           /* Set the IDS password level to TMIDS Command Request */
08203           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08204               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08205           /* Set the Command code for IDS SetPassword operation to TMIDS Command Request */
08206           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08207               (llrp_u8_t)args->CommandCode);
08208           /* Set the IDS Password to TMIDS Command Request */
08209           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08210               (llrp_u32_t)args->Password);
08211           /* Set the IDS Command Request to TMIDS SetPassword opspec */
08212           LLRP_ThingMagicIDSSL900ASetIDSPassword_setThingMagicIDSSL900ACommandRequest(pTMIdsSetPassword,
08213               pTMIdsCommandRequest);
08214           /* Set the IDS New PasswordLevel */
08215           LLRP_ThingMagicIDSSL900ASetIDSPassword_setNewPasswordLevel(pTMIdsSetPassword,
08216               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->NewPasswordLevel);
08217           /* Set the IDS New Password */
08218           LLRP_ThingMagicIDSSL900ASetIDSPassword_setNewIDSPassword(pTMIdsSetPassword,
08219               (llrp_u32_t)args->NewPassword);
08220 
08224           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08225               (LLRP_tSParameter *)pTMIdsSetPassword);
08226           break;
08227         }
08228 
08229       case TMR_TAGOP_GEN2_IMPINJ_MONZA4_QTREADWRITE:
08230         {
08231           TMR_TagOp_GEN2_Impinj_Monza4_QTReadWrite *args;
08232           LLRP_tSThingMagicImpinjMonza4QTReadWrite *pQTReadWrite;
08233           LLRP_tSThingMagicMonza4ControlByte       *pControlByte;
08234           LLRP_tSThingMagicMonza4Payload           *pPayload;
08235 
08236           args = &tagop->u.gen2.u.custom.u.impinj.u.monza4.u.qtReadWrite;
08237 
08238           /* Construct and initialize monza4 opspec */
08239           pQTReadWrite = LLRP_ThingMagicImpinjMonza4QTReadWrite_construct();
08240           /* Set OpSpecId */
08241           LLRP_ThingMagicImpinjMonza4QTReadWrite_setOpSpecID(
08242                     pQTReadWrite, reader->u.llrpReader.opSpecId);
08243           /* Set Access Password */
08244           LLRP_ThingMagicImpinjMonza4QTReadWrite_setAccessPassword(
08245                     pQTReadWrite, args->accessPassword);
08246           /* Initialize and set controlbyte */
08247           pControlByte = LLRP_ThingMagicMonza4ControlByte_construct();
08248           pControlByte->Persistance = args->controlByte.bits.persistence;
08249           pControlByte->ReadWrite = args->controlByte.bits.readWrite;
08250 
08251           LLRP_ThingMagicImpinjMonza4QTReadWrite_setThingMagicMonza4ControlByte(
08252               pQTReadWrite, pControlByte);
08253 
08254           /* Initialize and set payload */
08255           pPayload = LLRP_ThingMagicMonza4Payload_construct();
08256           pPayload->QT_MEM = args->payload.bits.QT_MEM;
08257           pPayload->QT_SR = args->payload.bits.QT_SR;
08258 
08259           LLRP_ThingMagicImpinjMonza4QTReadWrite_setThingMagicMonza4Payload(
08260               pQTReadWrite, pPayload);
08261 
08265           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08266               (LLRP_tSParameter *)pQTReadWrite);
08267           break;
08268         }
08269 
08270       case TMR_TAGOP_GEN2_IDS_SL900A_GETSENSOR:
08271         {
08272           TMR_TagOp_GEN2_IDS_SL900A_GetSensorValue  *args;
08273           LLRP_tSThingMagicIDSSL900ASensorValue     *pTMIdsGetSensor;
08274           LLRP_tSThingMagicIDSSL900ACommandRequest  *pTMIdsCommandRequest;
08275 
08276           args = &tagop->u.gen2.u.custom.u.ids.u.sensor;
08277 
08278           /* Construct and initialize TMIDS GetSensor opspec */
08279           pTMIdsGetSensor = LLRP_ThingMagicIDSSL900ASensorValue_construct();
08280           /* Construct and initialize TMIDS Command Request */
08281           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08282           /* Set OpSpecId to TMIDS Command Request */
08283           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08284               reader->u.llrpReader.opSpecId);
08285           /* Set access password to TMIDS Command Request */
08286           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08287               (llrp_u32_t) args->AccessPassword);
08288           /* Set the IDS password level to TMIDS Command Request */
08289           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08290               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08291           /* Set the Command code for IDS GetSensor operation to TMIDS Command Request */
08292           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08293               (llrp_u8_t)args->CommandCode);
08294           /* Set the IDS Password to TMIDS Command Request */
08295           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08296               (llrp_u32_t)args->Password);
08297           /* Set the IDS Command Request to TMIDS GetSensor opspec */
08298           LLRP_ThingMagicIDSSL900ASensorValue_setThingMagicIDSSL900ACommandRequest(pTMIdsGetSensor,
08299               pTMIdsCommandRequest);
08300           /* Set the Sensor type to TMIDS GetSensor opspec */
08301           LLRP_ThingMagicIDSSL900ASensorValue_setSensorType(pTMIdsGetSensor,
08302               (LLRP_tEThingMagicCustomIDSSensorType)args->sl900A.sensortype);
08303 
08307           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08308               (LLRP_tSParameter *)pTMIdsGetSensor);
08309           break;
08310 
08311         }
08312 
08313       case TMR_TAGOP_GEN2_IDS_SL900A_INITIALIZE:
08314         {
08315           TMR_TagOp_GEN2_IDS_SL900A_Initialize      *args;
08316           LLRP_tSThingMagicIDSSL900AInitialize      *pTMIdsInitialize;
08317           LLRP_tSThingMagicIDSDelayTime             *pTMIdsDelayTime;
08318           LLRP_tSThingMagicIDSApplicationData       *pTMIdsApplicationData;
08319           LLRP_tSThingMagicIDSSL900ACommandRequest  *pTMIdsCommandRequest;
08320 
08321           args = &tagop->u.gen2.u.custom.u.ids.u.initialize;
08322 
08323           /* Construct and initialize TMIDS Initialize opspec */
08324           pTMIdsInitialize = LLRP_ThingMagicIDSSL900AInitialize_construct();
08325           /* Construct and initialize TMIDS Command Request */
08326           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08327           /* Set OpSpecId to TMIDS Command Request */
08328           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08329               reader->u.llrpReader.opSpecId);
08330           /* Set access password to TMIDS Command Request */
08331           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08332               (llrp_u32_t) args->AccessPassword);
08333           /* Set the IDS password level to TMIDS Command Request */
08334           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08335               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08336           /* Set the Command code for IDS Initialize operation to TMIDS Command Request */
08337           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08338               (llrp_u8_t)args->CommandCode);
08339           /* Set the IDS Password to TMIDS Command Request */
08340           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08341               (llrp_u32_t)args->Password);
08342           /* Set the IDS Command Request to TMIDS Initialize opspec */
08343           LLRP_ThingMagicIDSSL900AInitialize_setThingMagicIDSSL900ACommandRequest(pTMIdsInitialize,
08344               pTMIdsCommandRequest);
08345           /* Set the Delay time parameters */
08346           pTMIdsDelayTime = LLRP_ThingMagicIDSDelayTime_construct();
08347           pTMIdsDelayTime->delayMode = (llrp_u8_t) args->delayTime.Mode;
08348           pTMIdsDelayTime->delayTime = (llrp_u16_t) args->delayTime.Time;
08349           pTMIdsDelayTime->timerEnable = (llrp_u1_t) args->delayTime.IrqTimerEnable;
08350           LLRP_ThingMagicIDSSL900AInitialize_setThingMagicIDSDelayTime(pTMIdsInitialize,
08351               pTMIdsDelayTime);
08352           /* Set the Application Data */
08353           pTMIdsApplicationData = LLRP_ThingMagicIDSApplicationData_construct();
08354           pTMIdsApplicationData->brokenWordPointer = (llrp_u8_t) args->applicationData.BrokenWordPointer;
08355           pTMIdsApplicationData->numberOfWords = (llrp_u16_t) args->applicationData.NumberOfWords;
08356           LLRP_ThingMagicIDSSL900AInitialize_setThingMagicIDSApplicationData(pTMIdsInitialize,
08357               pTMIdsApplicationData);
08358 
08362           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08363               (LLRP_tSParameter *)pTMIdsInitialize);
08364           break;
08365         }
08366 
08367       case TMR_TAGOP_GEN2_IDS_SL900A_SETLOGMODE:
08368         {
08369           TMR_TagOp_GEN2_IDS_SL900A_SetLogMode      *args;
08370           LLRP_tSThingMagicIDSSL900ASetLogMode      *pTMIdsSetLogMode;
08371           LLRP_tSThingMagicIDSSL900ACommandRequest  *pTMIdsCommandRequest;
08372 
08373           args = &tagop->u.gen2.u.custom.u.ids.u.setLogMode;
08374 
08375           /* Construct and initialize TMIDS SetLogMode opspec */
08376           pTMIdsSetLogMode = LLRP_ThingMagicIDSSL900ASetLogMode_construct();
08377           /* Construct and initialize TMIDS Command Request */
08378           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08379           /* Set OpSpecId to TMIDS Command Request */
08380           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08381               reader->u.llrpReader.opSpecId);
08382           /* Set access password to TMIDS Command Request */
08383           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08384               (llrp_u32_t) args->AccessPassword);
08385           /* Set the IDS password level to TMIDS Command Request */
08386           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08387               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08388           /* Set the Command code for IDS SetLogMode operation to TMIDS Command Request */
08389           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08390               (llrp_u8_t)args->CommandCode);
08391           /* Set the IDS Password to TMIDS Command Request */
08392           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08393               (llrp_u32_t)args->Password);
08394           /* Set the IDS Command Request to TMIDS SetLogMode opspec */
08395           LLRP_ThingMagicIDSSL900ASetLogMode_setThingMagicIDSSL900ACommandRequest(pTMIdsSetLogMode,
08396               pTMIdsCommandRequest);
08397           /* Set the logging Form */
08398           LLRP_ThingMagicIDSSL900ASetLogMode_setLoggingForm(pTMIdsSetLogMode,
08399               (LLRP_tEThingMagicCustomIDSLoggingForm)args->sl900A.dataLog);
08400           /* Set the Storage rule */
08401           LLRP_ThingMagicIDSSL900ASetLogMode_setStorageRule(pTMIdsSetLogMode,
08402               (LLRP_tEThingMagicCustomIDSStorageRule)args->sl900A.rule);
08403           /* Enable log for EXT1 external sensor */
08404           LLRP_ThingMagicIDSSL900ASetLogMode_setExt1Enable(pTMIdsSetLogMode,
08405               (llrp_u1_t)args->Ext1Enable);
08406           /* Enable log for EXT2 external sensor */
08407           LLRP_ThingMagicIDSSL900ASetLogMode_setExt2Enable(pTMIdsSetLogMode,
08408               (llrp_u1_t)args->Ext2Enable);
08409           /* Enable log for Temperature sensor */
08410           LLRP_ThingMagicIDSSL900ASetLogMode_setTempEnable(pTMIdsSetLogMode,
08411               (llrp_u1_t)args->TempEnable);
08412           /* Enable log for BATT sensor */
08413           LLRP_ThingMagicIDSSL900ASetLogMode_setBattEnable(pTMIdsSetLogMode,
08414               (llrp_u1_t)args->BattEnable);
08415           /* Set the log interval */
08416           LLRP_ThingMagicIDSSL900ASetLogMode_setLogInterval(pTMIdsSetLogMode,
08417               (llrp_u16_t)args->LogInterval);
08418 
08422           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08423               (LLRP_tSParameter *)pTMIdsSetLogMode);
08424           break;
08425         }
08426 
08427       case TMR_TAGOP_GEN2_IDS_SL900A_STARTLOG:
08428         {
08429           TMR_TagOp_GEN2_IDS_SL900A_StartLog        *args;
08430           LLRP_tSThingMagicIDSSL900AStartLog        *pTMIdsStartLog;
08431           LLRP_tSThingMagicIDSSL900ACommandRequest  *pTMIdsCommandRequest;
08432 
08433           args = &tagop->u.gen2.u.custom.u.ids.u.startLog;
08434 
08435           /* Construct and initialize TMIDS StartLog opspec */
08436           pTMIdsStartLog = LLRP_ThingMagicIDSSL900AStartLog_construct();
08437           /* Construct and initialize TMIDS Command Request */
08438           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08439           /* Set OpSpecId to TMIDS Command Request */
08440           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08441               reader->u.llrpReader.opSpecId);
08442           /* Set access password to TMIDS Command Request */
08443           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08444               (llrp_u32_t) args->AccessPassword);
08445           /* Set the IDS password level to TMIDS Command Request */
08446           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08447               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08448           /* Set the Command code for IDS StartLog operation to TMIDS Command Request */
08449           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08450               (llrp_u8_t)args->CommandCode);
08451           /* Set the IDS Password to TMIDS Command Request */
08452           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08453               (llrp_u32_t)args->Password);
08454           /* Set the IDS Command Request to TMIDS StartLog opspec */
08455           LLRP_ThingMagicIDSSL900AStartLog_setThingMagicIDSSL900ACommandRequest(pTMIdsStartLog,
08456               pTMIdsCommandRequest);
08457           /* Set the Time to initialize log timestamp counter with */
08458           LLRP_ThingMagicIDSSL900AStartLog_setStartTime(pTMIdsStartLog,
08459               (llrp_u32_t)args->startTime);
08460 
08464           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08465               (LLRP_tSParameter *)pTMIdsStartLog);
08466           break;
08467         }
08468 
08469       case TMR_TAGOP_GEN2_IDS_SL900A_GETLOGSTATE:
08470         {
08471           TMR_TagOp_GEN2_IDS_SL900A_GetLogState     *args;
08472           LLRP_tSThingMagicIDSSL900AGetLogState     *pTMIdsGetLogState;
08473           LLRP_tSThingMagicIDSSL900ACommandRequest  *pTMIdsCommandRequest;
08474 
08475           args = &tagop->u.gen2.u.custom.u.ids.u.getLog;
08476 
08477           /* Construct and initialize TMIDS StartLog opspec */
08478           pTMIdsGetLogState = LLRP_ThingMagicIDSSL900AGetLogState_construct();
08479           /* Construct and initialize TMIDS Command Request */
08480           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08481           /* Set OpSpecId to TMIDS Command Request */
08482           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08483               reader->u.llrpReader.opSpecId);
08484           /* Set access password to TMIDS Command Request */
08485           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08486               (llrp_u32_t) args->AccessPassword);
08487           /* Set the IDS password level to TMIDS Command Request */
08488           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08489               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08490           /* Set the Command code for IDS GetLogState operation to TMIDS Command Request */
08491           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08492               (llrp_u8_t)args->CommandCode);
08493           /* Set the IDS Password to TMIDS Command Request */
08494           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08495               (llrp_u32_t)args->Password);
08496           /* Set the IDS Command Request to TMIDS GetLogState opspec */
08497           LLRP_ThingMagicIDSSL900AGetLogState_setThingMagicIDSSL900ACommandRequest(pTMIdsGetLogState,
08498               pTMIdsCommandRequest);
08499 
08503           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08504               (LLRP_tSParameter *)pTMIdsGetLogState);
08505           break;
08506         }
08507 
08508       case TMR_TAGOP_GEN2_IDS_SL900A_ENDLOG:
08509         {
08510           TMR_TagOp_GEN2_IDS_SL900A_EndLog          *args;
08511           LLRP_tSThingMagicIDSSL900AEndLog          *pTMIdsEndLog;
08512           LLRP_tSThingMagicIDSSL900ACommandRequest  *pTMIdsCommandRequest;
08513 
08514           args = &tagop->u.gen2.u.custom.u.ids.u.endLog;
08515 
08516           /* Construct and initialize TMIDS EndLOg opspec */
08517           pTMIdsEndLog = LLRP_ThingMagicIDSSL900AEndLog_construct();
08518           /* Construct and initialize TMIDS Command Request */
08519           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08520           /* Set OpSpecId to TMIDS Command Request */
08521           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08522               reader->u.llrpReader.opSpecId);
08523           /* Set access password to TMIDS Command Request */
08524           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08525               (llrp_u32_t) args->AccessPassword);
08526           /* Set the IDS password level to TMIDS Command Request */
08527           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08528               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08529           /* Set the Command code for IDS EndLog operation to TMIDS Command Request */
08530           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08531               (llrp_u8_t)args->CommandCode);
08532           /* Set the IDS Password to TMIDS Command Request */
08533           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08534               (llrp_u32_t)args->Password);
08535           /* Set the IDS Command Request to TMIDS EndLog opspec */
08536           LLRP_ThingMagicIDSSL900AEndLog_setThingMagicIDSSL900ACommandRequest(pTMIdsEndLog,
08537               pTMIdsCommandRequest);
08538 
08542           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08543               (LLRP_tSParameter *)pTMIdsEndLog);
08544           break;
08545         }
08546 
08547       case TMR_TAGOP_GEN2_IDS_SL900A_ACCESSFIFOSTATUS:
08548         {
08549           TMR_TagOp_GEN2_IDS_SL900A_AccessFifoStatus  *args;
08550           LLRP_tSThingMagicIDSSL900AAccessFIFOStatus  *pTMIdsAccessFifoStatus;
08551           LLRP_tSThingMagicIDSSL900ACommandRequest    *pTMIdsCommandRequest;
08552 
08553           args = &tagop->u.gen2.u.custom.u.ids.u.accessFifoStatus;
08554 
08555           /* Construct and initialize TMIDS FifoStatus opspec */
08556           pTMIdsAccessFifoStatus = LLRP_ThingMagicIDSSL900AAccessFIFOStatus_construct();
08557           /* Construct and initialize TMIDS Command Request */
08558           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08559           /* Set OpSpecId to TMIDS Command Request */
08560           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08561               reader->u.llrpReader.opSpecId);
08562           /* Set access password to TMIDS Command Request */
08563           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08564               (llrp_u32_t) args->status.AccessPassword);
08565           /* Set the IDS password level to TMIDS Command Request */
08566           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08567               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->status.sl900A.level);
08568           /* Set the Command code for IDS AccessFifoStatus operation to TMIDS Command Request */
08569           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08570               (llrp_u8_t)args->status.CommandCode);
08571           /* Set the IDS Password to TMIDS Command Request */
08572           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08573               (llrp_u32_t)args->status.Password);
08574           /* Set the IDS Command Request to TMIDS AccessFifoStatus opspec */
08575           LLRP_ThingMagicIDSSL900AAccessFIFOStatus_setThingMagicIDSSL900ACommandRequest(pTMIdsAccessFifoStatus,
08576               pTMIdsCommandRequest);
08577 
08581           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08582               (LLRP_tSParameter *)pTMIdsAccessFifoStatus);
08583           break;
08584         }
08585 
08586       case TMR_TAGOP_GEN2_IDS_SL900A_ACCESSFIFOWRITE:
08587         {
08588           TMR_TagOp_GEN2_IDS_SL900A_AccessFifoWrite  *args;
08589           LLRP_tSThingMagicIDSSL900AAccessFIFOWrite  *pTMIdsAccessFifoWrite;
08590           LLRP_tSThingMagicIDSSL900ACommandRequest   *pTMIdsCommandRequest;
08591 
08592           args = &tagop->u.gen2.u.custom.u.ids.u.accessFifoWrite;
08593 
08594           /* Construct and initialize TMIDS FifoWrite opspec */
08595           pTMIdsAccessFifoWrite = LLRP_ThingMagicIDSSL900AAccessFIFOWrite_construct();
08596           /* Construct and initialize TMIDS Command Request */
08597           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08598           /* Set OpSpecId to TMIDS Command Request */
08599           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08600               reader->u.llrpReader.opSpecId);
08601           /* Set access password to TMIDS Command Request */
08602           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08603               (llrp_u32_t) args->write.AccessPassword);
08604           /* Set the IDS password level to TMIDS Command Request */
08605           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08606               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->write.sl900A.level);
08607           /* Set the Command code for IDS AccessFifoWrite operation to TMIDS Command Request */
08608           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08609               (llrp_u8_t)args->write.CommandCode);
08610           /* Set the IDS Password to TMIDS Command Request */
08611           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08612               (llrp_u32_t)args->write.Password);
08613           /* Set the IDS Command Request to TMIDS AccessFifoWrite opspec */
08614           LLRP_ThingMagicIDSSL900AAccessFIFOWrite_setThingMagicIDSSL900ACommandRequest(pTMIdsAccessFifoWrite,
08615               pTMIdsCommandRequest);
08616           /* Set the writePayLoad */
08617           {
08618             llrp_u8v_t  writePayLoad;
08619             /* construct and initialize the writePayLoad */
08620             writePayLoad = LLRP_u8v_construct((llrp_u16_t)args->payLoad->len);
08621             memcpy(writePayLoad.pValue, args->payLoad->list,
08622                 (size_t) (args->payLoad->len * sizeof (args->payLoad->list[0])));
08623             LLRP_ThingMagicIDSSL900AAccessFIFOWrite_setwritePayLoad(pTMIdsAccessFifoWrite,
08624                 writePayLoad);
08625           }
08626 
08630           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08631               (LLRP_tSParameter *)pTMIdsAccessFifoWrite);
08632           break;
08633         }
08634 
08635       case TMR_TAGOP_GEN2_IDS_SL900A_ACCESSFIFOREAD:
08636         {
08637           TMR_TagOp_GEN2_IDS_SL900A_AccessFifoRead  *args;
08638           LLRP_tSThingMagicIDSSL900AAccessFIFORead  *pTMIdsAccessFifoRead;
08639           LLRP_tSThingMagicIDSSL900ACommandRequest  *pTMIdsCommandRequest;
08640 
08641           args = &tagop->u.gen2.u.custom.u.ids.u.accessFifoRead;
08642 
08643           /* Construct and initialize TMIDS FifoRead opspec */
08644           pTMIdsAccessFifoRead = LLRP_ThingMagicIDSSL900AAccessFIFORead_construct();
08645           /* Construct and initialize TMIDS Command Request */
08646           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08647           /* Set OpSpecId to TMIDS Command Request */
08648           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08649               reader->u.llrpReader.opSpecId);
08650           /* Set access password to TMIDS Command Request */
08651           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08652               (llrp_u32_t) args->read.AccessPassword);
08653           /* Set the IDS password level to TMIDS Command Request */
08654           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08655               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->read.sl900A.level);
08656           /* Set the Command code for IDS AccessFifoRead operation to TMIDS Command Request */
08657           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08658               (llrp_u8_t)args->read.CommandCode);
08659           /* Set the IDS Password to TMIDS Command Request */
08660           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08661               (llrp_u32_t)args->read.Password);
08662           /* Set the IDS Command Request to TMIDS AccessFifoRead opspec */
08663           LLRP_ThingMagicIDSSL900AAccessFIFORead_setThingMagicIDSSL900ACommandRequest(pTMIdsAccessFifoRead,
08664               pTMIdsCommandRequest);
08665           /* Specify the fifo read length */
08666           LLRP_ThingMagicIDSSL900AAccessFIFORead_setFIFOReadLength(pTMIdsAccessFifoRead,
08667               (llrp_u8_t)args->length);
08668 
08672           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08673               (LLRP_tSParameter *)pTMIdsAccessFifoRead);
08674           break;
08675         }
08676 
08677       case TMR_TAGOP_GEN2_IDS_SL900A_GETCALIBRATIONDATA:
08678         {
08679           TMR_TagOp_GEN2_IDS_SL900A_GetCalibrationData *args;
08680           LLRP_tSThingMagicIDSSL900AGetCalibrationData *pTMIdsGetCalibrationData;
08681           LLRP_tSThingMagicIDSSL900ACommandRequest     *pTMIdsCommandRequest;
08682 
08683           args = &tagop->u.gen2.u.custom.u.ids.u.calibrationData;
08684 
08685           /* Construct and initialize TMIDS GetCalibration opspec */
08686           pTMIdsGetCalibrationData = LLRP_ThingMagicIDSSL900AGetCalibrationData_construct();
08687           /* Construct and initialize TMIDS Command Request */
08688           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08689           /* Set OpSpecId to TMIDS Command Request */
08690           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08691               reader->u.llrpReader.opSpecId);
08692           /* Set access password to TMIDS Command Request */
08693           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08694               (llrp_u32_t) args->AccessPassword);
08695           /* Set the IDS password level to TMIDS Command Request */
08696           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08697               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08698           /* Set the Command code for IDS GetCalibrationData operation to TMIDS Command Request */
08699           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08700               (llrp_u8_t)args->CommandCode);
08701           /* Set the IDS Password to TMIDS Command Request */
08702           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08703               (llrp_u32_t)args->Password);
08704           /* Set the IDS Command Request to TMIDS GetCalibrationData opspec */
08705           LLRP_ThingMagicIDSSL900AGetCalibrationData_setThingMagicIDSSL900ACommandRequest(pTMIdsGetCalibrationData,
08706               pTMIdsCommandRequest);
08707 
08711           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08712               (LLRP_tSParameter *)pTMIdsGetCalibrationData);
08713           break;
08714         }
08715 
08716       case TMR_TAGOP_GEN2_IDS_SL900A_SETCALIBRATIONDATA:
08717         {
08718           TMR_TagOp_GEN2_IDS_SL900A_SetCalibrationData *args;
08719           LLRP_tSThingMagicIDSSL900ASetCalibrationData *pTMIdsSetCalibrationData;
08720           LLRP_tSThingMagicIDSSL900ACommandRequest     *pTMIdsCommandRequest;
08721           LLRP_tSThingMagicIDSCalibrationData          *pTMIdsCalibrationData;
08722 
08723           args = &tagop->u.gen2.u.custom.u.ids.u.setCalibration;
08724 
08725           /* Construct and initialize TMIDS SetCalibration opspec */
08726           pTMIdsSetCalibrationData = LLRP_ThingMagicIDSSL900ASetCalibrationData_construct();
08727           /* Construct and initialize TMIDS Command Request */
08728           pTMIdsCommandRequest = LLRP_ThingMagicIDSSL900ACommandRequest_construct();
08729           /* Set OpSpecId to TMIDS Command Request */
08730           LLRP_ThingMagicIDSSL900ACommandRequest_setOpSpecID(pTMIdsCommandRequest,
08731               reader->u.llrpReader.opSpecId);
08732           /* Set access password to TMIDS Command Request */
08733           LLRP_ThingMagicIDSSL900ACommandRequest_setAccessPassword(pTMIdsCommandRequest,
08734               (llrp_u32_t) args->AccessPassword);
08735           /* Set the IDS password level to TMIDS Command Request */
08736           LLRP_ThingMagicIDSSL900ACommandRequest_setPasswordLevel(pTMIdsCommandRequest,
08737               (LLRP_tEThingMagicCustomIDSPasswordLevel)args->sl900A.level);
08738           /* Set the Command code for IDS SetCalibration operation to TMIDS Command Request */
08739           LLRP_ThingMagicIDSSL900ACommandRequest_setCommandCode(pTMIdsCommandRequest,
08740               (llrp_u8_t)args->CommandCode);
08741           /* Set the IDS Password to TMIDS Command Request */
08742           LLRP_ThingMagicIDSSL900ACommandRequest_setIDSPassword(pTMIdsCommandRequest,
08743               (llrp_u32_t)args->Password);
08744           /* Set the IDS Command Request to TMIDS SetCalibrationData opspec */
08745           LLRP_ThingMagicIDSSL900ASetCalibrationData_setThingMagicIDSSL900ACommandRequest(pTMIdsSetCalibrationData,
08746               pTMIdsCommandRequest);
08747           /* Construct and initialize the TMIDS CalibrationData */
08748           {
08749             pTMIdsCalibrationData = LLRP_ThingMagicIDSCalibrationData_construct();
08750             /* Set the Raw Binary stream to CalibrationData */
08751             LLRP_ThingMagicIDSCalibrationData_setraw(pTMIdsCalibrationData, (llrp_u64_t)args->cal.raw);
08752             /* AD1 lower voltage reference - fine - DO NOT MODIFY */
08753             LLRP_ThingMagicIDSCalibrationData_setad1(pTMIdsCalibrationData, (llrp_u8_t)args->cal.Ad1);
08754             /* AD2 lower voltage reference - fine - DO NOT MODIFY */
08755             LLRP_ThingMagicIDSCalibrationData_setad2(pTMIdsCalibrationData, (llrp_u8_t)args->cal.Ad2);
08756             /* AD1 lower voltage reference - coarse */
08757             LLRP_ThingMagicIDSCalibrationData_setcoars1(pTMIdsCalibrationData, (llrp_u8_t)args->cal.Coarse1);
08758             /* AD2 lower voltage reference - coarse */
08759             LLRP_ThingMagicIDSCalibrationData_setcoars2(pTMIdsCalibrationData, (llrp_u8_t)args->cal.Coarse2);
08760             /* Switches the lower AD voltage reference to ground */
08761             LLRP_ThingMagicIDSCalibrationData_setgndSwitch(pTMIdsCalibrationData, (llrp_u1_t)args->cal.GndSwitch);
08762             /* POR voltage level for 1.5V system */
08763             LLRP_ThingMagicIDSCalibrationData_setselp12(pTMIdsCalibrationData, (llrp_u8_t)args->cal.Selp12);
08764             /* Main reference voltage calibration -- DO NOT MODIFY */
08765             LLRP_ThingMagicIDSCalibrationData_setadf(pTMIdsCalibrationData, (llrp_u8_t)args->cal.Adf);
08766             /* RTC oscillator calibration */
08767             LLRP_ThingMagicIDSCalibrationData_setdf(pTMIdsCalibrationData, (llrp_u8_t)args->cal.Df);
08768             /* Controlled battery supply for external sensor - the battery voltage is connected to the EXC pin */
08769             LLRP_ThingMagicIDSCalibrationData_setswExtEn(pTMIdsCalibrationData, (llrp_u1_t)args->cal.SwExtEn);
08770             /* POR voltage level for 3V system */
08771             LLRP_ThingMagicIDSCalibrationData_setselp22(pTMIdsCalibrationData, (llrp_u8_t)args->cal.Selp22);
08772             /* Voltage level interrupt level for external sensor -- ratiometric */
08773             LLRP_ThingMagicIDSCalibrationData_setirlev(pTMIdsCalibrationData, (llrp_u8_t)args->cal.Irlev);
08774             /* Main system clock oscillator calibration -- DO NOT MODIFY */
08775             LLRP_ThingMagicIDSCalibrationData_setringCal(pTMIdsCalibrationData, (llrp_u8_t)args->cal.RingCal);
08776             /* Temperature conversion offset calibration -- DO NOT MODIFY */
08777             LLRP_ThingMagicIDSCalibrationData_setoffInt(pTMIdsCalibrationData, (llrp_u8_t)args->cal.OffInt);
08778             /* Bandgap voltage temperature coefficient calibration -- DO NOT MODIFY */
08779             LLRP_ThingMagicIDSCalibrationData_setreftc(pTMIdsCalibrationData, (llrp_u8_t)args->cal.Reftc);
08780             /* Excitate for resistive sensors without DC */
08781             LLRP_ThingMagicIDSCalibrationData_setexcRes(pTMIdsCalibrationData, (llrp_u1_t)args->cal.ExcRes);
08782             /* Reserved for Future Use */
08783             LLRP_ThingMagicIDSCalibrationData_setRFU(pTMIdsCalibrationData, (llrp_u8_t)args->cal.RFU);
08784 
08785             LLRP_ThingMagicIDSSL900ASetCalibrationData_setThingMagicIDSCalibrationData(pTMIdsSetCalibrationData,
08786                 (LLRP_tSThingMagicIDSCalibrationData *)pTMIdsCalibrationData);
08787           }
08788 
08792           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08793               (LLRP_tSParameter *)pTMIdsSetCalibrationData);
08794           break;
08795         }
08796 
08797       case TMR_TAGOP_GEN2_DENATRAN_IAV_ACTIVATESECUREMODE:
08798         {
08799           TMR_TagOp_GEN2_Denatran_IAV_Activate_Secure_Mode *args;
08800           LLRP_tSThingMagicDenatranIAVActivateSecureMode   *pTMDenatranIAVActivateSecureMode;
08801           LLRP_tSThingMagicDenatranIAVCommandRequest       *pTMDenatranIAVCommandRequest;
08802 
08803           args = &tagop->u.gen2.u.custom.u.IavDenatran.u.secureMode;
08804 
08805           /* Construct and initialize the TMDenatranIAV ActivateSecureMode OpSpec */
08806           pTMDenatranIAVActivateSecureMode = LLRP_ThingMagicDenatranIAVActivateSecureMode_construct();
08807           /* Construct and initialize the TM DenatranIAV Command request */
08808           pTMDenatranIAVCommandRequest = LLRP_ThingMagicDenatranIAVCommandRequest_construct();
08809           /* Set the OpSpecId to the TM Denatran IAV Command request */
08810           LLRP_ThingMagicDenatranIAVCommandRequest_setOpSpecID(pTMDenatranIAVCommandRequest,
08811               reader->u.llrpReader.opSpecId);
08812           /* Set the DenatranIAV Payload value to the TM DenatranIAV Command request */
08813           LLRP_ThingMagicDenatranIAVCommandRequest_setPayLoad(pTMDenatranIAVCommandRequest,
08814               args->payload);
08815           /* Set the DenatranIAV Command request to the TM DenatranIAV ActivateSecureMode */
08816           LLRP_ThingMagicDenatranIAVActivateSecureMode_setThingMagicDenatranIAVCommandRequest(pTMDenatranIAVActivateSecureMode,
08817               pTMDenatranIAVCommandRequest);
08818 
08822           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08823               (LLRP_tSParameter *)pTMDenatranIAVActivateSecureMode);
08824           break;
08825         }
08826       case TMR_TAGOP_GEN2_DENATRAN_IAV_AUTHENTICATEOBU:
08827         {
08828           TMR_TagOp_GEN2_Denatran_IAV_Authenticate_OBU *args;
08829           LLRP_tSThingMagicDenatranIAVAuthenticateOBU  *pTMDenatranIAVAuthenticateOBU;
08830           LLRP_tSThingMagicDenatranIAVCommandRequest   *pTMDenatranIAVCommandRequest;
08831 
08832           args = &tagop->u.gen2.u.custom.u.IavDenatran.u.authenticateOBU;
08833 
08834           /* Construct and Initialize the TMDenatranIAV AuthenticateOBU OpSpec */
08835           pTMDenatranIAVAuthenticateOBU = LLRP_ThingMagicDenatranIAVAuthenticateOBU_construct();
08836           /* Construct and Initialize the TMDenatranIAV Command request */
08837           pTMDenatranIAVCommandRequest = LLRP_ThingMagicDenatranIAVCommandRequest_construct();
08838           /* Set the OpSpecId to the TM Denatran IAV Command request */
08839           LLRP_ThingMagicDenatranIAVCommandRequest_setOpSpecID(pTMDenatranIAVCommandRequest,
08840               reader->u.llrpReader.opSpecId);
08841           /* Set the DenatranIAV Payload value to the TM DenatranIAV Command request */
08842           LLRP_ThingMagicDenatranIAVCommandRequest_setPayLoad(pTMDenatranIAVCommandRequest,
08843               args->payload);
08844           /* Set the DenatranIAV Command request to the TM DenatranIAV ActivateSecureMode */
08845           LLRP_ThingMagicDenatranIAVAuthenticateOBU_setThingMagicDenatranIAVCommandRequest(pTMDenatranIAVAuthenticateOBU,
08846               pTMDenatranIAVCommandRequest);
08847 
08851           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08852               (LLRP_tSParameter *)pTMDenatranIAVAuthenticateOBU);
08853           break;
08854         }
08855       case TMR_TAGOP_GEN2_ACTIVATE_SINIAV_MODE:
08856         {
08857           TMR_TagOp_GEN2_Denatran_IAV_Activate_Siniav_Mode *args;
08858           LLRP_tSThingMagicDenatranIAVActivateSiniavMode   *pTMDenatranIAVSiniavMode;
08859           LLRP_tSThingMagicDenatranIAVCommandRequest       *pTMDenatranIAVCommandRequest;
08860 
08861           args = &tagop->u.gen2.u.custom.u.IavDenatran.u.activateSiniavMode;
08862 
08863           /* Construct and Initialize the TMDenatranIAV ActivateSiniavMode OpSpec */
08864           pTMDenatranIAVSiniavMode = LLRP_ThingMagicDenatranIAVActivateSiniavMode_construct();
08865           /* Construct and Initialize the TMDenatranIAV Command request */
08866           pTMDenatranIAVCommandRequest = LLRP_ThingMagicDenatranIAVCommandRequest_construct();
08867           /* Set the OpSpecId to the TM Denatran IAV Command request */
08868           LLRP_ThingMagicDenatranIAVCommandRequest_setOpSpecID(pTMDenatranIAVCommandRequest,
08869               reader->u.llrpReader.opSpecId);
08870           /* Set the DenatranIAV Payload value to the TM DenatranIAV Command request */
08871           LLRP_ThingMagicDenatranIAVCommandRequest_setPayLoad(pTMDenatranIAVCommandRequest,
08872               args->payload);
08873           {
08878             llrp_u8v_t temp;
08879             uint8_t len = 8;
08880 
08881             temp = LLRP_u8v_construct((llrp_u16_t)len);
08882             memcpy(temp.pValue, args->token, (size_t)temp.nValue);
08883             LLRP_ThingMagicDenatranIAVActivateSiniavMode_settokenData(pTMDenatranIAVSiniavMode,
08884                 temp);
08885           }
08886 
08887           /* Set the DenatranIAV Command request to the TM DenatranIAV ActivateSecureMode */
08888           LLRP_ThingMagicDenatranIAVActivateSiniavMode_setThingMagicDenatranIAVCommandRequest(pTMDenatranIAVSiniavMode,
08889               pTMDenatranIAVCommandRequest);
08890 
08894           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08895               (LLRP_tSParameter *)pTMDenatranIAVSiniavMode);
08896           break;
08897         }
08898       case TMR_TAGOP_GEN2_OBU_AUTH_ID:
08899         {
08900           TMR_TagOp_GEN2_Denatran_IAV_OBU_Auth_ID       *args;
08901           LLRP_tSThingMagicDenatranIAVOBUAuthenticateID *pTMDenatranIAVOBUAuthID;
08902           LLRP_tSThingMagicDenatranIAVCommandRequest    *pTMDenatranIAVCommandRequest;
08903 
08904           args = &tagop->u.gen2.u.custom.u.IavDenatran.u.obuAuthId;
08905 
08906           /* Construct and Initialize the TMDenatranIAV OBU AuthID OpSpec */
08907           pTMDenatranIAVOBUAuthID = LLRP_ThingMagicDenatranIAVOBUAuthenticateID_construct();
08908           /* Construct and Initialize the TMDenatranIAV Command request */
08909           pTMDenatranIAVCommandRequest = LLRP_ThingMagicDenatranIAVCommandRequest_construct();
08910           /* Set the OpSpecId to the TM Denatran IAV Command request */
08911           LLRP_ThingMagicDenatranIAVCommandRequest_setOpSpecID(pTMDenatranIAVCommandRequest,
08912               reader->u.llrpReader.opSpecId);
08913           /* Set the DenatranIAV Payload value to the TM DenatranIAV Command request */
08914           LLRP_ThingMagicDenatranIAVCommandRequest_setPayLoad(pTMDenatranIAVCommandRequest,
08915               args->payload);
08916           /* Set the DenatranIAV Command request to the TM DenatranIAV ActivateSecureMode */
08917           LLRP_ThingMagicDenatranIAVOBUAuthenticateID_setThingMagicDenatranIAVCommandRequest(pTMDenatranIAVOBUAuthID,
08918               pTMDenatranIAVCommandRequest);
08919 
08923           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08924               (LLRP_tSParameter *)pTMDenatranIAVOBUAuthID);
08925           break;
08926         }
08927       case TMR_TAGOP_GEN2_AUTHENTICATE_OBU_FULL_PASS1:
08928         {
08929           TMR_TagOp_GEN2_Denatran_IAV_OBU_Auth_Full_Pass1      *args;
08930           LLRP_tSThingMagicDenatranIAVOBUAuthenticateFullPass1 *pTMDenatranIAVOBUFullPass1;
08931           LLRP_tSThingMagicDenatranIAVCommandRequest           *pTMDenatranIAVCommandRequest;
08932 
08933           args = &tagop->u.gen2.u.custom.u.IavDenatran.u.obuAuthFullPass1;
08934 
08935           /* Construct and Initialize the TMDenatranIAV OBU Full Pass1 OpSpec */
08936           pTMDenatranIAVOBUFullPass1 = LLRP_ThingMagicDenatranIAVOBUAuthenticateFullPass1_construct();
08937           /* Construct and Initialize the TMDenatranIAV Command request */
08938           pTMDenatranIAVCommandRequest = LLRP_ThingMagicDenatranIAVCommandRequest_construct();
08939           /* Set the OpSpecId to the TM Denatran IAV Command request */
08940           LLRP_ThingMagicDenatranIAVCommandRequest_setOpSpecID(pTMDenatranIAVCommandRequest,
08941               reader->u.llrpReader.opSpecId);
08942           /* Set the DenatranIAV Payload value to the TM DenatranIAV Command request */
08943           LLRP_ThingMagicDenatranIAVCommandRequest_setPayLoad(pTMDenatranIAVCommandRequest,
08944               args->payload);
08945           /* Set the DenatranIAV Command request to the TM DenatranIAV ActivateSecureMode */
08946           LLRP_ThingMagicDenatranIAVOBUAuthenticateFullPass1_setThingMagicDenatranIAVCommandRequest(pTMDenatranIAVOBUFullPass1,
08947               pTMDenatranIAVCommandRequest);
08948 
08952           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08953               (LLRP_tSParameter *)pTMDenatranIAVOBUFullPass1);
08954           break;
08955         }
08956       case TMR_TAGOP_GEN2_AUTHENTICATE_OBU_FULL_PASS2:
08957         {
08958           TMR_TagOp_GEN2_Denatran_IAV_OBU_Auth_Full_Pass2      *args;
08959           LLRP_tSThingMagicDenatranIAVOBUAuthenticateFullPass2 *pTMDenatranIAVOBUFullPass2;
08960           LLRP_tSThingMagicDenatranIAVCommandRequest           *pTMDenatranIAVCommandRequest;
08961 
08962           args = &tagop->u.gen2.u.custom.u.IavDenatran.u.obuAuthFullPass2;
08963 
08964           /* Construct and Initialize the TMDenatranIAV OBU Full Pass2 OpSpec */
08965           pTMDenatranIAVOBUFullPass2 = LLRP_ThingMagicDenatranIAVOBUAuthenticateFullPass2_construct();
08966           /* Construct and Initialize the TMDenatranIAV Command request */
08967           pTMDenatranIAVCommandRequest = LLRP_ThingMagicDenatranIAVCommandRequest_construct();
08968           /* Set the OpSpecId to the TM Denatran IAV Command request */
08969           LLRP_ThingMagicDenatranIAVCommandRequest_setOpSpecID(pTMDenatranIAVCommandRequest,
08970               reader->u.llrpReader.opSpecId);
08971           /* Set the DenatranIAV Payload value to the TM DenatranIAV Command request */
08972           LLRP_ThingMagicDenatranIAVCommandRequest_setPayLoad(pTMDenatranIAVCommandRequest,
08973               args->payload);
08974           /* Set the DenatranIAV Command request to the TM DenatranIAV ActivateSecureMode */
08975           LLRP_ThingMagicDenatranIAVOBUAuthenticateFullPass2_setThingMagicDenatranIAVCommandRequest(pTMDenatranIAVOBUFullPass2,
08976               pTMDenatranIAVCommandRequest);
08977 
08981           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
08982               (LLRP_tSParameter *)pTMDenatranIAVOBUFullPass2);
08983           break;
08984         }
08985       case TMR_TAGOP_GEN2_OBU_READ_FROM_MEM_MAP:
08986         {
08987           TMR_TagOp_GEN2_Denatran_IAV_OBU_ReadFromMemMap *args;
08988           LLRP_tSThingMagicDenatranIAVOBUReadFromMemMap  *pTMDenatranIAVOBUReadFromMemMap;
08989           LLRP_tSThingMagicDenatranIAVCommandRequest     *pTMDenatranIAVCommandRequest;
08990 
08991           args = &tagop->u.gen2.u.custom.u.IavDenatran.u.obuReadFromMemMap;
08992 
08993           /* Construct and Initialize the TMDenatranIAV OBU ReadFromMemMap OpSpec */
08994           pTMDenatranIAVOBUReadFromMemMap = LLRP_ThingMagicDenatranIAVOBUReadFromMemMap_construct();
08995           /* Construct and Initialize the TMDenatranIAV Command request */
08996           pTMDenatranIAVCommandRequest = LLRP_ThingMagicDenatranIAVCommandRequest_construct();
08997           /* Set the OpSpecId to the TM Denatran IAV Command request */
08998           LLRP_ThingMagicDenatranIAVCommandRequest_setOpSpecID(pTMDenatranIAVCommandRequest,
08999               reader->u.llrpReader.opSpecId);
09000           /* Set the DenatranIAV Payload value to the TM DenatranIAV Command request */
09001           LLRP_ThingMagicDenatranIAVCommandRequest_setPayLoad(pTMDenatranIAVCommandRequest,
09002               args->payload);
09003           /* Set the read pointer to the TMDenatranIAV OBU ReadFromMemMap read pointer */
09004           LLRP_ThingMagicDenatranIAVOBUReadFromMemMap_setReadPtr(pTMDenatranIAVOBUReadFromMemMap,
09005               args->readPtr);
09006           /* Set the DenatranIAV Command request to the TM DenatranIAV ActivateSecureMode */
09007           LLRP_ThingMagicDenatranIAVOBUReadFromMemMap_setThingMagicDenatranIAVCommandRequest(pTMDenatranIAVOBUReadFromMemMap,
09008               pTMDenatranIAVCommandRequest);
09009 
09013           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
09014               (LLRP_tSParameter *)pTMDenatranIAVOBUReadFromMemMap);
09015           break;
09016         }
09017       case TMR_TAGOP_GEN2_OBU_WRITE_TO_MEM_MAP:
09018         {
09019           TMR_TagOp_GEN2_Denatran_IAV_OBU_WriteToMemMap *args;
09020           LLRP_tSThingMagicDenatranIAVOBUWriteToMemMap  *pTMDenatranIAVOBUWriteToMemMap;
09021           LLRP_tSThingMagicDenatranIAVCommandRequest     *pTMDenatranIAVCommandRequest;
09022 
09023           args = &tagop->u.gen2.u.custom.u.IavDenatran.u.obuWriteToMemMap;
09024 
09025           /* Construct and Initialize the TMDenatranIAV OBU WriteToMemMap OpSpec */
09026           pTMDenatranIAVOBUWriteToMemMap = LLRP_ThingMagicDenatranIAVOBUWriteToMemMap_construct();
09027           /* Construct and Initialize the TMDenatranIAV Command request */
09028           pTMDenatranIAVCommandRequest = LLRP_ThingMagicDenatranIAVCommandRequest_construct();
09029           /* Set the OpSpecId to the TM Denatran IAV Command request */
09030           LLRP_ThingMagicDenatranIAVCommandRequest_setOpSpecID(pTMDenatranIAVCommandRequest,
09031               reader->u.llrpReader.opSpecId);
09032           /* Set the DenatranIAV Payload value to the TM DenatranIAV Command request */
09033           LLRP_ThingMagicDenatranIAVCommandRequest_setPayLoad(pTMDenatranIAVCommandRequest,
09034               args->payload);
09035           /* Set the write pointer to the TM DenatranIAV command write to mem map */
09036           LLRP_ThingMagicDenatranIAVOBUWriteToMemMap_setWritePtr(pTMDenatranIAVOBUWriteToMemMap,
09037               args->writePtr);
09038           /* Set the data to be written to the TM DenatranIAV Command writeToMemMap */
09039           LLRP_ThingMagicDenatranIAVOBUWriteToMemMap_setWordData(pTMDenatranIAVOBUWriteToMemMap,
09040               args->wordData);
09041 
09042           {
09047             llrp_u8v_t temp; 
09048             uint8_t len = 8;
09049 
09050             temp = LLRP_u8v_construct((llrp_u16_t)len);
09051             memcpy(temp.pValue, args->dataBuf, (size_t)temp.nValue);
09052             LLRP_ThingMagicDenatranIAVOBUWriteToMemMap_setTagIdentification(pTMDenatranIAVOBUWriteToMemMap,
09053                 temp);
09054           }
09055 
09056           {
09061             llrp_u8v_t temp; 
09062             uint8_t len = 16;
09063 
09064             temp = LLRP_u8v_construct((llrp_u16_t)len);
09065             memcpy(temp.pValue, args->dataBuf, (size_t)temp.nValue);
09066             LLRP_ThingMagicDenatranIAVOBUWriteToMemMap_setDataBuf(pTMDenatranIAVOBUWriteToMemMap,
09067                 temp);
09068           }
09069 
09070           /* Set the DenatranIAV Command request to the TM DenatranIAV ActivateSecureMode */
09071           LLRP_ThingMagicDenatranIAVOBUWriteToMemMap_setThingMagicDenatranIAVCommandRequest(pTMDenatranIAVOBUWriteToMemMap,
09072               pTMDenatranIAVCommandRequest);
09073 
09077           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
09078               (LLRP_tSParameter *)pTMDenatranIAVOBUWriteToMemMap);
09079           break;
09080         }
09081 
09082 #ifdef TMR_ENABLE_ISO180006B
09083       case TMR_TAGOP_ISO180006B_READDATA:
09084         {
09085           TMR_TagOp_ISO180006B_ReadData    *args;
09086           LLRP_tSThingMagicISO180006BRead  *pTMisoRead;
09087           llrp_u16_t                        data;
09088 
09089           args = &tagop->u.iso180006b.u.readData;
09090 
09091           /* Construct and initialize TMISO Read opspec */
09092           pTMisoRead = LLRP_ThingMagicISO180006BRead_construct();
09093           /* Set OpSpecId */
09094           LLRP_ThingMagicISO180006BRead_setOpSpecID(pTMisoRead, reader->u.llrpReader.opSpecId);
09095           /* Set the byte address */
09096           /* As API  datatype is uint8_t but
09097            * llrp takes  of type uint16_t
09098            * so, mapping the uint8_t data into uint16_t
09099            */
09100           data = args->byteAddress;
09101           LLRP_ThingMagicISO180006BRead_setByteAddress(pTMisoRead, data);
09102 
09103           /* Set the byte len */
09104           data = args->len;
09105           LLRP_ThingMagicISO180006BRead_setByteLen(pTMisoRead, data);
09106 
09110           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
09111               (LLRP_tSParameter *)pTMisoRead);
09112           break;
09113         }
09114        
09115       case TMR_TAGOP_ISO180006B_WRITEDATA:
09116         {
09117           TMR_TagOp_ISO180006B_WriteData    *args;
09118           LLRP_tSThingMagicISO180006BWrite  *pTMisoWriteData;
09119           llrp_u8v_t                         writeData;
09120           llrp_u16_t                         data;
09121 
09122           args = &tagop->u.iso180006b.u.writeData;
09123 
09124           /* Construct and initialize the TM iso write data */
09125           pTMisoWriteData = LLRP_ThingMagicISO180006BWrite_construct();
09126           /*  Set the OpSpec id */
09127           LLRP_ThingMagicISO180006BWrite_setOpSpecID(pTMisoWriteData, reader->u.llrpReader.opSpecId);
09128           /* Set the byte addresss */
09129           /* As API datatype  is uint8_t but
09130            * llrp takes  of type uint16_t
09131            * so, mapping the uint8_t data into uint16_t
09132            **/
09133           data = args->byteAddress;
09134           LLRP_ThingMagicISO180006BWrite_setByteAddress(pTMisoWriteData, data);
09135           /* set the data to be written */
09136           writeData = LLRP_u8v_construct(args->data.len);
09137           memcpy(writeData.pValue, args->data.list, writeData.nValue);
09138           LLRP_ThingMagicISO180006BWrite_setWriteData(pTMisoWriteData,
09139               writeData);
09140 
09144           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
09145               (LLRP_tSParameter *)pTMisoWriteData);
09146 
09147           break;
09148         }
09149         
09150       case TMR_TAGOP_ISO180006B_LOCK:
09151         {
09152           TMR_TagOp_ISO180006B_Lock          *args;
09153           LLRP_tSThingMagicISO180006BLock    *pTMisoLock;
09154 
09155           args = &tagop->u.iso180006b.u.lock;
09156 
09157           /* Construct and initialize the TM iso write data */
09158           pTMisoLock = LLRP_ThingMagicISO180006BLock_construct();
09159           /*  Set the OpSpec id */
09160           LLRP_ThingMagicISO180006BLock_setOpSpecID(pTMisoLock, reader->u.llrpReader.opSpecId);
09161           /* Set the address to lock */
09162           LLRP_ThingMagicISO180006BLock_setAddress(pTMisoLock, args->address);
09163 
09167           LLRP_AccessCommand_addAccessCommandOpSpec(pAccessCommand,
09168               (LLRP_tSParameter *)pTMisoLock);
09169 
09170           break;
09171         }
09172 #endif /* TMR_ENABLE_ISO180006B */
09173       case TMR_TAGOP_LIST:
09174         {
09179           return TMR_ERROR_UNSUPPORTED;
09180         }
09181 
09182       default:
09183         {
09184           /* Unknown tagop - return unsupported error */
09185           return TMR_ERROR_UNSUPPORTED; 
09186         }
09187     }
09188   }
09189 
09190   return ret;
09191 }
09192 
09205 TMR_Status
09206 TMR_LLRP_cmdAddAccessSpec(TMR_Reader *reader, 
09207                           TMR_TagProtocol protocol,
09208                           TMR_TagFilter *filter,
09209                           llrp_u32_t roSpecId,
09210                           TMR_TagOp *tagop,
09211                           bool isStandalone)
09212 {
09213   TMR_Status ret;
09214   LLRP_tSADD_ACCESSSPEC               *pCmd;
09215   LLRP_tSMessage                      *pCmdMsg;
09216   LLRP_tSMessage                      *pRspMsg;
09217   LLRP_tSADD_ACCESSSPEC_RESPONSE      *pRsp;
09218 
09219   LLRP_tSAccessSpec                   *pAccessSpec;
09220   LLRP_tSAccessSpecStopTrigger        *pAccessSpecStopTrigger;
09221   LLRP_tSAccessCommand                *pAccessCommand;
09222 
09223   ret = TMR_SUCCESS;
09224   
09228   pCmd = LLRP_ADD_ACCESSSPEC_construct();
09229 
09242   /* Construct AccessSpec parameter */
09243   pAccessSpec = LLRP_AccessSpec_construct();
09244   if (NULL == pAccessSpec)
09245   {
09246     TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
09247     return TMR_ERROR_LLRP;
09248   }
09249 
09250   {
09251     /* 1. Set AccessSpec Id */
09252     LLRP_AccessSpec_setAccessSpecID(pAccessSpec, reader->u.llrpReader.accessSpecId);
09253     
09254     /* 2. Set Antenna Id */
09261     if (isStandalone)
09262     {
09268       uint8_t antenna = 0;
09269 
09270       antenna = reader->tagOpParams.antenna;
09271       LLRP_AccessSpec_setAntennaID(pAccessSpec, antenna);
09272     }
09273     else
09274     {
09275       LLRP_AccessSpec_setAntennaID(pAccessSpec, 0);
09276     }
09277 
09278     /* 3. Set Current State */
09279     LLRP_AccessSpec_setCurrentState(pAccessSpec, 
09280                                 LLRP_AccessSpecState_Disabled);
09281 
09282     /* 4. Set Protocol */
09283     switch (protocol)
09284     {
09285       case TMR_TAG_PROTOCOL_GEN2:
09286         {
09287           LLRP_AccessSpec_setProtocolID(pAccessSpec,
09288               LLRP_AirProtocols_EPCGlobalClass1Gen2);
09289 
09290           break;
09291         }
09292       case TMR_TAG_PROTOCOL_ISO180006B:
09293         {
09294           LLRP_AccessSpec_setProtocolID(pAccessSpec,
09295               LLRP_AirProtocols_Unspecified);
09296 
09297           break;
09298         }
09299       default:
09300         {
09301           TMR_LLRP_freeMessage((LLRP_tSMessage *)pAccessSpec);
09302           TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
09303           return TMR_ERROR_UNIMPLEMENTED_FEATURE;
09304 
09305           break;
09306         }
09307     }
09308 
09309 
09310     /* 5. Set ROSpec ID */
09311     LLRP_AccessSpec_setROSpecID(pAccessSpec, roSpecId); 
09312 
09313     /* 6. Set AccessSpec Stop trigger */
09314     {
09315       /* Construct and initialize AccessSpec stop trigger */
09316       pAccessSpecStopTrigger = LLRP_AccessSpecStopTrigger_construct();
09317 
09321       LLRP_AccessSpecStopTrigger_setAccessSpecStopTrigger(pAccessSpecStopTrigger,
09322                               LLRP_AccessSpecStopTriggerType_Operation_Count);
09323 
09328       if (isStandalone)
09329       {
09334         LLRP_AccessSpecStopTrigger_setOperationCountValue(pAccessSpecStopTrigger, 1);
09335       }
09336       else
09337       {
09343         LLRP_AccessSpecStopTrigger_setOperationCountValue(pAccessSpecStopTrigger, 0);
09344       }
09345 
09346       /* Set stoptrigger to accessspec */
09347       LLRP_AccessSpec_setAccessSpecStopTrigger(pAccessSpec, pAccessSpecStopTrigger);
09348     }
09349 
09350     /* 7. Set Access Command operation */
09351     {
09352       /* Initialize AccessCommand parameter */
09353       pAccessCommand = LLRP_AccessCommand_construct();
09354 
09355       /* prepare TagSpec and OpSpec and add them to AccessCommand */
09356       ret = TMR_LLRP_msgPrepareAccessCommand(reader, pAccessCommand, filter, tagop);
09357       if (TMR_SUCCESS != ret)
09358       {
09359         TMR_LLRP_freeMessage((LLRP_tSMessage *)pAccessCommand);
09360         TMR_LLRP_freeMessage((LLRP_tSMessage *)pAccessSpec);
09361         TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
09362         return ret;
09363       }
09364 
09365       /* Set AccessCommand to AccessSpec parameter */
09366       LLRP_AccessSpec_setAccessCommand(pAccessSpec, pAccessCommand);
09367     }
09368 
09369     /* 8. Set AccessReportSpec */
09376   }
09377 
09378   /* Now AccessSpec is fully framed, add to ADD_ACCESSSPEC message */
09379   LLRP_ADD_ACCESSSPEC_setAccessSpec(pCmd, pAccessSpec);
09380 
09381   pCmdMsg = &pCmd->hdr;
09385   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
09386   
09391   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
09392   if (TMR_SUCCESS != ret)
09393   {
09394     return ret;
09395   }
09396 
09400   pRsp = (LLRP_tSADD_ACCESSSPEC_RESPONSE *) pRspMsg;
09401   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
09402   {
09403     TMR_LLRP_freeMessage(pRspMsg);
09404     return TMR_ERROR_LLRP; 
09405   }
09406 
09410   TMR_LLRP_freeMessage(pRspMsg);
09411 
09412   return ret;
09413 }
09414 
09419 TMR_Status
09420 TMR_LLRP_parseCustomTagOpSpecResultType(LLRP_tEThingMagicCustomTagOpSpecResultType status)
09421 {
09422   switch (status)
09423   {
09424     case LLRP_ThingMagicCustomTagOpSpecResultType_Success:
09425       {
09426         return TMR_SUCCESS;
09427       }
09428 
09429     case LLRP_ThingMagicCustomTagOpSpecResultType_Nonspecific_Tag_Error:
09430       {
09431         return TMR_ERROR_GENERAL_TAG_ERROR;
09432       }
09433 
09434     case LLRP_ThingMagicCustomTagOpSpecResultType_No_Response_From_Tag:
09435       {
09436         return TMR_ERROR_GEN2_PROTOCOL_OTHER_ERROR;
09437       }
09438 
09439     case LLRP_ThingMagicCustomTagOpSpecResultType_Nonspecific_Reader_Error:
09440       {
09441         return TMR_ERROR_LLRP_READER_ERROR;
09442       }
09443 
09444     default:
09445       return TMR_ERROR_LLRP;
09446   }
09447 }
09448 
09457 TMR_Status
09458 TMR_LLRP_verifyOpSpecResultStatus(TMR_Reader *reader, 
09459                                   LLRP_tSParameter *pParameter)
09460 {
09461   TMR_Status ret;
09462 
09463   ret = TMR_SUCCESS;
09464 
09468   switch (pParameter->elementHdr.pType->TypeNum)
09469   {
09470 
09480     case TMR_LLRP_C1G2READOPSPECRESULT:
09481       {
09482         LLRP_tSC1G2ReadOpSpecResult *pC1G2ReadOpSpecResult;
09483         pC1G2ReadOpSpecResult = (LLRP_tSC1G2ReadOpSpecResult *)pParameter;
09484 
09485         switch (pC1G2ReadOpSpecResult->eResult)
09486         {
09487           case LLRP_C1G2ReadResultType_Success:
09488             {
09489               ret = TMR_SUCCESS;
09490               break;
09491             }
09492 
09493           case LLRP_C1G2ReadResultType_Nonspecific_Tag_Error:
09494             {
09495               ret = TMR_ERROR_GENERAL_TAG_ERROR;
09496               break;
09497             }
09498 
09499           case LLRP_C1G2ReadResultType_No_Response_From_Tag:
09500             {
09501               ret = TMR_ERROR_GEN2_PROTOCOL_OTHER_ERROR;
09502               break;
09503             }
09504 
09505           case LLRP_C1G2ReadResultType_Nonspecific_Reader_Error:
09506             {
09507               ret = TMR_ERROR_LLRP_READER_ERROR;
09508               break;
09509             }
09510 
09511           case LLRP_C1G2ReadResultType_Memory_Overrun_Error:
09512             {
09513               ret = TMR_ERROR_GEN2_PROTOCOL_MEMORY_OVERRUN_BAD_PC;
09514               break;
09515             }
09516 
09517           case LLRP_C1G2ReadResultType_Memory_Locked_Error:
09518             {
09519               ret = TMR_ERROR_GEN2_PROCOCOL_MEMORY_LOCKED;
09520               break;
09521             }
09522 
09523           default:
09524             ret = TMR_ERROR_LLRP;
09525         }
09526         break;
09527       }
09528 
09532     case TMR_LLRP_C1G2WRITEOPSPECRESULT:
09533       {
09534         LLRP_tSC1G2WriteOpSpecResult *pC1G2WriteOpSpecResult;
09535         pC1G2WriteOpSpecResult = (LLRP_tSC1G2WriteOpSpecResult *)pParameter;
09536 
09537         switch (pC1G2WriteOpSpecResult->eResult)
09538         {
09539           case LLRP_C1G2WriteResultType_Success:
09540             {
09541               ret = TMR_SUCCESS;
09542               break;
09543             }
09544 
09545           case LLRP_C1G2WriteResultType_Tag_Memory_Overrun_Error:
09546             {
09547               ret = TMR_ERROR_GEN2_PROTOCOL_MEMORY_OVERRUN_BAD_PC;
09548               break;
09549             }
09550 
09551           case LLRP_C1G2WriteResultType_Tag_Memory_Locked_Error:
09552             {
09553               ret = TMR_ERROR_GEN2_PROCOCOL_MEMORY_LOCKED;
09554               break;
09555             }
09556 
09557           case LLRP_C1G2WriteResultType_Insufficient_Power:
09558             {
09559               ret = TMR_ERROR_GEN2_PROTOCOL_INSUFFICIENT_POWER;
09560               break;
09561             }
09562 
09563           case LLRP_C1G2WriteResultType_Nonspecific_Tag_Error:
09564             {
09565               ret = TMR_ERROR_GENERAL_TAG_ERROR;
09566               break;
09567             }
09568 
09569           case LLRP_C1G2WriteResultType_No_Response_From_Tag:
09570             {
09571               ret = TMR_ERROR_GEN2_PROTOCOL_OTHER_ERROR;
09572               break;
09573             }
09574 
09575           case LLRP_C1G2WriteResultType_Nonspecific_Reader_Error:
09576             {
09577               ret = TMR_ERROR_LLRP_READER_ERROR;
09578               break;
09579             }
09580 
09581           default:
09582             ret = TMR_ERROR_LLRP;
09583         }
09584         break;
09585       }
09586 
09590     case TMR_LLRP_C1G2KILLOPSPECRESULT:
09591       {
09592         LLRP_tSC1G2KillOpSpecResult *pC1G2KillOpSpecResult;
09593         pC1G2KillOpSpecResult = (LLRP_tSC1G2KillOpSpecResult *)pParameter;
09594 
09595         switch (pC1G2KillOpSpecResult->eResult)
09596         {
09597           case LLRP_C1G2KillResultType_Success:
09598             {
09599               ret = TMR_SUCCESS;
09600               break;
09601             }
09602 
09603           case LLRP_C1G2KillResultType_Zero_Kill_Password_Error:
09604             {
09605               ret = TMR_ERROR_PROTOCOL_INVALID_KILL_PASSWORD;
09606               break;
09607             }
09608 
09609           case LLRP_C1G2KillResultType_Insufficient_Power:
09610             {
09611               ret = TMR_ERROR_GEN2_PROTOCOL_INSUFFICIENT_POWER;
09612               break;
09613             }
09614 
09615           case LLRP_C1G2KillResultType_Nonspecific_Tag_Error:
09616             {
09617               ret = TMR_ERROR_GENERAL_TAG_ERROR;
09618               break;
09619             }
09620 
09621           case LLRP_C1G2KillResultType_No_Response_From_Tag:
09622             {
09623               ret = TMR_ERROR_GEN2_PROTOCOL_OTHER_ERROR;
09624               break;
09625             }
09626 
09627           case LLRP_C1G2KillResultType_Nonspecific_Reader_Error:
09628             {
09629               ret = TMR_ERROR_LLRP_READER_ERROR;
09630               break;
09631             }
09632 
09633           default:
09634             ret = TMR_ERROR_LLRP;
09635         }
09636         break;
09637       }
09638 
09642     case TMR_LLRP_C1G2LOCKOPSPECRESULT:
09643       {
09644         LLRP_tSC1G2LockOpSpecResult *pC1G2LockOpSpecResult;
09645         pC1G2LockOpSpecResult = (LLRP_tSC1G2LockOpSpecResult *)pParameter;
09646 
09647         switch (pC1G2LockOpSpecResult->eResult)
09648         {
09649           case LLRP_C1G2LockResultType_Success:
09650             {
09651               ret = TMR_SUCCESS;
09652               break;
09653             }
09654 
09655           case LLRP_C1G2LockResultType_Insufficient_Power:
09656             {
09657               ret = TMR_ERROR_GEN2_PROTOCOL_INSUFFICIENT_POWER;
09658               break;
09659             }
09660 
09661           case LLRP_C1G2LockResultType_Nonspecific_Tag_Error:
09662             {
09663               ret = TMR_ERROR_GENERAL_TAG_ERROR;
09664               break;
09665             }
09666 
09667           case LLRP_C1G2LockResultType_No_Response_From_Tag:
09668             {
09669               ret = TMR_ERROR_GEN2_PROTOCOL_OTHER_ERROR;
09670               break;
09671             }
09672 
09673           case LLRP_C1G2LockResultType_Nonspecific_Reader_Error:
09674             {
09675               ret = TMR_ERROR_LLRP_READER_ERROR;
09676               break;
09677             }
09678 
09679           default:
09680             ret = TMR_ERROR_LLRP;
09681         }
09682         break;
09683       }
09684 
09688     case TMR_LLRP_C1G2BLOCKERASEOPSPECRESULT:
09689       {
09690         LLRP_tSC1G2BlockEraseOpSpecResult *pC1G2BlockEraseOpSpecResult;
09691         pC1G2BlockEraseOpSpecResult = (LLRP_tSC1G2BlockEraseOpSpecResult *)pParameter;
09692 
09693         switch (pC1G2BlockEraseOpSpecResult->eResult)
09694         {
09695           case LLRP_C1G2BlockEraseResultType_Success:
09696             {
09697               ret = TMR_SUCCESS;
09698               break;
09699             }
09700 
09701           case LLRP_C1G2BlockEraseResultType_Tag_Memory_Overrun_Error:
09702             {
09703               ret = TMR_ERROR_GEN2_PROTOCOL_MEMORY_OVERRUN_BAD_PC;
09704               break;
09705             }
09706 
09707           case LLRP_C1G2BlockEraseResultType_Tag_Memory_Locked_Error:
09708             {
09709               ret = TMR_ERROR_GEN2_PROCOCOL_MEMORY_LOCKED;
09710               break;
09711             }
09712 
09713           case LLRP_C1G2BlockEraseResultType_Insufficient_Power:
09714             {
09715               ret = TMR_ERROR_GEN2_PROTOCOL_INSUFFICIENT_POWER;
09716               break;
09717             }
09718 
09719           case LLRP_C1G2BlockEraseResultType_Nonspecific_Tag_Error:
09720             {
09721               ret = TMR_ERROR_GENERAL_TAG_ERROR;
09722               break;
09723             }
09724 
09725           case LLRP_C1G2BlockEraseResultType_No_Response_From_Tag:
09726             {
09727               ret = TMR_ERROR_GEN2_PROTOCOL_OTHER_ERROR;
09728               break;
09729             }
09730 
09731           case LLRP_C1G2BlockEraseResultType_Nonspecific_Reader_Error:
09732             {
09733               ret = TMR_ERROR_LLRP_READER_ERROR;
09734               break;
09735             }
09736 
09737           default:
09738             ret = TMR_ERROR_LLRP;
09739         }
09740         break;
09741       }
09742 
09746     case TMR_LLRP_C1G2BLOCKWRITEOPSPECRESULT:
09747       {
09748         LLRP_tSC1G2BlockWriteOpSpecResult *pC1G2BlockWriteOpSpecResult;
09749         pC1G2BlockWriteOpSpecResult = (LLRP_tSC1G2BlockWriteOpSpecResult *)pParameter;
09750 
09751         switch (pC1G2BlockWriteOpSpecResult->eResult)
09752         {
09753           case LLRP_C1G2BlockWriteResultType_Success:
09754             {
09755               ret = TMR_SUCCESS;
09756               break;
09757             }
09758 
09759           case LLRP_C1G2BlockWriteResultType_Tag_Memory_Overrun_Error:
09760             {
09761               ret = TMR_ERROR_GEN2_PROTOCOL_MEMORY_OVERRUN_BAD_PC;
09762               break;
09763             }
09764 
09765           case LLRP_C1G2BlockWriteResultType_Tag_Memory_Locked_Error:
09766             {
09767               ret = TMR_ERROR_GEN2_PROCOCOL_MEMORY_LOCKED;
09768               break;
09769             }
09770 
09771           case LLRP_C1G2BlockWriteResultType_Insufficient_Power:
09772             {
09773               ret = TMR_ERROR_GEN2_PROTOCOL_INSUFFICIENT_POWER;
09774               break;
09775             }
09776 
09777           case LLRP_C1G2BlockWriteResultType_Nonspecific_Tag_Error:
09778             {
09779               ret = TMR_ERROR_GENERAL_TAG_ERROR;
09780               break;
09781             }
09782 
09783           case LLRP_C1G2BlockWriteResultType_No_Response_From_Tag:
09784             {
09785               ret = TMR_ERROR_GEN2_PROTOCOL_OTHER_ERROR;
09786               break;
09787             }
09788 
09789           case LLRP_C1G2BlockWriteResultType_Nonspecific_Reader_Error:
09790             {
09791               ret = TMR_ERROR_LLRP_READER_ERROR;
09792               break;
09793             }
09794 
09795           default:
09796             ret = TMR_ERROR_LLRP;
09797         }
09798         break;
09799       }
09800 
09804     case TMR_LLRP_CUSTOM_BLOCKPERMALOCKOPSPECRESULT:
09805       {
09806         LLRP_tSThingMagicBlockPermalockOpSpecResult *pResult;
09807         pResult = (LLRP_tSThingMagicBlockPermalockOpSpecResult *)pParameter;
09808         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09809 
09810         break;
09811       }
09812 
09816     case TMR_LLRP_CUSTOM_HIGGS2PARTIALLOADIMAGEOPSPECRESULT:
09817       {
09818         LLRP_tSThingMagicHiggs2PartialLoadImageOpSpecResult *pResult;
09819         pResult = (LLRP_tSThingMagicHiggs2PartialLoadImageOpSpecResult *)pParameter;
09820         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09821 
09822        break;
09823       }
09824 
09828     case TMR_LLRP_CUSTOM_HIGGS2FULLLOADIMAGEOPSPECRESULT:
09829       {
09830         LLRP_tSThingMagicHiggs2FullLoadImageOpSpecResult *pResult;
09831         pResult = (LLRP_tSThingMagicHiggs2FullLoadImageOpSpecResult *)pParameter;
09832         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09833 
09834         break;
09835       }
09836 
09840     case TMR_LLRP_CUSTOM_HIGGS3FASTLOADIMAGEOPSPECRESULT:
09841       {
09842         LLRP_tSThingMagicHiggs3FastLoadImageOpSpecResult *pResult;
09843         pResult = (LLRP_tSThingMagicHiggs3FastLoadImageOpSpecResult *)pParameter;
09844         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09845 
09846         break;
09847       }
09848 
09852     case TMR_LLRP_CUSTOM_HIGGS3LOADIMAGEOPSPECRESULT:
09853       {
09854         LLRP_tSThingMagicHiggs3LoadImageOpSpecResult *pResult;
09855         pResult = (LLRP_tSThingMagicHiggs3LoadImageOpSpecResult *)pParameter;
09856         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09857 
09858         break;
09859       }
09860 
09864     case TMR_LLRP_CUSTOM_HIGGS3BLOCKREADLOCKOPSPECRESULT:
09865       {
09866         LLRP_tSThingMagicHiggs3BlockReadLockOpSpecResult *pResult;
09867         pResult = (LLRP_tSThingMagicHiggs3BlockReadLockOpSpecResult *)pParameter;
09868         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09869 
09870         break;
09871       }
09872 
09876     case TMR_LLRP_CUSTOM_G2ISETREADPROTECTOPSPECRESULT:
09877       {
09878         LLRP_tSThingMagicNXPG2ISetReadProtectOpSpecResult *pResult;
09879         pResult = (LLRP_tSThingMagicNXPG2ISetReadProtectOpSpecResult *)pParameter;
09880         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09881 
09882         break;
09883       }
09884  
09888     case TMR_LLRP_CUSTOM_G2XSETREADPROTECTOPSPECRESULT:
09889       {
09890         LLRP_tSThingMagicNXPG2XSetReadProtectOpSpecResult *pResult;
09891         pResult = (LLRP_tSThingMagicNXPG2XSetReadProtectOpSpecResult *)pParameter;
09892         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09893 
09894         break;
09895       }
09896  
09900     case TMR_LLRP_CUSTOM_G2IRESETREADPROTECTOPSPECRESULT:
09901       {
09902         LLRP_tSThingMagicNXPG2IResetReadProtectOpSpecResult *pResult;
09903         pResult = (LLRP_tSThingMagicNXPG2IResetReadProtectOpSpecResult *)pParameter;
09904         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09905 
09906         break;
09907       }
09908  
09912     case TMR_LLRP_CUSTOM_G2XRESETREADPROTECTOPSPECRESULT:
09913       {
09914         LLRP_tSThingMagicNXPG2XResetReadProtectOpSpecResult *pResult;
09915         pResult = (LLRP_tSThingMagicNXPG2XResetReadProtectOpSpecResult *)pParameter;
09916         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09917 
09918         break;
09919       }
09920  
09924     case TMR_LLRP_CUSTOM_G2ICHANGEEASOPSPECRESULT:
09925       {
09926         LLRP_tSThingMagicNXPG2IChangeEASOpSpecResult *pResult;
09927         pResult = (LLRP_tSThingMagicNXPG2IChangeEASOpSpecResult *)pParameter;
09928         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09929 
09930         break;
09931       }
09932  
09936     case TMR_LLRP_CUSTOM_G2XCHANGEEASOPSPECRESULT:
09937       {
09938         LLRP_tSThingMagicNXPG2XChangeEASOpSpecResult *pResult;
09939         pResult = (LLRP_tSThingMagicNXPG2XChangeEASOpSpecResult *)pParameter;
09940         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09941 
09942         break;
09943       }
09944  
09948     case TMR_LLRP_CUSTOM_G2IEASALARMOPSPECRESULT:
09949       {
09950         LLRP_tSThingMagicNXPG2IEASAlarmOpSpecResult *pResult;
09951         pResult = (LLRP_tSThingMagicNXPG2IEASAlarmOpSpecResult *)pParameter;
09952         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09953 
09954         break;
09955       }
09956  
09960     case TMR_LLRP_CUSTOM_G2XEASALARMOPSPECRESULT:
09961       {
09962         LLRP_tSThingMagicNXPG2XEASAlarmOpSpecResult *pResult;
09963         pResult = (LLRP_tSThingMagicNXPG2XEASAlarmOpSpecResult *)pParameter;
09964         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09965 
09966         break;
09967       }
09968  
09972     case TMR_LLRP_CUSTOM_G2ICALIBRATEOPSPECRESULT:
09973       {
09974         LLRP_tSThingMagicNXPG2ICalibrateOpSpecResult *pResult;
09975         pResult = (LLRP_tSThingMagicNXPG2ICalibrateOpSpecResult *)pParameter;
09976         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09977 
09978         break;
09979       }
09980  
09984     case TMR_LLRP_CUSTOM_G2XCALIBRATEOPSPECRESULT:
09985       {
09986         LLRP_tSThingMagicNXPG2XCalibrateOpSpecResult *pResult;
09987         pResult = (LLRP_tSThingMagicNXPG2XCalibrateOpSpecResult *)pParameter;
09988         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
09989 
09990         break;
09991       }
09992 
09996     case TMR_LLRP_CUSTOM_G2ICHANGECONFIGOPSPECRESULT:
09997       {
09998         LLRP_tSThingMagicNXPG2IChangeConfigOpSpecResult *pResult;
09999         pResult = (LLRP_tSThingMagicNXPG2IChangeConfigOpSpecResult *)pParameter;
10000         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10001 
10002         break;
10003       }
10004  
10008     case TMR_LLRP_CUSTOM_MONZA4QTREADWRITEOPSPECRESULT:
10009       {
10010         LLRP_tSThingMagicImpinjMonza4QTReadWriteOpSpecResult *pResult;
10011         pResult = (LLRP_tSThingMagicImpinjMonza4QTReadWriteOpSpecResult *)pParameter;
10012         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10013 
10014         break;
10015       }
10016 
10020     case TMR_LLRP_CUSTOM_IDS_SETSFEPARAMETERSOPSPECRESULT:
10021       {
10022         LLRP_tSThingMagicIDSSL900ASetSFEParamsOpSpecResult *pResult;
10023         pResult = (LLRP_tSThingMagicIDSSL900ASetSFEParamsOpSpecResult *)pParameter;
10024         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10025 
10026         break;
10027       }
10028 
10032     case TMR_LLRP_CUSTOM_IDS_GETMEASUREMENTSETUPOPSPECRESULT:
10033       {
10034         LLRP_tSThingMagicIDSSL900AGetMeasurementSetupOpSpecResult *pResult;
10035         pResult = (LLRP_tSThingMagicIDSSL900AGetMeasurementSetupOpSpecResult *)pParameter;
10036         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10037 
10038         break;
10039       }
10040 
10044     case TMR_LLRP_CUSTOM_IDS_GETBATTERYLEVELOPSPECRESULT:
10045       {
10046         LLRP_tSThingMagicIDSSL900AGetBatteryLevelOpSpecResult *pResult;
10047         pResult = (LLRP_tSThingMagicIDSSL900AGetBatteryLevelOpSpecResult *)pParameter;
10048         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10049 
10050         break;
10051       }
10052 
10056     case TMR_LLRP_CUSTOM_IDS_SETLOGLIMITSOPSPECRESULT:
10057       {
10058         LLRP_tSThingMagicIDSSL900ASetLogLimitsOpSpecResult *pResult;
10059         pResult = (LLRP_tSThingMagicIDSSL900ASetLogLimitsOpSpecResult *)pParameter;
10060         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10061 
10062         break;
10063       }
10064 
10068     case TMR_LLRP_CUSTOM_IDS_SETSHELFLIFEOPSPECRESULT:
10069     {
10070         LLRP_tSThingMagicIDSSetShelfLifeOpSpecResult *pResult;
10071       pResult = (LLRP_tSThingMagicIDSSetShelfLifeOpSpecResult *)pParameter;
10072       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10073 
10074       break;
10075     }
10076 
10080     case TMR_LLRP_CUSTOM_IDS_SETPASSWORDOPSPECRESULT:
10081     {
10082       LLRP_tSThingMagicIDSSL900ASetPasswordOpSpecResult *pResult;
10083       pResult = (LLRP_tSThingMagicIDSSL900ASetPasswordOpSpecResult *)pParameter;
10084       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10085 
10086       break;
10087     }
10088 
10092     case TMR_LLRP_CUSTOM_WRITETAGOPSPECRESULT:
10093       {
10094         LLRP_tSThingMagicWriteTagOpSpecResult  *pResult;
10095         pResult = (LLRP_tSThingMagicWriteTagOpSpecResult *)pParameter;
10096         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10097 
10098         break;
10099       }
10100 
10104     case TMR_LLRP_CUSTOM_IDS_GETSENSORVALUEOPSPECRESULT:
10105       {
10106         LLRP_tSThingMagicIDSSL900ASensorValueOpSpecResult *pResult;
10107         pResult = (LLRP_tSThingMagicIDSSL900ASensorValueOpSpecResult *)pParameter;
10108         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10109 
10110         break;
10111       }
10112 
10116     case TMR_LLRP_CUSTOM_IDS_SETLOGMODEOPSPECRESULT:
10117       {
10118         LLRP_tSThingMagicIDSSL900ASetLogModeOpSpecResult *pResult;
10119         pResult = (LLRP_tSThingMagicIDSSL900ASetLogModeOpSpecResult *)pParameter;
10120         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10121 
10122         break;
10123       }
10124 
10128     case TMR_LLRP_CUSTOM_IDS_STARTLOGMODEOPSPECRESULT:
10129       {
10130         LLRP_tSThingMagicIDSSL900AStartLogOpSpecResult *pResult;
10131         pResult = (LLRP_tSThingMagicIDSSL900AStartLogOpSpecResult *)pParameter;
10132         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10133 
10134         break;
10135       }
10136 
10140     case TMR_LLRP_CUSTOM_IDS_GETLOGSTATEOPSPECRESULT:
10141       {
10142         LLRP_tSThingMagicIDSSL900ALogStateOpSpecResult *pResult;
10143         pResult = (LLRP_tSThingMagicIDSSL900ALogStateOpSpecResult *)pParameter;
10144         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10145 
10146         break;
10147       }
10148 
10152     case TMR_LLRP_CUSTOM_IDS_ENDLOGOPSPECRESULT:
10153       {
10154         LLRP_tSThingMagicIDSSL900AEndLogOpSpecResult *pResult;
10155         pResult = (LLRP_tSThingMagicIDSSL900AEndLogOpSpecResult *)pParameter;
10156         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10157 
10158         break;
10159       }
10160 
10164     case TMR_LLRP_CUSTOM_IDS_INITIALIZEOPSPECRESULT:
10165       {
10166         LLRP_tSThingMagicIDSSL900AInitializeOpSpecResult *pResult;
10167         pResult = (LLRP_tSThingMagicIDSSL900AInitializeOpSpecResult *)pParameter;
10168         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10169 
10170         break;
10171       }
10172 
10176     case TMR_LLRP_CUSTOM_IDS_ACCESSFIFOSTATUSOPSPECRESULT:
10177       {
10178         LLRP_tSThingMagicIDSSL900AAccessFIFOStatusOpSpecResult *pResult;
10179         pResult = (LLRP_tSThingMagicIDSSL900AAccessFIFOStatusOpSpecResult *)pParameter;
10180         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10181 
10182         break;
10183       }
10184 
10188     case TMR_LLRP_CUSTOM_IDS_ACCESSFIFOWRITEOPSPECRESULT:
10189       {
10190         LLRP_tSThingMagicIDSSL900AAccessFIFOWriteOpSpecResult *pResult;
10191         pResult = (LLRP_tSThingMagicIDSSL900AAccessFIFOWriteOpSpecResult *)pParameter;
10192         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10193 
10194         break;
10195       }
10196 
10200     case TMR_LLRP_CUSTOM_IDS_ACCESSFIFOREADOPSPECRESULT:
10201       {
10202         LLRP_tSThingMagicIDSSL900AAccessFIFOReadOpSpecResult *pResult;
10203         pResult = (LLRP_tSThingMagicIDSSL900AAccessFIFOReadOpSpecResult *)pParameter;
10204         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10205 
10206         break;
10207       }
10208 
10212     case TMR_LLRP_CUSTOM_IDS_GETCALIBRATIONDATAOPSPECRESULT:
10213     {
10214         LLRP_tSThingMagicIDSSL900AGetCalibrationDataOpSpecResult *pResult;
10215       pResult = (LLRP_tSThingMagicIDSSL900AGetCalibrationDataOpSpecResult *)pParameter;
10216       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10217 
10218       break;
10219     }
10220 
10224     case TMR_LLRP_CUSTOM_IDS_SETCALIBRATIONDATAOPSPECRESULT:
10225     {
10226         LLRP_tSThingMagicIDSSL900ASetCalibrationDataOpSpecResult *pResult;
10227       pResult = (LLRP_tSThingMagicIDSSL900ASetCalibrationDataOpSpecResult *)pParameter;
10228       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10229 
10230       break;
10231     }
10232 
10236     case TMR_LLRP_CUSTOM_DENATRAN_IAV_ACTIVATESECUREMODEOPSPECRESULT:
10237     {
10238       LLRP_tSThingMagicDenatranIAVActivateSecureModeOpSpecResult *pResult;
10239       pResult = (LLRP_tSThingMagicDenatranIAVActivateSecureModeOpSpecResult *)pParameter;
10240       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10241 
10242       break;
10243     }
10244 
10248     case TMR_LLRP_CUSTOM_DENATRAN_IAV_AUTHENTICATEOBUOPSPECRESULT:
10249     {
10250       LLRP_tSThingMagicDenatranIAVAuthenticateOBUOpSpecResult *pResult;
10251       pResult = (LLRP_tSThingMagicDenatranIAVAuthenticateOBUOpSpecResult *)pParameter;
10252       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10253 
10254       break;
10255     }
10256 
10260     case TMR_LLRP_CUSTOM_DENATRAN_IAV_ACTIVATESINIAVMODEOPSPECRESULT:
10261     {
10262       LLRP_tSThingMagicDenatranIAVActivateSiniavModeOpSpecResult *pResult;
10263       pResult = (LLRP_tSThingMagicDenatranIAVActivateSiniavModeOpSpecResult *)pParameter;
10264       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10265 
10266       break;
10267     }
10268 
10272     case TMR_LLRP_CUSTOM_DENATRAN_IAV_AUTHENTICATEIDOPSPECRESULT:
10273     {
10274       LLRP_tSThingMagicDenatranIAVOBUAuthenticateIDOpSpecResult *pResult;
10275       pResult = (LLRP_tSThingMagicDenatranIAVOBUAuthenticateIDOpSpecResult *)pParameter;
10276       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10277 
10278       break;
10279     }
10280 
10284     case TMR_LLRP_CUSTOM_DENATRAN_IAV_AUTHENTICATEFULLPASS1OPSPECRESULT:
10285     {
10286       LLRP_tSThingMagicDenatranIAVOBUAuthenticateFullPass1OpSpecResult *pResult;
10287       pResult = (LLRP_tSThingMagicDenatranIAVOBUAuthenticateFullPass1OpSpecResult *)pParameter;
10288       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10289 
10290       break;
10291     }
10292 
10296     case TMR_LLRP_CUSTOM_DENATRAN_IAV_AUTHENTICATEFULLPASS2OPSPECRESULT:
10297     {
10298       LLRP_tSThingMagicDenatranIAVOBUAuthenticateFullPass2OpSpecResult *pResult;
10299       pResult = (LLRP_tSThingMagicDenatranIAVOBUAuthenticateFullPass2OpSpecResult *)pParameter;
10300       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10301 
10302       break;
10303     }
10304 
10308     case TMR_LLRP_CUSTOM_DENATRAN_IAV_OBUREADFROMMEMMAPOPSPECRESULT:
10309     {
10310       LLRP_tSThingMagicDenatranIAVOBUReadFromMemMapOpSpecResult *pResult;
10311       pResult = (LLRP_tSThingMagicDenatranIAVOBUReadFromMemMapOpSpecResult *)pParameter;
10312       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10313 
10314       break;
10315     }
10316 
10320     case TMR_LLRP_CUSTOM_DENATRAN_IAV_OBUWRITETOMEMMAPOPSPECRESULT:
10321     {
10322       LLRP_tSThingMagicDenatranIAVOBUWriteToMemMapOpSpecResult *pResult;
10323       pResult = (LLRP_tSThingMagicDenatranIAVOBUWriteToMemMapOpSpecResult *)pParameter;
10324       ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10325 
10326       break;
10327     }
10328 
10329 
10330 #ifdef TMR_ENABLE_ISO180006B
10331     case TMR_LLRP_CUSTOM_ISO_READDATAOPSPECRESULT:
10332       {
10333         LLRP_tSThingMagicISO180006BReadOpSpecResult  *pResult;
10334         pResult = (LLRP_tSThingMagicISO180006BReadOpSpecResult *)pParameter;
10335         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10336 
10337         break;
10338       }
10339 
10340     case TMR_LLRP_CUSTOM_ISO_WRITEDATAOPSPECRESULT:
10341       {
10342         LLRP_tSThingMagicISO180006BWriteOpSpecResult  *pResult;
10343         pResult = (LLRP_tSThingMagicISO180006BWriteOpSpecResult *)pParameter;
10344         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10345 
10346         break;
10347       }
10348     case TMR_LLRP_CUSTOM_ISO_LOCKOPSPECRESULT:
10349       {
10350         LLRP_tSThingMagicISO180006BLockOpSpecResult  *pResult;
10351         pResult = (LLRP_tSThingMagicISO180006BLockOpSpecResult *)pParameter;
10352         ret = TMR_LLRP_parseCustomTagOpSpecResultType(pResult->eResult);
10353 
10354         break;
10355       }
10356 #endif /* TMR_ENABLE_ISO180006B */
10357 
10358     default:
10359       {
10364         ret = TMR_ERROR_LLRP_MSG_PARSE_ERROR;
10365       }
10366   }
10367 
10368   return ret;
10369 }
10370 
10376 TMR_Status
10377 TMR_LLRP_cmdDeleteAllAccessSpecs(TMR_Reader *reader)
10378 {
10379   TMR_Status ret;
10380   LLRP_tSDELETE_ACCESSSPEC          *pCmd;
10381   LLRP_tSMessage                    *pCmdMsg;
10382   LLRP_tSMessage                    *pRspMsg;
10383   LLRP_tSDELETE_ACCESSSPEC_RESPONSE *pRsp;
10384 
10385   ret = TMR_SUCCESS;
10386 
10390   pCmd = LLRP_DELETE_ACCESSSPEC_construct();
10391   LLRP_DELETE_ACCESSSPEC_setAccessSpecID(pCmd, 0);        /* All */
10392 
10393   pCmdMsg = &pCmd->hdr;
10397   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
10402   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
10403   if (TMR_SUCCESS != ret)
10404   {
10405     return ret;
10406   }
10407 
10411   pRsp = (LLRP_tSDELETE_ACCESSSPEC_RESPONSE *) pRspMsg;
10412   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
10413   {
10414     TMR_LLRP_freeMessage(pRspMsg);
10415     return TMR_ERROR_LLRP; 
10416   }
10417 
10421   TMR_LLRP_freeMessage(pRspMsg);
10422 
10423   return ret;
10424 }
10425 
10426 TMR_Status
10427 TMR_LLRP_cmdStopReading(struct TMR_Reader *reader)
10428 {
10429   if (TMR_READ_PLAN_TYPE_SIMPLE == reader->readParams.readPlan->type)
10430   {
10431     /* receiveResponse = false, as we do not need here */
10432     return TMR_LLRP_cmdStopROSpec(reader, false);
10433   }
10434   else
10435   {
10441     return TMR_LLRP_cmdDeleteAllROSpecs(reader, false);
10442   }
10443 }
10444 
10445 TMR_Status
10446 TMR_LLRP_cmdGetReport(TMR_Reader *reader)
10447 {
10448   TMR_Status ret;
10449   LLRP_tSGET_REPORT *pCmd;
10450   LLRP_tSMessage    *pCmdMsg;
10451 
10452   ret = TMR_SUCCESS;
10453 
10457   pCmd = LLRP_GET_REPORT_construct();
10458   pCmdMsg = &pCmd->hdr;
10459  
10465   ret = TMR_LLRP_sendMessage(reader, pCmdMsg, 
10466           reader->u.llrpReader.transportTimeout);
10471   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
10472   if (TMR_SUCCESS != ret)
10473   {
10474     return ret;
10475   }
10476 
10477   return ret;
10478 }
10479 
10480 TMR_Status
10481 TMR_LLRP_cmdrebootReader(TMR_Reader *reader)
10482 {
10483   TMR_Status ret;
10484   LLRP_tSTHINGMAGIC_CONTROL_REQUEST_POWER_CYCLE_READER  *pCmd;
10485   LLRP_tSMessage                                        *pCmdMsg;
10486   LLRP_tSMessage                                        *pRspMsg;
10487   LLRP_tSTHINGMAGIC_CONTROL_RESPONSE_POWER_CYCLE_READER *pRsp;
10488 
10489   ret = TMR_SUCCESS;
10490 
10494   pCmd = LLRP_THINGMAGIC_CONTROL_REQUEST_POWER_CYCLE_READER_construct();
10495 
10496   /* Add the thingmagic magic number to recycle the reader */
10497   LLRP_THINGMAGIC_CONTROL_REQUEST_POWER_CYCLE_READER_setMagicNumber(pCmd, TMR_POWER_CYCLE_MAGIC_NUMBER);
10498 
10499   /* Add the safe mode option */
10500   LLRP_THINGMAGIC_CONTROL_REQUEST_POWER_CYCLE_READER_setBootToSafeMode(pCmd, false);
10501 
10502   pCmdMsg = &pCmd->hdr;
10503 
10507   ret = TMR_LLRP_send(reader, pCmdMsg, &pRspMsg);
10512   TMR_LLRP_freeMessage((LLRP_tSMessage *)pCmd);
10513   if (TMR_SUCCESS != ret)
10514   {
10515     return ret;
10516   }
10517 
10521   pRsp = (LLRP_tSTHINGMAGIC_CONTROL_RESPONSE_POWER_CYCLE_READER *) pRspMsg;
10522   if (TMR_SUCCESS != TMR_LLRP_checkLLRPStatus(pRsp->pLLRPStatus))  
10523   {
10524     TMR_LLRP_freeMessage(pRspMsg);
10525     return TMR_ERROR_LLRP; 
10526   }
10527 
10531   TMR_LLRP_freeMessage(pRspMsg);
10532 
10536   tmr_sleep(90000);
10537 
10538   return ret;
10539 }
10540 #endif  /* TMR_ENABLE_LLRP_READER */
10541 


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