Classes | Defines | Typedefs | Enumerations | Functions
tm_reader.h File Reference

Mercury API Reader Interface. More...

#include "tm_config.h"
#include "tmr_types.h"
#include "tmr_status.h"
#include "tmr_gpio.h"
#include "tmr_params.h"
#include "tmr_read_plan.h"
#include "tmr_tag_auth.h"
#include "tmr_tag_data.h"
#include "tmr_tag_lock_action.h"
#include "tmr_tag_protocol.h"
#include "tmr_tagop.h"
#include "tmr_serial_reader.h"
Include dependency graph for tm_reader.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  TMR_AuthReqListenerBlock
struct  TMR_memoryCookie
struct  TMR_Queue_tagReads
struct  TMR_Reader
struct  TMR_Reader_StatsValues
struct  TMR_ReadExceptionListenerBlock
struct  TMR_ReadListenerBlock
struct  TMR_readParams
struct  TMR_StatsListenerBlock
struct  TMR_StatsPerAntennaValues
struct  TMR_StatsPerAntennaValuesList
struct  TMR_StatusListenerBlock
struct  TMR_tagOpParams
struct  TMR_TransportListenerBlock

Defines

#define TMR_connect(reader)   ((reader)->connect(reader))
#define TMR_destroy(reader)   ((reader)->destroy(reader))
#define TMR_executeTagOp(reader, tagop, filter, data)   ((reader)->executeTagOp((reader), (tagop), (filter), (data)))
#define TMR_firmwareLoad(reader, cookie, provider)   ((reader)->firmwareLoad((reader),(cookie),(provider)))
#define TMR_getNextTag(reader, read)   ((reader)->getNextTag((reader),(read)))
#define TMR_gpiGet(reader, count, state)   ((reader)->gpiGet((reader),(count),(state)))
#define TMR_gpoSet(reader, count, state)   ((reader)->gpoSet((reader),(count),(state)))
#define TMR_hasMoreTags(reader)   ((reader)->hasMoreTags(reader))
#define TMR_killTag(reader, filter, auth)   ((reader)->killTag((reader),(filter),(auth)))
#define TMR_lockTag(reader, filter, action)   ((reader)->lockTag((reader),(filter),(action)))
#define TMR_modifyFlash(reader, sector, address, password, length, data, offset)   ((reader->modifyFlash((reader),(sector),(address),(password),(length),(data),(offset)))
#define TMR_read(reader, timeoutMs, tagCount)   ((reader)->read((reader),(timeoutMs),(tagCount)))
#define TMR_readTagMemBytes(reader, target, bank, address, count, data)   ((reader)->readTagMemBytes((reader),(target),(bank),(address),(count),(data)))
#define TMR_readTagMemWords(reader, target, bank, address, count, data)   ((reader)->readTagMemWords((reader),(target),(bank),(address),(count),(data)))
#define TMR_reboot(reader)   ((reader)->reboot(reader))
#define TMR_writeTag(reader, filter, data)   ((reader)->writeTag((reader),(filter),(data)))
#define TMR_writeTagMemBytes(reader, target, bank, address, count, data)   ((reader)->writeTagMemBytes((reader),(target),(bank),(address),(count),(data)))
#define TMR_writeTagMemWords(reader, target, bank, address, count, data)   ((reader)->writeTagMemWords((reader),(target),(bank),(address),(count),(data)))

Typedefs

