tmr_serial_reader.h
Go to the documentation of this file.
00001 /* ex: set tabstop=2 shiftwidth=2 expandtab cindent: */
00002 #ifndef _TMR_SERIAL_READER_H
00003 #define _TMR_SERIAL_READER_H
00004 
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 
00033 #include "tmr_region.h"
00034 #include "tmr_tag_protocol.h"
00035 #include "tmr_serial_transport.h"
00036 
00037 #define TMR_SR_MAX_PACKET_SIZE 256
00038 
00039 #ifdef  __cplusplus
00040 extern "C" {
00041 #endif
00042 
00048 typedef enum TMR_SR_PowerMode
00049 {
00050   TMR_SR_POWER_MODE_MIN     = 0,
00051   TMR_SR_POWER_MODE_FULL    = 0,
00052   TMR_SR_POWER_MODE_MINSAVE = 1,
00053   TMR_SR_POWER_MODE_MEDSAVE = 2,
00054   TMR_SR_POWER_MODE_MAXSAVE = 3,
00055   TMR_SR_POWER_MODE_SLEEP   = 4,
00056   TMR_SR_POWER_MODE_MAX     = TMR_SR_POWER_MODE_SLEEP,
00057   TMR_SR_POWER_MODE_INVALID = TMR_SR_POWER_MODE_MAX + 1,
00058 } TMR_SR_PowerMode;
00059 
00063 typedef enum TMR_SR_SetProtocolLicenseOption
00064 {
00066 TMR_SR_SET_LICENSE_KEY = 0x01,     
00068 TMR_SR_ERASE_LICENSE_KEY = 0x02, 
00069 }TMR_SR_SetProtocolLicenseOption;
00070 
00074 typedef enum TMR_SR_UserConfigOperation
00075 {          
00077 TMR_USERCONFIG_SAVE = 0x01,     
00079 TMR_USERCONFIG_RESTORE = 0x02, 
00081 TMR_USERCONFIG_VERIFY = 0x03,  
00083 TMR_USERCONFIG_CLEAR = 0x04,
00085 TMR_USERCONFIG_SAVE_WITH_READPLAN = 0x05,
00086 }TMR_SR_UserConfigOperation; 
00087 
00091 typedef enum TMR_SR_UserConfigCategory
00092 {
00094 TMR_SR_ALL=0x01,   
00095 }TMR_SR_UserConfigCategory;
00096 
00100 typedef enum TMR_SR_UserConfigType
00101 {
00103 TMR_SR_FIRMWARE_DEFAULT=0x00,
00105 TMR_SR_CUSTOM_CONFIGURATION=0x01,      
00106 }TMR_SR_UserConfigType;
00107 
00111 typedef struct TMR_SR_UserConfigOp
00112 {
00116   TMR_SR_UserConfigCategory category;
00118   TMR_SR_UserConfigOperation op;
00119 }TMR_SR_UserConfigOp;
00120 
00126 typedef enum TMR_SR_UserMode
00127 {
00128   TMR_SR_USER_MODE_MIN      = 0,
00129   TMR_SR_USER_MODE_UNSPEC   = 0,
00130   TMR_SR_USER_MODE_PRINTER  = 1,
00131   TMR_SR_USER_MODE_CONVEYOR = 2,
00132   TMR_SR_USER_MODE_PORTAL   = 3,
00133   TMR_SR_USER_MODE_HANDHELD = 4,
00134   TMR_SR_USER_MODE_MAX      = TMR_SR_USER_MODE_HANDHELD,
00135   TMR_SR_USER_MODE_INVALID  = TMR_SR_USER_MODE_MAX + 1,
00136 }TMR_SR_UserMode;
00137 
00141 typedef enum TMR_SR_GEN2_QType
00142 {
00143   TMR_SR_GEN2_Q_MIN     = 0,
00144   TMR_SR_GEN2_Q_DYNAMIC = 0,
00145   TMR_SR_GEN2_Q_STATIC  = 1,
00146   TMR_SR_GEN2_Q_MAX     = TMR_SR_GEN2_Q_STATIC,
00147   TMR_SR_GEN2_Q_INVALID = TMR_SR_GEN2_Q_MAX + 1,
00148 } TMR_SR_GEN2_QType;
00149 
00151 typedef struct TMR_SR_GEN2_QStatic
00152 {
00154   uint8_t initialQ;
00155 } TMR_SR_GEN2_QStatic;
00156 
00160 typedef struct TMR_SR_GEN2_Q
00161 {
00163   TMR_SR_GEN2_QType type;
00164   union
00165   {
00167     TMR_SR_GEN2_QStatic staticQ;
00168   }u;
00169 } TMR_SR_GEN2_Q;
00170 
00171 
00173 typedef struct TMR_PortValue
00174 {
00176   uint8_t port;
00178   int32_t value;
00179 } TMR_PortValue;
00180 
00182 typedef struct TMR_PortValueList
00183 {
00185   TMR_PortValue *list;
00187   uint8_t max;
00189   uint8_t len;
00190 } TMR_PortValueList;
00191 
00192 
00197 typedef struct TMR_AntennaMap
00198 {
00200   uint8_t antenna;
00202   uint8_t txPort;
00204   uint8_t rxPort;
00205 } TMR_AntennaMap;
00206 
00208 typedef struct TMR_AntennaMapList
00209 {
00211   TMR_AntennaMap *list;
00213   uint8_t max;
00215   uint8_t len;
00216 } TMR_AntennaMapList;
00217 
00221 typedef struct TMR_SR_VersionInfo
00222 {
00224   uint8_t bootloader[4];
00226   uint8_t hardware[4];
00228   uint8_t fwDate[4];
00230   uint8_t fwVersion[4];
00232   uint32_t protocols;
00233 } TMR_SR_VersionInfo;
00234 
00238 typedef enum TMR_TransportType
00239 {
00240   /* Serial */
00241   TMR_SR_MSG_SOURCE_SERIAL = 0x0000,
00242   /* USB */
00243   TMR_SR_MSG_SOURCE_USB = 0x0003,
00244   /* Unknown */
00245   TMR_SR_MSG_SOURCE_UNKNOWN = 0x0004,
00246 }TMR_TransportType;
00247 
00251 typedef struct TM_SR_SerialReader
00252 {
00255   /* Serial transport information */
00256   TMR_SR_SerialTransport transport;
00257   union
00258   {
00259 #ifdef TMR_ENABLE_SERIAL_TRANSPORT_NATIVE
00260     TMR_SR_SerialPortNativeContext nativeContext;
00261 #endif
00262   } transportContext;
00263 
00264   /* User-configurable values */
00265   uint32_t baudRate;
00266   TMR_AntennaMapList *txRxMap;
00267   TMR_GEN2_Password gen2AccessPassword;
00268   uint32_t transportTimeout;
00269   uint32_t commandTimeout;
00270   TMR_Region regionId;
00271 
00272   /* Static storage for the default map */
00273   TMR_AntennaMap staticTxRxMapData[TMR_SR_MAX_ANTENNA_PORTS];
00274   TMR_AntennaMapList staticTxRxMap;
00275 
00276   /* Mostly-fixed information about the connected reader */
00277   TMR_SR_VersionInfo versionInfo;
00278   uint32_t portMask;
00279 
00280   /* Option to enable or disable the pre-amble */
00281   bool supportsPreamble;
00282 
00283   /* Cache extendedEPC setting */
00284   bool extendedEPC;
00285 
00286   /* Cached values */
00287   TMR_SR_PowerMode powerMode;
00288   TMR_TagProtocol currentProtocol;
00289   int8_t gpioDirections;
00290 
00291   /* Large bitmask that stores whether each parameter's presence
00292    * is known or not.
00293    */
00294   uint32_t paramConfirmed[TMR_PARAMWORDS];
00295   /* Large bitmask that, if the corresponding bit in paramConfirmed is set,
00296    * stores whether each parameter is present or not.
00297    */
00298   uint32_t paramPresent[TMR_PARAMWORDS];
00299 
00300   /* Temporary storage during a read and subsequent fetch of tags */
00301   uint32_t readTimeLow, readTimeHigh;
00302   uint32_t lastSentTagTimestampHigh, lastSentTagTimestampLow;
00303   uint32_t searchTimeoutMs;
00304   
00305   /* Number of tags reported by module read command.
00306    * In streaming mode, exact quantity is unknown, so use
00307    * 0 if stream has ended, non-zero if end-of-stream has
00308    * not yet been detected. */
00309   int tagsRemaining;
00310   /* Buffer tag records fetched from module but not yet passed to caller. */
00311   uint8_t bufResponse[TMR_SR_MAX_PACKET_SIZE];
00312   /* bufResopnse read index */
00313   uint8_t bufPointer;
00314   /* Number of tag records in buffer but not yet passed to caller */
00315   uint8_t tagsRemainingInBuffer;
00316   /*TMR opCode*/
00317   uint8_t opCode;
00318   /*Gen2 Q Value from previous tagop */
00319   TMR_SR_GEN2_Q oldQ;
00320   /*Gen2 WriteMode*/
00321   TMR_GEN2_WriteMode writeMode;
00322   /* Buffer to store additional error message */
00323   char errMsg[TMR_SR_MAX_PACKET_SIZE];
00324   /* Product group id */
00325   uint16_t productId;
00326   /* Tag operation success count */
00327   uint16_t tagopSuccessCount;
00328   /* Tag operation failure count */
00329   uint16_t tagopFailureCount;
00330   /* Enable read filtering */
00331   bool enableReadFiltering;
00332   /* Read filter timeout */
00333   int32_t readFilterTimeout;
00334   /* Option to use the user specified transportTimeout */
00335   bool usrTimeoutEnable;
00336   /* Enable CRC calculation */
00337   bool crcEnabled;
00338   /* TransportType */
00339   TMR_TransportType transportType;
00340   /* Option for Gen2 all memory bank read */
00341   bool gen2AllMemoryBankEnabled;
00342   /* option for Gen2 Bap parameter */
00343   bool isBapEnabled;
00344   /* baud rates to be used for serial communication */
00345   TMR_uint32List probeBaudRates;
00346   /* storage for the probe baud rates */
00347   uint32_t baudRates[TMR_MAX_PROBE_BAUDRATE_LENGTH];
00348   /* Flag to be raised when Autonomous read is requested */
00349   bool enableAutonomousRead;
00350   /* The flag to be used in case of tag reading */
00351   bool isBasetimeUpdated;
00352 } TMR_SR_SerialReader;
00353 
00357 typedef struct TMR_SR_ReaderStatistics
00358 {
00360   uint8_t numPorts;
00362   uint32_t rfOnTime[TMR_SR_MAX_ANTENNA_PORTS];
00364   uint32_t noiseFloor[TMR_SR_MAX_ANTENNA_PORTS];
00366   uint32_t noiseFloorTxOn[TMR_SR_MAX_ANTENNA_PORTS];
00367 }TMR_SR_ReaderStatistics;
00368 
00372 typedef struct TMR_SR_AntennaStatusReport
00373 {
00375   uint8_t ant;
00376 }TMR_SR_AntennaStatusReport;
00377 
00381 typedef struct TMR_SR_FrequencyStatusReport
00382 {
00384   uint32_t freq;
00385 }TMR_SR_FrequencyStatusReport;
00386 
00390 typedef struct TMR_SR_TemperatureStatusReport
00391 {
00393   int8_t temp;
00394 }TMR_SR_TemperatureStatusReport;
00395 
00399 typedef enum TMR_SR_StatusType
00400 {
00401   /* None */
00402   TMR_SR_STATUS_NONE = 0x0000,
00403   /* Frequency */
00404   TMR_SR_STATUS_FREQUENCY = 0x0002,
00405   /* Temperature */
00406   TMR_SR_STATUS_TEMPERATURE = 0x0004,
00407   /* Current Antenna Ports */
00408   TMR_SR_STATUS_ANTENNA = 0x0008,
00409   /* All */
00410   TMR_SR_STATUS_ALL = 0x000E,
00411   TMR_SR_STATUS_MAX = 4,
00412 }TMR_SR_StatusType;
00413 
00418 typedef struct TMR_SR_StatusReport
00419 {
00420   TMR_SR_StatusType type;
00421   union
00422   {
00424     TMR_SR_AntennaStatusReport asr;
00426     TMR_SR_FrequencyStatusReport fsr;
00428     TMR_SR_TemperatureStatusReport tsr;
00429   } u;
00430 }TMR_SR_StatusReport;
00431 
00432 
00433 TMR_Status TMR_SR_connect(struct TMR_Reader *reader);
00434 TMR_Status TMR_SR_destroy(struct TMR_Reader *reader);
00435 TMR_Status TMR_SR_read(struct TMR_Reader *reader, uint32_t timeoutMs, int32_t *tagCount);
00436 TMR_Status TMR_SR_hasMoreTags(struct TMR_Reader *reader);
00437 TMR_Status TMR_SR_getNextTag(struct TMR_Reader *reader, TMR_TagReadData *read);
00438 TMR_Status TMR_SR_executeTagOp(struct TMR_Reader *reader, TMR_TagOp *tagop, TMR_TagFilter *filter, TMR_uint8List *data);
00439 TMR_Status TMR_SR_writeTag(struct TMR_Reader *reader, const TMR_TagFilter *filter, const TMR_TagData *data);
00440 TMR_Status TMR_SR_killTag(struct TMR_Reader *reader, const TMR_TagFilter *filter, const TMR_TagAuthentication *auth);
00441 TMR_Status TMR_SR_lockTag(struct TMR_Reader *reader, const TMR_TagFilter *filter, TMR_TagLockAction *action);
00442 TMR_Status TMR_SR_readTagMemBytes(struct TMR_Reader *reader, const TMR_TagFilter *filter,
00443                               uint32_t bank, uint32_t address,
00444                               uint16_t count, uint8_t data[]);
00445 TMR_Status TMR_SR_readTagMemWords(struct TMR_Reader *reader, const TMR_TagFilter *filter,
00446                               uint32_t bank, uint32_t address,
00447                               uint16_t count, uint16_t *data);
00448 TMR_Status TMR_SR_writeTagMemBytes(struct TMR_Reader *reader, const TMR_TagFilter *filter,
00449                                uint32_t bank, uint32_t address,
00450                                uint16_t count, const uint8_t data[]);
00451 TMR_Status TMR_SR_writeTagMemWords(struct TMR_Reader *reader, const TMR_TagFilter *filter,
00452                                uint32_t bank, uint32_t address,
00453                                uint16_t count, const uint16_t data[]);
00454 TMR_Status TMR_SR_gpoSet(struct TMR_Reader *reader, uint8_t count, const TMR_GpioPin state[]);
00455 TMR_Status TMR_SR_gpiGet(struct TMR_Reader *reader, uint8_t *count, TMR_GpioPin state[]);
00456 TMR_Status TMR_SR_firmwareLoad(TMR_Reader *reader, void *cookie,
00457                                TMR_FirmwareDataProvider provider);
00458 TMR_Status TMR_SR_modifyFlash(TMR_Reader *reader, uint8_t sector, uint32_t address,uint32_t password,
00459                               uint8_t length, const uint8_t data[], uint32_t offset);
00460 TMR_Status TMR_init_UserConfigOp(TMR_SR_UserConfigOp *config, TMR_SR_UserConfigOperation op);
00461 TMR_Status TMR_SR_reboot(struct TMR_Reader *reader);
00462 
00467 TMR_Status TMR_SR_SerialReader_init(TMR_Reader *reader);
00468 
00469 #ifdef __cplusplus
00470 }
00471 #endif
00472 
00473 #endif /* _TMR_SERIAL_READER_H */


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