00001
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <inttypes.h>
00031 #include <stdio.h>
00032 #include <stdlib.h>
00033 #include <string.h>
00034
00035 #include "tm_reader.h"
00036 #include "serial_reader_imp.h"
00037 #include "tmr_utils.h"
00038
00039 #ifdef TMR_ENABLE_SERIAL_READER
00040
00041 static TMR_Status filterbytes(TMR_TagProtocol protocol,
00042 const TMR_TagFilter *filter,
00043 uint8_t *option, uint8_t *i, uint8_t *msg,
00044 uint32_t accessPassword, bool usePassword);
00045 TMR_Status
00046 TMR_SR_sendBytes(TMR_Reader *reader, uint8_t len, uint8_t *data, uint32_t timeoutMs);
00047
00048
00049
00050
00051
00052 static uint16_t crctable[] =
00053 {
00054 0x0000, 0x1021, 0x2042, 0x3063,
00055 0x4084, 0x50a5, 0x60c6, 0x70e7,
00056 0x8108, 0x9129, 0xa14a, 0xb16b,
00057 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef,
00058 };
00059
00060 static uint16_t
00061 tm_crc(uint8_t *u8Buf, uint8_t len)
00062 {
00063 uint16_t crc;
00064 int i;
00065
00066 crc = 0xffff;
00067
00068 for (i = 0; i < len ; i++)
00069 {
00070 crc = ((crc << 4) | (u8Buf[i] >> 4)) ^ crctable[crc >> 12];
00071 crc = ((crc << 4) | (u8Buf[i] & 0xf)) ^ crctable[crc >> 12];
00072 }
00073
00074 return crc;
00075 }
00076
00077
00086 TMR_Status
00087 TMR_SR_sendBytes(TMR_Reader *reader, uint8_t len, uint8_t *data, uint32_t timeoutMs)
00088 {
00089 TMR_SR_SerialTransport *transport;
00090 TMR_Status ret;
00091
00092 transport = &reader->u.serialReader.transport;
00093
00094 if (NULL != reader->transportListeners)
00095 {
00096 TMR__notifyTransportListeners(reader, true, len, data, timeoutMs);
00097 }
00098
00099 ret = transport->sendBytes(transport, len, data, timeoutMs);
00100 return ret;
00101 }
00102
00111 TMR_Status
00112 TMR_SR_sendMessage(TMR_Reader *reader, uint8_t *data, uint8_t *opcode, uint32_t timeoutMs)
00113 {
00114 TMR_SR_SerialReader *sr;
00115 TMR_Status ret;
00116 uint16_t crc;
00117 uint8_t len;
00118 uint8_t j;
00119
00120
00121 sr = &reader->u.serialReader;
00122 timeoutMs += sr->transportTimeout;
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134 if (sr->supportsPreamble && ((sr->powerMode == TMR_SR_POWER_MODE_INVALID) ||
00135 (sr->powerMode == TMR_SR_POWER_MODE_SLEEP)) )
00136 {
00137 uint8_t flushBytes[] = {
00138 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF
00139 };
00140
00141 TMR_SR_sendBytes(reader, sizeof(flushBytes)/sizeof(uint8_t), flushBytes, timeoutMs);
00142 {
00143 uint32_t bytesper100ms;
00144 uint32_t bytesSent;
00145
00146
00147
00148
00149 bytesper100ms = sr->baudRate / 50;
00150 for (bytesSent=0; bytesSent<bytesper100ms;
00151 bytesSent += (sizeof(flushBytes)/sizeof(uint8_t)))
00152 {
00153 TMR_SR_sendBytes(reader, sizeof(flushBytes)/sizeof(uint8_t), flushBytes, timeoutMs);
00154 }
00155 }
00156 }
00157
00158
00159
00160
00161
00162 data[0] = 0xff;
00163 len = data[1];
00164 *opcode = data[2];
00165
00166 if (isContinuousReadParamSupported(reader))
00167 {
00168 for (j = 0; j <= len; j++)
00169 {
00170 reader->paramMessage[j] = data[2 + j];
00171 }
00172 data[1] = 5 + len;
00173 data[2] = 0x2f;
00174 data[3] = 0x00;
00175 data[4] = 0x00;
00176 data[5] = 0x04;
00177 data[6] = len;
00178 for (j = 0; j <= len ; j++)
00179 {
00180 data[7 + j] = reader->paramMessage[j];
00181 }
00182 len = data[1];
00183 reader->paramWait = true;
00184 }
00185
00186
00187 {
00188 crc = tm_crc(&data[1], len + 2);
00189 data[len + 3] = crc >> 8;
00190 data[len + 4] = crc & 0xff;
00191 }
00192
00193 ret = TMR_SR_sendBytes(reader, len+5, data, timeoutMs);
00194 return ret;
00195 }
00196
00197
00198 bool
00199 isContinuousReadParamSupported(TMR_Reader *reader)
00200 {
00201 uint16_t i;
00202 uint8_t *readerVersion = reader->u.serialReader.versionInfo.fwVersion ;
00203 uint8_t checkVersion[4];
00204
00205 if (reader->hasContinuousReadStarted == false || reader->continuousReading == false)
00206 return false;
00207
00208 switch (reader->u.serialReader.versionInfo.hardware[0])
00209 {
00210 case TMR_SR_MODEL_M6E:
00211 case TMR_SR_MODEL_M6E_I:
00212 checkVersion[0] = 0x01; checkVersion[1] = 0x21; checkVersion[2] = 0x01; checkVersion[3] = 0x19;
00213 break;
00214 case TMR_SR_MODEL_MICRO:
00215 checkVersion[0] = 0x01; checkVersion[1] = 0x09; checkVersion[2] = 0x00; checkVersion[3] = 0x14;
00216 break;
00217 case TMR_SR_MODEL_M6E_NANO:
00218 checkVersion[0] = 0x01; checkVersion[1] = 0x07; checkVersion[2] = 0x00; checkVersion[3] = 0x0E;
00219 break;
00220 default:
00221 checkVersion[0] = 0xFF; checkVersion[1] = 0xFF; checkVersion[2] = 0xFF; checkVersion[3] = 0xFF;
00222 }
00223 for (i = 0; i < 4; i++)
00224 {
00225 if (readerVersion[i] < checkVersion[i])
00226 {
00227 return false;
00228 }
00229 }
00230 return true;
00231 }
00232
00242 TMR_Status
00243 TMR_SR_receiveMessage(TMR_Reader *reader, uint8_t *data, uint8_t opcode, uint32_t timeoutMs)
00244 {
00245 TMR_Status ret;
00246 uint16_t crc, status;
00247 uint8_t len,headerOffset;
00248 uint8_t receiveBytesLen;
00249 uint32_t inlen;
00250 int i;
00251 TMR_SR_SerialTransport *transport;
00252 uint8_t retryCount = 0;
00253
00254 transport = &reader->u.serialReader.transport;
00255 timeoutMs += reader->u.serialReader.transportTimeout;
00256
00261 if (reader->u.serialReader.crcEnabled)
00262 {
00263 receiveBytesLen = 7;
00264 }
00265 else
00266 {
00267 receiveBytesLen = 5;
00268 }
00269
00270 headerOffset = 0;
00271 retryHeader:
00272 inlen = 0;
00273 retryCount++;
00274 ret = transport->receiveBytes(transport, receiveBytesLen - headerOffset, &inlen, data + headerOffset, timeoutMs);
00275 if (TMR_SUCCESS != ret)
00276 {
00277
00278 TMR__notifyTransportListeners(reader, false, inlen, data, timeoutMs);
00279 return ret;
00280 }
00281
00282 if (data[0] != (uint8_t)0xFF)
00283 {
00284 for (i = 1; i < receiveBytesLen; i++)
00285 {
00286 if (data[i] == 0xFF)
00287 {
00288
00289 headerOffset = receiveBytesLen - i;
00290 memmove(data, data + i, headerOffset);
00291 goto retryHeader;
00292 }
00293 }
00294 if (retryCount < 20)
00295 {
00296
00297 goto retryHeader;
00298 }
00299 return TMR_ERROR_TIMEOUT;
00300 }
00301
00302
00303
00304
00305
00306
00307
00308 len = data[1];
00309
00310 if (0 == len)
00311 {
00312 inlen = 0;
00313 }
00314 else if ((TMR_SR_MAX_PACKET_SIZE - receiveBytesLen) < len)
00315 {
00321 return TMR_ERROR_TOO_BIG;
00322 }
00323 else
00324 {
00325 ret = transport->receiveBytes(transport, len, &inlen, data + receiveBytesLen, timeoutMs);
00326 }
00327
00328 if (NULL != reader->transportListeners)
00329 {
00330 TMR__notifyTransportListeners(reader, false, inlen + receiveBytesLen, data, timeoutMs);
00331 }
00332
00333 if (TMR_SUCCESS != ret)
00334 {
00335
00336 return ret;
00337 }
00338
00343 if (reader->u.serialReader.crcEnabled)
00344 {
00345 crc = tm_crc(&data[1], len + 4);
00346 if ((data[len + 5] != (crc >> 8)) ||
00347 (data[len + 6] != (crc & 0xff)))
00348 {
00349 return TMR_ERROR_CRC_ERROR;
00350 }
00351 }
00352
00353 if ((data[2] != opcode) && ((data[2] != 0x2F) || (!reader->continuousReading)))
00354 {
00355 if(data[2] == 0x9D)
00356 {
00357 return TMR_ERROR_AUTOREAD_ENABLED;
00358 }
00359
00360
00361
00362
00363
00364
00365 return TMR_ERROR_DEVICE_RESET;
00366 }
00367
00368 status = GETU16AT(data, 3);
00369 if (status != 0)
00370 {
00371 ret = TMR_ERROR_CODE(status);
00372 if (ret == TMR_ERROR_TM_ASSERT_FAILED)
00373 {
00374 uint32_t line;
00375 uint8_t *assert = (uint8_t *) (data + 5);
00376
00377 memset(reader->u.serialReader.errMsg, 0 ,TMR_SR_MAX_PACKET_SIZE);
00378 line = GETU32AT(assert, 0);
00379 sprintf(reader->u.serialReader.errMsg, "Assertion failed at line %"PRId32" in file ", line);
00380 memcpy(reader->u.serialReader.errMsg + strlen(reader->u.serialReader.errMsg), assert + 4, len - 4);
00381 }
00382 }
00383 return ret;
00384 }
00385
00394 TMR_Status
00395 TMR_SR_sendTimeout(TMR_Reader *reader, uint8_t *data, uint32_t timeoutMs)
00396 {
00397 TMR_Status ret;
00398 uint8_t opcode;
00399 ret = TMR_SR_sendMessage(reader, data, &opcode, timeoutMs);
00400 if (TMR_SUCCESS != ret)
00401 {
00402 return ret;
00403 }
00404 if (isContinuousReadParamSupported(reader))
00405 {
00406 while(reader->paramWait)
00407 { }
00408 reader->paramWait = false;
00409 memcpy(data , &reader->paramMessage[5], reader->paramMessage[1] * sizeof(uint8_t));
00410 data[0] = 0xFF;
00411 ret = (TMR_Status) GETU16AT(&reader->paramMessage[0], 3);
00412 if (TMR_SUCCESS != ret)
00413 {
00414 return TMR_ERROR_CODE(ret);
00415 }
00416 ret = (TMR_Status) GETU16AT(data, 3);
00417 if (TMR_SUCCESS != ret)
00418 {
00419 return TMR_ERROR_CODE(ret);
00420 }
00421 }
00422 else
00423 {
00424 ret = TMR_SR_receiveMessage(reader, data, opcode, timeoutMs);
00425 if (TMR_SUCCESS != ret)
00426 {
00427 return ret;
00428 }
00429 }
00430 return ret;
00431 }
00432
00433
00434 TMR_Status
00435 TMR_SR_send(TMR_Reader *reader, uint8_t *data)
00436 {
00437 return TMR_SR_sendTimeout(reader, data,
00438 reader->u.serialReader.commandTimeout);
00439 }
00440
00448 TMR_Status
00449 TMR_SR_cmdTestSetFrequency(TMR_Reader *reader, uint32_t frequency)
00450 {
00451
00452 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00453 uint8_t i;
00454 i = 2;
00455 SETU8(msg, i,TMR_SR_OPCODE_SET_OPERATING_FREQ);
00456 SETU32(msg, i, frequency);
00457 msg[1] = i - 3;
00458 return TMR_SR_send(reader, msg);
00459 }
00460
00468 TMR_Status
00469 TMR_SR_cmdTestSendCw(TMR_Reader *reader, bool on)
00470 {
00471 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00472 uint8_t i;
00473 i = 2;
00474 SETU8(msg, i,TMR_SR_OPCODE_TX_CW_SIGNAL);
00475 if(on)
00476 SETU8(msg, i,1);
00477 else
00478 SETU8(msg, i,0);
00479 msg[1] = i - 3;
00480 return TMR_SR_send(reader, msg);
00481 }
00482
00491 TMR_Status
00492 TMR_SR_cmdTestSendPrbs(TMR_Reader *reader, uint16_t duration)
00493 {
00494 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00495 uint8_t i;
00496 i = 2;
00497 SETU8(msg, i,TMR_SR_OPCODE_TX_CW_SIGNAL);
00498 SETU8(msg, i,2);
00499 SETU16(msg, i,duration);
00500 msg[1] = i - 3;
00501 return TMR_SR_send(reader, msg);
00502 }
00503
00513 TMR_Status
00514 TMR_SR_cmdSetUserProfile(TMR_Reader *reader,TMR_SR_UserConfigOperation op,TMR_SR_UserConfigCategory category, TMR_SR_UserConfigType type)
00515 {
00516 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00517 uint8_t i;
00518 TMR_Status ret;
00519 TMR_Status ret1;
00520 uint16_t readTime = 250;
00521 TMR_SR_SerialReader *sr;
00522 TMR_SR_SerialTransport *transport;
00523
00524 sr = &reader->u.serialReader;
00525 transport = &reader->u.serialReader.transport;
00526
00527 i = 2;
00528 SETU8(msg,i,TMR_SR_OPCODE_SET_USER_PROFILE);
00529 SETU8(msg,i,op);
00530 SETU8(msg,i,category);
00531 SETU8(msg,i,type);
00532
00533 #ifdef TMR_ENABLE_BACKGROUND_READS
00534 readTime = (uint16_t)reader->readParams.asyncOnTime;
00535 #endif
00536
00537 if (op == TMR_USERCONFIG_CLEAR)
00538 {
00539
00540 sr->enableAutonomousRead = false;
00541 }
00542
00543 if (op == TMR_USERCONFIG_SAVE_WITH_READPLAN)
00544 {
00550 TMR_uint8List *antennaList = NULL;
00551 TMR_ReadPlan *rp;
00552 uint8_t tempMsg[TMR_SR_MAX_PACKET_SIZE];
00553
00554 rp = reader->readParams.readPlan;
00555
00562
00563 sr->enableAutonomousRead = rp->enableAutonomousRead;
00564 SETU8(msg,i,rp->enableAutonomousRead);
00565
00566 if (TMR_READ_PLAN_TYPE_MULTI == rp->type)
00567 {
00568
00569 uint8_t i;
00570 TMR_TagProtocolList p;
00571 TMR_TagProtocolList *protocolList = &p;
00572 TMR_TagFilter *filters[TMR_MAX_SERIAL_MULTIPROTOCOL_LENGTH];
00573 TMR_TagProtocol protocols[TMR_MAX_SERIAL_MULTIPROTOCOL_LENGTH];
00574
00575 if (TMR_MAX_SERIAL_MULTIPROTOCOL_LENGTH < rp->u.multi.planCount)
00576 {
00577 return TMR_ERROR_TOO_BIG ;
00578 }
00579 protocolList->len = rp->u.multi.planCount;
00580 protocolList->max = rp->u.multi.planCount;
00581 protocolList->list = protocols;
00582
00583 for (i = 0; i < rp->u.multi.planCount; i++)
00584 {
00585 protocolList->list[i] = rp->u.multi.plans[i]->u.simple.protocol;
00586 filters[i]= rp->u.multi.plans[i]->u.simple.filter;
00587 }
00588
00589 if ((0 < rp->u.multi.planCount) &&
00590 (rp->u.multi.plans[0]->type == TMR_READ_PLAN_TYPE_SIMPLE) &&
00591 (compareAntennas(&rp->u.multi)))
00592 {
00593 TMR_SR_SearchFlag antennas = TMR_SR_SEARCH_FLAG_CONFIGURED_LIST;
00594
00595 reader->continuousReading = true;
00596 antennas |= ((reader->continuousReading)? TMR_SR_SEARCH_FLAG_TAG_STREAMING : 0);
00597 antennaList = &(rp->u.multi.plans[0]->u.simple.antennas);
00598 ret = prepForSearch(reader, antennaList);
00599 if (TMR_SUCCESS != ret)
00600 {
00601 return ret;
00602 }
00603
00604 if (reader->continuousReading)
00605 {
00606 bool value = false;
00607 ret = TMR_SR_cmdSetReaderConfiguration(reader, TMR_SR_CONFIGURATION_ENABLE_READ_FILTER, &value);
00608 if (TMR_SUCCESS != ret)
00609 {
00610 return ret;
00611 }
00612 }
00613
00614
00615 ret = TMR_SR_msgSetupMultipleProtocolSearch(reader, tempMsg, TMR_SR_OPCODE_READ_TAG_ID_MULTIPLE, protocolList,
00616 reader->userMetadataFlag, antennas, filters, (uint16_t)readTime);
00617 if (TMR_SUCCESS != ret)
00618 {
00619 return ret;
00620 }
00621 }
00622 else
00623 {
00630 return TMR_ERROR_UNSUPPORTED;
00631 }
00632 }
00633 else
00634 {
00635
00636 TMR_TagProtocolList p;
00637 TMR_TagProtocolList *protocolList = &p;
00638 TMR_TagFilter *filters[TMR_MAX_SERIAL_MULTIPROTOCOL_LENGTH];
00639 TMR_TagProtocol protocols[TMR_MAX_SERIAL_MULTIPROTOCOL_LENGTH];
00640 TMR_SR_SearchFlag antennas;
00641
00642 antennaList = &rp->u.simple.antennas;
00643 reader->continuousReading = true;
00644 reader->fastSearch = rp->u.simple.useFastSearch;
00645 reader->triggerRead = rp->u.simple.triggerRead.enable;
00646 protocolList->len = 1;
00647 protocolList->max = 1;
00648 protocolList->list = protocols;
00649
00650 ret = prepForSearch(reader, antennaList);
00651 if (TMR_SUCCESS != ret)
00652 {
00653 return ret;
00654 }
00655
00656 if (reader->continuousReading)
00657 {
00658 bool value = false;
00659 ret = TMR_SR_cmdSetReaderConfiguration(reader, TMR_SR_CONFIGURATION_ENABLE_READ_FILTER, &value);
00660 if (TMR_SUCCESS != ret)
00661 {
00662 return ret;
00663 }
00664 }
00665
00666 protocolList->list[0] = rp->u.simple.protocol;
00667 filters[0]= rp->u.simple.filter;
00668
00669 antennas = TMR_SR_SEARCH_FLAG_CONFIGURED_LIST;
00670 antennas |= ((reader->continuousReading)? TMR_SR_SEARCH_FLAG_TAG_STREAMING : 0);
00671 antennaList = &(rp->u.simple.antennas);
00672
00673 ret = TMR_SR_msgSetupMultipleProtocolSearch(reader, tempMsg, TMR_SR_OPCODE_READ_TAG_ID_MULTIPLE, protocolList,
00674 reader->userMetadataFlag, antennas, filters, (uint16_t)readTime);
00675 if (TMR_SUCCESS != ret)
00676 {
00677 return ret;
00678 }
00679 }
00680
00681
00682 memcpy((msg + i), tempMsg+1, tempMsg[1]+2);
00683
00684 i = (i + tempMsg[1] + 2);
00685 reader->continuousReading = false;
00686 }
00687
00688 msg[1] = i - 3;
00689 ret1 = TMR_SR_send(reader, msg);
00690 if (TMR_SUCCESS != ret1)
00691 {
00692 return ret1;
00693 }
00694
00695
00696 if (!sr->enableAutonomousRead)
00697 {
00698 if ((op == TMR_USERCONFIG_RESTORE)||(op == TMR_USERCONFIG_CLEAR))
00699 {
00700 uint32_t rate;
00701 if (reader->connected == false)
00702 {
00703 ret = transport->open(transport);
00704 if (TMR_SUCCESS != ret)
00705 {
00706 return ret;
00707 }
00708 }
00709
00710 ret = TMR_SR_cmdProbeBaudRate(reader, &rate);
00711 if (TMR_SUCCESS != ret)
00712 {
00713 return ret;
00714 }
00715 reader->connected = true;
00716 }
00717
00718
00719 if ((op == TMR_USERCONFIG_RESTORE) || (op == TMR_USERCONFIG_CLEAR))
00720 {
00721 ret = TMR_SR_cmdGetRegion(reader, &sr->regionId);
00722 if (TMR_SUCCESS != ret)
00723 {
00724 return ret;
00725 }
00726
00727 ret = TMR_SR_cmdGetCurrentProtocol(reader, &reader->tagOpParams.protocol);
00728 if (TMR_SUCCESS != ret)
00729 {
00730 return ret;
00731 }
00732 sr->currentProtocol = reader->tagOpParams.protocol;
00733 }
00734 }
00735 return ret1;
00736 }
00737
00748 TMR_Status TMR_SR_cmdGetUserProfile(TMR_Reader *reader, uint8_t byte[], uint8_t length, uint8_t response[], uint8_t* response_length)
00749 {
00750 TMR_Status ret;
00751 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00752 uint8_t i,j;
00753 i = 2;
00754 SETU8(msg,i,TMR_SR_OPCODE_GET_USER_PROFILE);
00755 for(j=0;j<length;j++)
00756 {
00757 SETU8(msg,i,byte[j]);
00758 }
00759 msg[1] = i - 3;
00760 ret = TMR_SR_send(reader, msg);
00761 if (TMR_SUCCESS != ret)
00762 {
00763 return ret;
00764 }
00765 for(j=0;j<msg[1];j++)
00766 {
00767 response[j]=msg[5+j];
00768 }
00769 *response_length=msg[1];
00770 return ret;
00771 }
00772
00773 TMR_Status TMR_SR_cmdBlockWrite(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Bank bank, uint32_t wordPtr,
00774 uint32_t wordCount, const uint16_t* data, uint32_t accessPassword, const TMR_TagFilter* target)
00775 {
00776 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00777 uint8_t i, option=0,rec;
00778 i = 2;
00779 SETU8(msg,i,TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
00780 SETU16(msg, i,timeout);
00781 SETU8(msg,i,0x00);
00782 rec=i;
00783 SETU8(msg,i,0x40);
00784 SETU8(msg,i,0x00);
00785 SETU8(msg,i,0xC7);
00786 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, &i, msg,accessPassword,true);
00787 msg[rec]=msg[rec]|option;
00788 SETU8(msg,i,0x00);
00789 SETU8(msg,i,bank);
00790 SETU32(msg,i,wordPtr);
00791 SETU8(msg,i,(uint8_t)wordCount);
00792 {
00793 uint32_t iWord;
00794 for (iWord = 0; iWord < wordCount; iWord++)
00795 {
00796 SETU8(msg, i, ((data[iWord]>>8)&0xFF));
00797 SETU8(msg, i, ((data[iWord]>>0)&0xFF));
00798 }
00799 }
00800 msg[1] = i - 3;
00801 return TMR_SR_send(reader, msg);
00802 }
00803
00804 TMR_Status
00805 TMR_SR_cmdBlockErase(TMR_Reader *reader, uint16_t timeout,
00806 TMR_GEN2_Bank bank, uint32_t wordPtr,
00807 uint8_t wordCount, uint32_t accessPassword,
00808 TMR_TagFilter *target)
00809 {
00810 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00811 uint8_t i;
00812 i = 2;
00813
00814 TMR_SR_msgAddGEN2BlockErase(msg, &i, timeout, wordPtr, bank, wordCount, accessPassword, target);
00815
00816 msg[1] = i - 3;
00817 return TMR_SR_send(reader, msg);
00818 }
00819
00820 TMR_Status
00821 TMR_SR_cmdBlockPermaLock(TMR_Reader *reader, uint16_t timeout,uint32_t readLock, TMR_GEN2_Bank bank, uint32_t blockPtr, uint32_t blockRange, uint16_t* mask, uint32_t accessPassword, TMR_TagFilter* target, TMR_uint8List* data)
00822 {
00823 TMR_Status ret;
00824 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00825 uint8_t i, option=0,rec;
00826 unsigned int j;
00827 i = 2;
00828 SETU8(msg,i,TMR_SR_OPCODE_ERASE_BLOCK_TAG_SPECIFIC);
00829 SETU16(msg,i,timeout);
00830 SETU8(msg,i,0x00);
00831 rec=i;
00832 SETU8(msg,i,0x40);
00833 SETU8(msg,i,0x01);
00834 filterbytes(TMR_TAG_PROTOCOL_GEN2,target, &option, &i, msg,accessPassword,true);
00835 msg[rec]=msg[rec]|option;
00836 SETU8(msg,i,0x00);
00837 SETU8(msg,i,(uint8_t)readLock);
00838
00839 SETU8(msg,i,bank);
00840 SETU32(msg,i,blockPtr);
00841 SETU8(msg,i,(uint8_t)blockRange);
00842
00843 if (readLock==0x01)
00844 {
00845 for(j=0;j<blockRange;j++)
00846 {
00847 SETU8(msg,i,(mask[j]>>8)&(0xff));
00848 SETU8(msg,i,(mask[j]>>0) & (0xff));
00849 }
00850 }
00851 msg[1] = i - 3;
00852 ret = TMR_SR_send(reader, msg);
00853 if (TMR_SUCCESS != ret)
00854 {
00855 return ret;
00856 }
00857 if ((0 == readLock) && (NULL != data))
00858 {
00859 data->len = msg[1]-2;
00860 if (data->len > data->max)
00861 {
00862 data->len = data->max;
00863 }
00864 memcpy(data->list, msg+7, data->len);
00865 }
00866 return ret;
00867 }
00868 TMR_Status
00869 TMR_SR_cmdVersion(TMR_Reader *reader, TMR_SR_VersionInfo *info)
00870 {
00871 TMR_Status ret;
00872 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00873 uint8_t i, j;
00874 uint32_t tTimeout = 0;
00875
00876 tTimeout = reader->u.serialReader.transportTimeout;
00877
00882 if (false == reader->u.serialReader.usrTimeoutEnable)
00883 {
00884 reader->u.serialReader.transportTimeout = 100;
00885 }
00886
00887 i = 2;
00888 SETU8(msg, i, TMR_SR_OPCODE_VERSION);
00889 msg[1] = i - 3;
00890
00891 ret = TMR_SR_sendTimeout(reader, msg, 0);
00892 if (TMR_SUCCESS != ret)
00893 {
00894 reader->u.serialReader.transportTimeout = tTimeout;
00895 return ret;
00896 }
00897 if (NULL != info)
00898 {
00899 i = 5;
00900 for (j = 0; j < 4 ; j++)
00901 {
00902 info->bootloader[j] = GETU8(msg, i);
00903 }
00904 for (j = 0; j < 4 ; j++)
00905 {
00906 info->hardware[j] = GETU8(msg, i);
00907 }
00908 for (j = 0; j < 4 ; j++)
00909 {
00910 info->fwDate[j] = GETU8(msg, i);
00911 }
00912 for (j = 0; j < 4 ; j++)
00913 {
00914 info->fwVersion[j] = GETU8(msg, i);
00915 }
00916 info->protocols = GETU32(msg, i);
00917 }
00918
00919 reader->u.serialReader.transportTimeout = tTimeout;
00920 return TMR_SUCCESS;
00921 }
00922
00923
00924 TMR_Status
00925 TMR_SR_cmdBootFirmware(TMR_Reader *reader)
00926 {
00927 TMR_Status ret;
00928 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00929 uint8_t i, j;
00930
00931 i = 2;
00932 SETU8(msg, i, TMR_SR_OPCODE_BOOT_FIRMWARE);
00933 msg[1] = i - 3;
00934
00935 ret = TMR_SR_sendTimeout(reader, msg, 1000);
00936 if (TMR_SUCCESS != ret)
00937 {
00938 return ret;
00939 }
00940
00941 i = 5;
00942 for (j = 0; j < 4 ; j++)
00943 {
00944 reader->u.serialReader.versionInfo.bootloader[j] = GETU8(msg, i);
00945 }
00946 for (j = 0; j < 4 ; j++)
00947 {
00948 reader->u.serialReader.versionInfo.hardware[j] = GETU8(msg, i);
00949 }
00950 for (j = 0; j < 4 ; j++)
00951 {
00952 reader->u.serialReader.versionInfo.fwDate[j] = GETU8(msg, i);
00953 }
00954 for (j = 0; j < 4 ; j++)
00955 {
00956 reader->u.serialReader.versionInfo.fwVersion[j] = GETU8(msg, i);
00957 }
00958 reader->u.serialReader.versionInfo.protocols = GETU32(msg, i);
00959
00960 return TMR_SUCCESS;
00961 }
00962
00963
00964 TMR_Status
00965 TMR_SR_cmdSetBaudRate(TMR_Reader *reader, uint32_t rate)
00966 {
00967 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00968 uint8_t i;
00969
00970 i = 2;
00971 SETU8(msg, i, TMR_SR_OPCODE_SET_BAUD_RATE);
00972 SETU32(msg, i, rate);
00973 msg[1] = i - 3;
00974
00975 return TMR_SR_send(reader, msg);
00976 }
00977
00978
00979 TMR_Status
00980 TMR_SR_cmdEraseFlash(TMR_Reader *reader, uint8_t sector, uint32_t password)
00981 {
00982 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
00983 uint8_t i;
00984
00985 i = 2;
00986 SETU8(msg, i, TMR_SR_OPCODE_ERASE_FLASH);
00987 SETU32(msg, i, password);
00988 SETU8(msg, i, sector);
00989 msg[1] = i - 3;
00990
00991 return TMR_SR_sendTimeout(reader, msg, 30000);
00992 }
00993
00994
00995 TMR_Status
00996 TMR_SR_cmdWriteFlashSector(TMR_Reader *reader, uint8_t sector, uint32_t address,
00997 uint32_t password, uint8_t length, const uint8_t data[],
00998 uint32_t offset)
00999 {
01000 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
01001 uint8_t i;
01002
01003 i = 2;
01004 SETU8(msg, i, TMR_SR_OPCODE_WRITE_FLASH_SECTOR);
01005 SETU32(msg, i, password);
01006 SETU32(msg, i, address);
01007 SETU8(msg, i, sector);
01008 memcpy(&msg[i], data + offset, length);
01009 i += length;
01010 msg[1] = i - 3;
01011
01012 return TMR_SR_sendTimeout(reader, msg, 3000);
01013 }
01014
01015
01016
01017 TMR_Status
01018 TMR_SR_cmdModifyFlashSector(TMR_Reader *reader, uint8_t sector, uint32_t address,
01019 uint32_t password, uint8_t length, const uint8_t data[],
01020 uint32_t offset)
01021 {
01022 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
01023 uint8_t i;
01024
01025 i = 2;
01026 SETU8(msg, i, TMR_SR_OPCODE_MODIFY_FLASH_SECTOR);
01027 SETU32(msg, i, password);
01028 SETU32(msg, i, address);
01029 SETU8(msg, i, sector);
01030 memcpy(&msg[i], data + offset, length);
01031 i += length;
01032 msg[1] = i - 3;
01033
01034 return TMR_SR_sendTimeout(reader, msg, 3000);
01035 }
01036
01037 TMR_Status
01038 TMR_SR_cmdBootBootloader(TMR_Reader *reader)
01039 {
01040 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
01041 uint8_t i;
01042
01043 i = 2;
01044 SETU8(msg, i, TMR_SR_OPCODE_BOOT_BOOTLOADER);
01045 msg[1] = i - 3;
01046
01047 reader->u.serialReader.crcEnabled = true;
01048 return TMR_SR_send(reader, msg);
01049 }
01050
01051
01052 TMR_Status
01053 TMR_SR_cmdGetHardwareVersion(TMR_Reader *reader, uint8_t option, uint8_t flags,
01054 uint8_t* count, uint8_t data[])
01055 {
01056 TMR_Status ret;
01057 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
01058 uint8_t i;
01059
01060 i = 2;
01061 SETU8(msg, i, TMR_SR_OPCODE_HW_VERSION);
01062 SETU8(msg, i, option);
01063 SETU8(msg, i, flags);
01064 msg[1] = i - 3;
01065
01066 ret = TMR_SR_send(reader, msg);
01067 if (TMR_SUCCESS != ret)
01068 {
01069 return ret;
01070 }
01071
01072 for (i = 0 ; i < msg[1] && i < *count; i++)
01073 {
01074 data[i] = msg[5 + i];
01075 }
01076
01077 *count = msg[1];
01078
01079 return TMR_SUCCESS;
01080 }
01081
01082
01083 TMR_Status
01084 TMR_SR_cmdGetCurrentProgram(TMR_Reader *reader, uint8_t *program)
01085 {
01086 TMR_Status ret;
01087 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
01088 uint8_t i;
01089
01090 i = 2;
01091 SETU8(msg, i, TMR_SR_OPCODE_GET_CURRENT_PROGRAM);
01092 msg[1] = i - 3;
01093
01094 ret = TMR_SR_send(reader, msg);
01095 *program = msg[5];
01096
01097 return ret;
01098 }
01099
01100 TMR_Status TMR_SR_msgSetupReadTagSingle(uint8_t *msg, uint8_t *i, TMR_TagProtocol protocol,TMR_TRD_MetadataFlag metadataFlags, const TMR_TagFilter *filter,uint16_t timeout)
01101 {
01102 uint8_t optbyte;
01103
01104 SETU8(msg, *i, TMR_SR_OPCODE_READ_TAG_ID_SINGLE);
01105 SETU16(msg, *i, timeout);
01106 optbyte = *i;
01107 SETU8(msg, *i, 0);
01108 msg[optbyte] |= TMR_SR_GEN2_SINGULATION_OPTION_FLAG_METADATA;
01109 SETU16(msg,*i, metadataFlags);
01110 filterbytes(protocol, filter, &msg[optbyte], i, msg,0, true);
01111 msg[optbyte] |= TMR_SR_GEN2_SINGULATION_OPTION_FLAG_METADATA;
01112 return TMR_SUCCESS;
01113
01114 }
01115
01116 TMR_Status
01117 TMR_SR_msgSetupReadTagMultiple(TMR_Reader *reader, uint8_t *msg, uint8_t *i, uint16_t timeout,
01118 TMR_SR_SearchFlag searchFlag,
01119 const TMR_TagFilter *filter,
01120 TMR_TagProtocol protocol,
01121 TMR_GEN2_Password accessPassword)
01122 {
01123 return TMR_SR_msgSetupReadTagMultipleWithMetadata(reader, msg, i, timeout,
01124 searchFlag, reader->userMetadataFlag, filter, protocol,accessPassword);
01125 }
01126
01127
01128 TMR_Status
01129 TMR_SR_msgSetupReadTagMultipleWithMetadata(TMR_Reader *reader, uint8_t *msg, uint8_t *i, uint16_t timeout,
01130 TMR_SR_SearchFlag searchFlag,
01131 TMR_TRD_MetadataFlag metadataFlag,
01132 const TMR_TagFilter *filter,
01133 TMR_TagProtocol protocol,
01134 TMR_GEN2_Password accessPassword)
01135 {
01136 TMR_Status ret;
01137 TMR_SR_SerialReader *sr;
01138 uint8_t optbyte;
01139
01140 sr = &reader->u.serialReader;
01141 sr->opCode = TMR_SR_OPCODE_READ_TAG_ID_MULTIPLE;
01142 ret = TMR_SUCCESS;
01143
01144 SETU8(msg, *i, TMR_SR_OPCODE_READ_TAG_ID_MULTIPLE);
01145
01153 if (sr->isBapEnabled)
01154 {
01155 SETU8(msg,*i,0x81);
01156 }
01157
01158 optbyte = *i;
01159 SETU8(msg, *i, 0);
01160
01161
01162 searchFlag= (TMR_SR_SearchFlag)(searchFlag | TMR_SR_SEARCH_FLAG_LARGE_TAG_POPULATION_SUPPORT);
01163
01164 if (reader->continuousReading)
01165 {
01166 msg[optbyte] |= TMR_SR_GEN2_SINGULATION_OPTION_FLAG_METADATA;
01167 searchFlag = (TMR_SR_SearchFlag)(searchFlag
01168 | TMR_SR_SEARCH_FLAG_TAG_STREAMING);
01169
01175 if (TMR_SR_STATUS_NONE != reader->streamStats)
01176 {
01177 searchFlag |= TMR_SR_SEARCH_FLAG_STATUS_REPORT_STREAMING;
01178 }
01179 else
01180 {
01181 if (TMR_READER_STATS_FLAG_NONE != reader->statsFlag)
01182 {
01183 searchFlag |= TMR_SR_SEARCH_FLAG_STATS_REPORT_STREAMING;
01184 }
01185 }
01186 }
01187
01191 if (reader->fastSearch)
01192 {
01193 searchFlag = (TMR_SR_SearchFlag)(searchFlag
01194 |TMR_SR_SEARCH_FLAG_READ_MULTIPLE_FAST_SEARCH);
01195 reader->fastSearch = false;
01196 }
01197
01201 if (reader->triggerRead)
01202 {
01203 searchFlag = (TMR_SR_SearchFlag)(searchFlag
01204 |TMR_SR_SEARCH_FLAG_GPI_TRIGGER_READ);
01205 reader->triggerRead = false;
01206 }
01207
01211 if (reader->dutyCycle)
01212 {
01213 searchFlag = (TMR_SR_SearchFlag)(searchFlag
01214 |TMR_SR_SEARCH_FLAG_DUTY_CYCLE_CONTROL);
01215 }
01216
01217 if (reader->isStopNTags && !reader->continuousReading)
01218 {
01223 searchFlag = (TMR_SR_SearchFlag)(searchFlag
01224 |TMR_SR_SEARCH_FLAG_RETURN_ON_N_TAGS);
01225 }
01226
01227 SETU16(msg, *i, searchFlag);
01228 SETU16(msg, *i, timeout);
01229 if(reader->dutyCycle)
01230 {
01231 uint32_t offtime;
01232 ret = TMR_paramGet(reader,TMR_PARAM_READ_ASYNCOFFTIME,&offtime);
01233 SETU16(msg, *i, (uint16_t)offtime);
01234 }
01235 reader->dutyCycle = false;
01236 if (reader->continuousReading)
01237 {
01238 SETU16(msg, *i, metadataFlag);
01239
01240 if (TMR_READER_STATS_FLAG_NONE != reader->statsFlag)
01241 {
01247 if ((0x80) > reader->statsFlag)
01248 {
01249 SETU16(msg, *i, (uint16_t)reader->statsFlag);
01250 }
01251 else
01252 {
01253 SETU16(msg, *i, ((uint16_t)reader->statsFlag));
01254 }
01255 }
01256 else
01257 {
01258 if (TMR_SR_STATUS_NONE != reader->streamStats)
01259 {
01260
01261 SETU16(msg, *i, (uint16_t)reader->streamStats);
01262 }
01263 }
01264 }
01265
01271 if (reader->isStopNTags && !reader->continuousReading)
01272 {
01273 SETU32(msg ,*i, (uint32_t)reader->numberOfTagsToRead);
01274 }
01275
01276
01277
01278
01279
01280
01281
01282 if (TMR_TAG_PROTOCOL_ISO180006B == protocol && NULL == filter)
01283 {
01284
01285 }
01286 else
01287 {
01288 ret = filterbytes(protocol, filter, &msg[optbyte], i, msg,
01289 accessPassword, true);
01290 }
01291
01292 if (reader->continuousReading)
01293 {
01294 msg[optbyte] |= TMR_SR_GEN2_SINGULATION_OPTION_FLAG_METADATA;
01295 }
01296 if (isSecureAccessEnabled)
01297 {
01298 msg[optbyte] |= TMR_SR_GEN2_SINGULATION_OPTION_SECURE_READ_DATA;
01299 }
01300
01301 return ret;
01302 }
01303
01304 TMR_Status
01305 TMR_SR_cmdReadTagMultiple(TMR_Reader *reader, uint16_t timeout,
01306 TMR_SR_SearchFlag searchFlag,
01307 const TMR_TagFilter *filter, TMR_TagProtocol protocol,
01308 uint32_t *tagCount)
01309 {
01310 TMR_Status ret;
01311 TMR_SR_SerialReader *sr;
01312 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
01313 uint8_t i;
01314
01315 i = 2;
01316 ret = TMR_SR_msgSetupReadTagMultiple(reader, msg, &i, timeout, searchFlag,
01317 filter, protocol, 0);
01318 if (TMR_SUCCESS != ret)
01319 {
01320 return ret;
01321 }
01322 msg[1] = i - 3;
01323
01324 sr = &reader->u.serialReader;
01325 sr->opCode = TMR_SR_OPCODE_READ_TAG_ID_MULTIPLE;
01326 if (reader->continuousReading)
01327 {
01328 uint8_t opcode;
01329 ret = TMR_SR_sendMessage(reader, msg, &opcode, timeout);
01330 *tagCount = (uint32_t)0;
01331 return ret;
01332 }
01333 else
01334 {
01335 ret = TMR_SR_sendTimeout(reader, msg, timeout);
01336 if (TMR_SUCCESS != ret)
01337 {
01338 return ret;
01339 }
01340
01341 if (NULL != tagCount)
01342 {
01343 if (4 == msg[1])
01344 {
01345
01346 *tagCount = GETU8AT(msg, 8);
01347 }
01348 else if (5 == msg[1])
01349 {
01350
01351 *tagCount = GETU8AT(msg, 9);
01352 }
01353 else if (7 == msg[1])
01354 {
01355
01356 *tagCount = GETU32AT(msg, 8);
01357 }
01358 else if (8 == msg[1])
01359 {
01360
01361
01362
01363 *tagCount = GETU32AT(msg, 9);
01364 }
01365 else
01366 {
01367 return TMR_ERROR_PARSE;
01368 }
01369 }
01370
01371 return TMR_SUCCESS;
01372 }
01373 }
01374
01375
01376 TMR_Status
01377 TMR_SR_executeEmbeddedRead(TMR_Reader *reader, uint8_t *msg, uint16_t timeout,
01378 TMR_SR_MultipleStatus *status)
01379 {
01380 TMR_Status ret;
01381 uint8_t i, len, index;
01382 uint8_t newMsg[TMR_SR_MAX_PACKET_SIZE];
01383
01384 if (reader->continuousReading)
01385 {
01386 uint8_t opcode = TMR_SR_OPCODE_MULTI_PROTOCOL_TAG_OP;
01387 i = 2;
01388 SETU8(newMsg, i, opcode);
01389
01390
01391 SETU16(newMsg, i, 0);
01392 SETU8(newMsg, i, (uint8_t)0x1);
01393 SETU8(newMsg, i, (uint8_t)TMR_SR_OPCODE_READ_TAG_ID_MULTIPLE);
01394 SETU16(newMsg, i, (uint16_t)0x0000);
01395 SETU8(newMsg, i, (uint8_t)TMR_TAG_PROTOCOL_GEN2);
01396
01397 len = msg[1];
01398 index = i;
01399 SETU8(newMsg, i, 0);
01400
01401
01402 memcpy(&newMsg[i], &msg[2], (size_t)(len + 1));
01403 i += len + 1;
01404
01405
01406 newMsg[index] = i - index - 2;
01407
01408
01409 newMsg[1]=i - 3;
01410
01411 ret = TMR_SR_sendMessage(reader, newMsg, &opcode, timeout);
01412 status->tagsFound = status->successCount = status->failureCount = 0;
01413
01414 return ret;
01415 }
01416 else
01417 {
01418 uint16_t searchFlags = GETU16AT(msg, 4);
01419
01420 ret = TMR_SR_sendTimeout(reader, msg, timeout);
01421 if (TMR_SUCCESS != ret)
01422 {
01423 return ret;
01424 }
01425
01426 if (NULL != status)
01427 {
01428 int readIdx = 8;
01429 if ((TMR_SR_SEARCH_FLAG_LARGE_TAG_POPULATION_SUPPORT & searchFlags) &&
01430 ((TMR_SR_MODEL_M6E == reader->u.serialReader.versionInfo.hardware[0]) ||
01431 (TMR_SR_MODEL_M6E_I == reader->u.serialReader.versionInfo.hardware[0]) ||
01432 (TMR_SR_MODEL_M6E_NANO == reader->u.serialReader.versionInfo.hardware[0]) ||
01433 (TMR_SR_MODEL_MICRO == reader->u.serialReader.versionInfo.hardware[0])))
01434 {
01435
01436 status->tagsFound = (uint16_t)GETU32AT(msg, readIdx);
01437 readIdx += 4;
01438 }
01439 else
01440 {
01441 status->tagsFound = GETU8AT(msg, readIdx);
01442 readIdx += 1;
01443 }
01444 readIdx += 2;
01445 status->successCount = GETU16AT(msg, readIdx);
01446 readIdx += 2;
01447 status->failureCount = GETU16AT(msg, readIdx);
01448 readIdx += 2;
01449 }
01450 }
01451
01452 return TMR_SUCCESS;
01453 }
01454
01455 void
01456 TMR_SR_msgAddGEN2WriteTagEPC(uint8_t *msg, uint8_t *i, uint16_t timeout, uint8_t *epc, uint8_t count)
01457 {
01458 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_ID);
01459 SETU16(msg, *i, timeout);
01460 SETU16(msg, *i, 0);
01461 memcpy(&msg[*i], epc, count);
01462 *i += count;
01463 }
01464
01465 void
01466 TMR_SR_msgAddGEN2DataRead(uint8_t *msg, uint8_t *i, uint16_t timeout,
01467 TMR_GEN2_Bank bank, uint32_t wordAddress, uint8_t len, uint8_t option, bool withMetaData)
01468 {
01469
01470 SETU8(msg, *i, TMR_SR_OPCODE_READ_TAG_DATA);
01471 SETU16(msg, *i, timeout);
01472 SETU8(msg, *i, option);
01473 if (withMetaData)
01474 {
01475 SETU16(msg, *i, 0x0000);
01476 }
01477 SETU8(msg, *i, bank);
01478 SETU32(msg, *i, wordAddress);
01479 SETU8(msg, *i, len);
01480 }
01481
01482
01483 void
01484 TMR_SR_msgAddGEN2DataWrite(uint8_t *msg, uint8_t *i, uint16_t timeout,
01485 TMR_GEN2_Bank bank, uint32_t address)
01486 {
01487
01488 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_DATA);
01489 SETU16(msg, *i, timeout);
01490 SETU8(msg, *i, 0);
01491 SETU32(msg, *i, address);
01492 SETU8(msg, *i, bank);
01493 }
01494
01495
01496 void
01497 TMR_SR_msgAddGEN2LockTag(uint8_t *msg, uint8_t *i, uint16_t timeout, uint16_t mask,
01498 uint16_t action, TMR_GEN2_Password accessPassword)
01499 {
01500
01501 SETU8(msg, *i, TMR_SR_OPCODE_LOCK_TAG);
01502 SETU16(msg, *i, timeout);
01503 SETU8(msg, *i, 0);
01504 SETU32(msg, *i, accessPassword);
01505 SETU16(msg, *i, mask);
01506 SETU16(msg, *i, action);
01507 }
01508
01509
01510 void
01511 TMR_SR_msgAddGEN2KillTag(uint8_t *msg, uint8_t *i, uint16_t timeout,
01512 TMR_GEN2_Password password)
01513 {
01514
01515 SETU8(msg, *i, TMR_SR_OPCODE_KILL_TAG);
01516 SETU16(msg, *i, timeout);
01517 SETU8(msg, *i, 0);
01518 SETU32(msg, *i, password);
01519 SETU8(msg, *i, 0);
01520 }
01521
01522 void
01523 TMR_SR_msgAddGEN2BlockWrite(uint8_t *msg, uint8_t *i, uint16_t timeout,TMR_GEN2_Bank bank, uint32_t wordPtr, uint32_t wordCount, uint16_t* data, uint32_t accessPassword, TMR_TagFilter* target)
01524 {
01525 uint8_t option=0,rec;
01526 SETU8(msg,*i,TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
01527 SETU16(msg, *i,timeout);
01528 SETU8(msg,*i,0x00);
01529 rec=*i;
01530 SETU8(msg,*i,0x40);
01531 SETU8(msg,*i,0x00);
01532 SETU8(msg,*i,0xC7);
01533 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg,accessPassword,true);
01534 msg[rec]=msg[rec]|option;
01535 SETU8(msg,*i,0x00);
01536 SETU8(msg,*i,bank);
01537 SETU32(msg,*i,wordPtr);
01538 SETU8(msg,*i,(uint8_t)wordCount);
01539 {
01540 uint32_t iWord;
01541 for (iWord=0; iWord<wordCount; iWord++)
01542 {
01543 SETU8(msg, *i, ((data[iWord]>>8)&0xFF));
01544 SETU8(msg, *i, ((data[iWord]>>0)&0xFF));
01545 }
01546 }
01547 }
01548
01549 void
01550 TMR_SR_msgAddGEN2BlockPermaLock(uint8_t *msg, uint8_t *i, uint16_t timeout, uint32_t readLock, TMR_GEN2_Bank bank, uint32_t blockPtr, uint32_t blockRange, uint16_t* mask, uint32_t accessPassword,TMR_TagFilter* target)
01551 {
01552 uint8_t option=0,rec;
01553 SETU8(msg,*i,TMR_SR_OPCODE_ERASE_BLOCK_TAG_SPECIFIC);
01554 SETU16(msg,*i,timeout);
01555 SETU8(msg,*i,0x00);
01556 rec=*i;
01557 SETU8(msg,*i,0x40);
01558 SETU8(msg,*i,0x01);
01559 filterbytes(TMR_TAG_PROTOCOL_GEN2,target, &option, i, msg,accessPassword,true);
01560 msg[rec]=msg[rec]|option;
01561 SETU8(msg,*i,0x00);
01562 SETU8(msg,*i,(uint8_t)readLock);
01563
01564 SETU8(msg,*i,bank);
01565 SETU32(msg,*i,blockPtr);
01566 SETU8(msg,*i,(uint8_t)blockRange);
01567 if (readLock==0x01)
01568 {
01569 SETU16(msg, *i, *mask);
01570 }
01571
01572 }
01573
01574 void
01575 TMR_SR_msgAddGEN2BlockErase(uint8_t *msg, uint8_t *i, uint16_t timeout,
01576 uint32_t wordPtr, TMR_GEN2_Bank bank, uint8_t wordCount,
01577 uint32_t accessPassword, TMR_TagFilter* target)
01578 {
01579 uint8_t option = 0, rec;
01580
01581 SETU8(msg, *i, TMR_SR_OPCODE_ERASE_BLOCK_TAG_SPECIFIC);
01582 SETU16(msg, *i, timeout);
01583 SETU8(msg, *i, 0x00);
01584
01585 rec = *i;
01586 SETU8(msg, *i, 0x40);
01587 SETU8(msg, *i, 0x00);
01588 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
01589 msg[rec] = msg[rec] | option;
01590
01591 SETU32(msg, *i, wordPtr);
01592 SETU8(msg, *i, bank);
01593 SETU8(msg,*i, wordCount);
01594 }
01595
01596 TMR_Status
01597 TMR_SR_cmdWriteGen2TagEpc(TMR_Reader *reader, const TMR_TagFilter *filter, TMR_GEN2_Password accessPassword,
01598 uint16_t timeout, uint8_t count, const uint8_t *id, bool lock)
01599 {
01600 TMR_Status ret;
01601 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
01602 uint8_t i, optbyte;
01603
01604 i = 2;
01605 SETU8(msg, i, TMR_SR_OPCODE_WRITE_TAG_ID);
01606 SETU16(msg, i, timeout);
01607 optbyte = i;
01608 SETU8(msg, i, 0);
01609
01610
01611 ret = filterbytes(TMR_TAG_PROTOCOL_GEN2, filter, &msg[optbyte], &i, msg,
01612 accessPassword, true);
01613 if (TMR_SUCCESS != ret)
01614 {
01615 return ret;
01616 }
01617
01618 if (0 == msg[optbyte])
01619 {
01620 SETU8(msg, i, 0);
01621 }
01622
01623 if (i + count + 1 > TMR_SR_MAX_PACKET_SIZE)
01624 {
01625 return TMR_ERROR_TOO_BIG;
01626 }
01627
01628 memcpy(&msg[i], id, count);
01629 i += count;
01630 msg[1] = i - 3;
01631
01632 return TMR_SR_sendTimeout(reader, msg, timeout);
01633 }
01634
01635
01636 TMR_Status
01637 TMR_SR_cmdClearTagBuffer(TMR_Reader *reader)
01638 {
01639 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
01640 uint8_t i;
01641
01642 i = 2;
01643 SETU8(msg, i, TMR_SR_OPCODE_CLEAR_TAG_ID_BUFFER);
01644 msg[1] = i - 3;
01645
01646 return TMR_SR_send(reader, msg);
01647 }
01648
01649 TMR_Status TMR_SR_cmdGetTagsRemaining(TMR_Reader *reader, uint16_t *tagCount)
01650 {
01651 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
01652 uint8_t i;
01653 TMR_Status ret;
01654
01655 i = 2;
01656 SETU8(msg, i, TMR_SR_OPCODE_GET_TAG_ID_BUFFER);
01657 msg[1] = i-3;
01658 ret = TMR_SR_send(reader, msg);
01659 if (TMR_SUCCESS != ret)
01660 {
01661 return ret;
01662 }
01663
01664 *tagCount = GETU16AT(msg, 7) - GETU16AT(msg, 5);
01665 return TMR_SUCCESS;
01666 }
01667
01668 void
01669 TMR_SR_parseMetadataFromMessage(TMR_Reader *reader, TMR_TagReadData *read, uint16_t flags,
01670 uint8_t *i, uint8_t msg[])
01671 {
01672 int msgEpcLen;
01673
01674 read->metadataFlags = flags;
01675 read->tag.protocol = TMR_TAG_PROTOCOL_NONE;
01676 read->readCount = 0;
01677 read->rssi = 0;
01678 read->antenna = 0;
01679 read->phase = 0;
01680 read->frequency = 0;
01681 read->dspMicros = 0;
01682 read->timestampLow = 0;
01683 read->timestampHigh = 0;
01684 read->isAsyncRead = false;
01685
01686 switch(reader->u.serialReader.versionInfo.hardware[0])
01687 {
01688 case TMR_SR_MODEL_M5E:
01689 read->gpioCount = 2;
01690 break;
01691 case TMR_SR_MODEL_M6E:
01692 read->gpioCount = 4;
01693 break;
01694 default:
01695 read->gpioCount = 4;
01696 break;
01697 }
01698
01699
01700
01701 if (flags & TMR_TRD_METADATA_FLAG_READCOUNT)
01702 {
01703 read->readCount = GETU8(msg, *i);
01704 }
01705 if (flags & TMR_TRD_METADATA_FLAG_RSSI)
01706 {
01707 read->rssi = (int8_t)GETU8(msg, *i);
01708 }
01709 if (flags & TMR_TRD_METADATA_FLAG_ANTENNAID)
01710 {
01711 read->antenna = GETU8(msg, *i);
01712 }
01713 if (flags & TMR_TRD_METADATA_FLAG_FREQUENCY)
01714 {
01715 read->frequency = GETU24(msg, *i);
01716 }
01717 if (flags & TMR_TRD_METADATA_FLAG_TIMESTAMP)
01718 {
01719 read->dspMicros = GETU32(msg, *i);
01720 }
01721 if (flags & TMR_TRD_METADATA_FLAG_PHASE)
01722 {
01723 read->phase = GETU16(msg, *i);
01724 }
01725 if (flags & TMR_TRD_METADATA_FLAG_PROTOCOL)
01726 {
01727 read->tag.protocol = (TMR_TagProtocol)GETU8(msg, *i);
01728 }
01729 if (flags & TMR_TRD_METADATA_FLAG_DATA)
01730 {
01731 int msgDataLen, copyLen;
01732
01733 msgDataLen = tm_u8s_per_bits(GETU16(msg, *i));
01734 read->data.len = msgDataLen;
01735 copyLen = msgDataLen;
01736 if (copyLen > read->data.max)
01737 {
01738 copyLen = read->data.max;
01739 }
01740 if (NULL != read->data.list)
01741 {
01742 memcpy(read->data.list, &msg[*i], copyLen);
01743 }
01744
01749 if (reader->u.serialReader.gen2AllMemoryBankEnabled)
01750 {
01751 uint16_t dataLength = read->data.len;
01752 uint8_t readOffSet = 0;
01753 uint8_t bank;
01754 uint16_t epcDataLength;
01755 while (dataLength != 0)
01756 {
01757 if (readOffSet == dataLength)
01758 break;
01759 bank = ((read->data.list[readOffSet] >> 4) & 0x1F);
01760 epcDataLength = (read->data.list[readOffSet + 1] * 2);
01761 switch (bank)
01762 {
01763 case TMR_GEN2_BANK_EPC:
01764 {
01765 read->epcMemData.len = epcDataLength;
01766 if (epcDataLength > read->epcMemData.max)
01767 {
01768 epcDataLength = read->epcMemData.max;
01769 }
01770 if (NULL != read->epcMemData.list)
01771 {
01772 memcpy(read->epcMemData.list, (read->data.list + readOffSet + 2), epcDataLength);
01773 }
01774 readOffSet += (epcDataLength + 2);
01775 break;
01776
01777 }
01778 case TMR_GEN2_BANK_RESERVED:
01779 {
01780 read->reservedMemData.len = epcDataLength;
01781 if (epcDataLength > read->epcMemData.max)
01782 {
01783 epcDataLength = read->reservedMemData.max;
01784 }
01785 if (NULL != read->reservedMemData.list)
01786 {
01787 memcpy(read->reservedMemData.list, (read->data.list + readOffSet + 2), epcDataLength);
01788 }
01789 readOffSet += (epcDataLength + 2);
01790 break;
01791
01792 }
01793 case TMR_GEN2_BANK_TID:
01794 {
01795 read->tidMemData.len = epcDataLength;
01796 if (epcDataLength > read->tidMemData.max)
01797 {
01798 epcDataLength = read->tidMemData.max;
01799 }
01800 if (NULL != read->tidMemData.list)
01801 {
01802 memcpy(read->tidMemData.list, (read->data.list + readOffSet + 2), epcDataLength);
01803 }
01804 readOffSet += (epcDataLength + 2);
01805 break;
01806
01807 }
01808 case TMR_GEN2_BANK_USER:
01809 {
01810 read->userMemData.len = epcDataLength;
01811 if (epcDataLength > read->userMemData.max)
01812 {
01813 epcDataLength = read->userMemData.max;
01814 }
01815 if (NULL != read->userMemData.list)
01816 {
01817 memcpy(read->userMemData.list, (read->data.list + readOffSet + 2), epcDataLength);
01818 }
01819 readOffSet += (epcDataLength + 2);
01820 break;
01821
01822 }
01823 default:
01824 break;
01825 }
01826 }
01827 }
01832 reader->u.serialReader.gen2AllMemoryBankEnabled = false;
01833
01834 *i += msgDataLen;
01835 }
01836 if (flags & TMR_TRD_METADATA_FLAG_GPIO_STATUS)
01837 {
01838 int j;
01839 uint8_t gpioByte=GETU8(msg, *i);
01840 for (j=0;j<read->gpioCount;j++)
01841 {
01842 read->gpio[j].id = j+1;
01843 read->gpio[j].high = (((gpioByte >> j)&0x1)== 1);
01844 }
01845 }
01846
01847 msgEpcLen = tm_u8s_per_bits(GETU16(msg, *i));
01848 if (TMR_TAG_PROTOCOL_ATA != read->tag.protocol)
01849 {
01850
01851 msgEpcLen -= 2;
01852 }
01853 if (TMR_TAG_PROTOCOL_GEN2 == read->tag.protocol)
01854 {
01855 read->tag.u.gen2.pc[0] = GETU8(msg, *i);
01856 read->tag.u.gen2.pc[1] = GETU8(msg, *i);
01857 msgEpcLen -= 2;
01858 read->tag.u.gen2.pcByteCount = 2;
01859
01860
01861
01862
01863 if ((read->tag.u.gen2.pc[0] & 0x02) == 0x02)
01864 {
01865
01866
01867
01868 read->tag.u.gen2.pc[2] = GETU8(msg, *i);
01869 read->tag.u.gen2.pc[3] = GETU8(msg, *i);
01870 msgEpcLen -= 2;
01871 read->tag.u.gen2.pcByteCount += 2;
01872
01873 if ((read->tag.u.gen2.pc[2] & 0x80) == 0x80)
01874 {
01875
01876
01877
01878
01879 read->tag.u.gen2.pc[4] = GETU8(msg, *i);
01880 read->tag.u.gen2.pc[5] = GETU8(msg, *i);
01881 msgEpcLen -= 2;
01882 read->tag.u.gen2.pcByteCount += 2;
01883 }
01884 }
01885 }
01886 read->tag.epcByteCount = msgEpcLen;
01887 if (read->tag.epcByteCount > TMR_MAX_EPC_BYTE_COUNT)
01888 {
01889 read->tag.epcByteCount = TMR_MAX_EPC_BYTE_COUNT;
01890 }
01891
01892 memcpy(read->tag.epc, &msg[*i], read->tag.epcByteCount);
01893 *i += msgEpcLen;
01894 if (TMR_TAG_PROTOCOL_ATA != read->tag.protocol)
01895 {
01896 read->tag.crc = GETU16(msg, *i);
01897 }
01898 else
01899 {
01900 read->tag.crc = 0xffff;
01901 }
01902
01903 if(reader->continuousReading)
01904 {
01905 read->isAsyncRead = true;
01906 }
01907 else
01908 {
01909 read->isAsyncRead = false;
01910 }
01911
01912 }
01913
01914 void
01915 TMR_SR_parseMetadataOnly(TMR_Reader *reader, TMR_TagReadData *read, uint16_t flags,
01916 uint8_t *i, uint8_t msg[])
01917 {
01918 read->metadataFlags = flags;
01919 read->tag.protocol = TMR_TAG_PROTOCOL_NONE;
01920 read->readCount = 0;
01921 read->rssi = 0;
01922 read->antenna = 0;
01923 read->phase = 0;
01924 read->frequency = 0;
01925 read->dspMicros = 0;
01926 read->timestampLow = 0;
01927 read->timestampHigh = 0;
01928 read->isAsyncRead = false;
01929
01930 switch(reader->u.serialReader.versionInfo.hardware[0])
01931 {
01932 case TMR_SR_MODEL_M5E:
01933 read->gpioCount = 2;
01934 break;
01935 case TMR_SR_MODEL_M6E:
01936 read->gpioCount = 4;
01937 break;
01938 default:
01939 read->gpioCount = 4;
01940 break;
01941 }
01942
01943
01944 if (flags & TMR_TRD_METADATA_FLAG_READCOUNT)
01945 {
01946 read->readCount = GETU8(msg, *i);
01947 }
01948 if (flags & TMR_TRD_METADATA_FLAG_RSSI)
01949 {
01950 read->rssi = GETU8(msg, *i);
01951 }
01952 if (flags & TMR_TRD_METADATA_FLAG_ANTENNAID)
01953 {
01954 read->antenna = GETU8(msg, *i);
01955 }
01956 if (flags & TMR_TRD_METADATA_FLAG_FREQUENCY)
01957 {
01958 read->frequency = GETU24(msg, *i);
01959 }
01960 if (flags & TMR_TRD_METADATA_FLAG_TIMESTAMP)
01961 {
01962 read->dspMicros = GETU32(msg, *i);
01963 }
01964 if (flags & TMR_TRD_METADATA_FLAG_PHASE)
01965 {
01966 read->phase = GETU16(msg, *i);
01967 }
01968 if (flags & TMR_TRD_METADATA_FLAG_PROTOCOL)
01969 {
01970 read->tag.protocol = (TMR_TagProtocol)GETU8(msg, *i);
01971 }
01972 if (flags & TMR_TRD_METADATA_FLAG_DATA)
01973 {
01974 int msgDataLen, copyLen;
01975
01976 msgDataLen = tm_u8s_per_bits(GETU16(msg, *i));
01977 read->data.len = msgDataLen;
01978 copyLen = msgDataLen;
01979 if (copyLen > read->data.max)
01980 {
01981 copyLen = read->data.max;
01982 }
01983 memcpy(read->data.list, &msg[*i], copyLen);
01984 *i += msgDataLen;
01985 }
01986 if (flags & TMR_TRD_METADATA_FLAG_GPIO_STATUS)
01987 {
01988 int j;
01989 uint8_t gpioByte=GETU8(msg, *i);
01990 for (j=0;j<read->gpioCount ;j++)
01991 {
01992 read->gpio[j].id = j+1;
01993 read->gpio[j].high = (((gpioByte >> j)&0x1)== 1);
01994 }
01995 }
01996 }
01997
01998 void
01999 TMR_SR_postprocessReaderSpecificMetadata(TMR_TagReadData *read, TMR_SR_SerialReader *sr)
02000 {
02001 uint16_t j;
02002 uint32_t timestampLow;
02003 uint64_t currTime64, lastSentTagTime64;
02004 int32_t tempDiff;
02005
02006 timestampLow = sr->readTimeLow;
02007 read->timestampHigh = sr->readTimeHigh;
02008
02009 timestampLow = timestampLow + read->dspMicros;
02010 currTime64 = ((uint64_t)read->timestampHigh << 32) | timestampLow;
02011 lastSentTagTime64 = ((uint64_t)sr->lastSentTagTimestampHigh << 32) | sr->lastSentTagTimestampLow;
02012 if (lastSentTagTime64 >= currTime64)
02013 {
02014 tempDiff = (int32_t)(currTime64 - lastSentTagTime64);
02015 timestampLow = timestampLow - tempDiff + 1;
02016 if (timestampLow < sr->lastSentTagTimestampLow)
02017 {
02018 read->timestampHigh++;
02019 }
02020 }
02021 if (timestampLow < sr->readTimeLow)
02022 {
02023 read->timestampHigh++;
02024 }
02025 read->timestampLow = timestampLow;
02026 sr->lastSentTagTimestampHigh = read->timestampHigh;
02027 sr->lastSentTagTimestampLow = read->timestampLow;
02028
02029 {
02030 uint8_t tx;
02031 uint8_t rx;
02032 tx = (read->antenna >> 4) & 0xF;
02033 rx = (read->antenna >> 0) & 0xF;
02034
02035
02036 if (0 == tx) { tx = 16; }
02037 if (0 == rx) { rx = 16; }
02038
02039 for (j = 0; j < sr->txRxMap->len; j++)
02040 {
02041 if (rx == sr->txRxMap->list[j].rxPort &&
02042 tx == sr->txRxMap->list[j].txPort)
02043 {
02044 read->antenna = sr->txRxMap->list[j].antenna;
02045 if (read->gpioCount > 2)
02046 {
02047 if (read->gpio[2].high)
02048 read->antenna += 16;
02049 }
02050 break;
02051 }
02052 }
02053 }
02054 }
02055
02056 #ifdef TMR_ENABLE_ISO180006B
02057 TMR_Status
02058 TMR_SR_cmdISO180006BReadTagData(TMR_Reader *reader,
02059 uint16_t timeout, uint8_t address,
02060 uint8_t length, const TMR_TagFilter *filter,
02061 TMR_TagReadData *read)
02062 {
02063 TMR_Status ret;
02064 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02065 uint8_t copylen, i;
02066
02067 if (length > 8
02068 || filter == NULL
02069 || TMR_FILTER_TYPE_TAG_DATA != filter->type
02070 || filter->u.tagData.epcByteCount != 8)
02071 {
02072 return TMR_ERROR_INVALID;
02073 }
02074
02075 i = 2;
02076 SETU8(msg, i, TMR_SR_OPCODE_READ_TAG_DATA);
02077 SETU16(msg, i, timeout);
02078 SETU8(msg, i, 0x01);
02079 SETU8(msg, i, TMR_SR_ISO180006B_COMMAND_READ);
02080 SETU8(msg, i, 0x00);
02081 SETU8(msg, i, length);
02082 SETU8(msg, i, address);
02083 memcpy(&msg[i], filter->u.tagData.epc, 8);
02084 i += 8;
02085 msg[1] = i - 3;
02086
02087 ret = TMR_SR_sendTimeout(reader, msg, timeout);
02088 if (TMR_SUCCESS != ret)
02089 {
02090 return ret;
02091 }
02092
02093 read->metadataFlags = TMR_TRD_METADATA_FLAG_DATA;
02094 read->tag.protocol = TMR_TAG_PROTOCOL_ISO180006B;
02095 read->tag.epcByteCount = 0;
02096
02097 read->data.len = msg[1];
02098 copylen = (uint8_t)read->data.len;
02099 if (copylen > read->data.max)
02100 {
02101 copylen = (uint8_t)read->data.max;
02102 }
02103 if (NULL != read->data.list)
02104 {
02105 memcpy(read->data.list, &msg[5], copylen);
02106 }
02107
02108 return TMR_SUCCESS;
02109 }
02110
02111 TMR_Status
02112 TMR_SR_cmdISO180006BWriteTagData(TMR_Reader *reader,
02113 uint16_t timeout, uint8_t address,
02114 uint8_t count, const uint8_t data[],
02115 const TMR_TagFilter *filter)
02116 {
02117 TMR_Status ret;
02118 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02119 uint8_t i;
02120
02121 i = 2;
02122
02123 SETU8(msg, i, TMR_SR_OPCODE_WRITE_TAG_DATA);
02124 SETU16(msg, i, timeout);
02125 if (NULL != filter
02126 && TMR_FILTER_TYPE_TAG_DATA == filter->type
02127 && filter->u.tagData.epcByteCount == 8)
02128 {
02129 SETU8(msg, i,
02130 TMR_SR_ISO180006B_WRITE_OPTION_READ_VERIFY_AFTER
02131 | TMR_SR_ISO180006B_WRITE_OPTION_COUNT_PROVIDED);
02132 SETU8(msg, i, TMR_SR_ISO180006B_COMMAND_WRITE4BYTE);
02133 SETU8(msg, i, TMR_SR_ISO180006B_WRITE_LOCK_NO);
02134 SETU8(msg, i, address);
02135 memcpy(&msg[i], filter->u.tagData.epc, 8);
02136 i += 8;
02137 }
02138 else
02139 {
02140 SETU8(msg, i, TMR_SR_ISO180006B_WRITE_OPTION_GROUP_SELECT
02141 | TMR_SR_ISO180006B_WRITE_OPTION_COUNT_PROVIDED);
02142 SETU8(msg, i, TMR_SR_ISO180006B_COMMAND_WRITE4BYTE_MULTIPLE);
02143 SETU8(msg, i, TMR_SR_ISO180006B_WRITE_LOCK_NO);
02144 SETU8(msg, i, address);
02145
02146
02147
02148
02149 ret = filterbytes(TMR_TAG_PROTOCOL_ISO180006B, filter, NULL,
02150 &i, msg, 1, false);
02151 if (TMR_SUCCESS != ret)
02152 {
02153 return ret;
02154 }
02155 }
02156 SETU16(msg, i, count);
02157 memcpy(&msg[i], data, count);
02158 i += count;
02159 msg[1] = i - 3;
02160
02161 return TMR_SR_sendTimeout(reader, msg, timeout);
02162
02163 }
02164
02165
02166 TMR_Status
02167 TMR_SR_cmdISO180006BLockTag(TMR_Reader *reader, uint16_t timeout,
02168 uint8_t address, const TMR_TagFilter *filter)
02169 {
02170 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02171 uint8_t i;
02172
02173 if (filter == NULL
02174 || TMR_FILTER_TYPE_TAG_DATA != filter->type
02175 || filter->u.tagData.epcByteCount != 8)
02176 {
02177 return TMR_ERROR_INVALID;
02178 }
02179
02180 i = 2;
02181 SETU8(msg, i, TMR_SR_OPCODE_LOCK_TAG);
02182 SETU16(msg, i, timeout);
02183 SETU8(msg, i, TMR_SR_ISO180006B_LOCK_OPTION_TYPE_FOLLOWS);
02184 SETU8(msg, i, TMR_SR_ISO180006B_LOCK_TYPE_QUERYLOCK_THEN_LOCK);
02185 SETU8(msg, i, address);
02186 memcpy(&msg[i], filter->u.tagData.epc, 8);
02187 i += 8;
02188 msg[1] = i - 3;
02189
02190 return TMR_SR_sendTimeout(reader, msg, timeout);
02191 }
02192 #endif
02193
02194 TMR_Status
02195 TMR_SR_cmdGEN2WriteTagData(TMR_Reader *reader,
02196 uint16_t timeout, TMR_GEN2_Bank bank,
02197 uint32_t address, uint8_t count,
02198 const uint8_t data[],
02199 TMR_GEN2_Password accessPassword,
02200 const TMR_TagFilter *filter)
02201 {
02202 TMR_Status ret;
02203 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02204 uint8_t optbyte, i;
02205
02206 i = 2;
02207 TMR_SR_msgAddGEN2DataWrite(msg, &i, timeout, bank, address);
02208 optbyte = 5;
02209 ret = filterbytes(TMR_TAG_PROTOCOL_GEN2, filter, &msg[optbyte], &i, msg,
02210 accessPassword, true);
02211 if (TMR_SUCCESS != ret)
02212 {
02213 return ret;
02214 }
02215 if (i + count + 1 > TMR_SR_MAX_PACKET_SIZE)
02216 {
02217 return TMR_ERROR_TOO_BIG;
02218 }
02219 memcpy(&msg[i], data, count);
02220 i += count;
02221 msg[1] = i - 3;
02222
02223 return TMR_SR_sendTimeout(reader, msg, timeout);
02224 }
02225
02226 TMR_Status
02227 TMR_SR_cmdGEN2LockTag(TMR_Reader *reader, uint16_t timeout,
02228 uint16_t mask, uint16_t action,
02229 TMR_GEN2_Password accessPassword,
02230 const TMR_TagFilter *filter)
02231 {
02232 TMR_Status ret;
02233 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02234 uint8_t optbyte, i;
02235
02236 i = 2;
02237 TMR_SR_msgAddGEN2LockTag(msg, &i, timeout, mask, action, accessPassword);
02238 optbyte = 5;
02239 ret = filterbytes(TMR_TAG_PROTOCOL_GEN2, filter, &msg[optbyte], &i, msg,
02240 0, false);
02241 if (TMR_SUCCESS != ret)
02242 {
02243 return ret;
02244 }
02245 msg[1] = i - 3;
02246
02247 return TMR_SR_sendTimeout(reader, msg, timeout);
02248 }
02249
02250 TMR_Status
02251 TMR_SR_cmdrebootReader(TMR_Reader *reader)
02252 {
02253 TMR_Status ret;
02254 TMR_SR_SerialReader *sr;
02255 TMR_SR_SerialTransport *transport;
02256
02257 sr = &reader->u.serialReader;
02258 transport = &sr->transport;
02259
02260
02261
02262
02263
02264
02265 if (NULL != transport->setBaudRate)
02266 {
02273 ret = TMR_SR_cmdSetBaudRate(reader, 9600);
02274 if (TMR_SUCCESS != ret)
02275 {
02276 return ret;
02277 }
02278 ret = transport->setBaudRate(transport, 9600);
02279 if (TMR_SUCCESS != ret)
02280 {
02281 return ret;
02282 }
02283 }
02284 ret = TMR_SR_cmdBootBootloader(reader);
02285 if ((TMR_SUCCESS != ret)
02286
02287 && (TMR_ERROR_INVALID_OPCODE != ret))
02288 {
02289 return ret;
02290 }
02291
02292
02293
02294
02295 tmr_sleep(200);
02296
02297 return ret;
02298 }
02299
02300 TMR_Status
02301 TMR_SR_cmdKillTag(TMR_Reader *reader, uint16_t timeout,
02302 TMR_GEN2_Password killPassword,
02303 const TMR_TagFilter *filter)
02304 {
02305 TMR_Status ret;
02306 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02307 uint8_t optbyte, i;
02308
02309 i = 2;
02310 TMR_SR_msgAddGEN2KillTag(msg, &i, timeout, killPassword);
02311 optbyte = 5;
02312 ret = filterbytes(TMR_TAG_PROTOCOL_GEN2, filter, &msg[optbyte], &i, msg,
02313 0, false);
02314 if (TMR_SUCCESS != ret)
02315 {
02316 return ret;
02317 }
02318 msg[1] = i - 3;
02319
02320 return TMR_SR_sendTimeout(reader, msg, timeout);
02321 }
02322
02323
02324 TMR_Status
02325 TMR_SR_cmdGEN2ReadTagData(TMR_Reader *reader,
02326 uint16_t timeout, TMR_GEN2_Bank bank,
02327 uint32_t address, uint8_t length,
02328 uint32_t accessPassword, const TMR_TagFilter *filter,
02329 TMR_TagReadData *read)
02330 {
02331 TMR_Status ret;
02332 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02333 uint8_t optbyte, i, mdfbyte;
02334 uint32_t starttimeHigh, starttimeLow;
02335
02336 i = 2;
02337 TMR_SR_msgAddGEN2DataRead(msg, &i, timeout, bank, address, length, 0x00, true);
02338 optbyte = 5;
02339 ret = filterbytes(TMR_TAG_PROTOCOL_GEN2, filter, &msg[optbyte], &i, msg,
02340 accessPassword, true);
02341
02342
02343 msg[optbyte] |= 0x10;
02344 mdfbyte = 6;
02345 read->metadataFlags |= TMR_TRD_METADATA_FLAG_DATA | TMR_TRD_METADATA_FLAG_PROTOCOL;
02346 SETU16(msg, mdfbyte, read->metadataFlags);
02347
02348
02349 if (TMR_SUCCESS != ret)
02350 {
02351 return ret;
02352 }
02353 msg[1] = i - 3;
02354
02355
02356 tm_gettime_consistent(&starttimeHigh, &starttimeLow);
02357 reader->u.serialReader.readTimeHigh = starttimeHigh;
02358 reader->u.serialReader.readTimeLow = starttimeLow;
02359
02360 ret = TMR_SR_sendTimeout(reader, msg, timeout);
02361 if (TMR_SUCCESS != ret)
02362 {
02363 return ret;
02364 }
02365
02366 if (NULL != read->data.list)
02367 {
02368 i = 8;
02369
02370 TMR_SR_parseMetadataOnly(reader, read, read->metadataFlags , &i, msg);
02371 TMR_SR_postprocessReaderSpecificMetadata(read, &reader->u.serialReader);
02372
02373
02374
02375 {
02376 uint16_t dataLength;
02377 uint16_t copyLength;
02378
02379 copyLength = dataLength = msg[1] + 5 - i;
02380 if (copyLength > read->data.max)
02381 {
02382 copyLength = read->data.max;
02383 }
02384 read->data.len = copyLength;
02385 memcpy(read->data.list, &msg[i], copyLength);
02386 i += dataLength;
02387 }
02388 }
02389
02390 return TMR_SUCCESS;
02391 }
02392
02393 TMR_Status
02394 TMR_SR_cmdSetTxRxPorts(TMR_Reader *reader, uint8_t txPort, uint8_t rxPort)
02395 {
02396 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02397 uint8_t i;
02398
02399 i = 2;
02400 SETU8(msg, i, TMR_SR_OPCODE_SET_ANTENNA_PORT);
02401 SETU8(msg, i, txPort);
02402 SETU8(msg, i, rxPort);
02403 msg[1] = i - 3;
02404
02405 return TMR_SR_send(reader, msg);
02406 }
02407
02408
02409 TMR_Status
02410 TMR_SR_cmdSetAntennaSearchList(TMR_Reader *reader, uint8_t count,
02411 const TMR_SR_PortPair *ports)
02412 {
02413 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02414 uint8_t i;
02415 uint8_t j;
02416
02417 i = 2;
02418 SETU8(msg, i, TMR_SR_OPCODE_SET_ANTENNA_PORT);
02419 SETU8(msg, i, 2);
02420 for (j = 0; j < count ; j++)
02421 {
02422 SETU8(msg, i, ports[j].txPort);
02423 SETU8(msg, i, ports[j].rxPort);
02424 }
02425 msg[1] = i - 3;
02426
02427 return TMR_SR_send(reader, msg);
02428 }
02429
02430 TMR_Status
02431 TMR_SR_cmdSetAntennaPortPowersAndSettlingTime(
02432 TMR_Reader *reader, uint8_t count, const TMR_SR_PortPowerAndSettlingTime *ports)
02433 {
02434 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02435 uint8_t j, i;
02436
02437 i = 2;
02438 SETU8(msg, i, TMR_SR_OPCODE_SET_ANTENNA_PORT);
02439 SETU8(msg, i, 4);
02440
02441 for (j = 0; j < count; j++)
02442 {
02443 SETU8(msg, i, ports[j].port);
02444 SETS16(msg, i, (int16_t) ports[j].readPower);
02445 SETS16(msg, i, (int16_t)ports[j].writePower);
02446 SETU16(msg, i, ports[j].settlingTime);
02447 }
02448 msg[1] = i - 3;
02449
02450 return TMR_SR_send(reader, msg);
02451 }
02452
02453
02454 TMR_Status
02455 TMR_SR_cmdSetReadTxPower(TMR_Reader *reader, int32_t power)
02456 {
02457 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02458 uint8_t i;
02459
02460 i = 2;
02461 SETU8(msg, i, TMR_SR_OPCODE_SET_READ_TX_POWER);
02462
02464 if (power > 32767 || power < -32768)
02465 {
02466 return TMR_ERROR_ILLEGAL_VALUE;
02467 }
02468
02469 SETS16(msg,i, (int16_t)power);
02470 msg[1] = i - 3;
02471
02472 return TMR_SR_send(reader, msg);
02473 }
02474
02475
02476 TMR_Status
02477 TMR_SR_cmdSetProtocol(TMR_Reader *reader, TMR_TagProtocol protocol)
02478 {
02479 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02480 uint8_t i;
02481
02482 i = 2;
02483 SETU8(msg, i, TMR_SR_OPCODE_SET_TAG_PROTOCOL);
02484 SETU16(msg, i, protocol);
02485 msg[1] = i - 3;
02486
02487 return TMR_SR_send(reader, msg);
02488 }
02489
02490
02491 TMR_Status
02492 TMR_SR_cmdSetWriteTxPower(TMR_Reader *reader, int32_t power)
02493 {
02494 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02495 uint8_t i;
02496
02497 i = 2;
02498 SETU8(msg, i, TMR_SR_OPCODE_SET_WRITE_TX_POWER);
02499
02501 if (power > 32767 || power < -32768)
02502 {
02503 return TMR_ERROR_ILLEGAL_VALUE;
02504 }
02505
02506 SETS16(msg, i, (int16_t)power);
02507 msg[1] = i - 3;
02508
02509 return TMR_SR_send(reader, msg);
02510 }
02511
02512
02513 TMR_Status
02514 TMR_SR_cmdSetFrequencyHopTable(TMR_Reader *reader, uint8_t count,
02515 const uint32_t *table)
02516 {
02517 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02518 uint8_t i, j;
02519
02520 i = 2;
02521
02522 if (count > 62)
02523 {
02524 return TMR_ERROR_TOO_BIG;
02525 }
02526
02527 SETU8(msg, i, TMR_SR_OPCODE_SET_FREQ_HOP_TABLE);
02528 for (j = 0; j < count; j++)
02529 {
02530 SETU32(msg, i, table[j]);
02531 }
02532 msg[1] = i - 3;
02533
02534 return TMR_SR_send(reader, msg);
02535 }
02536
02537
02538 TMR_Status
02539 TMR_SR_cmdSetFrequencyHopTime(TMR_Reader *reader, uint32_t hopTime)
02540 {
02541 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02542 uint8_t i;
02543
02544 i = 2;
02545 SETU8(msg, i, TMR_SR_OPCODE_SET_FREQ_HOP_TABLE);
02546 SETU8(msg, i, 1);
02547 SETU32(msg, i, hopTime);
02548 msg[1] = i - 3;
02549
02550 return TMR_SR_send(reader, msg);
02551 }
02552
02553
02554 TMR_Status
02555 TMR_SR_cmdSetGPIO(TMR_Reader *reader, uint8_t gpio, bool high)
02556 {
02557 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02558 uint8_t i;
02559
02560 i = 2;
02561 SETU8(msg, i, TMR_SR_OPCODE_SET_USER_GPIO_OUTPUTS);
02562 SETU8(msg, i, gpio);
02563 SETU8(msg, i, (high == true));
02564 msg[1] = i - 3;
02565
02566 return TMR_SR_send(reader, msg);
02567 }
02568
02569
02570 TMR_Status
02571 TMR_SR_cmdSetRegion(TMR_Reader *reader, TMR_Region region)
02572 {
02573 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02574 uint8_t i;
02575
02576 i = 2;
02577 SETU8(msg, i, TMR_SR_OPCODE_SET_REGION);
02578 SETU8(msg, i, region);
02579 msg[1] = i - 3;
02580
02581 return TMR_SR_send(reader, msg);
02582 }
02583
02584
02585 TMR_Status
02586 TMR_SR_cmdSetRegionLbt(TMR_Reader *reader, TMR_Region region, bool lbt)
02587 {
02588 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02589 uint8_t i;
02590
02591 i = 2;
02592 SETU8(msg, i, TMR_SR_OPCODE_SET_REGION);
02593 SETU8(msg, i, region);
02594 SETU8(msg, i, lbt ? 1 : 0);
02595 msg[1] = i - 3;
02596
02597 return TMR_SR_send(reader, msg);
02598 }
02599
02600
02601 TMR_Status
02602 TMR_SR_cmdSetPowerMode(TMR_Reader *reader, TMR_SR_PowerMode mode)
02603 {
02604 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02605 uint8_t i;
02606
02607 i = 2;
02608 SETU8(msg, i, TMR_SR_OPCODE_SET_POWER_MODE);
02609 SETU8(msg, i, mode);
02610 msg[1] = i - 3;
02611
02612 return TMR_SR_send(reader, msg);
02613 }
02614
02615
02616 TMR_Status
02617 TMR_SR_cmdSetUserMode(TMR_Reader *reader, TMR_SR_UserMode mode)
02618 {
02619 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02620 uint8_t i;
02621
02622 i = 2;
02623 SETU8(msg, i, TMR_SR_OPCODE_SET_USER_MODE);
02624 SETU8(msg, i, mode);
02625 msg[1] = i - 3;
02626
02627 return TMR_SR_send(reader, msg);
02628 }
02629
02630
02631 TMR_Status
02632 TMR_SR_cmdSetReaderConfiguration(TMR_Reader *reader, TMR_SR_Configuration key,
02633 const void *value)
02634 {
02635 TMR_SR_SerialReader *sr = &reader->u.serialReader;
02636 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02637 uint8_t i;
02638
02639 i = 2;
02640 SETU8(msg, i, TMR_SR_OPCODE_SET_READER_OPTIONAL_PARAMS);
02641 SETU8(msg, i, 1);
02642 SETU8(msg, i, key);
02643
02644 switch (key)
02645 {
02646 case TMR_SR_CONFIGURATION_ANTENNA_CONTROL_GPIO:
02647 SETU8(msg, i, *(uint8_t *)value);
02648 break;
02649 case TMR_SR_CONFIGURATION_TRIGGER_READ_GPIO:
02650 SETU8(msg, i, *(uint8_t *)value);
02651 break;
02652
02653
02654 case TMR_SR_CONFIGURATION_UNIQUE_BY_ANTENNA:
02655 case TMR_SR_CONFIGURATION_UNIQUE_BY_DATA:
02656 case TMR_SR_CONFIGURATION_UNIQUE_BY_PROTOCOL:
02657 SETU8(msg, i, *(bool *)value ? 0 : 1);
02658 break;
02659 case TMR_SR_CONFIGURATION_TRANSMIT_POWER_SAVE:
02660 if(TMR_SR_MODEL_MICRO == sr->versionInfo.hardware[0])
02661 {
02662
02663 SETU8(msg, i, *(bool *)value ? 2 : 1);
02664 }
02665 else
02666 {
02667
02668 SETU8(msg, i, *(bool *)value ? 1 : 0);
02669 }
02670 break;
02671 case TMR_SR_CONFIGURATION_EXTENDED_EPC:
02672 case TMR_SR_CONFIGURATION_SAFETY_ANTENNA_CHECK:
02673 case TMR_SR_CONFIGURATION_SAFETY_TEMPERATURE_CHECK:
02674 case TMR_SR_CONFIGURATION_RECORD_HIGHEST_RSSI:
02675 case TMR_SR_CONFIGURATION_RSSI_IN_DBM:
02676 case TMR_SR_CONFIGURATION_SELF_JAMMER_CANCELLATION:
02677 case TMR_SR_CONFIGURATION_ENABLE_READ_FILTER:
02678 case TMR_SR_CONFIGURATION_SEND_CRC:
02679 SETU8(msg, i, *(bool *)value ? 1 : 0);
02680 break;
02681
02682 case TMR_SR_CONFIGURATION_READ_FILTER_TIMEOUT:
02683 SETS32(msg, i, *(int32_t *)value);
02684 break;
02685
02686 default:
02687 return TMR_ERROR_NOT_FOUND;
02688 }
02689 msg[1] = i - 3;
02690
02691 return TMR_SR_send(reader, msg);
02692 }
02693
02705 TMR_Status TMR_SR_cmdSetProtocolLicenseKey(TMR_Reader *reader,
02706 TMR_SR_SetProtocolLicenseOption option,
02707 uint8_t key[], int key_len,uint32_t *retData)
02708 {
02709 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02710 uint8_t i;
02711 TMR_Status ret;
02712 i = 2;
02713 SETU8(msg, i, TMR_SR_OPCODE_SET_PROTOCOL_LICENSEKEY);
02714 SETU8(msg, i, option);
02715
02716 if(TMR_SR_SET_LICENSE_KEY == option)
02717 {
02718 memcpy(msg+i, key, key_len);
02719 i+= key_len;
02720 }
02721
02722 msg[1] = i - 3;
02723
02724 ret = TMR_SR_send(reader, msg);
02725 if (ret != TMR_SUCCESS)
02726 {
02727 return ret;
02728 }
02729
02730 reader->u.serialReader.versionInfo.protocols = 0x00;
02731 for (i = 0; i < msg[1] - 2 ; i += 2)
02732 {
02733 reader->u.serialReader.versionInfo.protocols |= (1 << (GETU8AT(msg, 7 + i) - 1));
02734 }
02735
02736 return TMR_SUCCESS;
02737 }
02738
02739 TMR_Status
02740 TMR_SR_cmdSetProtocolConfiguration(TMR_Reader *reader, TMR_TagProtocol protocol,
02741 TMR_SR_ProtocolConfiguration key,
02742 const void *value)
02743 {
02744 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02745 uint8_t i;
02746 uint8_t BLF = 0;
02747
02748 i = 2;
02749 SETU8(msg, i, TMR_SR_OPCODE_SET_PROTOCOL_PARAM);
02750 SETU8(msg, i, protocol);
02751 if (TMR_TAG_PROTOCOL_GEN2 == key.protocol)
02752 {
02753 SETU8(msg, i, key.u.gen2);
02754 switch (key.u.gen2)
02755 {
02756 case TMR_SR_GEN2_CONFIGURATION_SESSION:
02757 SETU8(msg, i, *(TMR_GEN2_Session *)value);
02758 break;
02759
02760 case TMR_SR_GEN2_CONFIGURATION_TAGENCODING:
02761 SETU8(msg, i, *(TMR_GEN2_TagEncoding *)value);
02762 break;
02763
02764 case TMR_SR_GEN2_CONFIGURATION_LINKFREQUENCY:
02765 #ifndef BARE_METAL
02766 switch (*(int *)value)
02767 #else
02768 switch (*(TMR_GEN2_LinkFrequency *)value)
02769 #endif
02770 {
02771 case 40:
02772 BLF = 0x03;
02773 break;
02774 case 250:
02775 BLF = 0x00;
02776 break;
02777 case 320:
02778 BLF = 0x02;
02779 break;
02780 case 400:
02781 BLF = 0x02;
02782 break;
02783 case 640:
02784 BLF = 0x04;
02785 break;
02786 default:
02787 return TMR_ERROR_INVALID;
02788 }
02789 SETU8(msg, i, BLF);
02790 break;
02791
02792 case TMR_SR_GEN2_CONFIGURATION_TARI:
02793 SETU8(msg, i, *(TMR_GEN2_Tari *)value);
02794 break;
02795
02796 case TMR_SR_GEN2_CONFIGURATION_PROTCOLEXTENSION:
02797 SETU8(msg, i, *(TMR_GEN2_ProtocolExtension *)value);
02798 break;
02799
02800 case TMR_SR_GEN2_CONFIGURATION_TARGET:
02801 switch (*(TMR_GEN2_Target *)value)
02802 {
02803 case TMR_GEN2_TARGET_A:
02804 SETU16(msg, i, 0x0100);
02805 break;
02806 case TMR_GEN2_TARGET_B:
02807 SETU16(msg, i, 0x0101);
02808 break;
02809 case TMR_GEN2_TARGET_AB:
02810 SETU16(msg, i, 0x0000);
02811 break;
02812 case TMR_GEN2_TARGET_BA:
02813 SETU16(msg, i, 0x0001);
02814 break;
02815 default:
02816 return TMR_ERROR_INVALID;
02817 }
02818 break;
02819
02820 case TMR_SR_GEN2_CONFIGURATION_Q:
02821 {
02822 const TMR_SR_GEN2_Q *q = value;
02823 if (q->type == TMR_SR_GEN2_Q_DYNAMIC)
02824 {
02825 SETU8(msg, i, 0);
02826 }
02827 else if (q->type == TMR_SR_GEN2_Q_STATIC)
02828 {
02829 SETU8(msg, i, 1);
02830 SETU8(msg, i, q->u.staticQ.initialQ);
02831 }
02832 else
02833 {
02834 return TMR_ERROR_INVALID;
02835 }
02836 break;
02837 }
02838
02839 case TMR_SR_GEN2_CONFIGURATION_BAP:
02840 {
02841 TMR_GEN2_Bap *bap;
02842 bap = (TMR_GEN2_Bap *)value;
02843
02844 SETU8(msg, i, 0x01);
02845 SETU16(msg, i, 0x03);
02846 SETU32(msg, i, bap->powerUpDelayUs);
02847 SETU32(msg, i, bap->freqHopOfftimeUs);
02852 break;
02853 }
02854
02855 default:
02856 return TMR_ERROR_NOT_FOUND;
02857 }
02858 }
02859 #ifdef TMR_ENABLE_ISO180006B
02860 else if (TMR_TAG_PROTOCOL_ISO180006B == key.protocol
02861 || TMR_TAG_PROTOCOL_ISO180006B_UCODE == key.protocol)
02862 {
02863 switch (key.u.iso180006b)
02864 {
02865 case TMR_SR_ISO180006B_CONFIGURATION_LINKFREQUENCY:
02866 {
02867 switch (*(int *)value)
02868 {
02869 case 40:
02870 BLF = 0x01;
02871 break;
02872 case 160:
02873 BLF = 0x00;
02874 break;
02875 default:
02876 return TMR_ERROR_INVALID;
02877 }
02878 break;
02879 }
02880 case TMR_SR_ISO180006B_CONFIGURATION_MODULATION_DEPTH:
02881 {
02882 switch (*(int *)value)
02883 {
02884 case 0:
02885 BLF = TMR_ISO180006B_Modulation99percent;
02886 break;
02887 case 1:
02888 BLF = TMR_ISO180006B_Modulation11percent;
02889 break;
02890 default:
02891 return TMR_ERROR_INVALID;
02892 }
02893 break;
02894 }
02895 case TMR_SR_ISO180006B_CONFIGURATION_DELIMITER:
02896 {
02897 switch (*(int *)value)
02898 {
02899 case 1:
02900 BLF = TMR_ISO180006B_Delimiter1;
02901 break;
02902 case 4:
02903 BLF = TMR_ISO180006B_Delimiter4;
02904 break;
02905 default:
02906 return TMR_ERROR_INVALID;
02907 }
02908 break;
02909 }
02910 default:
02911 return TMR_ERROR_NOT_FOUND;
02912 }
02913
02914 SETU8(msg, i, key.u.iso180006b);
02915 SETU8(msg, i, BLF);
02916 }
02917 #endif
02918 else
02919 {
02920 return TMR_ERROR_INVALID;
02921 }
02922
02923 msg[1] = i - 3;
02924 return TMR_SR_send(reader, msg);
02925 }
02926
02927
02928 TMR_Status TMR_SR_cmdGetTxRxPorts(TMR_Reader *reader, TMR_SR_PortPair *ant)
02929 {
02930 TMR_Status ret;
02931 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02932 uint8_t i;
02933
02934 i = 2;
02935
02936 SETU8(msg, i, TMR_SR_OPCODE_GET_ANTENNA_PORT);
02937 SETU8(msg, i, 0);
02938 msg[1] = i - 3;
02939
02940 ret = TMR_SR_send(reader, msg);
02941 if (TMR_SUCCESS != ret)
02942 {
02943 return ret;
02944 }
02945
02946 ant->txPort = msg[5];
02947 ant->rxPort = msg[6];
02948
02949 return TMR_SUCCESS;
02950 }
02951
02952 TMR_Status
02953 TMR_SR_cmdAntennaDetect(TMR_Reader *reader, uint8_t *count,
02954 TMR_SR_PortDetect *ports)
02955 {
02956 TMR_Status ret;
02957 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02958 uint8_t i, j;
02959
02960 i = 2;
02961 SETU8(msg, i, TMR_SR_OPCODE_GET_ANTENNA_PORT);
02962 SETU8(msg, i, 5);
02963 msg[1] = i - 3;
02964
02965 ret = TMR_SR_send(reader, msg);
02966 if (TMR_SUCCESS != ret)
02967 {
02968 return ret;
02969 }
02970
02971
02972 for (i = 1, j = 0; i < msg[1] && j < *count; i += 2, j++)
02973 {
02974 ports[j].port = msg[i + 5];
02975 ports[j].detected = (msg[i + 6] == 1);
02976 }
02977 *count = j;
02978
02979 return TMR_SUCCESS;
02980 }
02981
02982
02983 TMR_Status
02984 TMR_SR_cmdGetAntennaPortPowersAndSettlingTime(
02985 TMR_Reader *reader, uint8_t *count, TMR_SR_PortPowerAndSettlingTime *ports)
02986 {
02987 TMR_Status ret;
02988 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
02989 uint8_t i, j;
02990
02991 i = 2;
02992 SETU8(msg, i, TMR_SR_OPCODE_GET_ANTENNA_PORT);
02993 SETU8(msg, i, 4);
02994 msg[1] = i - 3;
02995
02996 ret = TMR_SR_send(reader, msg);
02997 if (TMR_SUCCESS != ret)
02998 {
02999 return ret;
03000 }
03001
03002
03003 for (i = 1, j = 0; i < msg[1] && j < *count; i += 7, j++)
03004 {
03005 ports[j].port = GETU8AT(msg, i + 5);
03006 ports[j].readPower = (int16_t)GETS16AT(msg, i + 6);
03007 ports[j].writePower = (int16_t)GETS16AT(msg, i + 8);
03008 ports[j].settlingTime = GETU16AT(msg, i + 10);
03009 }
03010 *count = j;
03011
03012 return TMR_SUCCESS;
03013 }
03014
03015 TMR_Status
03016 TMR_SR_cmdGetAntennaReturnLoss(TMR_Reader *reader, TMR_PortValueList *ports)
03017 {
03018 TMR_Status ret;
03019 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03020 uint8_t i, j, count;
03021
03022 count = TMR_SR_MAX_ANTENNA_PORTS;
03023
03024 i = 2;
03025 SETU8(msg, i, TMR_SR_OPCODE_GET_ANTENNA_PORT);
03026 SETU8(msg, i, 6);
03027 msg[1] = i - 3;
03028
03029 ret = TMR_SR_send(reader, msg);
03030 if (TMR_SUCCESS != ret)
03031 {
03032 return ret;
03033 }
03034
03035 for (i = 1, j = 0; i < msg[1] && j < count; i += 2, j++)
03036 {
03037 if (j < ports->max)
03038 {
03039 ports->list[j].port = (uint8_t)GETU8AT(msg, i + 5);
03040 ports->list[j].value = (int16_t)GETU8AT(msg, i + 6);
03041 }
03042 else
03043 {
03044
03045 break;
03046 }
03047 }
03048 ports->len = (uint8_t)j;
03049
03050 return TMR_SUCCESS;
03051 }
03052
03053 TMR_Status
03054 TMR_SR_cmdGetReadTxPower(TMR_Reader *reader, int32_t *power)
03055 {
03056 TMR_Status ret;
03057 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03058 uint8_t i;
03059
03060 i = 2;
03061 SETU8(msg, i, TMR_SR_OPCODE_GET_READ_TX_POWER);
03062 SETU8(msg, i, 0);
03063 msg[1] = i - 3;
03064
03065 ret = TMR_SR_send(reader, msg);
03066 if (TMR_SUCCESS != ret)
03067 {
03068 return ret;
03069 }
03070
03071 *power = (int32_t)GETS16AT(msg, 6);
03072
03073 return TMR_SUCCESS;
03074 }
03075
03076
03077 TMR_Status
03078 TMR_SR_cmdGetReadTxPowerWithLimits(TMR_Reader *reader,
03079 TMR_SR_PowerWithLimits *power)
03080 {
03081 TMR_Status ret;
03082 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03083 uint8_t i;
03084
03085 i = 2;
03086 SETU8(msg, i, TMR_SR_OPCODE_GET_READ_TX_POWER);
03087 SETU8(msg, i, 1);
03088 msg[1] = i - 3;
03089
03090 ret = TMR_SR_send(reader, msg);
03091 if (TMR_SUCCESS != ret)
03092 {
03093 return ret;
03094 }
03095
03096 power->setPower = GETU16AT(msg, 6);
03097 power->maxPower = GETU16AT(msg, 8);
03098 power->minPower = GETU16AT(msg, 10);
03099
03100 return TMR_SUCCESS;
03101 }
03102
03103
03104 TMR_Status
03105 TMR_SR_cmdGetWriteTxPower(TMR_Reader *reader, int32_t *power)
03106 {
03107 TMR_Status ret;
03108 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03109 uint8_t i;
03110
03111 i = 2;
03112 SETU8(msg, i, TMR_SR_OPCODE_GET_WRITE_TX_POWER);
03113 SETU8(msg, i, 0);
03114 msg[1] = i - 3;
03115
03116 ret = TMR_SR_send(reader, msg);
03117 if (TMR_SUCCESS != ret)
03118 {
03119 return ret;
03120 }
03121
03122 *power = (int32_t)GETS16AT(msg, 6);
03123
03124 return TMR_SUCCESS;
03125 }
03126
03127
03128 TMR_Status
03129 TMR_SR_cmdGetFrequencyHopTable(TMR_Reader *reader, uint8_t *count,
03130 uint32_t *hopTable)
03131 {
03132 TMR_Status ret;
03133 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03134 uint8_t i, j, len;
03135
03136 i = 2;
03137 SETU8(msg, i, TMR_SR_OPCODE_GET_FREQ_HOP_TABLE);
03138 msg[1] = i - 3;
03139
03140 ret = TMR_SR_send(reader, msg);
03141 if (TMR_SUCCESS != ret)
03142 {
03143 return ret;
03144 }
03145
03146 len = msg[1] / 4;
03147 for (j = 0; i < *count && j < len ; j++)
03148 {
03149 hopTable[j] = GETU32AT(msg, 5 + 4*j);
03150 }
03151 *count = len;
03152
03153 return TMR_SUCCESS;
03154 }
03155
03156
03157 TMR_Status
03158 TMR_SR_cmdGetFrequencyHopTime(TMR_Reader *reader, uint32_t *hopTime)
03159 {
03160 TMR_Status ret;
03161 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03162 uint8_t i;
03163
03164 i = 2;
03165 SETU8(msg, i, TMR_SR_OPCODE_GET_FREQ_HOP_TABLE);
03166 SETU8(msg, i, 1);
03167 msg[1] = i - 3;
03168
03169 ret = TMR_SR_send(reader, msg);
03170 if (TMR_SUCCESS != ret)
03171 {
03172 return ret;
03173 }
03174
03175 *hopTime = GETU32AT(msg, 6);
03176
03177 return TMR_SUCCESS;
03178 }
03179
03180
03181 TMR_Status
03182 TMR_SR_cmdGetGPIO(TMR_Reader *reader, uint8_t *count, TMR_GpioPin *state)
03183 {
03184 TMR_Status ret;
03185 uint8_t msg[TMR_SR_MAX_PACKET_SIZE] = {0};
03186 uint8_t i, j, len, offset;
03187
03188 i = 2;
03189 SETU8(msg, i, TMR_SR_OPCODE_GET_USER_GPIO_INPUTS);
03190 SETU8(msg, i, 0x01);
03191 msg[1] = i - 3;
03192
03193 ret = TMR_SR_sendTimeout(reader, msg, reader->u.serialReader.commandTimeout);
03194 if (TMR_SUCCESS != ret)
03195 return ret;
03196
03197 len = (msg[1] - 1)/3;
03198 if (len > *count)
03199 {
03200 len = *count;
03201 }
03202
03203 offset = 6;
03204 for (j = 0; j < len ; j++)
03205 {
03206 state[j].id = msg[offset++];
03207 state[j].output = (1 == msg[offset++]) ? true : false;
03208 state[j].high = (1 == msg[offset++]) ? true : false;
03209 }
03210 *count = len;
03211
03212 return TMR_SUCCESS;
03213 }
03214
03215 TMR_Status
03216 TMR_SR_cmdGetGPIODirection(TMR_Reader *reader, uint8_t pin, bool *out)
03217 {
03218 TMR_Status ret;
03219 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03220 uint8_t i;
03221
03222 i = 2;
03223 SETU8(msg, i, TMR_SR_OPCODE_SET_USER_GPIO_OUTPUTS);
03224 SETU8(msg, i, pin);
03225 msg[1] = i - 3;
03226
03227 ret = TMR_SR_send(reader, msg);
03228 if (TMR_SUCCESS != ret)
03229 return ret;
03230
03231 *out = (msg[6] == 1);
03232
03233 return TMR_SUCCESS;
03234 }
03235
03236
03237 TMR_Status
03238 TMR_SR_cmdSetGPIODirection(TMR_Reader *reader, uint8_t pin, bool out)
03239 {
03240 TMR_Status ret;
03241 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03242 uint8_t i;
03243
03244 i = 2;
03245 SETU8(msg, i, TMR_SR_OPCODE_SET_USER_GPIO_OUTPUTS);
03246 SETU8(msg, i, 1);
03247 SETU8(msg, i, pin);
03248 SETU8(msg, i, (out == true) ? 1 : 0);
03249 SETU8(msg, i, 0);
03250 msg[1] = i - 3;
03251
03252 ret = TMR_SR_send(reader, msg);
03253 if (TMR_SUCCESS != ret)
03254 return ret;
03255
03256 return TMR_SUCCESS;
03257 }
03258
03259 TMR_Status
03260 TMR_SR_cmdGetCurrentProtocol(TMR_Reader *reader, TMR_TagProtocol *protocol)
03261 {
03262 TMR_Status ret;
03263 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03264 uint8_t i;
03265
03266 i = 2;
03267 SETU8(msg, i, TMR_SR_OPCODE_GET_TAG_PROTOCOL);
03268 msg[1] = i - 3;
03269
03270 ret = TMR_SR_send(reader, msg);
03271 if (TMR_SUCCESS != ret)
03272 {
03273 return ret;
03274 }
03275 *protocol = (TMR_TagProtocol)GETU16AT(msg, 5);
03276
03277 return TMR_SUCCESS;
03278 }
03279
03280 TMR_Status
03281 TMR_SR_cmdGetRegion(TMR_Reader *reader, TMR_Region *region)
03282 {
03283 TMR_Status ret;
03284 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03285 uint8_t i;
03286
03287 i = 2;
03288 SETU8(msg, i, TMR_SR_OPCODE_GET_REGION);
03289 msg[1] = i - 3;
03290
03291 ret = TMR_SR_send(reader, msg);
03292 if (TMR_SUCCESS != ret)
03293 {
03294 return ret;
03295 }
03296 *region = (TMR_Region)GETU8AT(msg, 5);
03297
03298 return TMR_SUCCESS;
03299 }
03300
03301 TMR_Status
03302 TMR_SR_cmdGetRegionConfiguration(TMR_Reader *reader,
03303 TMR_SR_RegionConfiguration key,
03304 void *value)
03305 {
03306 TMR_Status ret;
03307 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03308 uint8_t i;
03309
03310 i = 2;
03311 SETU8(msg, i, TMR_SR_OPCODE_GET_REGION);
03312 SETU8(msg, i, 1);
03313 SETU8(msg, i, key);
03314 msg[1] = i - 3;
03315
03316 ret = TMR_SR_send(reader, msg);
03317 if (TMR_SUCCESS != ret)
03318 {
03319 return ret;
03320 }
03321
03322 switch (key)
03323 {
03324 case TMR_SR_REGION_CONFIGURATION_LBT_ENABLED:
03325 *(bool *)value = (GETU8AT(msg, 8) == 1);
03326 break;
03327 default:
03328 return TMR_ERROR_NOT_FOUND;
03329 }
03330
03331 return TMR_SUCCESS;
03332 }
03333
03334
03335 TMR_Status
03336 TMR_SR_cmdGetPowerMode(TMR_Reader *reader, TMR_SR_PowerMode *mode)
03337 {
03338 TMR_Status ret;
03339 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03340 uint8_t i;
03341
03342 i = 2;
03343 SETU8(msg, i, TMR_SR_OPCODE_GET_POWER_MODE);
03344 msg[1] = i - 3;
03345
03346 ret = TMR_SR_send(reader, msg);
03347 if (TMR_SUCCESS != ret)
03348 {
03349 return ret;
03350 }
03351
03352 *mode = (TMR_SR_PowerMode)GETU8AT(msg, 5);
03353
03354 return TMR_SUCCESS;
03355 }
03356
03357
03358 TMR_Status
03359 TMR_SR_cmdGetUserMode(TMR_Reader *reader, TMR_SR_UserMode *mode)
03360 {
03361 TMR_Status ret;
03362 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03363 uint8_t i;
03364
03365 i = 2;
03366 SETU8(msg, i, TMR_SR_OPCODE_GET_USER_MODE);
03367 msg[1] = i - 3;
03368
03369 ret = TMR_SR_send(reader, msg);
03370 if (TMR_SUCCESS != ret)
03371 {
03372 return ret;
03373 }
03374
03375 *mode = (TMR_SR_UserMode)GETU8AT(msg, 5);
03376
03377 return TMR_SUCCESS;
03378 }
03379
03380
03381 TMR_Status
03382 TMR_SR_cmdGetReaderConfiguration(TMR_Reader *reader, TMR_SR_Configuration key,
03383 void *value)
03384 {
03385 TMR_SR_SerialReader *sr = &reader->u.serialReader;
03386 TMR_Status ret;
03387 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03388 uint8_t i;
03389
03390 i = 2;
03391 SETU8(msg, i, TMR_SR_OPCODE_GET_READER_OPTIONAL_PARAMS);
03392 SETU8(msg, i, 1);
03393 SETU8(msg, i, key);
03394 msg[1] = i - 3;
03395
03396 ret = TMR_SR_send(reader, msg);
03397 if (TMR_SUCCESS != ret)
03398 {
03399 return ret;
03400 }
03401
03402 switch (key)
03403 {
03404 case TMR_SR_CONFIGURATION_ANTENNA_CONTROL_GPIO:
03405 *(uint8_t *)value = GETU8AT(msg, 7);
03406 break;
03407 case TMR_SR_CONFIGURATION_TRIGGER_READ_GPIO:
03408 *(uint8_t *)value = GETU8AT(msg, 7);
03409 break;
03410
03411 case TMR_SR_CONFIGURATION_UNIQUE_BY_ANTENNA:
03412 case TMR_SR_CONFIGURATION_UNIQUE_BY_DATA:
03413 case TMR_SR_CONFIGURATION_UNIQUE_BY_PROTOCOL:
03414 *(bool *)value = (GETU8AT(msg, 7) == 0);
03415 break;
03416 case TMR_SR_CONFIGURATION_TRANSMIT_POWER_SAVE:
03417 if(TMR_SR_MODEL_MICRO == sr->versionInfo.hardware[0])
03418 {
03419 if(GETU8AT(msg, 7) == 2)
03420 {
03421
03422 *(bool *)value = 1;
03423 }
03424 else
03425 {
03426
03427 *(bool *)value = 0;
03428 }
03429 }
03430 else
03431 {
03432 *(bool *)value = (GETU8AT(msg, 7) == 1);
03433 }
03434 break;
03435 case TMR_SR_CONFIGURATION_EXTENDED_EPC:
03436 case TMR_SR_CONFIGURATION_SAFETY_ANTENNA_CHECK:
03437 case TMR_SR_CONFIGURATION_SAFETY_TEMPERATURE_CHECK:
03438 case TMR_SR_CONFIGURATION_RECORD_HIGHEST_RSSI:
03439 case TMR_SR_CONFIGURATION_RSSI_IN_DBM:
03440 case TMR_SR_CONFIGURATION_SELF_JAMMER_CANCELLATION:
03441 case TMR_SR_CONFIGURATION_ENABLE_READ_FILTER:
03442 case TMR_SR_CONFIGURATION_SEND_CRC:
03443 *(bool *)value = (GETU8AT(msg, 7) == 1);
03444 break;
03445 case TMR_SR_CONFIGURATION_CURRENT_MSG_TRANSPORT:
03446 *(uint8_t *)value = GETU8AT(msg, 7) ;
03447 break;
03448 case TMR_SR_CONFIGURATION_READ_FILTER_TIMEOUT:
03449 *(uint32_t *)value = GETU32AT(msg, 7);
03450 break;
03451
03452 case TMR_SR_CONFIGURATION_PRODUCT_GROUP_ID:
03453 *(uint16_t *)value = GETU16AT(msg, 7);
03454 break;
03455
03456 case TMR_SR_CONFIGURATION_PRODUCT_ID:
03457 *(uint16_t *)value = GETU16AT(msg, 7);
03458 break;
03459
03460 default:
03461 return TMR_ERROR_NOT_FOUND;
03462 }
03463
03464 return TMR_SUCCESS;
03465 }
03466
03467 TMR_Status
03468 TMR_SR_cmdGetProtocolConfiguration(TMR_Reader *reader, TMR_TagProtocol protocol,
03469 TMR_SR_ProtocolConfiguration key,
03470 void *value)
03471 {
03472 TMR_Status ret;
03473 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03474 uint8_t i;
03475
03476 i = 2;
03477 SETU8(msg, i, TMR_SR_OPCODE_GET_PROTOCOL_PARAM);
03478 SETU8(msg, i, protocol);
03479 if (TMR_TAG_PROTOCOL_GEN2 == key.protocol)
03480 {
03481 SETU8(msg, i, key.u.gen2);
03482 }
03483 #ifdef TMR_ENABLE_ISO180006B
03484 else if (TMR_TAG_PROTOCOL_ISO180006B == key.protocol
03485 || TMR_TAG_PROTOCOL_ISO180006B_UCODE == key.protocol)
03486 {
03487 SETU8(msg, i, key.u.iso180006b);
03488 }
03489 #endif
03490 else
03491 {
03492 return TMR_ERROR_INVALID;
03493 }
03494 msg[1] = i - 3;
03495
03496 ret = TMR_SR_send(reader, msg);
03497 if (TMR_SUCCESS != ret)
03498 {
03499 return ret;
03500 }
03501
03502 if (TMR_TAG_PROTOCOL_GEN2 == key.protocol)
03503 {
03504 switch (key.u.gen2)
03505 {
03506 case TMR_SR_GEN2_CONFIGURATION_SESSION:
03507 *(TMR_GEN2_Session *)value = (TMR_GEN2_Session)GETU8AT(msg, 7);
03508 break;
03509
03510 case TMR_SR_GEN2_CONFIGURATION_TAGENCODING:
03511 *(TMR_GEN2_TagEncoding *)value = (TMR_GEN2_TagEncoding)GETU8AT(msg, 7);
03512 break;
03513
03514 case TMR_SR_GEN2_CONFIGURATION_LINKFREQUENCY:
03515 *(TMR_GEN2_LinkFrequency *)value = (TMR_GEN2_LinkFrequency)GETU8AT(msg, 7);
03516 break;
03517
03518 case TMR_SR_GEN2_CONFIGURATION_TARI:
03519 *(TMR_GEN2_Tari *)value = (TMR_GEN2_Tari)GETU8AT(msg, 7);
03520 break;
03521
03522 case TMR_SR_GEN2_CONFIGURATION_PROTCOLEXTENSION:
03523 *(TMR_GEN2_ProtocolExtension *)value = (TMR_GEN2_ProtocolExtension)GETU8AT(msg, 7);
03524 break;
03525
03526 case TMR_SR_GEN2_CONFIGURATION_BAP:
03527 {
03528 TMR_GEN2_Bap *b = value;
03529
03530 i = 10;
03531 b->powerUpDelayUs = GETU32(msg,i);
03532 b->freqHopOfftimeUs = GETU32(msg,i);
03533 break;
03534 }
03535
03536 case TMR_SR_GEN2_CONFIGURATION_TARGET:
03537 {
03538 uint16_t target;
03539
03540 target = GETU16AT(msg, 7);
03541 switch (target)
03542 {
03543 case 0x0100:
03544 *(TMR_GEN2_Target *)value = TMR_GEN2_TARGET_A;
03545 break;
03546 case 0x0101:
03547 *(TMR_GEN2_Target *)value = TMR_GEN2_TARGET_B;
03548 break;
03549 case 0x0000:
03550 *(TMR_GEN2_Target *)value = TMR_GEN2_TARGET_AB;
03551 break;
03552 case 0x0001:
03553 *(TMR_GEN2_Target *)value = TMR_GEN2_TARGET_BA;
03554 break;
03555 default:
03556 *(TMR_GEN2_Target *)value = TMR_GEN2_TARGET_INVALID;
03557 }
03558 break;
03559 }
03560
03561 case TMR_SR_GEN2_CONFIGURATION_Q:
03562 {
03563 TMR_SR_GEN2_Q *q = value;
03564
03565 q->type = (TMR_SR_GEN2_QType)GETU8AT(msg, 7);
03566 if (q->type == TMR_SR_GEN2_Q_DYNAMIC)
03567 {
03568 ;
03569 }
03570 else if (q->type == TMR_SR_GEN2_Q_STATIC)
03571 {
03572 q->u.staticQ.initialQ = GETU8AT(msg, 8);
03573 }
03574 break;
03575 }
03576
03577 default:
03578 return TMR_ERROR_NOT_FOUND;
03579 }
03580 }
03581 #ifdef TMR_ENABLE_ISO180006B
03582 else if (TMR_TAG_PROTOCOL_ISO180006B == key.protocol
03583 || TMR_TAG_PROTOCOL_ISO180006B_UCODE == key.protocol)
03584 {
03585 switch (key.u.iso180006b)
03586 {
03587 case TMR_SR_ISO180006B_CONFIGURATION_LINKFREQUENCY:
03588 {
03589 TMR_iso18000BBLFValToInt(GETU8AT(msg, 7), value);
03590 break;
03591 }
03592 case TMR_SR_ISO180006B_CONFIGURATION_MODULATION_DEPTH:
03593 {
03594 uint8_t val;
03595 val = GETU8AT(msg, 7);
03596 switch (val)
03597 {
03598 case 0:
03599 *(TMR_ISO180006B_ModulationDepth *)value = TMR_ISO180006B_Modulation99percent;
03600 break;
03601 case 1:
03602 *(TMR_ISO180006B_ModulationDepth *)value = TMR_ISO180006B_Modulation11percent;
03603 break;
03604 default:
03605 return TMR_ERROR_NOT_FOUND;
03606 }
03607 break;
03608 }
03609 case TMR_SR_ISO180006B_CONFIGURATION_DELIMITER:
03610 {
03611 uint8_t val;
03612 val = GETU8AT(msg, 7);
03613 switch (val)
03614 {
03615 case 1:
03616 *(TMR_ISO180006B_Delimiter *)value = TMR_ISO180006B_Delimiter1;
03617 break;
03618 case 4:
03619 *(TMR_ISO180006B_Delimiter *)value = TMR_ISO180006B_Delimiter4;
03620 break;
03621 default:
03622 return TMR_ERROR_NOT_FOUND;
03623 }
03624 break;
03625 }
03626 default:
03627 return TMR_ERROR_NOT_FOUND;
03628 }
03629 }
03630 #endif
03631 else
03632 {
03633 return TMR_ERROR_INVALID;
03634 }
03635
03636 return TMR_SUCCESS;
03637 }
03638
03639 TMR_Status TMR_iso18000BBLFValToInt(int val, void *lf)
03640 {
03641 switch (val)
03642 {
03643 case 1:
03644 *(TMR_ISO180006B_LinkFrequency *)lf = TMR_ISO180006B_LINKFREQUENCY_40KHZ;
03645 break;
03646 case 0:
03647 *(TMR_ISO180006B_LinkFrequency *)lf = TMR_ISO180006B_LINKFREQUENCY_160KHZ;
03648 break;
03649 default:
03650 return TMR_ERROR_NOT_FOUND;
03651 }
03652 return TMR_SUCCESS;
03653 }
03654
03655
03656 TMR_Status
03657 TMR_SR_msgSetupMultipleProtocolSearch(TMR_Reader *reader, uint8_t *msg, TMR_SR_OpCode op, TMR_TagProtocolList *protocols, TMR_TRD_MetadataFlag metadataFlags, TMR_SR_SearchFlag antennas, TMR_TagFilter **filter, uint16_t timeout)
03658 {
03659 TMR_Status ret;
03660 uint8_t i;
03661 uint32_t j;
03662 uint16_t subTimeout;
03663
03664 ret = TMR_SUCCESS;
03665 i=2;
03666
03667 SETU8(msg, i, TMR_SR_OPCODE_MULTI_PROTOCOL_TAG_OP);
03668 if(reader->continuousReading)
03669 {
03670
03671 SETU16(msg, i, 0);
03672 SETU8(msg, i, (uint8_t)0x1);
03673 }
03674 else
03675 {
03676 SETU16(msg, i, timeout);
03677 SETU8(msg, i, (uint8_t)0x11);
03678 SETU16(msg, i, (uint16_t)metadataFlags);
03679 }
03680
03681 SETU8(msg, i, (uint8_t)op);
03682
03683 if (TMR_READ_PLAN_TYPE_MULTI == reader->readParams.readPlan->type)
03684 {
03685 reader->isStopNTags = false;
03689 for (j = 0; j < reader->readParams.readPlan->u.multi.planCount; j++)
03690 {
03691 if (reader->readParams.readPlan->u.multi.plans[j]->u.simple.stopOnCount.stopNTriggerStatus)
03692 {
03693 reader->numberOfTagsToRead += reader->readParams.readPlan->u.multi.plans[j]->u.simple.stopOnCount.noOfTags;
03694 reader->isStopNTags = true;
03695 }
03696 }
03697 }
03698 else
03699 {
03700 reader->numberOfTagsToRead += reader->readParams.readPlan->u.simple.stopOnCount.noOfTags;
03701 }
03702
03703 if (reader->isStopNTags && !reader->continuousReading)
03704 {
03710 SETU16(msg, i, (uint16_t)TMR_SR_SEARCH_FLAG_RETURN_ON_N_TAGS);
03711 SETU32(msg, i, reader->numberOfTagsToRead);
03712 }
03713 else
03714 {
03715 SETU16(msg, i, (uint16_t)0x0000);
03716 }
03717
03721 subTimeout =(uint16_t)(timeout/(protocols->len));
03722 for (j=0;j<protocols->len;j++)
03723 {
03724 int PLenIdx;
03725
03726
03727 TMR_TagProtocol subProtocol=protocols->list[j];
03728 SETU8(msg, i, (uint8_t)(subProtocol));
03729 PLenIdx = i;
03730 SETU8(msg, i, 0);
03731
03736 if (TMR_READ_PLAN_TYPE_MULTI == reader->readParams.readPlan->type)
03737 {
03738 if (0 != reader->readParams.readPlan->u.multi.totalWeight)
03739 {
03740 subTimeout = (uint16_t)(reader->readParams.readPlan->u.multi.plans[j]->weight * timeout
03741 / reader->readParams.readPlan->u.multi.totalWeight);
03742 }
03743 }
03744
03749 if (TMR_READ_PLAN_TYPE_MULTI == reader->readParams.readPlan->type)
03750 {
03751 reader->fastSearch = reader->readParams.readPlan->u.multi.plans[j]->u.simple.useFastSearch;
03752 reader->triggerRead = reader->readParams.readPlan->u.multi.plans[j]->u.simple.triggerRead.enable;
03753 reader->isStopNTags = false;
03754 reader->isStopNTags = reader->readParams.readPlan->u.multi.plans[j]->u.simple.stopOnCount.stopNTriggerStatus;
03755 reader->numberOfTagsToRead = reader->readParams.readPlan->u.multi.plans[j]->u.simple.stopOnCount.noOfTags;
03756 }
03757
03758 switch(op)
03759 {
03760 case TMR_SR_OPCODE_READ_TAG_ID_SINGLE :
03761 {
03762 ret = TMR_SR_msgSetupReadTagSingle(msg, &i, subProtocol,metadataFlags, filter[j], subTimeout);
03763 break;
03764 }
03765 case TMR_SR_OPCODE_READ_TAG_ID_MULTIPLE:
03766 {
03771 if (TMR_READ_PLAN_TYPE_MULTI == reader->readParams.readPlan->type)
03772 {
03773
03774 if (NULL != reader->readParams.readPlan->u.multi.plans[j]->u.simple.tagop)
03775 {
03776 uint32_t readTimeMs = (uint32_t)subTimeout;
03777 uint8_t lenbyte = 0;
03778
03779 ret = TMR_SR_addTagOp(reader,reader->readParams.readPlan->u.multi.plans[j]->u.simple.tagop,
03780 reader->readParams.readPlan->u.multi.plans[j], msg, &i, readTimeMs, &lenbyte);
03781 }
03782 else
03783 {
03784 ret = TMR_SR_msgSetupReadTagMultipleWithMetadata(reader, msg, &i, subTimeout, antennas, metadataFlags ,filter[j], subProtocol, 0);
03785 }
03786 }
03787 else
03788 {
03789 if (NULL != reader->readParams.readPlan->u.simple.tagop)
03790 {
03791 uint32_t readTimeMs = (uint32_t)subTimeout;
03792 uint8_t lenbyte = 0;
03793
03794 ret = TMR_SR_addTagOp(reader, reader->readParams.readPlan->u.simple.tagop,
03795 reader->readParams.readPlan, msg, &i, readTimeMs, &lenbyte);
03796 }
03797 else
03798 {
03799 ret = TMR_SR_msgSetupReadTagMultipleWithMetadata(reader, msg, &i, subTimeout, antennas, metadataFlags ,filter[j], subProtocol, 0);
03800 }
03801 }
03802 break;
03803 }
03804 default :
03805 {
03806 return TMR_ERROR_INVALID_OPCODE;
03807 }
03808 }
03809
03810 msg[PLenIdx]= i - PLenIdx - 2;
03811 msg[1]=i - 3;
03812 }
03813 return ret;
03814 }
03815
03816 TMR_Status TMR_SR_cmdMultipleProtocolSearch(TMR_Reader *reader,TMR_SR_OpCode op,TMR_TagProtocolList *protocols, TMR_TRD_MetadataFlag metadataFlags,TMR_SR_SearchFlag antennas, TMR_TagFilter **filter, uint16_t timeout, uint32_t *tagsFound)
03817 {
03818 TMR_Status ret;
03819 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03820 TMR_SR_SerialReader *sr;
03821
03822 sr = &reader->u.serialReader;
03823 *tagsFound = 0 ;
03824
03825 ret = TMR_SR_msgSetupMultipleProtocolSearch(reader, msg, op, protocols, metadataFlags, antennas, filter, timeout);
03826 if (ret != TMR_SUCCESS)
03827 {
03828 return ret;
03829 }
03830
03831 if (op == TMR_SR_OPCODE_READ_TAG_ID_SINGLE)
03832 {
03833 uint8_t opcode;
03834
03835 sr->opCode = op;
03836 ret = TMR_SR_sendMessage(reader, msg, &opcode, timeout);
03837 if (TMR_SUCCESS != ret)
03838 {
03839 return ret;
03840 }
03841 sr->tagsRemaining = 1;
03842 }
03843
03844 if (op == TMR_SR_OPCODE_READ_TAG_ID_MULTIPLE)
03845 {
03846 sr->opCode = op;
03847 if(reader->continuousReading)
03848 {
03849 uint8_t opcode;
03850 ret = TMR_SR_sendMessage(reader, msg, &opcode, timeout);
03851 if (TMR_SUCCESS != ret)
03852 {
03853 return ret;
03854 }
03855 reader->hasContinuousReadStarted = true;
03856 sr->tagsRemaining=1;
03857 }
03858 else
03859 {
03860 ret = TMR_SR_sendTimeout(reader, msg, timeout);
03861 if (TMR_ERROR_NO_TAGS_FOUND == ret)
03862 {
03863 sr->tagsRemaining = *tagsFound = 0;
03864 return ret;
03865 }
03866 else if ((TMR_ERROR_TM_ASSERT_FAILED == ret) ||
03867 (TMR_ERROR_TIMEOUT == ret))
03868 {
03869 return ret;
03870 }
03871 else if (TMR_SUCCESS != ret)
03872 {
03873 uint16_t remainingTagsCount;
03874 TMR_Status ret1;
03875
03876
03877 ret1 = TMR_SR_cmdGetTagsRemaining(reader, &remainingTagsCount);
03878 if (TMR_SUCCESS != ret1)
03879 {
03880 return ret1;
03881 }
03882
03883 *tagsFound = remainingTagsCount;
03884 sr->tagsRemaining = *tagsFound;
03885 return ret;
03886 }
03887
03888 *tagsFound = GETU32AT(msg , 9);
03889 sr->tagsRemaining = *tagsFound;
03890 }
03891 }
03892
03893 return TMR_SUCCESS;
03894 }
03895
03896 TMR_Status
03897 TMR_SR_cmdGetAvailableProtocols(TMR_Reader *reader,
03898 TMR_TagProtocolList *protocols)
03899 {
03900 TMR_Status ret;
03901 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03902 uint8_t i;
03903
03904 i = 2;
03905 SETU8(msg, i, TMR_SR_OPCODE_GET_AVAILABLE_PROTOCOLS);
03906 msg[1] = i - 3;
03907
03908 ret = TMR_SR_send(reader, msg);
03909 if (TMR_SUCCESS != ret)
03910 {
03911 return ret;
03912 }
03913
03914 protocols->len = 0;
03915 for (i = 0; i < msg[1] ; i += 2)
03916 {
03917 LISTAPPEND(protocols, (TMR_TagProtocol)GETU16AT(msg, 5 + i));
03918 }
03919
03920 reader->u.serialReader.versionInfo.protocols = 0x0000;
03921 for (i = 0 ; i < protocols->len; i ++)
03922 {
03923 reader->u.serialReader.versionInfo.protocols |= (1 << (protocols->list[i] - 1));
03924 }
03925
03926 return TMR_SUCCESS;
03927 }
03928
03929
03930 TMR_Status
03931 TMR_SR_cmdGetAvailableRegions(TMR_Reader *reader, TMR_RegionList *regions)
03932 {
03933 TMR_Status ret;
03934 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03935 uint8_t i;
03936
03937 i = 2;
03938 SETU8(msg, i, TMR_SR_OPCODE_GET_AVAILABLE_REGIONS);
03939 msg[1] = i - 3;
03940
03941 ret = TMR_SR_send(reader, msg);
03942 if (TMR_SUCCESS != ret)
03943 {
03944 return ret;
03945 }
03946
03947 regions->len = 0;
03948 for (i = 0; i < msg[1] ; i++)
03949 {
03950 LISTAPPEND(regions, (TMR_Region)GETU8AT(msg, 5 + i));
03951 }
03952
03953 return TMR_SUCCESS;
03954 }
03955
03956
03957
03958 TMR_Status
03959 TMR_SR_cmdGetTemperature(TMR_Reader *reader, int8_t *temp)
03960 {
03961 TMR_Status ret;
03962 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
03963 uint8_t i;
03964
03965 i = 2;
03966 SETU8(msg, i, TMR_SR_OPCODE_GET_TEMPERATURE);
03967 msg[1] = i - 3;
03968
03969 ret = TMR_SR_send(reader, msg);
03970 if (TMR_SUCCESS != ret)
03971 {
03972 return ret;
03973 }
03974
03975 *temp = msg[5];
03976 return TMR_SUCCESS;
03977 }
03978
03979
03980 static TMR_Status
03981 filterbytes(TMR_TagProtocol protocol, const TMR_TagFilter *filter,
03982 uint8_t *option, uint8_t *i, uint8_t *msg,
03983 uint32_t accessPassword, bool usePassword)
03984 {
03985 int j;
03986 if (isSecureAccessEnabled)
03987 {
03988 *option = TMR_SR_GEN2_SINGULATION_OPTION_SECURE_READ_DATA;
03989 }
03990
03991 if (NULL == filter && 0 == accessPassword)
03992 {
03993 *option = 0x00;
03994 return TMR_SUCCESS;
03995 }
03996
03997 if (TMR_TAG_PROTOCOL_GEN2 == protocol)
03998 {
03999 if (usePassword)
04000 {
04001 if (filter && TMR_FILTER_TYPE_GEN2_SELECT == filter->type)
04002 {
04003 if (filter->u.gen2Select.bank != TMR_GEN2_EPC_LENGTH_FILTER)
04004 SETU32(msg, *i, accessPassword);
04005 }
04006 else
04007 {
04008 SETU32(msg, *i, accessPassword);
04009 }
04010 }
04011 if (NULL == filter)
04012 {
04013 *option |= TMR_SR_GEN2_SINGULATION_OPTION_USE_PASSWORD;
04014 }
04015 else if (TMR_FILTER_TYPE_GEN2_SELECT == filter->type)
04016 {
04017 const TMR_GEN2_Select *fp;
04018
04019 fp = &filter->u.gen2Select;
04020
04021 if (1 == fp->bank)
04022 {
04023 *option |= TMR_SR_GEN2_SINGULATION_OPTION_SELECT_ON_ADDRESSED_EPC;
04024 }
04025 else
04026 {
04027 *option |= fp->bank;
04028 }
04029
04030 if (fp->bank == TMR_GEN2_EPC_LENGTH_FILTER)
04031 {
04032 SETU16(msg, *i, fp->maskBitLength);
04033 }
04034 else
04035 {
04036 if(true == fp->invert)
04037 {
04038 *option |= TMR_SR_GEN2_SINGULATION_OPTION_INVERSE_SELECT_BIT;
04039 }
04040
04041 if (fp->maskBitLength > 255)
04042 {
04043 *option |= TMR_SR_GEN2_SINGULATION_OPTION_EXTENDED_DATA_LENGTH;
04044 }
04045
04046 SETU32(msg, *i, fp->bitPointer);
04047
04048 if (fp->maskBitLength > 255)
04049 {
04050 SETU8(msg, *i, (fp->maskBitLength >> 8) & 0xFF);
04051 }
04052 SETU8(msg, *i, fp->maskBitLength & 0xFF);
04053
04054 if (*i + 1 + tm_u8s_per_bits(fp->maskBitLength) > TMR_SR_MAX_PACKET_SIZE)
04055 {
04056 return TMR_ERROR_TOO_BIG;
04057 }
04058
04059 for(j = 0; j < tm_u8s_per_bits(fp->maskBitLength) ; j++)
04060 {
04061 SETU8(msg, *i, fp->mask[j]);
04062 }
04063 }
04064 }
04065 else if (TMR_FILTER_TYPE_TAG_DATA == filter->type)
04066 {
04067 const TMR_TagData *fp;
04068 int bitCount;
04069
04070 fp = &filter->u.tagData;
04071 bitCount = fp->epcByteCount * 8;
04072
04073
04074 *option |= 1;
04075 if (bitCount > 255)
04076 {
04077 *option |= TMR_SR_GEN2_SINGULATION_OPTION_EXTENDED_DATA_LENGTH;
04078 SETU8(msg, *i, (bitCount>>8) & 0xFF);
04079 }
04080 SETU8(msg, *i, (bitCount & 0xFF));
04081
04082 if (*i + 1 + fp->epcByteCount > TMR_SR_MAX_PACKET_SIZE)
04083 {
04084 return TMR_ERROR_TOO_BIG;
04085 }
04086
04087 for(j = 0 ; j < fp->epcByteCount ; j++)
04088 {
04089 SETU8(msg, *i, fp->epc[j]);
04090 }
04091 }
04092 else
04093 {
04094 return TMR_ERROR_INVALID;
04095 }
04096 }
04097 #ifdef TMR_ENABLE_ISO180006B
04098 else if (TMR_TAG_PROTOCOL_ISO180006B == protocol)
04099 {
04100 if (option)
04101 {
04102 *option = 1;
04103 }
04104
04105 if (NULL == filter)
04106 {
04107
04108 SETU8(msg, *i, TMR_ISO180006B_SELECT_OP_EQUALS);
04109 SETU8(msg, *i, 0);
04110 SETU8(msg, *i, 0);
04111 SETU32(msg, *i, 0);
04112 SETU32(msg, *i, 0);
04113 return TMR_SUCCESS;
04114 }
04115 else if (TMR_FILTER_TYPE_ISO180006B_SELECT == filter->type)
04116 {
04117 const TMR_ISO180006B_Select *fp;
04118
04119 fp = &filter->u.iso180006bSelect;
04120 if (false == fp->invert)
04121 {
04122 SETU8(msg, *i, fp->op);
04123 }
04124 else
04125 {
04126 SETU8(msg, *i, fp->op | 4);
04127 }
04128 SETU8(msg, *i, fp->address);
04129 SETU8(msg, *i, fp->mask);
04130 for (j = 0 ; j < 8 ; j++)
04131 {
04132 SETU8(msg, *i, fp->data[j]);
04133 }
04134 }
04135 else if (TMR_FILTER_TYPE_TAG_DATA == filter->type)
04136 {
04137 const TMR_TagData *fp;
04138 uint8_t mask;
04139
04140 fp = &filter->u.tagData;
04141
04142 if (fp->epcByteCount > 8)
04143 {
04144 return TMR_ERROR_INVALID;
04145 }
04146
04147
04148 mask = (0xff00 >> fp->epcByteCount) & 0xff;
04149
04150 SETU8(msg, *i, TMR_ISO180006B_SELECT_OP_EQUALS);
04151 SETU8(msg, *i, 0);
04152 SETU8(msg, *i, mask);
04153 for (j = 0 ; j < fp->epcByteCount; j++)
04154 {
04155 SETU8(msg, *i, fp->epc[j]);
04156 }
04157 for ( ; j < 8 ; j++)
04158 {
04159 SETU8(msg, *i, 0);
04160 }
04161 }
04162 else
04163 {
04164 return TMR_ERROR_INVALID;
04165 }
04166
04167 }
04168 #endif
04169 else
04170 {
04171 return TMR_ERROR_INVALID;
04172 }
04173
04174 return TMR_SUCCESS;
04175 }
04176
04182 void TMR_SR_msgAddHiggs2PartialLoadImage(uint8_t *msg, uint8_t *i, uint16_t timeout,
04183 TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword, uint8_t len, const uint8_t *epc, TMR_TagFilter* target)
04184 {
04185 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04186 SETU16(msg, *i, timeout);
04187 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_ALIEN_HIGGS_SILICON);
04188 SETU8(msg, *i, (uint8_t)0x01);
04189 SETU32(msg, *i, killPassword);
04190 SETU32(msg, *i, accessPassword);
04191 memcpy(&msg[*i], epc, len);
04192 *i += len;
04193 }
04206 TMR_Status TMR_SR_cmdHiggs2PartialLoadImage(TMR_Reader *reader, uint16_t timeout,
04207 TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword,
04208 uint8_t len, const uint8_t epc[], TMR_TagFilter* target)
04209 {
04210 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04211 uint8_t i;
04212 i = 2;
04213
04214 if(NULL != target)
04215 {
04216 return TMR_ERROR_UNSUPPORTED;
04217 }
04218 TMR_SR_msgAddHiggs2PartialLoadImage(msg, &i, timeout, accessPassword, killPassword, len, epc, target);
04219 msg[1] = i - 3;
04220
04221 return TMR_SR_sendTimeout(reader, msg, timeout);
04222 }
04223
04224
04226 void TMR_SR_msgAddHiggs2FullLoadImage(uint8_t *msg, uint8_t *i, uint16_t timeout,
04227 TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword, uint16_t lockBits, uint16_t pcWord, uint8_t len, const uint8_t *epc, TMR_TagFilter* target)
04228 {
04229 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04230 SETU16(msg, *i, timeout);
04231 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_ALIEN_HIGGS_SILICON);
04232 SETU8(msg, *i, (uint8_t)0x03);
04233 SETU32(msg, *i, killPassword);
04234 SETU32(msg, *i, accessPassword);
04235 SETU16(msg, *i, lockBits);
04236 SETU16(msg, *i, pcWord);
04237 memcpy(&msg[*i], epc, len);
04238 *i += len;
04239 }
04254 TMR_Status TMR_SR_cmdHiggs2FullLoadImage(TMR_Reader *reader, uint16_t timeout,
04255 TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword,
04256 uint16_t lockBits, uint16_t pcWord, uint8_t len,
04257 const uint8_t epc[], TMR_TagFilter* target)
04258 {
04259 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04260 uint8_t i;
04261 i = 2;
04262
04263 if(NULL != target)
04264 {
04265 return TMR_ERROR_UNSUPPORTED;
04266 }
04267 TMR_SR_msgAddHiggs2FullLoadImage(msg, &i, timeout, accessPassword, killPassword, lockBits, pcWord, len, epc, target);
04268 msg[1] = i - 3;
04269
04270 return TMR_SR_sendTimeout(reader, msg, timeout);
04271 }
04272
04274 void TMR_SR_msgAddHiggs3FastLoadImage(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password currentAccessPassword,
04275 TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword, uint16_t pcWord, uint8_t len, const uint8_t *epc, TMR_TagFilter* target)
04276 {
04277 uint8_t option=0,rec;
04278
04279 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04280 SETU16(msg, *i, timeout);
04281 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_ALIEN_HIGGS3_SILICON);
04282
04283 rec=*i;
04284 SETU8(msg,*i,0x40);
04285 SETU8(msg, *i, (uint8_t)0x00);
04286 SETU8(msg, *i, (uint8_t)0x01);
04287
04288 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, 0, false);
04289 msg[rec]=msg[rec]|option;
04290
04291 SETU32(msg, *i, currentAccessPassword);
04292 SETU32(msg, *i, killPassword);
04293 SETU32(msg, *i, accessPassword);
04294 SETU16(msg, *i, pcWord);
04295 memcpy(&msg[*i], epc, len);
04296 *i += len;
04297 }
04312 TMR_Status
04313 TMR_SR_cmdHiggs3FastLoadImage(TMR_Reader *reader, uint16_t timeout,
04314 TMR_GEN2_Password currentAccessPassword, TMR_GEN2_Password accessPassword,
04315 TMR_GEN2_Password killPassword, uint16_t pcWord, uint8_t len, const uint8_t epc[], TMR_TagFilter* target)
04316 {
04317 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04318 uint8_t i;
04319 i = 2;
04320
04321 TMR_SR_msgAddHiggs3FastLoadImage(msg, &i, timeout, currentAccessPassword, accessPassword, killPassword, pcWord, len, epc, target);
04322 msg[1] = i - 3;
04323
04324 return TMR_SR_sendTimeout(reader, msg, timeout);
04325 }
04326
04328 void TMR_SR_msgAddHiggs3LoadImage(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password currentAccessPassword,
04329 TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword, uint16_t pcWord, uint8_t len, const uint8_t *epcAndUserData, TMR_TagFilter* target)
04330 {
04331 uint8_t option=0,rec;
04332
04333 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04334 SETU16(msg, *i, timeout);
04335 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_ALIEN_HIGGS3_SILICON);
04336
04337 rec=*i;
04338 SETU8(msg,*i,0x40);
04339 SETU8(msg, *i, (uint8_t)0x00);
04340 SETU8(msg, *i, (uint8_t)0x03);
04341
04342 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, 0, false);
04343 msg[rec]=msg[rec]|option;
04344
04345 SETU32(msg, *i, currentAccessPassword);
04346 SETU32(msg, *i, killPassword);
04347 SETU32(msg, *i, accessPassword);
04348 SETU16(msg, *i, pcWord);
04349 memcpy(&msg[*i], epcAndUserData, len);
04350 *i += len;
04351 }
04352
04368 TMR_Status TMR_SR_cmdHiggs3LoadImage(TMR_Reader *reader, uint16_t timeout,
04369 TMR_GEN2_Password currentAccessPassword,
04370 TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword,
04371 uint16_t pcWord, uint8_t len, const uint8_t epcAndUserData[], TMR_TagFilter* target)
04372 {
04373 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04374 uint8_t i;
04375 i = 2;
04376
04377 TMR_SR_msgAddHiggs3LoadImage(msg, &i, timeout, currentAccessPassword, accessPassword,
04378 killPassword, pcWord, len, epcAndUserData, target);
04379 msg[1] = i - 3;
04380
04381 return TMR_SR_sendTimeout(reader, msg, timeout);
04382 }
04383
04385 void TMR_SR_msgAddHiggs3BlockReadLock(uint8_t *msg, uint8_t *i, uint16_t timeout,
04386 TMR_GEN2_Password accessPassword, uint8_t lockBits, TMR_TagFilter* target)
04387 {
04388 uint8_t option=0,rec;
04389
04390 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04391 SETU16(msg, *i, timeout);
04392 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_ALIEN_HIGGS3_SILICON);
04393
04394 rec=*i;
04395 SETU8(msg,*i,0x40);
04396 SETU8(msg, *i, (uint8_t)0x00);
04397 SETU8(msg, *i, (uint8_t)0x09);
04398
04399 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, 0, false);
04400 msg[rec]=msg[rec]|option;
04401
04402 SETU32(msg, *i, accessPassword);
04403 SETU8(msg, *i, lockBits);
04404 }
04405
04416 TMR_Status TMR_SR_cmdHiggs3BlockReadLock(TMR_Reader *reader, uint16_t timeout,
04417 TMR_GEN2_Password accessPassword, uint8_t lockBits, TMR_TagFilter* target)
04418 {
04419 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04420 uint8_t i;
04421 i = 2;
04422
04423 TMR_SR_msgAddHiggs3BlockReadLock(msg, &i, timeout, accessPassword, lockBits, target);
04424 msg[1] = i - 3;
04425
04426 return TMR_SR_sendTimeout(reader, msg, timeout);
04427 }
04428
04435 void TMR_SR_msgAddNXPSetReadProtect(uint8_t *msg, uint8_t *i, uint16_t timeout,
04436 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_TagFilter* target)
04437 {
04438 uint8_t option=0,rec;
04439
04440 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04441 SETU16(msg, *i, timeout);
04442 SETU8(msg, *i, (uint8_t)chip);
04443
04444 rec=*i;
04445 SETU8(msg,*i,0x40);
04446 SETU8(msg, *i, (uint8_t)0x00);
04447 SETU8(msg, *i, (uint8_t)0x01);
04448 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, 0, false);
04449 msg[rec]=msg[rec]|option;
04450
04451 SETU32(msg, *i, accessPassword);
04452 }
04453
04455 void TMR_SR_msgAddNXPResetReadProtect(uint8_t *msg, uint8_t *i, uint16_t timeout,
04456 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_TagFilter* target)
04457 {
04458 uint8_t option=0,rec;
04459
04460 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04461 SETU16(msg, *i, timeout);
04462 SETU8(msg, *i, (uint8_t)chip);
04463
04464 rec=*i;
04465 SETU8(msg,*i,0x40);
04466 SETU8(msg, *i, (uint8_t)0x00);
04467 SETU8(msg, *i, (uint8_t)0x02);
04468 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, 0, false);
04469 msg[rec]=msg[rec]|option;
04470
04471 SETU32(msg, *i, accessPassword);
04472 }
04473
04484 TMR_Status TMR_SR_cmdNxpSetReadProtect(TMR_Reader *reader, uint16_t timeout,
04485 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_TagFilter* target)
04486 {
04487 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04488 uint8_t i;
04489 i = 2;
04490
04491 TMR_SR_msgAddNXPSetReadProtect(msg, &i, timeout, chip, accessPassword, target);
04492 msg[1] = i - 3;
04493
04494 return TMR_SR_sendTimeout(reader, msg, timeout);
04495 }
04496
04507 TMR_Status TMR_SR_cmdNxpResetReadProtect(TMR_Reader *reader, uint16_t timeout,
04508 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_TagFilter* target)
04509 {
04510 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04511 uint8_t i;
04512 i = 2;
04513
04514 TMR_SR_msgAddNXPResetReadProtect(msg, &i, timeout, chip, accessPassword, target);
04515 msg[1] = i - 3;
04516
04517 return TMR_SR_sendTimeout(reader, msg, timeout);
04518 }
04519
04521 void TMR_SR_msgAddNXPChangeEAS(uint8_t *msg, uint8_t *i, uint16_t timeout,
04522 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, bool reset, TMR_TagFilter* target)
04523 {
04524 uint8_t option=0,rec;
04525
04526 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04527 SETU16(msg, *i, timeout);
04528 SETU8(msg, *i, (uint8_t)chip);
04529
04530 rec=*i;
04531 SETU8(msg,*i,0x40);
04532 SETU8(msg, *i, (uint8_t)0x00);
04533 SETU8(msg, *i, (uint8_t)0x03);
04534
04535 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, 0, false);
04536 msg[rec]=msg[rec]|option;
04537
04538 SETU32(msg, *i, accessPassword);
04539 if(reset)
04540 {
04541 SETU8(msg, *i, (uint8_t)0x02);
04542 }
04543 else
04544 {
04545 SETU8(msg, *i, (uint8_t)0x01);
04546 }
04547 }
04548
04560 TMR_Status TMR_SR_cmdNxpChangeEas(TMR_Reader *reader, uint16_t timeout,
04561 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, bool reset, TMR_TagFilter* target)
04562 {
04563 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04564 uint8_t i;
04565 i = 2;
04566
04567 TMR_SR_msgAddNXPChangeEAS(msg, &i, timeout, chip, accessPassword, reset, target);
04568 msg[1] = i - 3;
04569
04570 return TMR_SR_sendTimeout(reader, msg, timeout);
04571 }
04572
04574 void TMR_SR_msgAddNXPEASAlarm(uint8_t *msg, uint8_t *i, uint16_t timeout,
04575 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_DivideRatio dr, TMR_GEN2_TagEncoding m, TMR_GEN2_TrExt trExt, TMR_TagFilter* target)
04576 {
04577 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04578 SETU16(msg, *i, timeout);
04579 SETU8(msg, *i, (uint8_t)chip);
04580
04581 SETU8(msg,*i,0x40);
04582 SETU8(msg, *i, (uint8_t)0x00);
04583 SETU8(msg, *i, (uint8_t)0x04);
04584
04585 SETU8(msg, *i, (uint8_t)dr);
04586 SETU8(msg, *i, (uint8_t)m);
04587 SETU8(msg, *i, (uint8_t)trExt);
04588 }
04589
04603 TMR_Status TMR_SR_cmdNxpEasAlarm(TMR_Reader *reader, uint16_t timeout,
04604 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_DivideRatio dr, TMR_GEN2_TagEncoding m, TMR_GEN2_TrExt trExt,
04605 TMR_uint8List *data, TMR_TagFilter* target)
04606 {
04607 TMR_Status ret;
04608 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04609 uint8_t i;
04610 i = 2;
04611
04612 if (NULL != target)
04613 {
04614 return TMR_ERROR_UNSUPPORTED;
04615 }
04616 TMR_SR_msgAddNXPEASAlarm(msg, &i, timeout, chip, dr, m, trExt, target);
04617 msg[1] = i - 3;
04618
04619 ret = TMR_SR_sendTimeout(reader, msg, timeout);
04620 if (TMR_SUCCESS != ret)
04621 {
04622 return ret;
04623 }
04624
04625
04626
04627
04628
04629
04630 i = 9;
04631 if (NULL != data)
04632 {
04633 uint16_t copyLength;
04634
04635 copyLength = msg[1] + 5 - i;
04636 memcpy(data->list, &msg[i], copyLength);
04637 data->len = copyLength;
04638 }
04639
04640 return TMR_SUCCESS;
04641 }
04642
04644 void TMR_SR_msgAddNXPCalibrate(uint8_t *msg, uint8_t *i, uint16_t timeout,
04645 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_TagFilter* target)
04646 {
04647 uint8_t option=0,rec;
04648
04649 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04650 SETU16(msg, *i, timeout);
04651 SETU8(msg, *i, (uint8_t)chip);
04652
04653 rec=*i;
04654 SETU8(msg,*i,0x40);
04655 SETU8(msg, *i, (uint8_t)0x00);
04656 SETU8(msg, *i, (uint8_t)0x05);
04657
04658 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, 0, false);
04659 msg[rec]=msg[rec]|option;
04660
04661 SETU32(msg, *i, accessPassword);
04662 }
04674 TMR_Status TMR_SR_cmdNxpCalibrate(TMR_Reader *reader, uint16_t timeout,
04675 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_uint8List *data, TMR_TagFilter* target)
04676 {
04677 TMR_Status ret;
04678 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04679 uint8_t i;
04680 i = 2;
04681
04682 TMR_SR_msgAddNXPCalibrate(msg, &i, timeout, chip, accessPassword, target);
04683 msg[1] = i - 3;
04684
04685 ret = TMR_SR_sendTimeout(reader, msg, timeout);
04686 if (TMR_SUCCESS != ret)
04687 {
04688 return ret;
04689 }
04690
04691
04692
04693
04694
04695
04696 i = 9;
04697 if (NULL != data)
04698 {
04699 uint16_t copyLength;
04700
04701 copyLength = msg[1] + 5 - i;
04702 memcpy(data->list, &msg[i], copyLength);
04703 data->len = copyLength;
04704 }
04705
04706 return TMR_SUCCESS;
04707 }
04708
04710 void TMR_SR_msgAddNXPChangeConfig(uint8_t *msg, uint8_t *i, uint16_t timeout,
04711 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_NXP_ConfigWord configWord, TMR_TagFilter* target)
04712 {
04713
04714 uint8_t option=0,rec;
04715
04716 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04717 SETU16(msg, *i, timeout);
04718 SETU8(msg, *i, (uint8_t)chip);
04719 rec=*i;
04720 SETU8(msg,*i,0x40);
04721 SETU8(msg, *i, (uint8_t)0x00);
04722 SETU8(msg, *i, (uint8_t)0x07);
04723 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
04724 msg[rec]=msg[rec]|option;
04725 SETU8(msg, *i, (uint8_t)0x00);
04726 SETU16(msg, *i, configWord.data);
04727 }
04728
04741 TMR_Status TMR_SR_cmdNxpChangeConfig(TMR_Reader *reader, uint16_t timeout,
04742 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_NXP_ConfigWord configWord,
04743 TMR_uint8List *data, TMR_TagFilter* target)
04744 {
04745 TMR_Status ret;
04746 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04747 uint8_t i;
04748 i = 2;
04749
04750 if (chip == TMR_SR_GEN2_NXP_G2X_SILICON)
04751 {
04752
04753 return TMR_ERROR_UNSUPPORTED;
04754 }
04755
04756 TMR_SR_msgAddNXPChangeConfig(msg, &i, timeout, chip, accessPassword, configWord, target);
04757 msg[1] = i - 3;
04758
04759 ret = TMR_SR_sendTimeout(reader, msg, timeout);
04760 if (TMR_SUCCESS != ret)
04761 {
04762 return ret;
04763 }
04764
04765
04766 i = 9;
04767
04768
04769
04770 {
04771 uint16_t copyLength;
04772
04773 copyLength = msg[1] + 5 - i;
04774 if (NULL != data)
04775 {
04776 memcpy(data->list, &msg[i], copyLength);
04777 data->len = copyLength;
04778 }
04779 }
04780 return TMR_SUCCESS;
04781 }
04782
04783 void TMR_SR_msgAddGen2v2NxpUntraceable(uint8_t *msg, uint8_t *i, uint16_t timeout,
04784 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, uint16_t configWord,
04785 TMR_TagOp_GEN2_NXP_Untraceable op ,TMR_TagFilter* target)
04786 {
04787 uint8_t option=0,rec;
04788 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04789 SETU16(msg, *i, timeout);
04790 SETU8(msg, *i, (uint8_t)chip);
04791 rec=*i;
04792 SETU8(msg,*i,0x00);
04793 SETU8(msg, *i, (uint8_t)op.subCommand);
04794 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, false);
04795 msg[rec]=msg[rec]|option;
04796 SETU16(msg, *i, configWord);
04797 if(op.subCommand == 0x02)
04798 {
04799 SETU8(msg,*i, op.auth.tam1Auth.Authentication);
04800 SETU8(msg,*i,op.auth.tam1Auth.CSI);
04801 SETU8(msg,*i,op.auth.tam1Auth.keyID);
04802 SETU8(msg,*i,op.auth.tam1Auth.KeyLength);
04803 {
04804 uint32_t iWord;
04805 for (iWord = 0; iWord < op.auth.tam1Auth.Key.len; iWord++)
04806 {
04807 SETU8(msg, *i, (op.auth.tam1Auth.Key.list[iWord]));
04808
04809 }
04810 }
04811 SETU8(msg,*i,op.auth.tam1Auth.IchallengeLength);
04812 {
04813 uint32_t iWord;
04814 for (iWord = 0; iWord < op.auth.tam1Auth.Ichallenge.len; iWord++)
04815 {
04816 SETU8(msg, *i, (op.auth.tam1Auth.Ichallenge.list[iWord]));
04817
04818 }
04819 }
04820 }
04821 else
04822 {
04823 SETU32(msg, *i,op.auth.accessPassword);
04824 }
04825 }
04826
04827 TMR_Status TMR_SR_cmdGen2v2NXPUntraceable(TMR_Reader *reader, uint16_t timeout,
04828 TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, uint16_t configWord,
04829 TMR_TagOp_GEN2_NXP_Untraceable op,TMR_uint8List *data, TMR_TagFilter* target)
04830 {
04831 TMR_Status ret;
04832 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04833 uint8_t i;
04834 i = 2;
04835
04836 TMR_SR_msgAddGen2v2NxpUntraceable(msg, &i, timeout, chip, accessPassword, configWord, op ,target);
04837 msg[1] = i - 3;
04838
04839 ret = TMR_SR_sendTimeout(reader, msg, timeout);
04840 if (TMR_SUCCESS != ret)
04841 {
04842 return ret;
04843 }
04844 return TMR_SUCCESS;
04845 }
04846 uint8_t getCmdProtModeBlockCount(uint8_t protMode, uint8_t blockCount)
04847 {
04848 uint8_t protModeBlockCount = 0x01;
04849 uint16_t mask = 0x0F;
04850 int pos = 4;
04851 protModeBlockCount |= ((blockCount & mask) << pos);
04852
04853 return protModeBlockCount;
04854 }
04855 uint16_t getCmdProfileOffset(uint16_t profile, uint16_t offset)
04856 {
04857 uint16_t profileOffset = 0x0000;
04858 uint16_t mask;
04859 int pos;
04860
04861 mask = 0xF;
04862 pos = 12;
04863 profileOffset |= ((profile & mask) << pos);
04864
04865 mask = 0xFFF;
04866 pos = 0;
04867 profileOffset |= ((offset & mask) << pos);
04868
04869 return profileOffset;
04870 }
04871 void TMR_SR_msgAddGen2v2NxpAuthenticate(uint8_t *msg, uint8_t *i, uint16_t timeout,TMR_SR_GEN2_SiliconType chip,
04872 TMR_GEN2_Password accessPassword,TMR_TagOp_GEN2_NXP_Authenticate op ,TMR_TagFilter* target)
04873 {
04874 uint8_t option=0,rec;
04875 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04876 SETU16(msg, *i, timeout);
04877 SETU8(msg, *i, (uint8_t)chip);
04878 rec=*i;
04879 SETU8(msg,*i,0x00);
04880 SETU8(msg, *i, (uint8_t)op.subCommand);
04881 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, false);
04882 msg[rec]=msg[rec]|option;
04883 SETU8(msg,*i, op.tam1Auth.Authentication);
04884 SETU8(msg,*i,op.tam1Auth.CSI);
04885 SETU8(msg,*i,op.tam1Auth.keyID);
04886 SETU8(msg,*i,op.tam1Auth.KeyLength);
04887 {
04888 uint8_t iWord;
04889 for (iWord = 0; iWord < op.tam1Auth.Key.len; iWord++)
04890 {
04891 SETU8(msg, *i, (op.tam1Auth.Key.list[iWord]));
04892 }
04893 }
04894 SETU8(msg,*i,op.tam1Auth.IchallengeLength);
04895 {
04896 uint8_t iWord;
04897 for (iWord = 0; iWord < op.tam1Auth.Ichallenge.len; iWord++)
04898 {
04899 SETU8(msg, *i, (op.tam1Auth.Ichallenge.list[iWord]));
04900 }
04901 }
04902 if(op.type == TAM2_AUTHENTICATION)
04903 {
04904 SETU16(msg, *i, getCmdProfileOffset(op.tam2Auth.profile,op.tam2Auth.Offset));
04905 SETU8(msg, *i, getCmdProtModeBlockCount(op.tam2Auth.ProtMode,op.tam2Auth.BlockCount));
04906 }
04907 }
04908
04909 TMR_Status TMR_SR_cmdGen2v2NXPAuthenticate(TMR_Reader *reader, uint16_t timeout,TMR_SR_GEN2_SiliconType chip,
04910 TMR_GEN2_Password accessPassword, TMR_TagOp_GEN2_NXP_Authenticate op, TMR_uint8List *data, TMR_TagFilter* target)
04911 {
04912 TMR_Status ret;
04913 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
04914 uint8_t i;
04915 i = 2;
04916
04917 TMR_SR_msgAddGen2v2NxpAuthenticate(msg, &i, timeout, chip, accessPassword, op ,target);
04918 msg[1] = i - 3;
04919
04920 ret = TMR_SR_sendTimeout(reader, msg, timeout);
04921
04922 if (TMR_SUCCESS != ret)
04923 {
04924 return ret;
04925 }
04926
04927 if (NULL != data->list)
04928 {
04929 i = 8;
04930 {
04931 uint16_t dataLength;
04932 uint16_t copyLength;
04933
04934 copyLength = dataLength = msg[1] + 5 - i;
04935 if (copyLength > data->max)
04936 {
04937 copyLength = data->max;
04938 }
04939 data->len = copyLength;
04940 memcpy(data->list, &msg[i], copyLength);
04941 i += dataLength;
04942 }
04943 }
04944 return TMR_SUCCESS;
04945 }
04946 uint16_t getCmdWordPointer(uint16_t wordPointer)
04947 {
04948 uint16_t rdBufferWordPointer = 0x0000;
04949 if (wordPointer > 0)
04950 {
04951 uint16_t mask = 0x0FFF;
04952 int pos = 0;
04953 rdBufferWordPointer |= ((wordPointer & mask) << pos);
04954 }
04955 return rdBufferWordPointer;
04956 }
04957 uint16_t getCmdBitCount(uint16_t bitCount)
04958 {
04959 uint16_t rdBufferBitCount = 0x0000;
04960 if (bitCount > 0)
04961 {
04962 uint16_t mask = 0x0FFF;
04963 int pos = 0;
04964 rdBufferBitCount |= ((bitCount & mask) << pos);
04965 }
04966 return rdBufferBitCount;
04967 }
04968 void TMR_SR_msgAddGen2v2NxpReadBuffer(uint8_t *msg, uint8_t *i, uint16_t timeout,TMR_SR_GEN2_SiliconType chip,
04969 TMR_GEN2_Password accessPassword,TMR_TagOp_GEN2_NXP_Readbuffer op ,TMR_TagFilter* target)
04970 {
04971 uint8_t option=0,rec;
04972 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
04973 SETU16(msg, *i, timeout);
04974 SETU8(msg, *i, (uint8_t)chip);
04975 rec=*i;
04976 SETU8(msg,*i,0x00);
04977 SETU8(msg, *i, (uint8_t)op.authenticate.subCommand);
04978 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, false);
04979 msg[rec]=msg[rec]|option;
04980 SETU16(msg, *i, getCmdWordPointer(op.wordPointer));
04981 SETU16(msg, *i, getCmdBitCount(op.bitCount));
04982 SETU8(msg,*i, op.authenticate.tam1Auth.Authentication);
04983 SETU8(msg,*i,op.authenticate.tam1Auth.CSI);
04984 SETU8(msg,*i,op.authenticate.tam1Auth.keyID);
04985 SETU8(msg,*i,op.authenticate.tam1Auth.KeyLength);
04986 {
04987 uint8_t iWord;
04988 for (iWord = 0; iWord < op.authenticate.tam1Auth.Key.len; iWord++)
04989 {
04990 SETU8(msg, *i, (op.authenticate.tam1Auth.Key.list[iWord]));
04991 }
04992 }
04993 SETU8(msg,*i,op.authenticate.tam1Auth.IchallengeLength);
04994 {
04995 uint8_t iWord;
04996 for (iWord = 0; iWord < op.authenticate.tam1Auth.Ichallenge.len; iWord++)
04997 {
04998 SETU8(msg, *i, (op.authenticate.tam1Auth.Ichallenge.list[iWord]));
04999 }
05000 }
05001 if(op.authenticate.type == TAM2_AUTHENTICATION)
05002 {
05003 SETU16(msg, *i, getCmdProfileOffset(op.authenticate.tam2Auth.profile,op.authenticate.tam2Auth.Offset));
05004 SETU8(msg, *i, getCmdProtModeBlockCount(op.authenticate.tam2Auth.ProtMode,op.authenticate.tam2Auth.BlockCount));
05005 }
05006 }
05007
05008 TMR_Status TMR_SR_cmdGen2v2NXPReadBuffer(TMR_Reader *reader, uint16_t timeout,TMR_SR_GEN2_SiliconType chip,
05009 TMR_GEN2_Password accessPassword, TMR_TagOp_GEN2_NXP_Readbuffer op, TMR_uint8List *data, TMR_TagFilter* target)
05010 {
05011 TMR_Status ret;
05012 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05013 uint8_t i;
05014 i = 2;
05015
05016 TMR_SR_msgAddGen2v2NxpReadBuffer(msg, &i, timeout, chip, accessPassword, op ,target);
05017 msg[1] = i - 3;
05018
05019 ret = TMR_SR_sendTimeout(reader, msg, timeout);
05020 if (TMR_SUCCESS != ret)
05021 {
05022 return ret;
05023 }
05024 if (NULL != data->list)
05025 {
05026 i = 8;
05027 {
05028 uint16_t dataLength;
05029 uint16_t copyLength;
05030
05031 copyLength = dataLength = msg[1] + 5 - i;
05032 if (copyLength > data->max)
05033 {
05034 copyLength = data->max;
05035 }
05036 data->len = copyLength;
05037 memcpy(data->list, &msg[i], copyLength);
05038 i += dataLength;
05039 }
05040 }
05041 return TMR_SUCCESS;
05042 }
05049 void TMR_SR_msgAddMonza4QTReadWrite(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05050 TMR_Monza4_ControlByte controlByte, TMR_Monza4_Payload payload, TMR_TagFilter* target)
05051 {
05052 uint8_t option=0,rec;
05053
05054 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05055 SETU16(msg, *i, timeout);
05056 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IMPINJ_MONZA4_SILICON);
05057 rec=*i;
05058 SETU8(msg,*i,0x40);
05059 SETU8(msg, *i, (uint8_t)0x00);
05060 SETU8(msg, *i, (uint8_t)0x00);
05061 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05062 msg[rec]=msg[rec]|option;
05063 SETU8(msg, *i, controlByte.data);
05064 SETU16(msg, *i, payload.data);
05065 }
05066
05081 TMR_Status TMR_SR_cmdMonza4QTReadWrite(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
05082 TMR_Monza4_ControlByte controlByte, TMR_Monza4_Payload payload, TMR_uint8List *data, TMR_TagFilter* target)
05083 {
05084 TMR_Status ret;
05085 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05086 uint8_t i;
05087 i = 2;
05088
05089 TMR_SR_msgAddMonza4QTReadWrite(msg, &i, timeout, accessPassword, controlByte, payload, target);
05090 msg[1] = i - 3;
05091
05092 ret = TMR_SR_sendTimeout(reader, msg, timeout);
05093 if (TMR_SUCCESS != ret)
05094 {
05095 return ret;
05096 }
05097
05098
05099 i = 9;
05100
05101
05102
05103 {
05104 uint16_t copyLength;
05105
05106 copyLength = msg[1] + 5 - i;
05107 if (NULL != data)
05108 {
05109 memcpy(data->list, &msg[i], copyLength);
05110 data->len = copyLength;
05111 }
05112 }
05113 return TMR_SUCCESS;
05114
05115 }
05116
05125 void TMR_SR_msgAddIdsSL900aGetBatteryLevel(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05126 uint8_t CommandCode, uint32_t password, PasswordLevel level, BatteryType batteryType,
05127 TMR_TagFilter* target)
05128 {
05129 uint8_t option = 0, rec;
05130
05131 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05132 SETU16(msg, *i, timeout);
05133 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05134 rec = *i;
05135 SETU8(msg,*i,0x40);
05136 SETU8(msg, *i, (uint8_t)0x00);
05137 SETU8(msg, *i, (uint8_t)CommandCode);
05138 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05139 msg[rec]=msg[rec]|option;
05140 SETU8(msg, *i, (uint8_t)level);
05141 SETU32(msg, *i, password);
05142 SETU8(msg, *i, batteryType);
05143 }
05144
05157 TMR_Status
05158 TMR_SR_cmdSL900aGetBatteryLevel(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
05159 uint8_t CommandCode, uint32_t password, PasswordLevel level,BatteryType type,
05160 TMR_uint8List *data, TMR_TagFilter* target)
05161 {
05162 TMR_Status ret;
05163 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05164 uint8_t i;
05165 i = 2;
05166
05167 TMR_SR_msgAddIdsSL900aGetBatteryLevel(msg, &i, timeout, accessPassword, CommandCode, password, level, type, target);
05168 msg[1] = i - 3;
05169
05170 ret = TMR_SR_sendTimeout(reader, msg, timeout);
05171 if (TMR_SUCCESS != ret)
05172 {
05173 return ret;
05174 }
05175
05176
05177 i = 9;
05178
05179
05180
05181 {
05182 uint16_t copyLength;
05183
05184 copyLength = msg[1] + 5 - i;
05185 if (NULL != data)
05186 {
05187 memcpy(data->list, &msg[i], copyLength);
05188 data->len = copyLength;
05189 }
05190 }
05191 return TMR_SUCCESS;
05192 }
05193
05197 void TMR_SR_msgAddIdsSL900aGetSensorValue(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05198 uint8_t CommandCode, uint32_t password, PasswordLevel level, Sensor sensortype,
05199 TMR_TagFilter* target)
05200 {
05201 uint8_t option = 0, rec;
05202
05203 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05204 SETU16(msg, *i, timeout);
05205 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05206 rec = *i;
05207 SETU8(msg,*i,0x40);
05208 SETU8(msg, *i, (uint8_t)0x00);
05209 SETU8(msg, *i, (uint8_t)CommandCode);
05210 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05211 msg[rec]=msg[rec]|option;
05212 SETU8(msg, *i, (uint8_t)level);
05213 SETU32(msg, *i, password);
05214 SETU8(msg, *i, sensortype);
05215 }
05216
05229 TMR_Status
05230 TMR_SR_cmdSL900aGetSensorValue(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
05231 uint8_t CommandCode, uint32_t password, PasswordLevel level,Sensor sensortype,
05232 TMR_uint8List *data, TMR_TagFilter* target)
05233 {
05234 TMR_Status ret;
05235 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05236 uint8_t i;
05237 i = 2;
05238
05239 TMR_SR_msgAddIdsSL900aGetSensorValue(msg, &i, timeout, accessPassword, CommandCode, password, level, sensortype, target);
05240 msg[1] = i - 3;
05241
05242 ret = TMR_SR_sendTimeout(reader, msg, timeout);
05243 if (TMR_SUCCESS != ret)
05244 {
05245 return ret;
05246 }
05247
05248
05249 i = 9;
05250
05251
05252
05253 {
05254 uint16_t copyLength;
05255
05256 copyLength = msg[1] + 5 - i;
05257 if (NULL != data)
05258 {
05259 memcpy(data->list, &msg[i], copyLength);
05260 data->len = copyLength;
05261 }
05262 }
05263 return TMR_SUCCESS;
05264 }
05265
05269 void TMR_SR_msgAddIdsSL900aGetMeasurementSetup(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05270 uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_TagFilter* target)
05271 {
05272 uint8_t option = 0, rec;
05273
05274 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05275 SETU16(msg, *i, timeout);
05276 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05277 rec = *i;
05278 SETU8(msg,*i,0x40);
05279 SETU8(msg, *i, (uint8_t)0x00);
05280 SETU8(msg, *i, (uint8_t)CommandCode);
05281 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05282 msg[rec]=msg[rec]|option;
05283 SETU8(msg, *i, (uint8_t)level);
05284 SETU32(msg, *i, password);
05285 }
05286
05299 TMR_Status
05300 TMR_SR_cmdSL900aGetMeasurementSetup(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
05301 uint8_t CommandCode, uint32_t password, PasswordLevel level,
05302 TMR_uint8List *data, TMR_TagFilter* target)
05303 {
05304 TMR_Status ret;
05305 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05306 uint8_t i;
05307 i = 2;
05308
05309 TMR_SR_msgAddIdsSL900aGetMeasurementSetup(msg, &i, timeout, accessPassword, CommandCode, password, level, target);
05310 msg[1] = i - 3;
05311
05312 ret = TMR_SR_sendTimeout(reader, msg, timeout);
05313 if (TMR_SUCCESS != ret)
05314 {
05315 return ret;
05316 }
05317
05318
05319 i = 9;
05320
05321
05322
05323 {
05324 uint16_t copyLength;
05325
05326 copyLength = msg[1] + 5 - i;
05327 if (NULL != data)
05328 {
05329 memcpy(data->list, &msg[i], copyLength);
05330 data->len = copyLength;
05331 }
05332 }
05333 return TMR_SUCCESS;
05334 }
05335
05339 void TMR_SR_msgAddIdsSL900aGetLogState(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05340 uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_TagFilter* target)
05341 {
05342 uint8_t option = 0, rec;
05343
05344 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05345 SETU16(msg, *i, timeout);
05346 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05347 rec = *i;
05348 SETU8(msg,*i,0x40);
05349 SETU8(msg, *i, (uint8_t)0x00);
05350 SETU8(msg, *i, (uint8_t)CommandCode);
05351 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05352 msg[rec]=msg[rec]|option;
05353 SETU8(msg, *i, (uint8_t)level);
05354 SETU32(msg, *i, password);
05355 }
05356
05370 TMR_Status
05371 TMR_SR_cmdSL900aGetLogState(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
05372 uint8_t CommandCode, uint32_t password, PasswordLevel level,TMR_uint8List *data,
05373 TMR_TagFilter* target)
05374 {
05375 TMR_Status ret;
05376 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05377 uint8_t i;
05378 i = 2;
05379
05380 TMR_SR_msgAddIdsSL900aGetLogState(msg, &i, timeout, accessPassword, CommandCode, password, level, target);
05381 msg[1] = i - 3;
05382
05383 ret = TMR_SR_sendTimeout(reader, msg, timeout);
05384 if (TMR_SUCCESS != ret)
05385 {
05386 return ret;
05387 }
05388
05389
05390 i = 9;
05391
05392
05393
05394 {
05395 uint16_t copyLength;
05396
05397 copyLength = msg[1] + 5 - i;
05398 if (NULL != data)
05399 {
05400 memcpy(data->list, &msg[i], copyLength);
05401 data->len = copyLength;
05402 }
05403 }
05404 return TMR_SUCCESS;
05405 }
05406
05410 void TMR_SR_msgAddIdsSL900aSetLogMode(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05411 uint8_t CommandCode, uint32_t password, PasswordLevel level, LoggingForm form,
05412 StorageRule rule, bool Ext1Enable, bool Ext2Enable, bool TempEnable, bool BattEnable,
05413 uint16_t LogInterval, TMR_TagFilter* target)
05414 {
05415 uint8_t option = 0, rec;
05416 uint32_t logmode = 0;
05417
05418 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05419 SETU16(msg, *i, timeout);
05420 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05421 rec = *i;
05422 SETU8(msg,*i,0x40);
05423 SETU8(msg, *i, (uint8_t)0x00);
05424 SETU8(msg, *i, (uint8_t)CommandCode);
05425 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05426 msg[rec]=msg[rec]|option;
05427 SETU8(msg, *i, (uint8_t)level);
05428 SETU32(msg, *i, password);
05429
05430 logmode |= (uint32_t)form << 21;
05431 logmode |= (uint32_t)rule << 20;
05432 logmode |= (uint32_t)(Ext1Enable ? 1 : 0) << 19;
05433 logmode |= (uint32_t)(Ext2Enable ? 1 : 0) << 18;
05434 logmode |= (uint32_t)(TempEnable ? 1 : 0) << 17;
05435 logmode |= (uint32_t)(BattEnable ? 1 : 0) << 16;
05436 logmode |= (uint32_t)LogInterval << 1;
05437 SETU8(msg, *i, (uint8_t)((logmode >> 16) & 0xFF));
05438 SETU8(msg, *i, (uint8_t)((logmode >> 8) & 0xFF));
05439 SETU8(msg, *i, (uint8_t)((logmode >> 0) & 0xFF));
05440 }
05441
05461 TMR_Status
05462 TMR_SR_cmdSL900aSetLogMode(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
05463 uint8_t CommandCode, uint32_t password, PasswordLevel level, LoggingForm form,
05464 StorageRule rule, bool Ext1Enable, bool Ext2Enable, bool TempEnable, bool BattEnable,
05465 uint16_t LogInterval, TMR_TagFilter* target)
05466 {
05467 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05468 uint8_t i;
05469 i = 2;
05470
05471 TMR_SR_msgAddIdsSL900aSetLogMode(msg, &i, timeout, accessPassword, CommandCode, password, level, form,
05472 rule, Ext1Enable, Ext2Enable, TempEnable, BattEnable, LogInterval, target);
05473
05474 msg[1] = i - 3;
05475
05476 return TMR_SR_sendTimeout(reader, msg, timeout);
05477 }
05478
05479
05480 void TMR_SR_msgAddIdsSL900aInitialize(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05481 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t delayTime,
05482 uint16_t applicatioData, TMR_TagFilter* target)
05483 {
05484 uint8_t option = 0, rec;
05485
05486 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05487 SETU16(msg, *i, timeout);
05488 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05489 rec = *i;
05490 SETU8(msg,*i,0x40);
05491 SETU8(msg, *i, (uint8_t)0x00);
05492 SETU8(msg, *i, (uint8_t)CommandCode);
05493 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05494 msg[rec]=msg[rec]|option;
05495 SETU8(msg, *i, (uint8_t)level);
05496 SETU32(msg, *i, password);
05497 SETU16(msg, *i, delayTime);
05498 SETU16(msg, *i, applicatioData);
05499 }
05500
05514 TMR_Status
05515 TMR_SR_cmdSL900aInitialize(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
05516 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t delayTime,
05517 uint16_t applicationData, TMR_TagFilter* target)
05518 {
05519 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05520 uint8_t i;
05521 i = 2;
05522
05523 TMR_SR_msgAddIdsSL900aInitialize(msg, &i, timeout, accessPassword, CommandCode, password, level, delayTime,
05524 applicationData, target);
05525
05526 msg[1] = i - 3;
05527
05528 return TMR_SR_sendTimeout(reader, msg, timeout);
05529 }
05530
05534 void TMR_SR_msgAddIdsSL900aEndLog(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05535 uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_TagFilter* target)
05536 {
05537 uint8_t option = 0, rec;
05538
05539 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05540 SETU16(msg, *i, timeout);
05541 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05542 rec = *i;
05543 SETU8(msg,*i,0x40);
05544 SETU8(msg, *i, (uint8_t)0x00);
05545 SETU8(msg, *i, (uint8_t)CommandCode);
05546 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05547 msg[rec]=msg[rec]|option;
05548 SETU8(msg, *i, (uint8_t)level);
05549 SETU32(msg, *i, password);
05550 }
05551
05564 TMR_Status
05565 TMR_SR_cmdSL900aEndLog(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
05566 uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_TagFilter* target)
05567 {
05568 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05569 uint8_t i;
05570 i = 2;
05571
05572 TMR_SR_msgAddIdsSL900aEndLog(msg, &i, timeout, accessPassword, CommandCode, password, level, target);
05573 msg[1] = i - 3;
05574
05575 return TMR_SR_sendTimeout(reader, msg, timeout);
05576 }
05577
05581 void TMR_SR_msgAddIdsSL900aSetPassword(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05582 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint32_t newPassword,
05583 PasswordLevel newPasswordLevel, TMR_TagFilter* target)
05584 {
05585 uint8_t option = 0, rec;
05586
05587 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05588 SETU16(msg, *i, timeout);
05589 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05590 rec = *i;
05591 SETU8(msg,*i,0x40);
05592 SETU8(msg, *i, (uint8_t)0x00);
05593 SETU8(msg, *i, (uint8_t)CommandCode);
05594 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05595 msg[rec]=msg[rec]|option;
05596 SETU8(msg, *i, (uint8_t)level);
05597 SETU32(msg, *i, password);
05598 SETU8(msg, *i, (uint8_t)newPasswordLevel);
05599 SETU32(msg, *i, newPassword);
05600 }
05601
05614 TMR_Status
05615 TMR_SR_cmdSL900aSetPassword(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
05616 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint32_t newPassword,
05617 PasswordLevel newPasswordLevel, TMR_TagFilter* target)
05618 {
05619 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05620 uint8_t i;
05621 i = 2;
05622
05623 TMR_SR_msgAddIdsSL900aSetPassword(msg, &i, timeout, accessPassword, CommandCode, password, level, newPassword, newPasswordLevel, target);
05624 msg[1] = i - 3;
05625
05626 return TMR_SR_sendTimeout(reader, msg, timeout);
05627 }
05628
05632 void TMR_SR_msgAddIdsSL900aAccessFifoStatus(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05633 uint8_t CommandCode, uint32_t password, PasswordLevel level, AccessFifoOperation operation,
05634 TMR_TagFilter* target)
05635 {
05636 uint8_t option = 0, rec;
05637
05638 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05639 SETU16(msg, *i, timeout);
05640 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05641 rec = *i;
05642 SETU8(msg,*i,0x40);
05643 SETU8(msg, *i, (uint8_t)0x00);
05644 SETU8(msg, *i, (uint8_t)CommandCode);
05645 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05646 msg[rec]=msg[rec]|option;
05647 SETU8(msg, *i, (uint8_t)level);
05648 SETU32(msg, *i, password);
05649 SETU8(msg, *i, (uint8_t)operation);
05650 }
05651
05664 TMR_Status
05665 TMR_SR_cmdSL900aAccessFifoStatus(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t CommandCode,
05666 uint32_t password, PasswordLevel level, AccessFifoOperation operation,TMR_uint8List *data, TMR_TagFilter* target)
05667 {
05668 TMR_Status ret;
05669 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05670 uint8_t i;
05671 i = 2;
05672
05673 TMR_SR_msgAddIdsSL900aAccessFifoStatus(msg, &i, timeout, accessPassword, CommandCode, password, level, operation, target);
05674 msg[1] = i - 3;
05675
05676 ret = TMR_SR_sendTimeout(reader, msg, timeout);
05677 if (TMR_SUCCESS != ret)
05678 {
05679 return ret;
05680 }
05681
05682
05683 i = 9;
05684
05685
05686
05687 {
05688 uint16_t copyLength;
05689
05690 copyLength = msg[1] + 5 - i;
05691 if (NULL != data)
05692 {
05693 memcpy(data->list, &msg[i], copyLength);
05694 data->len = copyLength;
05695 }
05696 }
05697 return TMR_SUCCESS;
05698 }
05699
05703 void TMR_SR_msgAddIdsSL900aAccessFifoRead(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05704 uint8_t CommandCode, uint32_t password, PasswordLevel level, AccessFifoOperation operation,
05705 uint8_t length, TMR_TagFilter* target)
05706 {
05707 uint8_t option = 0, rec;
05708
05709 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05710 SETU16(msg, *i, timeout);
05711 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05712 rec = *i;
05713 SETU8(msg,*i,0x40);
05714 SETU8(msg, *i, (uint8_t)0x00);
05715 SETU8(msg, *i, (uint8_t)CommandCode);
05716 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05717 msg[rec]=msg[rec]|option;
05718 SETU8(msg, *i, (uint8_t)level);
05719 SETU32(msg, *i, password);
05720 SETU8(msg, *i, (uint8_t)(operation | length));
05721 }
05722
05735 TMR_Status
05736 TMR_SR_cmdSL900aAccessFifoRead(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t CommandCode,
05737 uint32_t password, PasswordLevel level, AccessFifoOperation operation, uint8_t length, TMR_uint8List *data,
05738 TMR_TagFilter* target)
05739 {
05740 TMR_Status ret;
05741 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05742 uint8_t i;
05743 i = 2;
05744
05745 TMR_SR_msgAddIdsSL900aAccessFifoRead(msg, &i, timeout, accessPassword, CommandCode, password, level, operation, length, target);
05746 msg[1] = i - 3;
05747
05748 ret = TMR_SR_sendTimeout(reader, msg, timeout);
05749 if (TMR_SUCCESS != ret)
05750 {
05751 return ret;
05752 }
05753
05754
05755 i = 9;
05756
05757
05758
05759 {
05760 uint16_t copyLength;
05761
05762 copyLength = msg[1] + 5 - i;
05763 if (NULL != data)
05764 {
05765 memcpy(data->list, &msg[i], copyLength);
05766 data->len = copyLength;
05767 }
05768 }
05769 return TMR_SUCCESS;
05770 }
05771
05775 void TMR_SR_msgAddIdsSL900aAccessFifoWrite(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05776 uint8_t CommandCode, uint32_t password, PasswordLevel level, AccessFifoOperation operation,
05777 TMR_uint8List *payLoad, TMR_TagFilter* target)
05778 {
05779 uint8_t option = 0, rec;
05780
05781 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05782 SETU16(msg, *i, timeout);
05783 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05784 rec = *i;
05785 SETU8(msg,*i,0x40);
05786 SETU8(msg, *i, (uint8_t)0x00);
05787 SETU8(msg, *i, (uint8_t)CommandCode);
05788 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05789 msg[rec]=msg[rec]|option;
05790 SETU8(msg, *i, (uint8_t)level);
05791 SETU32(msg, *i, password);
05792 SETU8(msg, *i, (uint8_t)(operation | payLoad->len));
05793 memcpy(&msg[*i], payLoad->list, payLoad->len);
05794 *i += payLoad->len;
05795 }
05796
05809 TMR_Status
05810 TMR_SR_cmdSL900aAccessFifoWrite(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t CommandCode,
05811 uint32_t password, PasswordLevel level, AccessFifoOperation operation, TMR_uint8List *payLoad, TMR_uint8List *data,
05812 TMR_TagFilter* target)
05813 {
05814 TMR_Status ret;
05815 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05816 uint8_t i;
05817 i = 2;
05818
05819 TMR_SR_msgAddIdsSL900aAccessFifoWrite(msg, &i, timeout, accessPassword, CommandCode, password, level, operation, payLoad, target);
05820 msg[1] = i - 3;
05821
05822 ret = TMR_SR_sendTimeout(reader, msg, timeout);
05823 if (TMR_SUCCESS != ret)
05824 {
05825 return ret;
05826 }
05827
05828
05829 i = 9;
05830
05831
05832
05833 {
05834 uint16_t copyLength;
05835
05836 copyLength = msg[1] + 5 - i;
05837 if (NULL != data)
05838 {
05839 memcpy(data->list, &msg[i], copyLength);
05840 data->len = copyLength;
05841 }
05842 }
05843 return TMR_SUCCESS;
05844 }
05845
05849 void TMR_SR_msgAddIdsSL900aStartLog(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05850 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint32_t time, TMR_TagFilter* target)
05851 {
05852 uint8_t option = 0, rec;
05853
05854 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05855 SETU16(msg, *i, timeout);
05856 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05857 rec = *i;
05858 SETU8(msg,*i,0x40);
05859 SETU8(msg, *i, (uint8_t)0x00);
05860 SETU8(msg, *i, (uint8_t)CommandCode);
05861 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05862 msg[rec]=msg[rec]|option;
05863 SETU8(msg, *i, (uint8_t)level);
05864 SETU32(msg, *i, password);
05865 SETU32(msg, *i, time);
05866 }
05867
05880 TMR_Status
05881 TMR_SR_cmdSL900aStartLog(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t CommandCode,
05882 uint32_t password, PasswordLevel level, uint32_t time, TMR_TagFilter* target)
05883 {
05884 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05885 uint8_t i;
05886 i = 2;
05887
05888 TMR_SR_msgAddIdsSL900aStartLog(msg, &i, timeout, accessPassword, CommandCode, password, level, time, target);
05889 msg[1] = i - 3;
05890
05891 return TMR_SR_sendTimeout(reader, msg, timeout);
05892 }
05893
05897 void TMR_SR_msgAddIdsSL900aGetCalibrationData(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05898 uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_TagFilter* target)
05899 {
05900 uint8_t option = 0, rec;
05901
05902 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05903 SETU16(msg, *i, timeout);
05904 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05905 rec = *i;
05906 SETU8(msg,*i,0x40);
05907 SETU8(msg, *i, (uint8_t)0x00);
05908 SETU8(msg, *i, (uint8_t)CommandCode);
05909 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05910 msg[rec]=msg[rec]|option;
05911 SETU8(msg, *i, (uint8_t)level);
05912 SETU32(msg, *i, password);
05913 }
05914
05927 TMR_Status
05928 TMR_SR_cmdSL900aGetCalibrationData(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
05929 uint8_t CommandCode, uint32_t password, PasswordLevel level,
05930 TMR_uint8List *data, TMR_TagFilter* target)
05931 {
05932 TMR_Status ret;
05933 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
05934 uint8_t i;
05935 i = 2;
05936
05937 TMR_SR_msgAddIdsSL900aGetCalibrationData(msg, &i, timeout, accessPassword, CommandCode, password, level, target);
05938 msg[1] = i - 3;
05939
05940 ret = TMR_SR_sendTimeout(reader, msg, timeout);
05941 if (TMR_SUCCESS != ret)
05942 {
05943 return ret;
05944 }
05945
05946
05947 i = 9;
05948
05949
05950
05951 {
05952 uint16_t copyLength;
05953
05954 copyLength = msg[1] + 5 - i;
05955 if (NULL != data)
05956 {
05957 memcpy(data->list, &msg[i], copyLength);
05958 data->len = copyLength;
05959 }
05960 }
05961 return TMR_SUCCESS;
05962 }
05963
05967 void TMR_SR_msgAddIdsSL900aSetCalibrationData(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
05968 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint64_t calibration,
05969 TMR_TagFilter* target)
05970 {
05971 uint8_t option = 0, rec;
05972 uint8_t calBytes[8];
05973
05974 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
05975 SETU16(msg, *i, timeout);
05976 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
05977 rec = *i;
05978 SETU8(msg,*i,0x40);
05979 SETU8(msg, *i, (uint8_t)0x00);
05980 SETU8(msg, *i, (uint8_t)CommandCode);
05981 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
05982 msg[rec]=msg[rec]|option;
05983 SETU8(msg, *i, (uint8_t)level);
05984 SETU32(msg, *i, password);
05985
05986 calBytes[0] = (uint8_t) (calibration >> 56);
05987 calBytes[1] = (uint8_t) (calibration >> 48);
05988 calBytes[2] = (uint8_t) (calibration >> 40);
05989 calBytes[3] = (uint8_t) (calibration >> 32);
05990 calBytes[4] = (uint8_t) (calibration >> 24);
05991 calBytes[5] = (uint8_t) (calibration >> 16);
05992 calBytes[6] = (uint8_t) (calibration >> 8);
05993 calBytes[7] = (uint8_t) (calibration >> 0);
05994
05995 memcpy(&msg[*i], calBytes + 1, 7);
05996 *i += 7;
05997
05998 }
05999
06012 TMR_Status
06013 TMR_SR_cmdSL900aSetCalibrationData(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
06014 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint64_t calibration,
06015 TMR_TagFilter* target)
06016 {
06017 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06018 uint8_t i;
06019 i = 2;
06020
06021 TMR_SR_msgAddIdsSL900aSetCalibrationData(msg, &i, timeout, accessPassword, CommandCode, password, level, calibration, target);
06022 msg[1] = i - 3;
06023
06024 return TMR_SR_sendTimeout(reader, msg, timeout);
06025 }
06026
06030 void TMR_SR_msgAddIdsSL900aSetSfeParameters(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
06031 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t sfe,
06032 TMR_TagFilter* target)
06033 {
06034 uint8_t option = 0, rec;
06035
06036 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
06037 SETU16(msg, *i, timeout);
06038 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
06039 rec = *i;
06040 SETU8(msg,*i,0x40);
06041 SETU8(msg, *i, (uint8_t)0x00);
06042 SETU8(msg, *i, (uint8_t)CommandCode);
06043 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
06044 msg[rec]=msg[rec]|option;
06045 SETU8(msg, *i, (uint8_t)level);
06046 SETU32(msg, *i, password);
06047 SETU16(msg, *i, sfe);
06048 }
06049
06062 TMR_Status
06063 TMR_SR_cmdSL900aSetSfeParameters(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
06064 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t sfe,
06065 TMR_TagFilter* target)
06066 {
06067 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06068 uint8_t i;
06069 i = 2;
06070
06071 TMR_SR_msgAddIdsSL900aSetSfeParameters(msg, &i, timeout, accessPassword, CommandCode, password, level, sfe, target);
06072 msg[1] = i - 3;
06073
06074 return TMR_SR_sendTimeout(reader, msg, timeout);
06075 }
06076
06080 void TMR_SR_msgAddIdsSL900aSetLogLimit(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
06081 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t exLower,
06082 uint16_t lower, uint16_t upper, uint16_t exUpper, TMR_TagFilter* target)
06083 {
06084 uint8_t option = 0, rec;
06085 uint64_t temp = 0;
06086
06087 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
06088 SETU16(msg, *i, timeout);
06089 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
06090 rec = *i;
06091 SETU8(msg,*i,0x40);
06092 SETU8(msg, *i, (uint8_t)0x00);
06093 SETU8(msg, *i, (uint8_t)CommandCode);
06094 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
06095 msg[rec]=msg[rec]|option;
06096 SETU8(msg, *i, (uint8_t)level);
06097 SETU32(msg, *i, password);
06098
06099 temp |= (uint64_t)exLower << 30;
06100 temp |= (uint64_t)lower << 20;
06101 temp |= (uint64_t)upper << 10;
06102 temp |= (uint64_t)exUpper << 0;
06103
06104 SETU8(msg, *i, (uint8_t)((temp >> 32) & 0xFF));
06105 SETU8(msg, *i, (uint8_t)((temp >> 24) & 0xFF));
06106 SETU8(msg, *i, (uint8_t)((temp >> 16) & 0xFF));
06107 SETU8(msg, *i, (uint8_t)((temp >> 8) & 0xFF));
06108 SETU8(msg, *i, (uint8_t)((temp >> 0) & 0xFF));
06109 }
06110
06126 TMR_Status
06127 TMR_SR_cmdSL900aSetLogLimit(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
06128 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t exLower,
06129 uint16_t lower, uint16_t upper, uint16_t exUpper, TMR_TagFilter* target)
06130 {
06131 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06132 uint8_t i;
06133 i = 2;
06134
06135 TMR_SR_msgAddIdsSL900aSetLogLimit(msg, &i, timeout, accessPassword, CommandCode, password, level, exLower,
06136 lower, upper, exUpper, target);
06137
06138 msg[1] = i - 3;
06139
06140 return TMR_SR_sendTimeout(reader, msg, timeout);
06141 }
06142
06146 void TMR_SR_msgAddIdsSL900aSetShelfLife(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
06147 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint32_t block0, uint32_t block1,
06148 TMR_TagFilter* target)
06149 {
06150 uint8_t option = 0, rec;
06151
06152 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
06153 SETU16(msg, *i, timeout);
06154 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_IDS_SL900A_SILICON);
06155 rec = *i;
06156 SETU8(msg,*i,0x40);
06157 SETU8(msg, *i, (uint8_t)0x00);
06158 SETU8(msg, *i, (uint8_t)CommandCode);
06159 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
06160 msg[rec]=msg[rec]|option;
06161 SETU8(msg, *i, (uint8_t)level);
06162 SETU32(msg, *i, password);
06163 SETU32(msg, *i, block0);
06164 SETU32(msg, *i, block1);
06165 }
06166
06179 TMR_Status
06180 TMR_SR_cmdSL900aSetShelfLife(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
06181 uint8_t CommandCode, uint32_t password, PasswordLevel level, uint32_t block0, uint32_t block1,
06182 TMR_TagFilter* target)
06183 {
06184 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06185 uint8_t i;
06186 i = 2;
06187
06188 TMR_SR_msgAddIdsSL900aSetShelfLife(msg, &i, timeout, accessPassword, CommandCode, password, level, block0, block1, target);
06189
06190 msg[1] = i - 3;
06191
06192 return TMR_SR_sendTimeout(reader, msg, timeout);
06193 }
06194
06201 void TMR_SR_msgAddIAVDenatranCustomOp(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
06202 uint8_t mode, uint8_t payload, TMR_TagFilter* target)
06203 {
06204 uint8_t option=0,rec;
06205
06206 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
06207 SETU16(msg, *i, timeout);
06208 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_DENATRAN_IAV_SILICON);
06209 rec=*i;
06210 SETU8(msg,*i,0x40);
06211 SETU8(msg, *i, (uint8_t)0x00);
06212 SETU8(msg, *i, (uint8_t)mode);
06213 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
06214 msg[rec]=msg[rec]|option;
06215 SETU8(msg, *i, (uint8_t)payload);
06216 }
06217
06227 TMR_Status
06228 TMR_SR_cmdIAVDenatranCustomOp(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t payload,
06229 TMR_uint8List *data, TMR_TagFilter* target)
06230 {
06231 TMR_Status ret;
06232 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06233 uint8_t i;
06234 i = 2;
06235
06236 TMR_SR_msgAddIAVDenatranCustomOp(msg, &i, timeout, accessPassword, mode, payload, target);
06237 msg[1] = i - 3;
06238
06239 ret = TMR_SR_sendTimeout(reader, msg, timeout);
06240 if (TMR_SUCCESS != ret)
06241 {
06242 return ret;
06243 }
06244
06245
06246 i = 9;
06247
06248
06249
06250 {
06251 uint16_t copyLength;
06252
06253 copyLength = msg[1] + 5 - i;
06254
06255 if (copyLength > data->max)
06256 {
06257 copyLength = data->max;
06258 }
06259 if (NULL != data)
06260 {
06261 memcpy(data->list, &msg[i], copyLength);
06262 data->len = copyLength;
06263 }
06264 }
06265 return TMR_SUCCESS;
06266 }
06267
06269 void TMR_SR_msgAddIAVDenatranCustomReadFromMemMap(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
06270 uint8_t mode, uint8_t payload, TMR_TagFilter* target, uint16_t wordAddress)
06271 {
06272
06273 TMR_SR_msgAddIAVDenatranCustomOp(msg, i, timeout, accessPassword, mode, payload, target);
06274
06275 SETU16(msg, *i, wordAddress);
06276 }
06277
06287 TMR_Status
06288 TMR_SR_cmdIAVDenatranCustomReadFromMemMap(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t payload,
06289 TMR_uint8List *data, TMR_TagFilter* target, uint16_t wordAddress)
06290 {
06291 TMR_Status ret;
06292 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06293 uint8_t i;
06294 i = 2;
06295
06296 TMR_SR_msgAddIAVDenatranCustomReadFromMemMap(msg, &i, timeout, accessPassword, mode, payload, target, wordAddress);
06297 msg[1] = i - 3;
06298
06299 ret = TMR_SR_sendTimeout(reader, msg, timeout);
06300 if (TMR_SUCCESS != ret)
06301 {
06302 return ret;
06303 }
06304
06305
06306 i = 9;
06307
06308
06309
06310 {
06311 uint16_t copyLength;
06312
06313 copyLength = msg[1] + 5 - i;
06314
06315 if (copyLength > data->max)
06316 {
06317 copyLength = data->max;
06318 }
06319 if (NULL != data)
06320 {
06321 memcpy(data->list, &msg[i], copyLength);
06322 data->len = copyLength;
06323 }
06324 }
06325 return TMR_SUCCESS;
06326 }
06327
06329 void TMR_SR_msgAddIAVDenatranCustomReadSec(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
06330 uint8_t mode, uint8_t payload, TMR_TagFilter* target, uint16_t wordAddress)
06331 {
06332
06333 TMR_SR_msgAddIAVDenatranCustomOp(msg, i, timeout, accessPassword, mode, payload, target);
06334
06335 SETU16(msg, *i, wordAddress);
06336 }
06337
06347 TMR_Status
06348 TMR_SR_cmdIAVDenatranCustomReadSec(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t payload,
06349 TMR_uint8List *data, TMR_TagFilter* target, uint16_t wordAddress)
06350 {
06351 TMR_Status ret;
06352 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06353 uint8_t i;
06354 i = 2;
06355
06356 TMR_SR_msgAddIAVDenatranCustomReadSec(msg, &i, timeout, accessPassword, mode, payload, target, wordAddress);
06357 msg[1] = i - 3;
06358
06359 ret = TMR_SR_sendTimeout(reader, msg, timeout);
06360 if (TMR_SUCCESS != ret)
06361 {
06362 return ret;
06363 }
06364
06365
06366 i = 9;
06367
06368
06369
06370 {
06371 uint16_t copyLength;
06372
06373 copyLength = msg[1] + 5 - i;
06374
06375 if (copyLength > data->max)
06376 {
06377 copyLength = data->max;
06378 }
06379 if (NULL != data)
06380 {
06381 memcpy(data->list, &msg[i], copyLength);
06382 data->len = copyLength;
06383 }
06384 }
06385 return TMR_SUCCESS;
06386 }
06387
06389 void TMR_SR_msgAddIAVDenatranCustomActivateSiniavMode(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
06390 uint8_t mode, uint8_t payload, TMR_TagFilter* target, bool tokenDesc, uint8_t *token)
06391 {
06392 uint8_t j;
06393
06394 TMR_SR_msgAddIAVDenatranCustomOp(msg, i, timeout, accessPassword, mode, payload, target);
06395
06396 if (tokenDesc)
06397 {
06398 for (j = 0; j < 8; j++)
06399 {
06400 SETU8(msg, *i, token[j]);
06401 }
06402 }
06403 }
06404
06415 TMR_Status
06416 TMR_SR_cmdIAVDenatranCustomActivateSiniavMode(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t payload,
06417 TMR_uint8List *data, TMR_TagFilter* target, bool tokenDesc, uint8_t *token)
06418 {
06419 TMR_Status ret;
06420 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06421 uint8_t i;
06422 i = 2;
06423
06424 TMR_SR_msgAddIAVDenatranCustomActivateSiniavMode(msg, &i, timeout, accessPassword, mode, payload, target, tokenDesc, token);
06425 msg[1] = i - 3;
06426
06427 ret = TMR_SR_sendTimeout(reader, msg, timeout);
06428 if (TMR_SUCCESS != ret)
06429 {
06430 return ret;
06431 }
06432
06433
06434 i = 9;
06435
06436
06437
06438 {
06439 uint16_t copyLength;
06440
06441 copyLength = msg[1] + 5 - i;
06442
06443 if (copyLength > data->max)
06444 {
06445 copyLength = data->max;
06446 }
06447 if (NULL != data)
06448 {
06449 memcpy(data->list, &msg[i], copyLength);
06450 data->len = copyLength;
06451 }
06452 }
06453 return TMR_SUCCESS;
06454 }
06455
06457 void TMR_SR_msgAddIAVDenatranCustomWriteToMemMap(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
06458 uint8_t mode, uint8_t payload, TMR_TagFilter* target, uint16_t wordPtr, uint16_t wordData, uint8_t* tagId, uint8_t* dataBuf)
06459 {
06460 uint8_t j;
06461
06462 TMR_SR_msgAddIAVDenatranCustomOp(msg, i, timeout, accessPassword, mode, payload, target);
06463
06464 SETU16(msg, *i, wordPtr);
06465 SETU16(msg, *i, wordData);
06466 for (j = 0; j < 8; j++)
06467 {
06468 SETU8(msg, *i, tagId[j]);
06469 }
06470 for (j = 0; j < 16; j++)
06471 {
06472 SETU8(msg, *i, dataBuf[j]);
06473 }
06474 }
06475
06477 void TMR_SR_msgAddIAVDenatranCustomGetTokenId(uint8_t *msg, uint8_t *i, uint16_t timeout,
06478 TMR_GEN2_Password accessPassword, uint8_t mode, TMR_TagFilter* target)
06479 {
06480 uint8_t option = 0,rec;
06481
06482 SETU8(msg, *i, TMR_SR_OPCODE_WRITE_TAG_SPECIFIC);
06483 SETU16(msg, *i, timeout);
06484 SETU8(msg, *i, (uint8_t)TMR_SR_GEN2_DENATRAN_IAV_SILICON);
06485 rec=*i;
06486 SETU8(msg,*i,0x40);
06487 SETU8(msg, *i, (uint8_t)0x00);
06488 SETU8(msg, *i, (uint8_t)mode);
06489 filterbytes(TMR_TAG_PROTOCOL_GEN2, target, &option, i, msg, accessPassword, true);
06490 msg[rec]=msg[rec]|option;
06491 }
06492
06505 TMR_Status
06506 TMR_SR_cmdIAVDenatranCustomWriteToMemMap(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t payload,
06507 TMR_uint8List *data, TMR_TagFilter* target, uint16_t wordPtr, uint16_t wordData, uint8_t* tagId, uint8_t* dataBuf)
06508 {
06509 TMR_Status ret;
06510 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06511 uint8_t i;
06512 i = 2;
06513
06514 TMR_SR_msgAddIAVDenatranCustomWriteToMemMap(msg, &i, timeout, accessPassword, mode, payload, target, wordPtr, wordData, tagId, dataBuf);
06515 msg[1] = i - 3;
06516
06517 ret = TMR_SR_sendTimeout(reader, msg, timeout);
06518 if (TMR_SUCCESS != ret)
06519 {
06520 return ret;
06521 }
06522
06523
06524 i = 9;
06525
06526
06527
06528 {
06529 uint16_t copyLength;
06530
06531 copyLength = msg[1] + 5 - i;
06532
06533 if (copyLength > data->max)
06534 {
06535 copyLength = data->max;
06536 }
06537 if (NULL != data)
06538 {
06539 memcpy(data->list, &msg[i], copyLength);
06540 data->len = copyLength;
06541 }
06542 }
06543 return TMR_SUCCESS;
06544 }
06545
06547 void TMR_SR_msgAddIAVDenatranCustomWriteSec(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
06548 uint8_t mode, uint8_t payload, TMR_TagFilter* target, uint8_t* data, uint8_t* dataBuf)
06549 {
06550 uint8_t j;
06551
06552 TMR_SR_msgAddIAVDenatranCustomOp(msg, i, timeout, accessPassword, mode, payload, target);
06553
06554 for (j = 0; j < 6; j++)
06555 {
06556 SETU8(msg, *i, data[j]);
06557 }
06558 for (j = 0; j < 16; j++)
06559 {
06560 SETU8(msg, *i, dataBuf[j]);
06561 }
06562 }
06563
06576 TMR_Status
06577 TMR_SR_cmdIAVDenatranCustomWriteSec(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t payload,
06578 TMR_uint8List *data, TMR_TagFilter* target, uint8_t* dataWords, uint8_t* dataBuf)
06579 {
06580 TMR_Status ret;
06581 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06582 uint8_t i;
06583 i = 2;
06584
06585 TMR_SR_msgAddIAVDenatranCustomWriteSec(msg, &i, timeout, accessPassword, mode, payload, target, dataWords, dataBuf);
06586 msg[1] = i - 3;
06587
06588 ret = TMR_SR_sendTimeout(reader, msg, timeout);
06589 if (TMR_SUCCESS != ret)
06590 {
06591 return ret;
06592 }
06593
06594
06595 i = 9;
06596
06597
06598
06599 {
06600 uint16_t copyLength;
06601
06602 copyLength = msg[1] + 5 - i;
06603
06604 if (copyLength > data->max)
06605 {
06606 copyLength = data->max;
06607 }
06608 if (NULL != data)
06609 {
06610 memcpy(data->list, &msg[i], copyLength);
06611 data->len = copyLength;
06612 }
06613 }
06614 return TMR_SUCCESS;
06615 }
06616
06626 TMR_Status
06627 TMR_SR_cmdIAVDenatranCustomGetTokenId(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode,
06628 TMR_uint8List *data, TMR_TagFilter* target)
06629 {
06630 TMR_Status ret;
06631 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06632 uint8_t i;
06633 i = 2;
06634
06635 TMR_SR_msgAddIAVDenatranCustomGetTokenId(msg, &i, timeout, accessPassword, mode, target);
06636 msg[1] = i - 3;
06637
06638 ret = TMR_SR_sendTimeout(reader, msg, timeout);
06639 if (TMR_SUCCESS != ret)
06640 {
06641 return ret;
06642 }
06643
06644
06645 i = 9;
06646
06647
06648
06649 {
06650 uint16_t copyLength;
06651
06652 copyLength = msg[1] + 5 - i;
06653
06654 if (copyLength > data->max)
06655 {
06656 copyLength = data->max;
06657 }
06658 if (NULL != data)
06659 {
06660 memcpy(data->list, &msg[i], copyLength);
06661 data->len = copyLength;
06662 }
06663 }
06664 return TMR_SUCCESS;
06665 }
06666
06675 TMR_Status
06676 TMR_SR_cmdGetReaderStatistics(TMR_Reader *reader, TMR_SR_ReaderStatisticsFlag statFlags,
06677 TMR_SR_ReaderStatistics *stats)
06678 {
06679 TMR_Status ret;
06680 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06681 uint8_t i, length, offset;
06682 i = 2;
06683
06684 SETU8(msg, i, TMR_SR_OPCODE_GET_READER_STATS);
06685 SETU8(msg, i, (uint8_t)TMR_SR_READER_STATS_OPTION_GET_PER_PORT);
06686 SETU8(msg, i, (uint8_t)statFlags);
06687
06688 msg[1] = i - 3;
06689
06690 ret = TMR_SR_sendTimeout(reader, msg, reader->u.serialReader.commandTimeout);
06691 if (TMR_SUCCESS != ret)
06692 {
06693 return ret;
06694 }
06695
06696
06697 if (NULL != stats)
06698 {
06699 uint8_t port = 0;
06700 offset = 7;
06701
06702 length = reader->u.serialReader.txRxMap->len;
06703
06704 while (offset < (msg[1] + 2))
06705 {
06706 if (0 != (msg[offset] & TMR_SR_READER_STATS_FLAG_RF_ON_TIME))
06707 {
06708 offset += 2;
06709
06710 for (i = 0; i < length; i++)
06711 {
06712 port = msg[offset];
06713 if (i == (port-1))
06714 {
06715 offset ++;
06716 stats->rfOnTime[i] = GETU32(msg, offset);
06717 }
06718 else
06719 {
06720 stats->rfOnTime[i] = 0;
06721 }
06722 }
06723 stats->numPorts = length;
06724 }
06725 else if (0 != (msg[offset] & TMR_SR_READER_STATS_FLAG_NOISE_FLOOR))
06726 {
06727 offset += 2;
06728
06729 for (i = 0; i < length; i++)
06730 {
06731 port = msg[offset];
06732 if (i == (port-1))
06733 {
06734 offset ++;
06735 stats->noiseFloor[i] = msg[offset++];
06736 }
06737 else
06738 {
06739 stats->noiseFloor[i] = 0;
06740 }
06741 }
06742 stats->numPorts = length;
06743 }
06744 else if (0 != (msg[offset] & TMR_SR_READER_STATS_FLAG_NOISE_FLOOR_TX_ON))
06745 {
06746 offset += 2;
06747
06748 for (i = 0; i < length; i++)
06749 {
06750 port = msg[offset];
06751 if (i == (port-1))
06752 {
06753 offset ++;
06754 stats->noiseFloorTxOn[i] = msg[offset++];
06755 }
06756 else
06757 {
06758 stats->noiseFloorTxOn[i] = 0;
06759 }
06760 }
06761 stats->numPorts = length;
06762 }
06763 }
06764 }
06765 return TMR_SUCCESS;
06766 }
06767
06775 TMR_Status
06776 TMR_SR_cmdResetReaderStatistics(TMR_Reader *reader, TMR_SR_ReaderStatisticsFlag statFlags)
06777 {
06778 TMR_Status ret;
06779 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06780 uint8_t i;
06781 i = 2;
06782
06783 SETU8(msg, i, TMR_SR_OPCODE_GET_READER_STATS);
06784 SETU8(msg, i, (uint8_t)TMR_SR_READER_STATS_OPTION_RESET);
06785 SETU8(msg, i, (uint8_t)statFlags);
06786
06787 msg[1] = i - 3;
06788
06789 ret = TMR_SR_sendTimeout(reader, msg, reader->u.serialReader.commandTimeout);
06790 if (TMR_SUCCESS != ret)
06791 {
06792 return ret;
06793 }
06794 return TMR_SUCCESS;
06795 }
06796
06797
06801 TMR_Status
06802 TMR_fillReaderStats(TMR_Reader *reader, TMR_Reader_StatsValues* stats, uint16_t flag, uint8_t* msg, uint8_t offset)
06803 {
06804 uint8_t i;
06805 while (offset < (msg[1] + 2))
06806 {
06807 if ((0x80) > msg[offset])
06808 {
06809 flag = msg[offset];
06810 }
06811 else
06812 {
06817 flag = ((msg[offset] << 8) | (msg[offset + 1]));
06818 flag &= 0x7fff;
06819 flag = ((flag >> 1) | (flag & 0x7f));
06820 }
06821
06822
06823 if (flag & TMR_READER_STATS_FLAG_RF_ON_TIME)
06824 {
06825 uint8_t tx;
06826
06827 offset += 2;
06828
06829 for (i = 0; i < reader->u.serialReader.txRxMap->len; i++)
06830 {
06831 tx = GETU8(msg, offset);
06832 if (tx == reader->u.serialReader.txRxMap->list[i].txPort)
06833 {
06834 stats->perAntenna.list[i].antenna = reader->u.serialReader.txRxMap->list[i].antenna;
06835 stats->perAntenna.list[i].rfOnTime = GETU32(msg, offset);
06836 }
06837 }
06838 }
06839
06840 else if (flag & TMR_READER_STATS_FLAG_NOISE_FLOOR_SEARCH_RX_TX_WITH_TX_ON)
06841 {
06842 uint8_t tx,rx, len;
06843
06844 offset++;
06845 len = GETU8(msg, offset);
06846 while (len)
06847 {
06848 tx = GETU8(msg, offset);
06849 rx = GETU8(msg, offset);
06850 for (i = 0; i < reader->u.serialReader.txRxMap->len; i++)
06851 {
06852 if ((rx == reader->u.serialReader.txRxMap->list[i].rxPort) && (tx == reader->u.serialReader.txRxMap->list[i].txPort))
06853 {
06854 stats->perAntenna.list[i].antenna = reader->u.serialReader.txRxMap->list[i].antenna;
06855 stats->perAntenna.list[i].noiseFloor = GETU8(msg, offset);
06856 len -= 3;
06857 }
06858 }
06859 }
06860 }
06861
06862 else if (flag & TMR_READER_STATS_FLAG_FREQUENCY)
06863 {
06864 offset += 3;
06865 stats->frequency = GETU24(msg, offset);
06866 }
06867
06868 else if (flag & TMR_READER_STATS_FLAG_TEMPERATURE)
06869 {
06870 offset += 3;
06871 stats->temperature = GETU8(msg, offset);
06872 }
06873
06874 else if (flag & TMR_READER_STATS_FLAG_PROTOCOL)
06875 {
06876 offset += 3;
06877 stats->protocol = (TMR_TagProtocol)GETU8(msg, offset);
06878 }
06879
06880 else if (flag & TMR_READER_STATS_FLAG_ANTENNA_PORTS)
06881 {
06882 uint8_t tx, rx;
06883
06884 offset += 3;
06885 tx = GETU8(msg, offset);
06886 rx = GETU8(msg, offset);
06887
06888 for (i = 0; i < reader->u.serialReader.txRxMap->len; i++)
06889 {
06890 if ((rx == reader->u.serialReader.txRxMap->list[i].rxPort) && (tx == reader->u.serialReader.txRxMap->list[i].txPort))
06891 {
06892 stats->antenna = reader->u.serialReader.txRxMap->list[i].antenna;
06893 break;
06894 }
06895 }
06896 }
06897
06898 else if (flag & TMR_READER_STATS_FLAG_CONNECTED_ANTENNAS)
06899 {
06900 offset += 3;
06901 stats->connectedAntennas.len = msg[offset - 1];
06902 for (i = 0; i < stats->connectedAntennas.len; i++)
06903 {
06904 stats->connectedAntennas.list[i] = msg[offset++];
06905 }
06906 }
06907 else
06908 {
06909 return TMR_ERROR_INVALID;
06910 }
06911 }
06912 return TMR_SUCCESS;
06913 }
06914
06923 TMR_Status
06924 TMR_SR_cmdGetReaderStats(TMR_Reader *reader, TMR_Reader_StatsFlag statFlags,
06925 TMR_Reader_StatsValues *stats)
06926 {
06927 TMR_Status ret;
06928 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
06929 uint8_t i, offset;
06930 uint16_t flag = 0, temp = 0;
06931 i = 2;
06932
06933 SETU8(msg, i, TMR_SR_OPCODE_GET_READER_STATS);
06934 SETU8(msg, i, (uint8_t)TMR_SR_READER_STATS_OPTION_GET_PER_PORT);
06935
06941 if ((0x80) > statFlags)
06942 {
06943 SETU8(msg, i, (uint8_t)statFlags);
06944 }
06945 else
06946 {
06947 temp = statFlags & 0x7f;
06948 statFlags &= 0xFFFE;
06949 statFlags = (TMR_Reader_StatsFlag)((statFlags << 1) | temp);
06950 statFlags &= 0xFF7F;
06951 SETU16(msg, i, ((uint16_t)0x8000 | statFlags));
06952 }
06953
06954 msg[1] = i - 3;
06955
06956 ret = TMR_SR_sendTimeout(reader, msg, reader->u.serialReader.commandTimeout);
06957 if (TMR_SUCCESS != ret)
06958 {
06959 return ret;
06960 }
06961
06962
06963 if (NULL != stats)
06964 {
06965 uint8_t j;
06966 offset = 7;
06967
06972 for (i = 0; i < stats->perAntenna.max; i++)
06973 {
06974 stats->perAntenna.list[i].antenna = 0;
06975 stats->perAntenna.list[i].rfOnTime = 0;
06976 stats->perAntenna.list[i].noiseFloor = 0;
06977 }
06978
06979 if ((0x80) > statFlags)
06980 {
06981 offset = 7;
06982 }
06983 else
06984 {
06985 offset = 8;
06986 }
06987
06988 ret = TMR_fillReaderStats(reader, stats, flag, msg, offset);
06989 if (TMR_SUCCESS != ret)
06990 {
06991 return ret;
06992 }
06993
06999 for (i = 0; i < reader->u.serialReader.txRxMap->len; i++)
07000 {
07001 if (!stats->perAntenna.list[i].antenna )
07002 {
07003 for (j = i + 1; j < reader->u.serialReader.txRxMap->len; j++)
07004 {
07005 if (stats->perAntenna.list[j].antenna)
07006 {
07007 stats->perAntenna.list[i].antenna = stats->perAntenna.list[j].antenna;
07008 stats->perAntenna.list[i].rfOnTime = stats->perAntenna.list[j].rfOnTime;
07009 stats->perAntenna.list[i].noiseFloor = stats->perAntenna.list[j].noiseFloor;
07010 stats->perAntenna.list[j].antenna = 0;
07011 stats->perAntenna.list[j].rfOnTime = 0;
07012 stats->perAntenna.list[j].noiseFloor = 0;
07013
07014 stats->perAntenna.len++;
07015 break;
07016 }
07017 }
07018 }
07019 else
07020 {
07021
07022 stats->perAntenna.len++;
07023 }
07024 }
07025 }
07026
07027
07028 stats->valid = reader->statsFlag;
07029
07030 return TMR_SUCCESS;
07031 }
07032
07040 TMR_Status
07041 TMR_SR_cmdResetReaderStats(TMR_Reader *reader, TMR_Reader_StatsFlag statFlags)
07042 {
07043 TMR_Status ret;
07044 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
07045 uint8_t i;
07046 uint16_t temp = 0;
07047 i = 2;
07048
07049 SETU8(msg, i, TMR_SR_OPCODE_GET_READER_STATS);
07050 SETU8(msg, i, (uint8_t)TMR_SR_READER_STATS_OPTION_RESET);
07051
07057 if ((0x80) > statFlags)
07058 {
07059 SETU8(msg, i, (uint8_t)statFlags);
07060 }
07061 else
07062 {
07063 temp = statFlags & 0x7f;
07064 statFlags &= 0xFFFE;
07065 statFlags = (TMR_Reader_StatsFlag)((statFlags << 1) | temp);
07066 statFlags &= 0xFF7F;
07067 SETU16(msg, i, ((uint16_t)0x8000 | statFlags));
07068 }
07069
07070 msg[1] = i - 3;
07071
07072 ret = TMR_SR_sendTimeout(reader, msg, reader->u.serialReader.commandTimeout);
07073 if (TMR_SUCCESS != ret)
07074 {
07075 return ret;
07076 }
07077 return TMR_SUCCESS;
07078 }
07079
07080 TMR_Status
07081 TMR_SR_receiveAutonomousReading(struct TMR_Reader *reader, TMR_TagReadData *trd, TMR_Reader_StatsValues *stats)
07082 {
07083 TMR_Status ret;
07084
07085 ret = TMR_SUCCESS;
07086 reader->continuousReading = true;
07087
07088 ret = TMR_SR_hasMoreTags(reader);
07089 if (TMR_SUCCESS == ret)
07090 {
07091 uint16_t flags;
07092
07093 if (false == reader->isStatusResponse)
07094 {
07095
07096 flags = GETU16AT(reader->u.serialReader.bufResponse, 8);
07097 TMR_SR_parseMetadataFromMessage(reader, trd, flags, &reader->u.serialReader.bufPointer, reader->u.serialReader.bufResponse);
07098 TMR_SR_postprocessReaderSpecificMetadata(trd, &reader->u.serialReader);
07099 trd->reader = reader;
07100 reader->u.serialReader.tagsRemainingInBuffer--;
07101 }
07102 else
07103 {
07104
07105 uint8_t offset, i,j;
07106 uint16_t flags = 0;
07107
07108 TMR_STATS_init(stats);
07109 offset = reader->u.serialReader.bufPointer;
07110
07111
07112 if ((0x80) > reader->statsFlag)
07113 {
07114 offset += 1;
07115 }
07116 else
07117 {
07118 offset += 2;
07119 }
07120
07125 for (i = 0; i < stats->perAntenna.max; i++)
07126 {
07127 stats->perAntenna.list[i].antenna = 0;
07128 stats->perAntenna.list[i].rfOnTime = 0;
07129 stats->perAntenna.list[i].noiseFloor = 0;
07130 }
07131
07132 TMR_fillReaderStats(reader, stats, flags, reader->u.serialReader.bufResponse, offset);
07133
07139 for (i = 0; i < reader->u.serialReader.txRxMap->len; i++)
07140 {
07141 if (!stats->perAntenna.list[i].antenna)
07142 {
07143 for (j = i + 1; j < reader->u.serialReader.txRxMap->len; j++)
07144 {
07145 if (stats->perAntenna.list[j].antenna)
07146 {
07147 stats->perAntenna.list[i].antenna = stats->perAntenna.list[j].antenna;
07148 stats->perAntenna.list[i].rfOnTime = stats->perAntenna.list[j].rfOnTime;
07149 stats->perAntenna.list[i].noiseFloor = stats->perAntenna.list[j].noiseFloor;
07150 stats->perAntenna.list[j].antenna = 0;
07151 stats->perAntenna.list[j].rfOnTime = 0;
07152 stats->perAntenna.list[j].noiseFloor = 0;
07153
07154 stats->perAntenna.len++;
07155 break;
07156 }
07157 }
07158 }
07159 else
07160 {
07161
07162 stats->perAntenna.len++;
07163 }
07164 }
07165
07166
07167 stats->valid = reader->statsFlag;
07168 }
07169 }
07170
07171 reader->continuousReading = false;
07172 return ret;
07173 }
07174
07175 TMR_Status
07176 TMR_SR_cmdStopReading(struct TMR_Reader *reader)
07177 {
07178 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
07179 uint8_t i, op;
07180
07181 reader->hasContinuousReadStarted = false;
07182 i = 2;
07183 op = TMR_SR_OPCODE_MULTI_PROTOCOL_TAG_OP;
07184 SETU8(msg, i, op);
07185 SETU16(msg, i, 0);
07186 SETU8(msg, i, (uint8_t)0x02);
07187
07188 msg[1]=i - 3;
07189
07190
07191 return TMR_SR_sendMessage(reader, msg, &op, reader->u.serialReader.commandTimeout);
07192 }
07193
07194 TMR_Status
07195 TMR_SR_cmdGetReaderWriteTimeOut (struct TMR_Reader *reader, TMR_TagProtocol protocol,
07196 TMR_SR_Gen2ReaderWriteTimeOut *value)
07197 {
07198 TMR_Status ret;
07199 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
07200 uint8_t i, op;
07201
07202 i = 2;
07203 op = TMR_SR_OPCODE_GET_PROTOCOL_PARAM;
07204 SETU8(msg, i, op);
07205 SETU8(msg, i, protocol);
07206 SETU8(msg, i, (uint8_t)0x3f);
07207
07208 msg[1]=i - 3;
07209
07210 ret = TMR_SR_send(reader, msg);
07211 if (TMR_SUCCESS != ret)
07212 {
07213 return ret;
07214 }
07215
07216
07217 value->earlyexit = GETU8AT(msg, 7);
07218 value->writetimeout = GETU16AT(msg, 8);
07219
07220 return TMR_SUCCESS;
07221 }
07222
07223 TMR_Status
07224 TMR_SR_cmdSetReaderWriteTimeOut (struct TMR_Reader *reader, TMR_TagProtocol protocol,
07225 TMR_SR_Gen2ReaderWriteTimeOut *value)
07226 {
07227 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
07228 uint8_t i;
07229
07230 i = 2;
07231 SETU8(msg, i, TMR_SR_OPCODE_SET_PROTOCOL_PARAM);
07232 SETU8(msg, i, protocol);
07233 SETU8(msg, i, (uint8_t)0x3f);
07234 SETU8(msg, i, (uint8_t)value->earlyexit);
07235 SETU16(msg,i, value->writetimeout);
07236
07237 msg[1] = i - 3;
07238 return TMR_SR_send(reader, msg);
07239 }
07240
07241 TMR_Status
07242 TMR_SR_cmdAuthReqResponse(struct TMR_Reader *reader, TMR_TagAuthentication *auth)
07243 {
07244 uint8_t msg[TMR_SR_MAX_PACKET_SIZE];
07245 uint8_t i;
07246 uint8_t opcode;
07247
07248 i = 2;
07249 SETU8(msg, i, (uint8_t)TMR_SR_OPCODE_MULTI_PROTOCOL_TAG_OP);
07250 SETU8(msg, i, (uint8_t)0x00);
07251 SETU8(msg, i, (uint8_t)0x00);
07252 SETU8(msg, i, (uint8_t)0x03);
07253 SETU8(msg, i, (uint8_t)0x00);
07254 SETU8(msg, i, (uint8_t)0x01);
07255 SETU8(msg, i, (uint8_t)0x00);
07256
07257 switch (auth->type)
07258 {
07259 default:
07260 return TMR_ERROR_UNSUPPORTED;
07261
07262 case TMR_AUTH_TYPE_GEN2_PASSWORD:
07263 {
07264 TMR_GEN2_Password password = auth->u.gen2Password;
07265 SETU8(msg, i, (uint8_t)0x20);
07266 SETU8(msg, i, (uint8_t)(password>>24));
07267 SETU8(msg, i, (uint8_t)(password>>16));
07268 SETU8(msg, i, (uint8_t)(password>> 8));
07269 SETU8(msg, i, (uint8_t)(password>> 0));
07270 }
07271 break;
07272 }
07273
07274 msg[1] = i - 3;
07275 return TMR_SR_sendMessage(reader, msg, &opcode, 0);
07276 }
07277
07278 #endif