typedef void(* TMR_AuthReqListener )(TMR_Reader *reader, const TMR_TagReadData *trd, void *cookie, TMR_TagAuthentication *auth)
typedef struct
TMR_AuthReqListenerBlock 
TMR_AuthReqListenerBlock
typedef TMR_SR_GEN2_Q TMR_GEN2_Q
typedef TMR_SR_GEN2_QStatic TMR_GEN2_QStatic
typedef TMR_SR_GEN2_QType TMR_GEN2_QType
typedef struct TMR_memoryCookie TMR_memoryCookie
typedef struct TMR_Queue_tagReads TMR_Queue_tagReads
typedef struct TMR_Reader TMR_Reader
typedef enum TMR_Reader_StatsFlag TMR_Reader_StatsFlag
typedef struct
TMR_Reader_StatsValues 
TMR_Reader_StatsValues
typedef enum TMR_ReaderType TMR_ReaderType
typedef void(* TMR_ReadExceptionListener )(TMR_Reader *reader, TMR_Status error, void *cookie)
typedef struct
TMR_ReadExceptionListenerBlock 
TMR_ReadExceptionListenerBlock
typedef void(* TMR_ReadListener )(TMR_Reader *reader, const TMR_TagReadData *t, void *cookie)
typedef struct
TMR_ReadListenerBlock 
TMR_ReadListenerBlock
typedef struct TMR_readParams TMR_readParams
typedef enum TMR_ReadState TMR_ReadState
typedef void(* TMR_StatsListener )(TMR_Reader *reader, const TMR_Reader_StatsValues *value, void *cookie)
typedef struct
TMR_StatsListenerBlock 
TMR_StatsListenerBlock
typedef struct
TMR_StatsPerAntennaValues 
TMR_StatsPerAntennaValues
typedef struct
TMR_StatsPerAntennaValuesList 
TMR_StatsPerAntennaValuesList
typedef void(* TMR_StatusListener )(TMR_Reader *reader, const TMR_SR_StatusReport report[], void *cookie)
typedef struct
TMR_StatusListenerBlock 
TMR_StatusListenerBlock
typedef struct TMR_tagOpParams TMR_tagOpParams
typedef void(* TMR_TransportListener )(bool tx, uint32_t dataLen, const uint8_t data[], uint32_t timeout, void *cookie)
typedef struct
TMR_TransportListenerBlock 
TMR_TransportListenerBlock
typedef TMR_Status(* TMR_TransportNativeInit )(TMR_SR_SerialTransport *transport, TMR_SR_SerialPortNativeContext *context, const char *device)

Enumerations

enum  TMR_Reader_StatsFlag {
  TMR_READER_STATS_FLAG_NONE = 0x00, TMR_READER_STATS_FLAG_RF_ON_TIME = (1 << 0), TMR_READER_STATS_FLAG_NOISE_FLOOR_SEARCH_RX_TX_WITH_TX_ON = (1 << 6), TMR_READER_STATS_FLAG_FREQUENCY = (1 << 7),
  TMR_READER_STATS_FLAG_TEMPERATURE = (1 << 8), TMR_READER_STATS_FLAG_ANTENNA_PORTS = (1 << 9), TMR_READER_STATS_FLAG_PROTOCOL = (1 << 10), TMR_READER_STATS_FLAG_CONNECTED_ANTENNAS = (1 << 11),
  TMR_READER_STATS_FLAG_ALL
}
enum  TMR_ReaderType { TMR_READER_TYPE_INVALID, TMR_READER_TYPE_RQL, TMR_READER_TYPE_SERIAL, TMR_READER_TYPE_LLRP }
enum  TMR_ReadState {
  TMR_READ_STATE_IDLE, TMR_READ_STATE_STARTING, TMR_READ_STATE_STARTED, TMR_READ_STATE_ACTIVE,
  TMR_READ_STATE_DONE
}

Functions

