serial_reader_imp.h
Go to the documentation of this file.
00001 #ifndef _SERIAL_READER_IMP_H
00002 #define _SERIAL_READER_IMP_H
00003 
00011 /*
00012  * Copyright (c) 2009 ThingMagic, Inc.
00013  *
00014  * Permission is hereby granted, free of charge, to any person obtaining a copy
00015  * of this software and associated documentation files (the "Software"), to deal
00016  * in the Software without restriction, including without limitation the rights
00017  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00018  * copies of the Software, and to permit persons to whom the Software is
00019  * furnished to do so, subject to the following conditions:
00020  *
00021  * The above copyright notice and this permission notice shall be included in
00022  * all copies or substantial portions of the Software.
00023  * 
00024  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00025  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00026  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00027  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00028  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00029  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00030  * THE SOFTWARE.
00031  */
00032 #include "tm_reader.h"
00033 #include "tmr_status.h"
00034 
00035 #ifdef  __cplusplus
00036 extern "C" {
00037 #endif
00038 
00039   
00040 /* This is used to enable the Gen2 secure readdata option */
00041 
00042 #ifndef BARE_METAL
00043   bool isSecureAccessEnabled ;
00044 #else
00045   static bool isSecureAccessEnabled;    
00046 #endif
00047 
00048 typedef enum TMR_SR_OpCode
00049 {
00050   TMR_SR_OPCODE_WRITE_FLASH             = 0x01,
00051   TMR_SR_OPCODE_READ_FLASH              = 0x02,
00052   TMR_SR_OPCODE_VERSION                 = 0x03,
00053   TMR_SR_OPCODE_BOOT_FIRMWARE           = 0x04,
00054   TMR_SR_OPCODE_SET_BAUD_RATE           = 0x06,
00055   TMR_SR_OPCODE_ERASE_FLASH             = 0x07,
00056   TMR_SR_OPCODE_VERIFY_IMAGE_CRC        = 0x08,
00057   TMR_SR_OPCODE_BOOT_BOOTLOADER         = 0x09,
00058   TMR_SR_OPCODE_HW_VERSION              = 0x10,
00059   TMR_SR_OPCODE_MODIFY_FLASH            = 0x0A,
00060   TMR_SR_OPCODE_GET_DSP_SILICON_ID      = 0x0B,
00061   TMR_SR_OPCODE_GET_CURRENT_PROGRAM     = 0x0C,
00062   TMR_SR_OPCODE_WRITE_FLASH_SECTOR      = 0x0D,
00063   TMR_SR_OPCODE_GET_SECTOR_SIZE         = 0x0E,
00064   TMR_SR_OPCODE_MODIFY_FLASH_SECTOR     = 0x0F,
00065   TMR_SR_OPCODE_READ_TAG_ID_SINGLE      = 0x21,
00066   TMR_SR_OPCODE_READ_TAG_ID_MULTIPLE    = 0x22,
00067   TMR_SR_OPCODE_WRITE_TAG_ID            = 0x23,
00068   TMR_SR_OPCODE_WRITE_TAG_DATA          = 0x24,
00069   TMR_SR_OPCODE_LOCK_TAG                = 0x25,
00070   TMR_SR_OPCODE_KILL_TAG                = 0x26,
00071   TMR_SR_OPCODE_READ_TAG_DATA           = 0x28,
00072   TMR_SR_OPCODE_GET_TAG_ID_BUFFER       = 0x29,
00073   TMR_SR_OPCODE_CLEAR_TAG_ID_BUFFER     = 0x2A,
00074   TMR_SR_OPCODE_WRITE_TAG_SPECIFIC      = 0x2D,
00075   TMR_SR_OPCODE_ERASE_BLOCK_TAG_SPECIFIC= 0x2E,
00076   TMR_SR_OPCODE_MULTI_PROTOCOL_TAG_OP   = 0x2F,
00077   TMR_SR_OPCODE_GET_ANTENNA_PORT        = 0x61,
00078   TMR_SR_OPCODE_GET_READ_TX_POWER       = 0x62,
00079   TMR_SR_OPCODE_GET_TAG_PROTOCOL        = 0x63,
00080   TMR_SR_OPCODE_GET_WRITE_TX_POWER      = 0x64,
00081   TMR_SR_OPCODE_GET_FREQ_HOP_TABLE      = 0x65,
00082   TMR_SR_OPCODE_GET_USER_GPIO_INPUTS    = 0x66,
00083   TMR_SR_OPCODE_GET_REGION              = 0x67,
00084   TMR_SR_OPCODE_GET_POWER_MODE          = 0x68,
00085   TMR_SR_OPCODE_GET_USER_MODE           = 0x69,
00086   TMR_SR_OPCODE_GET_READER_OPTIONAL_PARAMS=0x6A,
00087   TMR_SR_OPCODE_GET_PROTOCOL_PARAM      = 0x6B,
00088   TMR_SR_OPCODE_GET_READER_STATS        = 0x6C,
00089   TMR_SR_OPCODE_GET_USER_PROFILE        = 0x6D,
00090   TMR_SR_OPCODE_GET_AVAILABLE_PROTOCOLS = 0x70,
00091   TMR_SR_OPCODE_GET_AVAILABLE_REGIONS   = 0x71,
00092   TMR_SR_OPCODE_GET_TEMPERATURE         = 0x72,
00093   TMR_SR_OPCODE_SET_ANTENNA_PORT        = 0x91,
00094   TMR_SR_OPCODE_SET_READ_TX_POWER       = 0x92,
00095   TMR_SR_OPCODE_SET_TAG_PROTOCOL        = 0x93,
00096   TMR_SR_OPCODE_SET_WRITE_TX_POWER      = 0x94,
00097   TMR_SR_OPCODE_SET_FREQ_HOP_TABLE      = 0x95,
00098   TMR_SR_OPCODE_SET_USER_GPIO_OUTPUTS   = 0x96,
00099   TMR_SR_OPCODE_SET_REGION              = 0x97,
00100   TMR_SR_OPCODE_SET_POWER_MODE          = 0x98,
00101   TMR_SR_OPCODE_SET_USER_MODE           =  0x99,
00102   TMR_SR_OPCODE_SET_READER_OPTIONAL_PARAMS=0x9a,
00103   TMR_SR_OPCODE_SET_PROTOCOL_PARAM      = 0x9B,
00104   TMR_SR_OPCODE_SET_USER_PROFILE        = 0x9D,
00105   TMR_SR_OPCODE_SET_PROTOCOL_LICENSEKEY = 0x9E,
00106   TMR_SR_OPCODE_SET_OPERATING_FREQ      = 0xC1,
00107   TMR_SR_OPCODE_TX_CW_SIGNAL            = 0xC3,
00108 }TMR_SR_OpCode;
00109 
00110 typedef enum TMR_SR_Gen2SingulationOptions
00111 {
00112   TMR_SR_GEN2_SINGULATION_OPTION_SELECT_DISABLED         = 0x00,
00113   TMR_SR_GEN2_SINGULATION_OPTION_SELECT_ON_EPC           = 0x01,
00114   TMR_SR_GEN2_SINGULATION_OPTION_SELECT_ON_TID           = 0x02,
00115   TMR_SR_GEN2_SINGULATION_OPTION_SELECT_ON_USER_MEM      = 0x03,
00116   TMR_SR_GEN2_SINGULATION_OPTION_SELECT_ON_ADDRESSED_EPC = 0x04,
00117   TMR_SR_GEN2_SINGULATION_OPTION_USE_PASSWORD            = 0x05,
00118   TMR_SR_GEN2_SINGULATION_OPTION_SELECT_ON_LENGTH_OF_EPC = 0x06,
00119   TMR_SR_GEN2_SINGULATION_OPTION_SELECT_GEN2TRUNCATE     = 0x07,
00120   TMR_SR_GEN2_SINGULATION_OPTION_INVERSE_SELECT_BIT      = 0x08,
00121   TMR_SR_GEN2_SINGULATION_OPTION_FLAG_METADATA           = 0x10,
00122   TMR_SR_GEN2_SINGULATION_OPTION_EXTENDED_DATA_LENGTH    = 0x20,
00123   TMR_SR_GEN2_SINGULATION_OPTION_SECURE_READ_DATA        = 0x40
00124 }TMR_SR_Gen2SingulationOptions;
00125 
00126 typedef enum TMR_SR_TagidOption
00127 {
00128   TMR_SR_TAG_ID_OPTION_NONE    = 0x00,
00129   TMR_SR_TAG_ID_OPTION_REWIND  = 0x01
00130 }TMR_SR_TagidOption;
00131 
00132 typedef enum TMR_SR_ModelHardwareID
00133 {
00134   TMR_SR_MODEL_M5E         = 0x00,
00135   TMR_SR_MODEL_M5E_COMPACT = 0x01,
00136   TMR_SR_MODEL_M5E_I       = 0x02,
00137   TMR_SR_MODEL_M4E         = 0x03,
00138   TMR_SR_MODEL_M6E         = 0x18,
00139   TMR_SR_MODEL_M6E_I       = 0x19,
00140   TMR_SR_MODEL_MICRO       = 0x20,
00141   TMR_SR_MODEL_M6E_NANO    = 0x30,
00142   TMR_SR_MODEL_UNKNOWN     = 0xFF,
00143 } TMR_SR_ModelHardwareID;
00144 
00145 typedef enum TMR_SR_ModelMicro
00146 {
00147   TMR_SR_MODEL_M6E_MICRO     = 0x01,
00148   TMR_SR_MODEL_M6E_MICRO_USB = 0x02,
00149   TMR_SR_MODEL_M6E_MICRO_USB_PRO = 0x03,
00150 }TMR_SR_ModelMicro;
00151 
00152 typedef enum TMR_SR_ModelM6E_I
00153 {
00154   TMR_SR_MODEL_M6E_I_REV1 = 0x01,
00155   TMR_SR_MODEL_M6E_I_PRC  = 0x02,
00156   TMR_SR_MODEL_M6E_I_JIC  = 0x03,
00157 }TMR_SR_ModelM6E_I;
00158 
00159 typedef enum TMR_SR_ModelM5EInternational
00160 {
00161   TMR_SR_MODEL_M5E_I_REV_EU  = 0x01,
00162   TMR_SR_MODEL_M5E_I_REV_NA  = 0x02,
00163   TMR_SR_MODEL_M5E_I_REV_JP  = 0x03,
00164   TMR_SR_MODEL_M5E_I_REV_PRC = 0x04,
00165 }TMR_SR_ModelM5EInternational;
00166 
00167 typedef enum TMR_SR_ProductGroupID
00168 {
00169   TMR_SR_PRODUCT_MODULE = 0,
00170   TMR_SR_PRODUCT_RUGGEDIZED_READER = 1,
00171   TMR_SR_PRODUCT_USB_READER = 2,
00172   TMR_SR_PRODUCT_INVALID = 0xFFFF,
00173 }TMR_SR_ProductGroupID;
00174 
00175 TMR_Status TMR_SR_sendTimeout(TMR_Reader *reader, uint8_t *data,
00176                               uint32_t timeoutMs);
00177 TMR_Status TMR_SR_send(TMR_Reader *reader, uint8_t *data);
00178 TMR_Status TMR_SR_sendMessage(TMR_Reader *reader, uint8_t *data,
00179                               uint8_t *opcode, uint32_t timeoutMs);
00180 TMR_Status TMR_SR_receiveMessage(TMR_Reader *reader, uint8_t *data,
00181                                  uint8_t opcode, uint32_t timeoutMs);
00182 TMR_Status TMR_SR_receiveAutonomousReading(struct TMR_Reader *reader, TMR_TagReadData *trd, TMR_Reader_StatsValues *stats);
00183 
00184 void TMR_SR_parseMetadataFromMessage(TMR_Reader *reader, TMR_TagReadData *read, uint16_t flags,
00185                                      uint8_t *i, uint8_t msg[]);
00186 
00187 void
00188 TMR_SR_parseMetadataOnly(TMR_Reader *reader, TMR_TagReadData *read, uint16_t flags,
00189                                 uint8_t *i, uint8_t msg[]);
00190 void TMR_SR_postprocessReaderSpecificMetadata(TMR_TagReadData *read,
00191                                               TMR_SR_SerialReader *sr);
00192 bool isContinuousReadParamSupported(TMR_Reader *reader);
00193 
00197 typedef struct TMR_SR_MultipleStatus
00198 {
00200   uint16_t tagsFound;
00202   uint16_t successCount;
00204   uint16_t failureCount;
00205 }TMR_SR_MultipleStatus;
00206 
00212 typedef struct TMR_SR_PortPair
00213 {
00215   uint8_t txPort;
00217   uint8_t rxPort;
00218 }TMR_SR_PortPair;
00219 
00223 typedef struct TMR_SR_PortDetect
00224 {
00226   uint8_t port;
00228   bool detected;
00229 }TMR_SR_PortDetect;
00230 
00234 typedef enum TMR_SR_ReaderStatsOption
00235 {
00236   /* Get statistics specified by the statistics flag */
00237   TMR_SR_READER_STATS_OPTION_GET=   0x00,
00238   /* Reset the specified statistic */
00239   TMR_SR_READER_STATS_OPTION_RESET= 0x01,
00240   /* Get the per-port statistics specified by the statistics flag*/
00241   TMR_SR_READER_STATS_OPTION_GET_PER_PORT = 0x02,
00242 }TMR_SR_ReaderStatsOption;
00243   
00244 
00248 typedef enum TMR_SR_ReaderStatisticsFlag
00249 {
00250   /* Total time the port has been transmitting, in milliseconds. Resettable */
00251   TMR_SR_READER_STATS_FLAG_RF_ON_TIME     = (1<<0),
00252   /* Detected noise floor with transmitter off. Recomputed when requested, not resettable.*/
00253   TMR_SR_READER_STATS_FLAG_NOISE_FLOOR    = (1<<1),
00254   /* Detected noise floor with transmitter on. Recomputed when requested, not resettable. */
00255   TMR_SR_READER_STATS_FLAG_NOISE_FLOOR_TX_ON = (1<<3),
00256   /* ALL */
00257   TMR_SR_READER_STATS_ALL = (TMR_SR_READER_STATS_FLAG_RF_ON_TIME | 
00258       TMR_SR_READER_STATS_FLAG_NOISE_FLOOR |
00259       TMR_SR_READER_STATS_FLAG_NOISE_FLOOR_TX_ON),
00260 }TMR_SR_ReaderStatisticsFlag;
00261 
00265 typedef struct TMR_SR_AntennaPort
00266 {
00268   uint8_t numPorts;
00270   uint8_t txPort;
00272   uint8_t rxPort;
00274   TMR_uint8List portTerminatedList;
00275 }TMR_SR_AntennaPort;
00276 
00278 typedef struct TMR_SR_PortPower
00279 {
00281   uint8_t port;
00283   uint16_t readPower;
00285   uint16_t writePower;
00286 } TMR_SR_PortPower;
00287 
00292 typedef struct TMR_SR_PortPowerAndSettlingTime
00293 {
00295   uint8_t port;
00297   int16_t readPower;
00299   int16_t writePower;
00301   uint16_t settlingTime;
00302 } TMR_SR_PortPowerAndSettlingTime;
00303 
00305 typedef struct TMR_SR_PowerWithLimits
00306 {
00308   uint16_t setPower;
00310   uint16_t maxPower;
00312   uint16_t minPower;
00313 } TMR_SR_PowerWithLimits;
00314 
00315 
00316 void TMR_hexDottedQuad(const uint8_t bytes[4], char buf[12]);
00317 TMR_Status TMR_hexDottedQuadToUint32(const char bytes[12], uint32_t *result);
00318 
00319 
00326 typedef enum TMR_SR_Configuration
00327 {
00334   TMR_SR_CONFIGURATION_UNIQUE_BY_ANTENNA        = 0,
00340   TMR_SR_CONFIGURATION_TRANSMIT_POWER_SAVE      = 1,
00346   TMR_SR_CONFIGURATION_EXTENDED_EPC             = 2,
00354   TMR_SR_CONFIGURATION_ANTENNA_CONTROL_GPIO     = 3,
00358   TMR_SR_CONFIGURATION_SAFETY_ANTENNA_CHECK     = 4,
00362   TMR_SR_CONFIGURATION_SAFETY_TEMPERATURE_CHECK = 5,
00369   TMR_SR_CONFIGURATION_RECORD_HIGHEST_RSSI      = 6,
00376   TMR_SR_CONFIGURATION_UNIQUE_BY_DATA           = 8,
00381   TMR_SR_CONFIGURATION_RSSI_IN_DBM              = 9,
00386   TMR_SR_CONFIGURATION_SELF_JAMMER_CANCELLATION = 0x0A,
00393   TMR_SR_CONFIGURATION_UNIQUE_BY_PROTOCOL       = 0x0B,
00397   TMR_SR_CONFIGURATION_ENABLE_READ_FILTER         = 0x0C,
00401   TMR_SR_CONFIGURATION_READ_FILTER_TIMEOUT        = 0x0D,
00405   TMR_SR_CONFIGURATION_CURRENT_MSG_TRANSPORT      = 0x0E,
00409   TMR_SR_CONFIGURATION_SEND_CRC               = 0x1B,
00416   TMR_SR_CONFIGURATION_PRODUCT_GROUP_ID         = 0x12,
00423   TMR_SR_CONFIGURATION_PRODUCT_ID              = 0x13,
00432   TMR_SR_CONFIGURATION_TRIGGER_READ_GPIO                     = 0x1E,
00433 } TMR_SR_Configuration;
00434 
00435 
00440 typedef enum TMR_SR_RegionConfiguration
00441 {
00442   TMR_SR_REGION_CONFIGURATION_LBT_ENABLED = 0x40,
00443 } TMR_SR_RegionConfiguration;
00444 
00450 typedef enum TMR_SR_Gen2Configuration
00451 {
00452   TMR_SR_GEN2_CONFIGURATION_SESSION = 0x00,
00453   TMR_SR_GEN2_CONFIGURATION_TARGET  = 0x01,
00454   TMR_SR_GEN2_CONFIGURATION_TAGENCODING = 0x02,
00455   TMR_SR_GEN2_CONFIGURATION_LINKFREQUENCY = 0x10,
00456   TMR_SR_GEN2_CONFIGURATION_TARI    = 0x11,
00457   TMR_SR_GEN2_CONFIGURATION_Q       = 0x12,
00458   TMR_SR_GEN2_CONFIGURATION_BAP    = 0x13,
00459   TMR_SR_GEN2_CONFIGURATION_PROTCOLEXTENSION = 0x14
00460 } TMR_SR_Gen2Configuration;
00461 
00465 typedef struct TMR_SR_Gen2ReaderWriteTimeOut
00466 {
00467   /* Status of reader timeout */
00468   bool earlyexit;
00469 
00470   /* Timeout value used for write opearation */
00471   uint16_t writetimeout;
00472 }TMR_SR_Gen2ReaderWriteTimeOut;
00478 typedef enum TMR_SR_Iso180006bConfiguration
00479 {
00480   TMR_SR_ISO180006B_CONFIGURATION_LINKFREQUENCY = 0x10,
00481   TMR_SR_ISO180006B_CONFIGURATION_MODULATION_DEPTH = 0x11,
00482   TMR_SR_ISO180006B_CONFIGURATION_DELIMITER = 0x12
00483 } TMR_SR_Iso180006bConfiguration;
00484 
00490 typedef enum TMR_SR_iPxConfiguration
00491 {
00492   TMR_SR_IPX_CONFIGURATION_LINKFREQUENCY = 0x10
00493 } TMR_SR_iPxConfiguration;
00494 
00495 
00502 typedef struct TMR_SR_ProtocolConfiguration
00503 {
00505   TMR_TagProtocol protocol;
00506   union
00507   {
00509     TMR_SR_Gen2Configuration gen2;
00511     TMR_SR_Iso180006bConfiguration iso180006b;
00512     TMR_SR_iPxConfiguration ipx;
00513   }u;
00514 } TMR_SR_ProtocolConfiguration;
00515 
00516 
00520 typedef enum TMR_SR_SearchFlag
00521 {
00522   TMR_SR_SEARCH_FLAG_CONFIGURED_ANTENNA = 0,
00523   TMR_SR_SEARCH_FLAG_ANTENNA_1_THEN_2   = 1,
00524   TMR_SR_SEARCH_FLAG_ANTENNA_2_THEN_1   = 2,
00525   TMR_SR_SEARCH_FLAG_CONFIGURED_LIST    = 3,
00526   TMR_SR_SEARCH_FLAG_ANTENNA_MASK       = 3,
00527   TMR_SR_SEARCH_FLAG_EMBEDDED_COMMAND   = 4,
00528   TMR_SR_SEARCH_FLAG_TAG_STREAMING      = 8,
00529   TMR_SR_SEARCH_FLAG_LARGE_TAG_POPULATION_SUPPORT = 16,
00530   TMR_SR_SEARCH_FLAG_STATUS_REPORT_STREAMING = 32,
00531   TMR_SR_SEARCH_FLAG_RETURN_ON_N_TAGS = 64,
00532   TMR_SR_SEARCH_FLAG_READ_MULTIPLE_FAST_SEARCH = 128,
00533   TMR_SR_SEARCH_FLAG_STATS_REPORT_STREAMING = 256,
00534   TMR_SR_SEARCH_FLAG_GPI_TRIGGER_READ = 512,
00535   TMR_SR_SEARCH_FLAG_DUTY_CYCLE_CONTROL = 1024,
00536 }TMR_SR_SearchFlag;
00537 
00538 typedef enum TMR_SR_ISO180006BCommands
00539 {
00540   TMR_SR_ISO180006B_COMMAND_DATA_READ           = 0x0B,
00541   TMR_SR_ISO180006B_COMMAND_READ                = 0x0C,
00542   TMR_SR_ISO180006B_COMMAND_WRITE               = 0x0D,
00543   TMR_SR_ISO180006B_COMMAND_WRITE_MULTIPLE      = 0x0E,
00544   TMR_SR_ISO180006B_COMMAND_WRITE4BYTE          = 0x1B,
00545   TMR_SR_ISO180006B_COMMAND_WRITE4BYTE_MULTIPLE = 0x1C,
00546 } TMR_SR_ISO180006BCommands;
00547 
00548 typedef enum TMR_SR_ISO180006BCommandOptions
00549 {
00550   TMR_SR_ISO180006B_WRITE_OPTION_READ_AFTER           = 0x00,
00551   TMR_SR_ISO180006B_WRITE_OPTION_NO_VERIFY            = 0x01,
00552   TMR_SR_ISO180006B_WRITE_OPTION_READ_VERIFY_AFTER    = 0x02,
00553   TMR_SR_ISO180006B_WRITE_OPTION_GROUP_SELECT         = 0x03,
00554   TMR_SR_ISO180006B_WRITE_OPTION_COUNT_PROVIDED       = 0x08,
00555   TMR_SR_ISO180006B_WRITE_LOCK_NO                     = 0x00,
00556   TMR_SR_ISO180006B_WRITE_LOCK_YES                    = 0x01,
00557   TMR_SR_ISO180006B_LOCK_OPTION_TYPE_FOLLOWS          = 0x01,
00558   TMR_SR_ISO180006B_LOCK_TYPE_QUERYLOCK_THEN_LOCK     = 0x01,
00559 } TMR_SR_ISO180006BCommandOptions;
00560 
00561 TMR_Status TMR_SR_cmdRaw(TMR_Reader *reader, uint32_t timeout, uint8_t msgLen,
00562             uint8_t msg[]);
00563 TMR_Status TMR_SR_setSerialBaudRate(TMR_Reader *reader, uint32_t rate);
00564 TMR_Status TMR_SR_cmdVersion(TMR_Reader *reader, TMR_SR_VersionInfo *info);
00565 TMR_Status TMR_SR_cmdBootFirmware(TMR_Reader *reader);
00566 TMR_Status TMR_SR_cmdSetBaudRate(TMR_Reader *reader, uint32_t rate);
00567 TMR_Status TMR_SR_cmdVerifyImage(TMR_Reader *reader, bool *status);
00568 TMR_Status TMR_SR_cmdEraseFlash(TMR_Reader *reader, uint8_t sector, 
00569             uint32_t password);
00570 TMR_Status TMR_SR_cmdWriteFlashSector(TMR_Reader *reader, uint8_t sector, 
00571             uint32_t address, uint32_t password, uint8_t length,
00572             const uint8_t data[], uint32_t offset);
00573 TMR_Status TMR_SR_cmdGetSectorSize(TMR_Reader *reader, uint8_t sector,
00574             uint32_t *size);
00575 TMR_Status TMR_SR_cmdModifyFlashSector(TMR_Reader *reader, uint8_t sector, 
00576             uint32_t address, uint32_t password, uint8_t length,
00577             const uint8_t data[], uint32_t offset);
00578 TMR_Status TMR_SR_cmdBootBootloader(TMR_Reader *reader);
00579 TMR_Status TMR_SR_cmdGetHardwareVersion(TMR_Reader *reader, uint8_t option,
00580             uint8_t flags, uint8_t* count, uint8_t data[]);
00581 TMR_Status TMR_SR_cmdGetCurrentProgram(TMR_Reader *reader, uint8_t *program);
00582 TMR_Status TMR_SR_cmdReadTagSingle(TMR_Reader *reader, uint16_t timeout, 
00583             uint16_t metadataFlags, const TMR_TagFilter *filter, 
00584             TMR_TagProtocol protocol, TMR_TagReadData *tagData);
00585 TMR_Status TMR_SR_cmdReadTagMultiple(TMR_Reader *reader, uint16_t timeout,
00586             TMR_SR_SearchFlag flags, const TMR_TagFilter *filter,
00587             TMR_TagProtocol protocol, uint32_t *tagCount);
00588 TMR_Status TMR_SR_cmdWriteGen2TagEpc(TMR_Reader *reader, const TMR_TagFilter *filter, TMR_GEN2_Password accessPassword,
00589                         uint16_t timeout, uint8_t count, const uint8_t *id, bool lock);
00590 TMR_Status TMR_SR_cmdGEN2WriteTagData(TMR_Reader *reader,
00591             uint16_t timeout, TMR_GEN2_Bank bank, uint32_t address,
00592             uint8_t count, const uint8_t data[],
00593             TMR_GEN2_Password accessPassword, const TMR_TagFilter *filter);
00594 TMR_Status TMR_SR_cmdGEN2LockTag(TMR_Reader *reader, uint16_t timeout, 
00595             uint16_t mask, uint16_t action, TMR_GEN2_Password accessPassword, 
00596             const TMR_TagFilter *filter);
00597 TMR_Status TMR_SR_cmdKillTag(TMR_Reader *reader, uint16_t timeout,
00598             TMR_GEN2_Password killPassword, const TMR_TagFilter *filter);
00599 TMR_Status TMR_SR_cmdGEN2ReadTagData(TMR_Reader *reader,
00600             uint16_t timeout, TMR_GEN2_Bank bank,
00601             uint32_t address, uint8_t length, uint32_t accessPassword,
00602             const TMR_TagFilter *filter, TMR_TagReadData *data);
00603 TMR_Status TMR_SR_cmdGetTagsRemaining(TMR_Reader *reader, uint16_t *remaining);
00604 TMR_Status TMR_SR_cmdGetTagBuffer(TMR_Reader *reader, uint16_t count, bool epc496,
00605             TMR_TagProtocol protocol, TMR_TagData tagData[]);
00606 TMR_Status TMR_SR_cmdClearTagBuffer(TMR_Reader *reader);
00607 TMR_Status TMR_SR_cmdHiggs2PartialLoadImage(TMR_Reader *reader, uint16_t timeout,
00608             TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword, 
00609             uint8_t len, const uint8_t epc[], TMR_TagFilter* target);
00610 TMR_Status TMR_SR_cmdHiggs2FullLoadImage(TMR_Reader *reader, uint16_t timeout,
00611             TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword,
00612             uint16_t lockBits, uint16_t pcWord, uint8_t count,
00613             const uint8_t epc[], TMR_TagFilter* target);
00614 TMR_Status TMR_SR_cmdHiggs3FastLoadImage(TMR_Reader *reader, uint16_t timeout,
00615             TMR_GEN2_Password currentAccessPassword, 
00616             TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword,
00617             uint16_t pcWord, uint8_t count, const uint8_t epc[], TMR_TagFilter* target);
00618 TMR_Status TMR_SR_cmdHiggs3LoadImage(TMR_Reader *reader, uint16_t timeout,
00619             TMR_GEN2_Password currentAccessPassword,
00620             TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword,
00621             uint16_t pcWord, uint8_t len, const uint8_t epcAndUserData[], TMR_TagFilter* target);
00622 TMR_Status TMR_SR_cmdHiggs3BlockReadLock(TMR_Reader *reader, uint16_t timeout,
00623             TMR_GEN2_Password accessPassword, uint8_t lockBits, TMR_TagFilter* target);
00624 TMR_Status TMR_SR_cmdNxpSetReadProtect(TMR_Reader *reader, uint16_t timeout,
00625             TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_TagFilter* target);
00626 TMR_Status TMR_SR_cmdNxpResetReadProtect(TMR_Reader *reader, uint16_t timeout,
00627             TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_TagFilter* target);
00628 TMR_Status TMR_SR_cmdNxpChangeEas(TMR_Reader *reader, uint16_t timeout,
00629             TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, bool reset, TMR_TagFilter* target);
00630 TMR_Status TMR_SR_cmdNxpEasAlarm(TMR_Reader *reader, uint16_t timeout,
00631             TMR_SR_GEN2_SiliconType chip, TMR_GEN2_DivideRatio dr, TMR_GEN2_TagEncoding m, TMR_GEN2_TrExt trExt,
00632             TMR_uint8List *data, TMR_TagFilter* target);
00633 TMR_Status TMR_SR_cmdNxpCalibrate(TMR_Reader *reader, uint16_t timeout,
00634             TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_uint8List *data, TMR_TagFilter* target);
00635 TMR_Status TMR_SR_cmdNxpChangeConfig(TMR_Reader *reader, uint16_t timeout,
00636             TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_NXP_ConfigWord configWord, TMR_uint8List *data, TMR_TagFilter* target);
00637 TMR_Status TMR_SR_cmdGen2v2NXPUntraceable(TMR_Reader *reader, uint16_t timeout,TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, uint16_t configWord,
00638                         TMR_TagOp_GEN2_NXP_Untraceable op,TMR_uint8List *data, TMR_TagFilter* target);
00639 TMR_Status TMR_SR_cmdGen2v2NXPAuthenticate(TMR_Reader *reader, uint16_t timeout,TMR_SR_GEN2_SiliconType chip,
00640                  TMR_GEN2_Password accessPassword, TMR_TagOp_GEN2_NXP_Authenticate op, TMR_uint8List *data, TMR_TagFilter* target);
00641 TMR_Status TMR_SR_cmdGen2v2NXPReadBuffer(TMR_Reader *reader, uint16_t timeout,TMR_SR_GEN2_SiliconType chip,
00642                                         TMR_GEN2_Password accessPassword, TMR_TagOp_GEN2_NXP_Readbuffer op, TMR_uint8List *data, TMR_TagFilter* target);
00643 TMR_Status TMR_SR_cmdMonza4QTReadWrite(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00644             TMR_Monza4_ControlByte controlByte, TMR_Monza4_Payload payload, TMR_uint8List *data, TMR_TagFilter* target);
00645 TMR_Status TMR_SR_cmdSL900aGetSensorValue(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00646             uint8_t CommandCode, uint32_t password, PasswordLevel level, Sensor sensortype, TMR_uint8List *data, TMR_TagFilter* target);
00647 TMR_Status TMR_SR_cmdSL900aGetMeasurementSetup(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00648             uint8_t CommandCode, uint32_t password, PasswordLevel level,TMR_uint8List *data, TMR_TagFilter* target);
00649 TMR_Status TMR_SR_cmdSL900aGetCalibrationData(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00650             uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_uint8List *data, TMR_TagFilter* target);
00651 TMR_Status TMR_SR_cmdSL900aSetCalibrationData(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00652             uint8_t CommandCode, uint32_t password, PasswordLevel level, uint64_t calibration, TMR_TagFilter* target);
00653 TMR_Status TMR_SR_cmdSL900aSetSfeParameters(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00654             uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t sfe, TMR_TagFilter* target);
00655 TMR_Status TMR_SR_cmdSL900aGetLogState(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00656             uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_uint8List *data, TMR_TagFilter* target);
00657 TMR_Status TMR_SR_cmdSL900aSetLogMode(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00658            uint8_t CommandCode, uint32_t password, PasswordLevel level, LoggingForm form, StorageRule rule, bool Ext1Enable,
00659            bool Ext2Enable, bool TempEnable, bool BattEnable, uint16_t LogInterval, TMR_TagFilter* target);
00660 TMR_Status TMR_SR_cmdSL900aSetLogLimit(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00661            uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t exLower,
00662            uint16_t lower, uint16_t upper, uint16_t exUpper, TMR_TagFilter* target);
00663 TMR_Status TMR_SR_cmdSL900aSetShelfLife(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00664                              uint8_t CommandCode, uint32_t password, PasswordLevel level, uint32_t block0, uint32_t block1,
00665                              TMR_TagFilter* target);
00666 TMR_Status TMR_SR_cmdSL900aInitialize(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00667                                       uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t delayTime,
00668                                       uint16_t applicatioData, TMR_TagFilter* target);
00669 TMR_Status TMR_SR_cmdSL900aStartLog(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t CommandCode,
00670                                     uint32_t password, PasswordLevel level, uint32_t time, TMR_TagFilter* target);
00671 TMR_Status TMR_SR_cmdSL900aEndLog(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00672            uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_TagFilter* target);
00673 TMR_Status TMR_SR_cmdSL900aSetPassword(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00674            uint8_t CommandCode, uint32_t password, PasswordLevel level, uint32_t newPassword,
00675            PasswordLevel newPasswordLevel, TMR_TagFilter* target);
00676 TMR_Status TMR_SR_cmdSL900aGetBatteryLevel(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword,
00677                                            uint8_t CommandCode, uint32_t password, PasswordLevel level,BatteryType type,
00678                                            TMR_uint8List *data, TMR_TagFilter* target);
00679 TMR_Status TMR_SR_cmdSL900aAccessFifoStatus(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t CommandCode,
00680            uint32_t password, PasswordLevel level, AccessFifoOperation opearation, TMR_uint8List * data, TMR_TagFilter* target);
00681 TMR_Status TMR_SR_cmdSL900aAccessFifoRead(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t CommandCode,
00682             uint32_t password, PasswordLevel level, AccessFifoOperation opearation, uint8_t length,TMR_uint8List * data, TMR_TagFilter* target);
00683 TMR_Status TMR_SR_cmdSL900aAccessFifoWrite(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t CommandCode,
00684            uint32_t password, PasswordLevel level, AccessFifoOperation opearation, TMR_uint8List *payLoad, TMR_uint8List * data, TMR_TagFilter* target);
00685 TMR_Status TMR_SR_cmdHibikiReadLock(TMR_Reader *reader, uint16_t timeout,
00686             TMR_GEN2_Password accessPassword, uint16_t mask, uint16_t action);
00687 TMR_Status TMR_SR_cmdHibikiGetSystemInformation(TMR_Reader *reader, uint16_t timeout,
00688             TMR_GEN2_Password accessPassword,
00689             TMR_GEN2_HibikiSystemInformation *info);
00690 TMR_Status TMR_SR_cmdHibikiSetAttenuate(TMR_Reader *reader, uint16_t timeout,
00691             TMR_GEN2_Password accessPassword, uint8_t level, bool lock);
00692 TMR_Status TMR_SR_cmdHibikiBlockLock(TMR_Reader *reader, uint16_t timeout,
00693             TMR_GEN2_Password accessPassword, uint8_t block,
00694             TMR_GEN2_Password blockPassword, uint8_t mask, uint8_t action);
00695 TMR_Status TMR_SR_cmdHibikiBlockReadLock(TMR_Reader *reader, uint16_t timeout,
00696             TMR_GEN2_Password accessPassword, uint8_t block,
00697             TMR_GEN2_Password blockPassword, uint8_t mask, uint8_t action);
00698 TMR_Status TMR_SR_cmdHibikiWriteMultipleWords(TMR_Reader *reader,
00699             uint16_t timeout, TMR_GEN2_Password accessPassword,
00700             TMR_GEN2_Bank bank, uint32_t wordOffset, uint8_t count,
00701             const uint8_t data[]);
00702 TMR_Status TMR_SR_cmdEraseBlockTagSpecific(TMR_Reader *reader, uint16_t timeout,
00703             TMR_GEN2_Bank bank, uint32_t address, uint8_t count);
00704 TMR_Status TMR_SR_cmdGetTxRxPorts(TMR_Reader *reader, TMR_SR_PortPair *ant);
00705 TMR_Status TMR_SR_cmdGetAntennaConfiguration(TMR_Reader *reader,
00706             TMR_SR_AntennaPort *config);
00707 TMR_Status TMR_SR_cmdGetAntennaSearchList(TMR_Reader *reader, uint8_t *count,
00708             TMR_SR_PortPair *ants);
00709 TMR_Status TMR_SR_cmdGetAntennaPortPowers(TMR_Reader *reader, uint8_t *count,
00710             TMR_SR_PortPower *ports);
00711 TMR_Status TMR_SR_cmdGetAntennaPortPowersAndSettlingTime(TMR_Reader *reader,
00712             uint8_t *count, TMR_SR_PortPowerAndSettlingTime *ports);
00713 TMR_Status TMR_SR_cmdGetAntennaReturnLoss(TMR_Reader *reader, TMR_PortValueList *ports);
00714 TMR_Status TMR_SR_cmdAntennaDetect(TMR_Reader *reader, uint8_t *count,
00715             TMR_SR_PortDetect *ports);
00716 TMR_Status TMR_SR_cmdGetReadTxPower(TMR_Reader *reader, int32_t *power);
00717 TMR_Status TMR_SR_cmdGetReadTxPowerWithLimits(TMR_Reader *reader,
00718             TMR_SR_PowerWithLimits *power);
00719 TMR_Status TMR_SR_cmdGetWriteTxPower(TMR_Reader *reader, int32_t *power);
00720 TMR_Status TMR_SR_cmdGetWriteTxPowerWithLimits(TMR_Reader *reader,
00721             TMR_SR_PowerWithLimits *power);
00722 TMR_Status TMR_SR_cmdGetCurrentProtocol(TMR_Reader *reader,
00723             TMR_TagProtocol *protocol);
00724 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);
00725 TMR_Status TMR_SR_cmdGetFrequencyHopTable(TMR_Reader *reader, uint8_t *count,
00726             uint32_t *hopTable);
00727 TMR_Status TMR_SR_cmdGetFrequencyHopTime(TMR_Reader *reader, uint32_t *hopTime);
00728 TMR_Status TMR_SR_cmdGetGPIO(TMR_Reader *reader, uint8_t *count, TMR_GpioPin *state);
00729 TMR_Status TMR_SR_cmdGetGPIODirection(TMR_Reader *reader, uint8_t pin,
00730             bool *out);
00731 TMR_Status TMR_SR_cmdGetRegion(TMR_Reader *reader, TMR_Region *region);
00732 TMR_Status TMR_SR_cmdGetRegionConfiguration(TMR_Reader *reader,
00733             TMR_SR_RegionConfiguration key, void *value);
00734 TMR_Status TMR_SR_cmdGetPowerMode(TMR_Reader *reader, TMR_SR_PowerMode *mode);
00735 TMR_Status TMR_SR_cmdGetUserMode(TMR_Reader *reader, TMR_SR_UserMode *mode);
00736 TMR_Status TMR_SR_cmdGetReaderConfiguration(TMR_Reader *reader,
00737             TMR_SR_Configuration key, void *value);
00738 TMR_Status TMR_SR_cmdIAVDenatranCustomOp(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t rfu,
00739            TMR_uint8List *data, TMR_TagFilter* target);
00740 TMR_Status TMR_SR_cmdIAVDenatranCustomActivateSiniavMode(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t payload,
00741            TMR_uint8List *data, TMR_TagFilter* target, bool tokenDesc, uint8_t *token);
00742 TMR_Status TMR_SR_cmdIAVDenatranCustomReadFromMemMap(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t payload,
00743             TMR_uint8List *data, TMR_TagFilter* target, uint16_t wordAddress);
00744 TMR_Status TMR_SR_cmdIAVDenatranCustomWriteToMemMap(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t payload,
00745             TMR_uint8List *data, TMR_TagFilter* target, uint16_t wordPtr, uint16_t wordData, uint8_t* tagId, uint8_t* dataBuf);
00746 TMR_Status TMR_SR_cmdIAVDenatranCustomWriteSec(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t payload,
00747             TMR_uint8List *data, TMR_TagFilter* target, uint8_t* dataWords, uint8_t* dataBuf);
00748 TMR_Status TMR_SR_cmdIAVDenatranCustomGetTokenId(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode,
00749            TMR_uint8List *data, TMR_TagFilter* target);
00750 TMR_Status TMR_SR_cmdIAVDenatranCustomReadSec(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t mode, uint8_t payload,
00751             TMR_uint8List *data, TMR_TagFilter* target, uint16_t wordAddress);
00752 TMR_Status TMR_SR_cmdGetProtocolConfiguration(TMR_Reader *reader, TMR_TagProtocol protocol,
00753             TMR_SR_ProtocolConfiguration key, void *value);
00754 TMR_Status TMR_SR_cmdGetReaderStats(TMR_Reader *reader,
00755            TMR_Reader_StatsFlag statFlags,
00756            TMR_Reader_StatsValues *stats);
00757 TMR_Status TMR_SR_cmdGetReaderStatistics(TMR_Reader *reader,
00758             TMR_SR_ReaderStatisticsFlag statFlags,
00759             TMR_SR_ReaderStatistics *stats);
00760 TMR_Status TMR_SR_cmdGetAvailableProtocols(TMR_Reader *reader,
00761             TMR_TagProtocolList *protocols);
00762 TMR_Status TMR_SR_cmdGetAvailableRegions(TMR_Reader *reader,
00763             TMR_RegionList *regions);
00764 TMR_Status TMR_SR_cmdGetTemperature(TMR_Reader *reader, int8_t *temp);
00765 TMR_Status TMR_SR_cmdSetTxRxPorts(TMR_Reader *reader, uint8_t txPrt,
00766             uint8_t rxPort);
00767 TMR_Status TMR_SR_cmdSetAntennaSearchList(TMR_Reader *reader,
00768             uint8_t count, const TMR_SR_PortPair *ports);
00769 TMR_Status TMR_SR_cmdSetAntennaPortPowers(TMR_Reader *reader,
00770             uint8_t count, const TMR_SR_PortPower *ports);
00771 TMR_Status TMR_SR_cmdSetAntennaPortPowersAndSettlingTime(TMR_Reader *reader,
00772             uint8_t count, const TMR_SR_PortPowerAndSettlingTime *ports);
00773 TMR_Status TMR_SR_cmdSetReadTxPower(TMR_Reader *reader, int32_t power);
00774 TMR_Status TMR_SR_cmdSetWriteTxPower(TMR_Reader *reader, int32_t power);
00775 TMR_Status TMR_SR_cmdSetProtocol(TMR_Reader *reader, TMR_TagProtocol protocol);
00776 TMR_Status TMR_SR_cmdSetFrequencyHopTable(TMR_Reader *reader, uint8_t count,
00777             const uint32_t *table);
00778 TMR_Status TMR_SR_cmdSetFrequencyHopTime(TMR_Reader *reader, uint32_t hopTime);
00779 TMR_Status TMR_SR_cmdSetGPIO(TMR_Reader *reader, uint8_t gpio, bool high);
00780 TMR_Status TMR_SR_cmdSetGPIODirection(TMR_Reader *reader, uint8_t pin,
00781             bool out);
00782 TMR_Status TMR_SR_cmdSetRegion(TMR_Reader *reader, TMR_Region region);
00783 TMR_Status TMR_SR_cmdSetRegionLbt(TMR_Reader *reader, TMR_Region region, bool lbt);
00784 TMR_Status TMR_SR_cmdSetPowerMode(TMR_Reader *reader, TMR_SR_PowerMode mode);
00785 TMR_Status TMR_SR_cmdSetUserMode(TMR_Reader *reader, TMR_SR_UserMode mode);
00786 TMR_Status TMR_SR_cmdSetReaderConfiguration(TMR_Reader *reader, 
00787             TMR_SR_Configuration key, const void *value);
00788 TMR_Status TMR_SR_cmdSetProtocolLicenseKey(TMR_Reader *reader, TMR_SR_SetProtocolLicenseOption option, uint8_t key[], int key_len,uint32_t *retData);
00789 TMR_Status TMR_SR_cmdSetProtocolConfiguration(TMR_Reader *reader,
00790             TMR_TagProtocol protocol, TMR_SR_ProtocolConfiguration key,
00791             const void *value);
00792 TMR_Status TMR_SR_cmdResetReaderStats(TMR_Reader *reader,
00793            TMR_Reader_StatsFlag statFlags);
00794 TMR_Status TMR_SR_cmdResetReaderStatistics(TMR_Reader *reader,
00795             TMR_SR_ReaderStatisticsFlag statFlags);
00796 TMR_Status TMR_SR_cmdTestSetFrequency(TMR_Reader *reader, uint32_t frequency);
00797 TMR_Status TMR_SR_cmdTestSendCw(TMR_Reader *reader, bool on);
00798 TMR_Status TMR_SR_cmdTestSendPrbs(TMR_Reader *reader, uint16_t duration);
00799 TMR_Status TMR_SR_cmdSetUserProfile(TMR_Reader *reader,
00800                                     TMR_SR_UserConfigOperation op,TMR_SR_UserConfigCategory category, TMR_SR_UserConfigType type);
00801 TMR_Status TMR_SR_cmdGetUserProfile(TMR_Reader *reader, 
00802                                     uint8_t byte[], uint8_t length, uint8_t response[], uint8_t* response_length);
00803 TMR_Status TMR_SR_cmdBlockWrite(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Bank bank, uint32_t wordPtr, 
00804                                  uint32_t wordCount, const uint16_t* data, uint32_t accessPassword, const TMR_TagFilter* target);
00805 TMR_Status TMR_SR_cmdBlockErase(TMR_Reader *reader, uint16_t timeout, TMR_GEN2_Bank bank, uint32_t wordPtr,
00806                                  uint8_t wordCount, uint32_t accessPassword, TMR_TagFilter *target);
00807 TMR_Status TMR_SR_cmdBlockPermaLock(TMR_Reader *reader, uint16_t timeout,uint32_t readLock, TMR_GEN2_Bank bank, 
00808                          uint32_t blockPtr, uint32_t blockRange, uint16_t* mask, uint32_t accessPassword, TMR_TagFilter* target, TMR_uint8List *data);
00809 TMR_Status TMR_SR_msgSetupReadTagMultiple(TMR_Reader *reader, uint8_t *msg, uint8_t *i,
00810             uint16_t timeout, TMR_SR_SearchFlag searchFlag,
00811             const TMR_TagFilter *filter, TMR_TagProtocol protocol,
00812             TMR_GEN2_Password accessPassword);
00813 
00814 TMR_Status
00815 TMR_SR_msgSetupReadTagMultipleWithMetadata(TMR_Reader *reader, uint8_t *msg, uint8_t *i, uint16_t timeout,
00816                                TMR_SR_SearchFlag searchFlag,
00817                                                                          TMR_TRD_MetadataFlag metadataFlag,
00818                                const TMR_TagFilter *filter,
00819                                TMR_TagProtocol protocol,
00820                                TMR_GEN2_Password accessPassword);
00821 
00822 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);
00823 void TMR_SR_msgAddGEN2WriteTagEPC(uint8_t *msg, uint8_t *i, uint16_t timeout, uint8_t *epc, uint8_t count);
00824 void TMR_SR_msgAddGEN2DataRead(uint8_t *msg, uint8_t *i, uint16_t timeout,
00825       TMR_GEN2_Bank bank, uint32_t wordAddress, uint8_t len, uint8_t option, bool withMetaData);
00826 void TMR_SR_msgAddGEN2DataWrite(uint8_t *msg, uint8_t *i, uint16_t timeout,
00827       TMR_GEN2_Bank bank, uint32_t address);
00828 void TMR_SR_msgAddGEN2LockTag(uint8_t *msg, uint8_t *i, uint16_t timeout,
00829       uint16_t mask, uint16_t action, TMR_GEN2_Password password);
00830 void TMR_SR_msgAddGEN2KillTag(uint8_t *msg, uint8_t *i, uint16_t timeout,
00831       TMR_GEN2_Password password);
00832 void
00833 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);
00834 
00835 void
00836 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);
00837 
00838 void
00839 TMR_SR_msgAddGEN2BlockErase(uint8_t *msg, uint8_t *i, uint16_t timeout, uint32_t wordPtr, TMR_GEN2_Bank bank,
00840                             uint8_t wordCount, uint32_t accessPassword, TMR_TagFilter* target);
00841 
00842 void 
00843 TMR_SR_msgAddHiggs2PartialLoadImage(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword, 
00844                                     TMR_GEN2_Password killPassword, uint8_t len, const uint8_t *epc, TMR_TagFilter* target);
00845 void 
00846 TMR_SR_msgAddHiggs2FullLoadImage(uint8_t *msg, uint8_t *i, uint16_t timeout,
00847       TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword, uint16_t lockBits, uint16_t pcWord, uint8_t len, const uint8_t *epc, TMR_TagFilter* target);
00848 void 
00849 TMR_SR_msgAddHiggs3FastLoadImage(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password currentAccessPassword,
00850       TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword, uint16_t pcWord, uint8_t len, const uint8_t *epc, TMR_TagFilter* target);
00851 void 
00852 TMR_SR_msgAddHiggs3LoadImage(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password currentAccessPassword,
00853       TMR_GEN2_Password accessPassword, TMR_GEN2_Password killPassword, uint16_t pcWord, uint8_t len, const uint8_t *epcAndUserData, TMR_TagFilter* target);
00854 
00855 void 
00856 TMR_SR_msgAddHiggs3BlockReadLock(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword, uint8_t lockBits, TMR_TagFilter* target);
00857 
00858 void 
00859 TMR_SR_msgAddNXPSetReadProtect(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_SR_GEN2_SiliconType chip,
00860                             TMR_GEN2_Password accessPassword, TMR_TagFilter* target);
00861 void 
00862 TMR_SR_msgAddNXPResetReadProtect(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_SR_GEN2_SiliconType chip,
00863                             TMR_GEN2_Password accessPassword, TMR_TagFilter* target);
00864 void
00865 TMR_SR_msgAddNXPChangeEAS(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_SR_GEN2_SiliconType chip,
00866                           TMR_GEN2_Password accessPassword, bool reset, TMR_TagFilter* target);
00867 void 
00868 TMR_SR_msgAddNXPEASAlarm(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_SR_GEN2_SiliconType chip,
00869                          TMR_GEN2_DivideRatio dr, TMR_GEN2_TagEncoding m, TMR_GEN2_TrExt trExt, TMR_TagFilter* target);
00870 void
00871 TMR_SR_msgAddIAVDenatranCustomOp(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00872                          uint8_t mode, uint8_t rfu, TMR_TagFilter* target);
00873 void 
00874 TMR_SR_msgAddIAVDenatranCustomActivateSiniavMode(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00875                          uint8_t mode, uint8_t payload, TMR_TagFilter* target, bool tokenDesc, uint8_t *token);
00876 void 
00877 TMR_SR_msgAddIAVDenatranCustomReadFromMemMap(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00878                         uint8_t mode, uint8_t payload, TMR_TagFilter* target, uint16_t wordAddress);
00879 void 
00880 TMR_SR_msgAddIAVDenatranCustomWriteToMemMap(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00881                         uint8_t mode, uint8_t payload, TMR_TagFilter* target, uint16_t wordPtr, uint16_t wordData, uint8_t* tagId, uint8_t* dataBuf);
00882 void
00883 TMR_SR_msgAddIAVDenatranCustomWriteSec(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00884                         uint8_t mode, uint8_t payload, TMR_TagFilter* target, uint8_t* data, uint8_t* dataBuf);
00885 void 
00886 TMR_SR_msgAddIAVDenatranCustomGetTokenId(uint8_t *msg, uint8_t *i, uint16_t timeout,
00887                         TMR_GEN2_Password accessPassword, uint8_t mode, TMR_TagFilter* target);
00888 void 
00889 TMR_SR_msgAddIAVDenatranCustomReadSec(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00890                         uint8_t mode, uint8_t payload, TMR_TagFilter* target, uint16_t wordAddress);
00891 void 
00892 TMR_SR_msgAddNXPCalibrate(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_SR_GEN2_SiliconType chip,
00893                          TMR_GEN2_Password accessPassword, TMR_TagFilter* target);
00894 void 
00895 TMR_SR_msgAddNXPChangeConfig(uint8_t *msg, uint8_t *i, uint16_t timeout,
00896                          TMR_SR_GEN2_SiliconType chip, TMR_GEN2_Password accessPassword, TMR_NXP_ConfigWord configword, TMR_TagFilter* target);
00897 void 
00898 TMR_SR_msgAddMonza4QTReadWrite(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00899                                TMR_Monza4_ControlByte controlByte, TMR_Monza4_Payload payload, TMR_TagFilter* target);
00900 
00901 void 
00902 TMR_SR_msgAddIdsSL900aGetSensorValue(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00903                                      uint8_t CommandCode, uint32_t password, PasswordLevel level, Sensor sensortype,
00904                                      TMR_TagFilter* target);
00905 void 
00906 TMR_SR_msgAddIdsSL900aGetMeasurementSetup(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00907                                           uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_TagFilter* target);
00908 
00909 void 
00910 TMR_SR_msgAddIdsSL900aGetCalibrationData(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00911                                      uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_TagFilter* target);
00912 void 
00913 TMR_SR_msgAddIdsSL900aSetCalibrationData(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00914                                           uint8_t CommandCode, uint32_t password, PasswordLevel level, uint64_t calibration, TMR_TagFilter* target);
00915 void 
00916 TMR_SR_msgAddIdsSL900aSetSfeParameters(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00917                                           uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t sfe,
00918                                           TMR_TagFilter* target);
00919 void 
00920 TMR_SR_msgAddIdsSL900aGetLogState(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00921                                   uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_TagFilter* target);
00922 void
00923 TMR_SR_msgAddIdsSL900aSetLogMode(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00924                                  uint8_t CommandCode, uint32_t password, PasswordLevel level, LoggingForm form,
00925                                  StorageRule rule, bool Ext1Enable, bool Ext2Enable, bool TempEnable, bool BattEnable,
00926                                  uint16_t LogInterval, TMR_TagFilter* target);
00927 void 
00928 TMR_SR_msgAddIdsSL900aSetLogLimit(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00929                                   uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t exLower,
00930                                   uint16_t lower, uint16_t upper, uint16_t exUpper, TMR_TagFilter* target);
00931 void 
00932 TMR_SR_msgAddIdsSL900aSetShelfLife(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00933                                    uint8_t CommandCode, uint32_t password, PasswordLevel level, uint32_t block0, uint32_t block1,
00934                                    TMR_TagFilter* target);
00935 void
00936 TMR_SR_msgAddIdsSL900aInitialize(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00937                                  uint8_t CommandCode, uint32_t password, PasswordLevel level, uint16_t delayTime,
00938                                  uint16_t applicatioData, TMR_TagFilter* target);
00939 void
00940 TMR_SR_msgAddIdsSL900aEndLog(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00941                              uint8_t CommandCode, uint32_t password, PasswordLevel level, TMR_TagFilter* target);
00942 void
00943 TMR_SR_msgAddIdsSL900aSetPassword(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00944                                   uint8_t CommandCode, uint32_t password, PasswordLevel level, uint32_t newPassword,
00945                                   PasswordLevel newPasswordLevel, TMR_TagFilter* target);
00946 void 
00947 TMR_SR_msgAddIdsSL900aAccessFifoStatus(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00948                                   uint8_t CommandCode, uint32_t password, PasswordLevel level, AccessFifoOperation opearation,
00949                                   TMR_TagFilter* target);
00950 void 
00951 TMR_SR_msgAddIdsSL900aGetBatteryLevel(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00952                                       uint8_t CommandCode, uint32_t password, PasswordLevel level, BatteryType batteryType,
00953                                       TMR_TagFilter* target);
00954 void 
00955 TMR_SR_msgAddIdsSL900aAccessFifoRead(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00956                                   uint8_t CommandCode, uint32_t password, PasswordLevel level, AccessFifoOperation opearation,
00957                                   uint8_t length, TMR_TagFilter* target);
00958 void 
00959 TMR_SR_msgAddIdsSL900aAccessFifoWrite(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00960                                   uint8_t CommandCode, uint32_t password, PasswordLevel level, AccessFifoOperation opearation,
00961                                   TMR_uint8List *payLoad, TMR_TagFilter* target);
00962 void 
00963 TMR_SR_msgAddIdsSL900aStartLog(uint8_t *msg, uint8_t *i, uint16_t timeout, TMR_GEN2_Password accessPassword,
00964                                uint8_t CommandCode, uint32_t password, PasswordLevel level, uint32_t time, TMR_TagFilter* target);
00965 
00966 TMR_Status TMR_SR_executeEmbeddedRead(TMR_Reader *reader, uint8_t *msg,
00967             uint16_t timeout, TMR_SR_MultipleStatus *status);
00968 
00969 TMR_Status TMR_SR_cmdISO180006BWriteTagData(TMR_Reader *reader,
00970       uint16_t timeout, uint8_t address, uint8_t count, const uint8_t data[],
00971       const TMR_TagFilter *filter);
00972 TMR_Status TMR_SR_cmdISO180006BReadTagData(TMR_Reader *reader,
00973       uint16_t timeout, uint8_t address, uint8_t length,
00974       const TMR_TagFilter *filter, TMR_TagReadData *read);
00975 TMR_Status TMR_SR_cmdISO180006BLockTag(TMR_Reader *reader, uint16_t timeout,
00976       uint8_t address, const TMR_TagFilter *filter);
00977 TMR_Status TMR_iso18000BBLFValToInt(int val, void *lf);
00978 TMR_Status TMR_SR_cmdStopReading(struct TMR_Reader *reader);
00979 TMR_Status TMR_SR_cmdGetReaderWriteTimeOut (struct TMR_Reader *reader, TMR_TagProtocol protocol,
00980                                                                                                                                                                                 TMR_SR_Gen2ReaderWriteTimeOut *value);
00981 TMR_Status TMR_SR_cmdSetReaderWriteTimeOut (struct TMR_Reader *reader, TMR_TagProtocol protocol,
00982                                                                                                                                                                                 TMR_SR_Gen2ReaderWriteTimeOut *value);
00983 TMR_Status TMR_SR_cmdAuthReqResponse(struct TMR_Reader *reader, TMR_TagAuthentication *auth);
00984 
00985 TMR_Status TMR_SR_addTagOp(struct TMR_Reader *reader, TMR_TagOp *tagop,TMR_ReadPlan *rp, uint8_t *msg, uint8_t *i, uint32_t readTimeMs, uint8_t *lenbyte);
00986 
00987 TMR_Status
00988 TMR_fillReaderStats(TMR_Reader *reader, TMR_Reader_StatsValues* stats, uint16_t flag, uint8_t* msg, uint8_t offset);
00989 bool compareAntennas(TMR_MultiReadPlan *multi);
00990 bool compareVersion(TMR_Reader *reader, uint8_t firstByte, uint8_t secondByte, uint8_t thirdByte, uint8_t fourthByte);
00991 TMR_Status
00992 TMR_SR_cmdrebootReader(TMR_Reader *reader);
00993 TMR_Status
00994 prepForSearch(TMR_Reader *reader, TMR_uint8List *antennaList);
00995 TMR_Status 
00996 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);
00997 TMR_Status TMR_SR_cmdProbeBaudRate(TMR_Reader *reader, uint32_t *currentBaudRate);
00998 void TMR_SR_updateBaseTimeStamp(TMR_Reader *reader);
00999 TMR_Status verifySearchStatus(TMR_Reader *reader);
01000 
01001 
01002 #ifdef TMR_ENABLE_BACKGROUND_READS
01003 void notify_authreq_listeners(TMR_Reader *reader, TMR_TagReadData *trd, TMR_TagAuthentication *auth);
01004 #endif
01005 
01006 
01007 #ifdef __cplusplus
01008 }
01009 #endif
01010 
01011 #endif /* _SERIAL_READER_IMP_H */


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