void cleanup_background_threads (TMR_Reader *reader)
void notify_exception_listeners (TMR_Reader *reader, TMR_Status status)
void TMR__notifyTransportListeners (TMR_Reader *reader, bool tx, uint32_t dataLen, uint8_t *data, int timeout)
TMR_Status TMR_addAuthReqListener (struct TMR_Reader *reader, TMR_AuthReqListenerBlock *block)
TMR_Status TMR_addReadExceptionListener (struct TMR_Reader *reader, TMR_ReadExceptionListenerBlock *block)
TMR_Status TMR_addReadListener (struct TMR_Reader *reader, TMR_ReadListenerBlock *block)
TMR_Status TMR_addStatsListener (struct TMR_Reader *reader, TMR_StatsListenerBlock *block)
TMR_Status TMR_addStatusListener (struct TMR_Reader *reader, TMR_StatusListenerBlock *block)
TMR_Status TMR_addTransportListener (TMR_Reader *reader, TMR_TransportListenerBlock *block)
TMR_Status TMR_connect (struct TMR_Reader *reader)
TMR_Status TMR_create (TMR_Reader *reader, const char *deviceUri)
TMR_Status TMR_create_alloc (TMR_Reader **readerPointer, const char *deviceUri)
TMR_Status TMR_destroy (TMR_Reader *reader)
TMR_Status TMR_executeTagOp (struct TMR_Reader *reader, TMR_TagOp *tagop, TMR_TagFilter *filter, TMR_uint8List *data)
bool TMR_fileProvider (void *cookie, uint16_t *size, uint8_t *data)
TMR_Status TMR_firmwareLoad (TMR_Reader *reader, void *cookie, TMR_FirmwareDataProvider provider)
TMR_Status TMR_getNextTag (TMR_Reader *reader, TMR_TagReadData *tagData)
TMR_Status TMR_gpiGet (TMR_Reader *reader, uint8_t *count, TMR_GpioPin state[])
TMR_Status TMR_gpoSet (TMR_Reader *reader, uint8_t count, const TMR_GpioPin state[])
TMR_Status TMR_hasMoreTags (TMR_Reader *reader)
TMR_Status TMR_killTag (TMR_Reader *reader, TMR_TagFilter *target, TMR_TagAuthentication *auth)
TMR_Status TMR_loadConfig (struct TMR_Reader *reader, char *filePath)
TMR_Status TMR_lockTag (TMR_Reader *reader, TMR_TagFilter *target, TMR_TagLockAction *action)
bool TMR_memoryProvider (void *cookie, uint16_t *size, uint8_t *data)
TMR_Status TMR_paramGet (struct TMR_Reader *reader, TMR_Param key, void *value)
TMR_Param TMR_paramID (const char *name)
TMR_Status TMR_paramList (struct TMR_Reader *reader, TMR_Param *keys, uint32_t *len)
const char * TMR_paramName (TMR_Param key)
void TMR_paramProbe (struct TMR_Reader *reader, TMR_Param key)
TMR_Status TMR_paramSet (struct TMR_Reader *reader, TMR_Param key, const void *value)
TMR_Status TMR_read (TMR_Reader *reader, uint32_t timeoutMs, int32_t *tagCount)
TMR_Status TMR_reader_init_internal (struct TMR_Reader *reader)
TMR_Status TMR_readIntoArray (struct TMR_Reader *reader, uint32_t timeoutMs, int32_t *tagCount, TMR_TagReadData *result[])
TMR_Status TMR_readTagMemBytes (TMR_Reader *reader, TMR_TagFilter *target, uint32_t bank, uint32_t byteAddress, uint16_t byteCount, uint8_t data[])
TMR_Status TMR_readTagMemWords (TMR_Reader *reader, TMR_TagFilter *target, uint32_t bank, uint32_t wordAddress, uint16_t wordCount, uint16_t data[])
TMR_Status TMR_reboot (struct TMR_Reader *reader)
TMR_Status TMR_receiveAutonomousReading (struct TMR_Reader *reader, TMR_TagReadData *trd, TMR_Reader_StatsValues *stats)
TMR_Status TMR_removeReadExceptionListener (struct TMR_Reader *reader, TMR_ReadExceptionListenerBlock *block)
TMR_Status TMR_removeReadListener (struct TMR_Reader *reader, TMR_ReadListenerBlock *block)
TMR_Status TMR_removeStatsListener (struct TMR_Reader *reader, TMR_StatsListenerBlock *block)
TMR_Status TMR_removeStatusListener (struct TMR_Reader *reader, TMR_StatusListenerBlock *block)
TMR_Status TMR_removeTransportListener (TMR_Reader *reader, TMR_TransportListenerBlock *block)
TMR_Status TMR_saveConfig (struct TMR_Reader *reader, char *filePath)
TMR_Status TMR_setSerialTransport (char *scheme, TMR_TransportNativeInit nativeInit)
TMR_Status TMR_startReading (struct TMR_Reader *reader)
TMR_Status TMR_STATS_init (TMR_Reader_StatsValues *stats)
TMR_Status TMR_stopReading (struct TMR_Reader *reader)
const char * TMR_strerr (TMR_Reader *reader, TMR_Status status)
TMR_Status TMR_writeTag (TMR_Reader *reader, const TMR_TagFilter *target, TMR_TagData *data)
TMR_Status TMR_writeTagMemBytes (TMR_Reader *reader, TMR_TagFilter *target, uint32_t bank, uint32_t byteAddress, uint16_t byteCount, const uint8_t data[])
TMR_Status TMR_writeTagMemWords (TMR_Reader *reader, TMR_TagFilter *target, uint32_t bank, uint32_t wordAddress, uint16_t wordCount, const uint16_t data[])
TMR_Status validateReadPlan (TMR_Reader *reader, TMR_ReadPlan *plan, TMR_AntennaMapList *txRxMap, uint32_t protocols)

Detailed Description

Mercury API Reader Interface.

Author:
Brian Fiegel
Date:
4/18/2009

Definition in file tm_reader.h.


Define Documentation

#define TMR_connect (   reader)    ((reader)->connect(reader))

The fact that these functions are implemented via macros is an implementation detail, not something for the public API documentation.

Definition at line 1251 of file tm_reader.h.

#define TMR_destroy (   reader)    ((reader)->destroy(reader))

Definition at line 1252 of file tm_reader.h.

#define TMR_executeTagOp (   reader,
  tagop,
  filter,
  data 
)    ((reader)->executeTagOp((reader), (tagop), (filter), (data)))

Definition at line 1263 of file tm_reader.h.

#define TMR_firmwareLoad (   reader,
  cookie,
  provider 
)    ((reader)->firmwareLoad((reader),(cookie),(provider)))

Definition at line 1266 of file tm_reader.h.

#define TMR_getNextTag (   reader,
  read 
)    ((reader)->getNextTag((reader),(read)))

Definition at line 1255 of file tm_reader.h.

#define TMR_gpiGet (   reader,
  count,
  state 
)    ((reader)->gpiGet((reader),(count),(state)))

Definition at line 1265 of file tm_reader.h.

#define TMR_gpoSet (   reader,
  count,
  state 
)    ((reader)->gpoSet((reader),(count),(state)))

Definition at line 1264 of file tm_reader.h.

#define TMR_hasMoreTags (   reader)    ((reader)->hasMoreTags(reader))

Definition at line 1254 of file tm_reader.h.

#define TMR_killTag (   reader,
  filter,
  auth 
)    ((reader)->killTag((reader),(filter),(auth)))

Definition at line 1261 of file tm_reader.h.

#define TMR_lockTag (   reader,
  filter,
  action 
)    ((reader)->lockTag((reader),(filter),(action)))

Definition at line 1262 of file tm_reader.h.

#define TMR_modifyFlash (   reader,
  sector,
  address,
  password,
  length,
  data,
  offset 
)    ((reader->modifyFlash((reader),(sector),(address),(password),(length),(data),(offset)))

Definition at line 1267 of file tm_reader.h.

#define TMR_read (   reader,
  timeoutMs,
  tagCount 
)    ((reader)->read((reader),(timeoutMs),(tagCount)))

Definition at line 1253 of file tm_reader.h.

#define TMR_readTagMemBytes (   reader,
  target,
  bank,
  address,
  count,
  data 
)    ((reader)->readTagMemBytes((reader),(target),(bank),(address),(count),(data)))

Definition at line 1258 of file tm_reader.h.

#define TMR_readTagMemWords (   reader,
  target,
  bank,
  address,
  count,
  data 
)    ((reader)->readTagMemWords((reader),(target),(bank),(address),(count),(data)))

Definition at line 1257 of file tm_reader.h.

#define TMR_reboot (   reader)    ((reader)->reboot(reader))

Definition at line 1268 of file tm_reader.h.

#define TMR_writeTag (   reader,
  filter,
  data 
)    ((reader)->writeTag((reader),(filter),(data)))

Definition at line 1256 of file tm_reader.h.

#define TMR_writeTagMemBytes (   reader,
  target,
  bank,
  address,
  count,
  data 
)    ((reader)->writeTagMemBytes((reader),(target),(bank),(address),(count),(data)))

Definition at line 1260 of file tm_reader.h.

#define TMR_writeTagMemWords (   reader,
  target,
  bank,
  address,
  count,
  data 
)    ((reader)->writeTagMemWords((reader),(target),(bank),(address),(count),(data)))

Definition at line 1259 of file tm_reader.h.


Typedef Documentation

typedef void(* TMR_AuthReqListener)(TMR_Reader *reader, const TMR_TagReadData *trd, void *cookie, TMR_TagAuthentication *auth)

Type of functions to be registered as tagauth request callbacks

Parameters:
readerReader object
trdTagReadData object
cookieArbitrary data structure to be passed to callback
auth[OUTPUT] Tag authentication value to initialize based on inputs

Definition at line 210 of file tm_reader.h.

User-allocated structure containing the callback pointer and the value to pass to that callback.

Definition at line 317 of file tm_reader.h.

Definition at line 316 of file tm_reader.h.

Definition at line 315 of file tm_reader.h.

Cookie for state storage of a TMR_memoryProvider.

Private: should not be used by user level application.

typedef struct TMR_Reader TMR_Reader

TMR_ENABLE_JNI_SERIAL_READER_ONLY is used for building JNI project, and is defined from Makefile.jni

Definition at line 48 of file tm_reader.h.

Reader Stats Flag Enum

This object is returned from TMR_cmdGetReaderStats

typedef void(* TMR_ReadExceptionListener)(TMR_Reader *reader, TMR_Status error, void *cookie)

Type of functions to be registered as read error callbacks

Definition at line 227 of file tm_reader.h.

User-allocated structure containing the callback pointer and the value to pass to that callback.

typedef void(* TMR_ReadListener)(TMR_Reader *reader, const TMR_TagReadData *t, void *cookie)

Type of functions to be registered as read callbacks

Definition at line 188 of file tm_reader.h.

User-allocated structure containing the callback pointer and the value to pass to that callback.

typedef void(* TMR_StatsListener)(TMR_Reader *reader, const TMR_Reader_StatsValues *value, void *cookie)

Type of functions to be registered as Status read callbacks

Definition at line 261 of file tm_reader.h.

User-allocated structure containing the callback pointer and the value to pass to that callback.

Per Antenna stats

Object to hold the per antenna stats

typedef void(* TMR_StatusListener)(TMR_Reader *reader, const TMR_SR_StatusReport report[], void *cookie)

Definition at line 263 of file tm_reader.h.

User-allocated structure containing the callback pointer and the value to pass to that callback.

typedef void(* TMR_TransportListener)(bool tx, uint32_t dataLen, const uint8_t data[], uint32_t timeout, void *cookie)

Type of functions to be registered as transport callbacks

Definition at line 243 of file tm_reader.h.

User-allocated structure containing the callback pointer and the value to pass to that callback.

typedef TMR_Status(* TMR_TransportNativeInit)(TMR_SR_SerialTransport *transport, TMR_SR_SerialPortNativeContext *context, const char *device)

Definition at line 73 of file tm_reader.h.


Enumeration Type Documentation

Reader Stats Flag Enum

Enumerator:
TMR_READER_STATS_FLAG_NONE 
TMR_READER_STATS_FLAG_RF_ON_TIME 

Total time the port has been transmitting, in milliseconds. Resettable

TMR_READER_STATS_FLAG_NOISE_FLOOR_SEARCH_RX_TX_WITH_TX_ON 

Noise floor with the TX on for the antennas were last configured for searching

TMR_READER_STATS_FLAG_FREQUENCY 

Current frequency in uints of Khz

TMR_READER_STATS_FLAG_TEMPERATURE 

Current temperature of the device in units of Celcius

TMR_READER_STATS_FLAG_ANTENNA_PORTS 

Current antenna

TMR_READER_STATS_FLAG_PROTOCOL 

Current protocol

TMR_READER_STATS_FLAG_CONNECTED_ANTENNAS 

Current connected antennas

TMR_READER_STATS_FLAG_ALL 

Definition at line 115 of file tm_reader.h.

Enumerator:
TMR_READER_TYPE_INVALID 
TMR_READER_TYPE_RQL 
TMR_READER_TYPE_SERIAL 
TMR_READER_TYPE_LLRP 

Definition at line 92 of file tm_reader.h.

Enumerator:
TMR_READ_STATE_IDLE 
TMR_READ_STATE_STARTING 
TMR_READ_STATE_STARTED 
TMR_READ_STATE_ACTIVE 
TMR_READ_STATE_DONE 

Definition at line 100 of file tm_reader.h.


Function Documentation

void notify_exception_listeners ( TMR_Reader reader,
TMR_Status  status 
)

Definition at line 544 of file tm_reader_async.c.

void TMR__notifyTransportListeners ( TMR_Reader reader,
bool  tx,
uint32_t  dataLen,
uint8_t *  data,
int  timeout 
)

Definition at line 767 of file tm_reader.c.

bool TMR_fileProvider ( void *  cookie,
uint16_t *  size,
uint8_t *  data 
)

This function can be used as a callback to TMR_firmwareLoad when the firmware image exists as a file.

Parameters:
cookieFILE * pointing to the file to read from.
[in]sizeThe number of bytes requested.
[out]sizeThe number of bytes returned.
dataPointer to buffer to fill.
Returns:
true if there is more firmware data to return.
TMR_Status TMR_killTag ( TMR_Reader reader,
TMR_TagFilter target,
TMR_TagAuthentication auth 
)
Deprecated:
This method is deprecated

Sends a kill command to a tag.

Parameters:
readerThe reader being operated on.
targetThe tag to kill, or NULL to kill the first tag seen.
authThe authentication needed to kill the tag.
Returns:
TMR_ERROR_NO_TAG_FOUND if no tag matching the filter could be found.
TMR_Status TMR_lockTag ( TMR_Reader reader,
TMR_TagFilter target,
TMR_TagLockAction action 
)
Deprecated:
This method is deprecated

Sends a lock command to a tag.

Parameters:
readerThe reader being operated on.
targetThe tag to kill, or NULL to kill the first tag seen.
actionThe locking action to apply.
Returns:
TMR_ERROR_NO_TAG_FOUND if no tag matching the filter could be found.
bool TMR_memoryProvider ( void *  cookie,
uint16_t *  size,
uint8_t *  data 
)

This function can be used as a callback to TMR_firmwareLoad when the firmware image exists in system memory. The cookie is a pointer to a TMR_memoryCookie that is initialized with the start of the firmware image in memory and its size.

Parameters:
cookieTMR_memoryCookie value.
[in]sizeThe number of bytes requested.
[out]sizeThe number of bytes returned.
dataPointer to buffer to fill.
Returns:
true if there is more firmware data to return.

Definition at line 782 of file tm_reader.c.

void TMR_paramProbe ( struct TMR_Reader reader,
TMR_Param  key 
)

pointer to TMR_Reader pointer to TMR_Param

Initialize a TMR_TagOp as a Higgs2 Partial Load Image operation with the provided parameters.

Parameters:
tagopPointer to the tagop structure to initialize.
killPasswordkill password
accessPasswordaccess password
epcEPC to write

Definition at line 3530 of file tm_reader.c.

Definition at line 296 of file tm_reader.c.

Definition at line 3613 of file tm_reader.c.

TMR_Status TMR_writeTag ( TMR_Reader reader,
const TMR_TagFilter target,
TMR_TagData data 
)
Deprecated:
This method is deprecated

Write a new EPC to an existing tag.

The /reader/tagop/antenna parameter controls which antenna will be used for the write operation. The /reader/tagop/protocol parameter controls which protocol will be used.

Parameters:
readerThe reader being operated on
targetThe existing tag to write.
dataThe EPC to write to the tag
Note:
target is not supported on serial or Astra readers and only TagData filters are supported on other fixed readers.
Returns:
TMR_ERROR_NO_TAG_FOUND if no tag matching the filter could be found.
Test:

Call should fail if reader is not connected.

Upon success, a subsequent TMR_read() should find the new tag ID.

TMR_Status TMR_writeTagMemBytes ( TMR_Reader reader,
TMR_TagFilter target,
uint32_t  bank,
uint32_t  byteAddress,
uint16_t  byteCount,
const uint8_t  data[] 
)
Deprecated:
This method is deprecated

Write 8-bit bytes to the memory bank of a tag. If the tag's fundamental memory unit is larger than 8 bits, trying to write sub-unit quantities will produce an error.

Parameters:
readerThe reader to operate on.
targetThe tag to write to, or NULL.
bankThe tag memory bank to write to.
byteAddressThe byte address to start writing to.
byteCountThe number of bytes to write.
dataThe bytes to write.
TMR_Status TMR_writeTagMemWords ( TMR_Reader reader,
TMR_TagFilter target,
uint32_t  bank,
uint32_t  wordAddress,
uint16_t  wordCount,
const uint16_t  data[] 
)
Deprecated:
This method is deprecated

Write 16-bit words to the memory bank of a tag. If the tag's fundamental memory unit is larger than 16 bits, trying to write sub-unit quantities will produce an error.

Parameters:
readerThe reader to operate on.
targetThe tag to write to, or NULL.
bankThe tag memory bank to write to.
wordAddressThe word address to start writing to.
wordCountThe number of words to write.
dataThe words to write.
TMR_Status validateReadPlan ( TMR_Reader reader,
TMR_ReadPlan plan,
TMR_AntennaMapList txRxMap,
uint32_t  protocols 
)

Definition at line 606 of file tm_reader.c.



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