Over 10 years we help companies reach their financial and branding goals. Engitech is a values-driven technology agency dedicated.

Gallery

Contacts

411 University St, Seattle, USA

engitech@oceanthemes.net

+1 -800-456-478-23

NFC/RFID Sensor-Module Interfacing with S32K3 MCU's Sensor-Modules-interfacing Sensor/Module Interfacing Sensors and Modules SPI Modules

MFRC522 RFID module interfacing with Host MCU

Table of Contents

Many of you may be familiar with the RFID module MFRC522, but I’m willing to bet that most of you have only interfaced this module with an Arduino and the Arduino IDE environment. However, if you need to use the RFID module with other MCUs, you may find yourself at a loss for how to proceed. If this is the case, you’ve come to the right place. In this blog, I will show you how to create a device driver for the RFID Module MFRC522, allowing you to interface it with any Host MCU. If you’re not sure what we mean by interfacing with a Host MCU or why it’s necessary, be sure to check out our blog for more information.

Continuing with the MFRC522 RFID reader interfacing to host MCU, Objective would be to interface this module with Host MCU’s like of NXP Semiconductors, STMicroelectronics or other vendors MCU’s. Will make the driver to interface the RFID Reader with any MCU, not unlike just with Arduino and Arduino IDE environment. You just need to change 2-3 low level API’s for running it on different MCU’s, would be telling about it in below sections. In this blog we are going to write the driver in c++ language. Before proceeding further would recommend viewers go through, the following set of blogs and videos to have a better understanding.

 Viewers can refer to this blog to know about RFID technology in detail.

or can watch this video which is in animated format to know about RFID technology.

RFID Reader MFRC522: Overview and Datasheet Explanation( Highly recommended to go through at first)

RFID Reader MFRC522

MIFRAME RFID Tags: Overview and Datasheet Explanation

Hardware Connection of MFRC522 Reader module

MFRC522 Module has 8 pins exposed out, which can be categorised into 3 parts: Communication pins, Power Supply Pins and Additional Pins. As explained below

MFRC522 Pinout

MFRC522 Functional Description API's

MFRC522 has a set of functional descriptions, on which the whole of the working of MFRC522 depends. To write the driver of MFRC522, it’s important to have an understanding of those functional blocks. Reading from the datasheet could be tiering, hence viewers can read and understand from here.

MFRC522 State Machines

State Machines for doing various operations with MFRC522.

In this would talk about different state machines for the working of MFRC522.

  1. MFRC522 init state machine
  2. MFRC522 scanning PICC state machine
  3. MFRC522 Get UID PICC state machine.
  4. MFRC522 CRC

Driver creation of MFRC522 Reader

GB_MFRC522.h

				
					#ifndef GB_MFRC522_H_
#define GB_MFRC522_H_


typedef uint8_t byte;

void yield(void)
{
	while(1);
}
/*
MFRC522 can communicate via SPI protocol at data speed upto 10Mbit/s.
--> Data bytes on both MOSI and MISO lines are sent with the MSB first. Data on both MOSI
and MISO lines must be stable on the rising edge of the clock and can be changed on the
falling edge. Data is provided by the MFRC522 on the falling clock edge and is stable
during the rising clock edge.
--> The MSB of the first byte defines the mode used. To read data from the MFRC522 the
MSB is set to logic 1. To write data to the MFRC522 the MSB must be set to logic 0. Bits 6
to 1 define the address and the LSB is set to logic 0.
--> 
*/

#define gb_MFRC522_CE PB0
#define gb_MFRC522_CE_pin_low gb_spi_port &= ~(1<<gb_SPI_SS)
#define gb_MFRC522_CE_pin_high gb_spi_port |= (1<<gb_SPI_SS)
enum PCD_Register {
	// Page 0: Command and status
	//						  0x00			// reserved for future use
	CommandReg				= 0x01 << 1,	// starts and stops command execution
	ComIEnReg				= 0x02 << 1,	// enable and disable interrupt request control bits
	DivIEnReg				= 0x03 << 1,	// enable and disable interrupt request control bits
	ComIrqReg				= 0x04 << 1,	// interrupt request bits
	DivIrqReg				= 0x05 << 1,	// interrupt request bits
	ErrorReg				= 0x06 << 1,	// error bits showing the error status of the last command executed
	Status1Reg				= 0x07 << 1,	// communication status bits
	Status2Reg				= 0x08 << 1,	// receiver and transmitter status bits
	FIFODataReg				= 0x09 << 1,	// input and output of 64 byte FIFO buffer
	FIFOLevelReg			= 0x0A << 1,	// number of bytes stored in the FIFO buffer
	WaterLevelReg			= 0x0B << 1,	// level for FIFO underflow and overflow warning
	ControlReg				= 0x0C << 1,	// miscellaneous control registers
	BitFramingReg			= 0x0D << 1,	// adjustments for bit-oriented frames
	CollReg					= 0x0E << 1,	// bit position of the first bit-collision detected on the RF interface
	//						  0x0F			// reserved for future use
	
	// Page 1: Command
	// 						  0x10			// reserved for future use
	ModeReg					= 0x11 << 1,	// defines general modes for transmitting and receiving
	TxModeReg				= 0x12 << 1,	// defines transmission data rate and framing
	RxModeReg				= 0x13 << 1,	// defines reception data rate and framing
	TxControlReg			= 0x14 << 1,	// controls the logical behavior of the antenna driver pins TX1 and TX2
	TxASKReg				= 0x15 << 1,	// controls the setting of the transmission modulation
	TxSelReg				= 0x16 << 1,	// selects the internal sources for the antenna driver
	RxSelReg				= 0x17 << 1,	// selects internal receiver settings
	RxThresholdReg			= 0x18 << 1,	// selects thresholds for the bit decoder
	DemodReg				= 0x19 << 1,	// defines demodulator settings
	// 						  0x1A			// reserved for future use
	// 						  0x1B			// reserved for future use
	MfTxReg					= 0x1C << 1,	// controls some MIFARE communication transmit parameters
	MfRxReg					= 0x1D << 1,	// controls some MIFARE communication receive parameters
	// 						  0x1E			// reserved for future use
	SerialSpeedReg			= 0x1F << 1,	// selects the speed of the serial UART interface
	
	// Page 2: Configuration
	// 						  0x20			// reserved for future use
	CRCResultRegH			= 0x21 << 1,	// shows the MSB and LSB values of the CRC calculation
	CRCResultRegL			= 0x22 << 1,
	// 						  0x23			// reserved for future use
	ModWidthReg				= 0x24 << 1,	// controls the ModWidth setting?
	// 						  0x25			// reserved for future use
	RFCfgReg				= 0x26 << 1,	// configures the receiver gain
	GsNReg					= 0x27 << 1,	// selects the conductance of the antenna driver pins TX1 and TX2 for modulation
	CWGsPReg				= 0x28 << 1,	// defines the conductance of the p-driver output during periods of no modulation
	ModGsPReg				= 0x29 << 1,	// defines the conductance of the p-driver output during periods of modulation
	TModeReg				= 0x2A << 1,	// defines settings for the internal timer
	TPrescalerReg			= 0x2B << 1,	// the lower 8 bits of the TPrescaler value. The 4 high bits are in TModeReg.
	TReloadRegH				= 0x2C << 1,	// defines the 16-bit timer reload value
	TReloadRegL				= 0x2D << 1,
	TCounterValueRegH		= 0x2E << 1,	// shows the 16-bit timer value
	TCounterValueRegL		= 0x2F << 1,
	
	// Page 3: Test Registers
	// 						  0x30			// reserved for future use
	TestSel1Reg				= 0x31 << 1,	// general test signal configuration
	TestSel2Reg				= 0x32 << 1,	// general test signal configuration
	TestPinEnReg			= 0x33 << 1,	// enables pin output driver on pins D1 to D7
	TestPinValueReg			= 0x34 << 1,	// defines the values for D1 to D7 when it is used as an I/O bus
	TestBusReg				= 0x35 << 1,	// shows the status of the internal test bus
	AutoTestReg				= 0x36 << 1,	// controls the digital self-test
	VersionReg				= 0x37 << 1,	// shows the software version
	AnalogTestReg			= 0x38 << 1,	// controls the pins AUX1 and AUX2
	TestDAC1Reg				= 0x39 << 1,	// defines the test value for TestDAC1
	TestDAC2Reg				= 0x3A << 1,	// defines the test value for TestDAC2
	TestADCReg				= 0x3B << 1		// shows the value of ADC I and Q channels
	// 						  0x3C			// reserved for production tests
	// 						  0x3D			// reserved for production tests
	// 						  0x3E			// reserved for production tests
	// 						  0x3F			// reserved for production tests
	};

// MFRC522 commands. Described in chapter 10 of the datasheet.
	enum PCD_Command : byte {
		PCD_Idle				= 0x00,		// no action, cancels current command execution
		PCD_Mem					= 0x01,		// stores 25 bytes into the internal buffer
		PCD_GenerateRandomID	= 0x02,		// generates a 10-byte random ID number
		PCD_CalcCRC				= 0x03,		// activates the CRC coprocessor or performs a self-test
		PCD_Transmit			= 0x04,		// transmits data from the FIFO buffer
		PCD_NoCmdChange			= 0x07,		// no command change, can be used to modify the CommandReg register bits without affecting the command, for example, the PowerDown bit
		PCD_Receive				= 0x08,		// activates the receiver circuits
		PCD_Transceive 			= 0x0C,		// transmits data from FIFO buffer to antenna and automatically activates the receiver after transmission
		PCD_MFAuthent 			= 0x0E,		// performs the MIFARE standard authentication as a reader
		PCD_SoftReset			= 0x0F		// resets the MFRC522
	};
// Commands sent to the PICC.
enum PICC_Command : byte {
	// The commands used by the PCD to manage communication with several PICCs (ISO 14443-3, Type A, section 6.4)
	PICC_CMD_REQA			= 0x26,		// REQuest command, Type A. Invites PICCs in state IDLE to go to READY and prepare for anticollision or selection. 7 bit frame.
	PICC_CMD_WUPA			= 0x52,		// Wake-UP command, Type A. Invites PICCs in state IDLE and HALT to go to READY(*) and prepare for anticollision or selection. 7 bit frame.
	PICC_CMD_CT				= 0x88,		// Cascade Tag. Not really a command, but used during anti collision.
	PICC_CMD_SEL_CL1		= 0x93,		// Anti collision/Select, Cascade Level 1
	PICC_CMD_SEL_CL2		= 0x95,		// Anti collision/Select, Cascade Level 2
	PICC_CMD_SEL_CL3		= 0x97,		// Anti collision/Select, Cascade Level 3
	PICC_CMD_HLTA			= 0x50,		// HaLT command, Type A. Instructs an ACTIVE PICC to go to state HALT.
	PICC_CMD_RATS           = 0xE0,     // Request command for Answer To Reset.
	// The commands used for MIFARE Classic (from http://www.mouser.com/ds/2/302/MF1S503x-89574.pdf, Section 9)
	// Use PCD_MFAuthent to authenticate access to a sector, then use these commands to read/write/modify the blocks on the sector.
	// The read/write commands can also be used for MIFARE Ultralight.
	PICC_CMD_MF_AUTH_KEY_A	= 0x60,		// Perform authentication with Key A
	PICC_CMD_MF_AUTH_KEY_B	= 0x61,		// Perform authentication with Key B
	PICC_CMD_MF_READ		= 0x30,		// Reads one 16 byte block from the authenticated sector of the PICC. Also used for MIFARE Ultralight.
	PICC_CMD_MF_WRITE		= 0xA0,		// Writes one 16 byte block to the authenticated sector of the PICC. Called "COMPATIBILITY WRITE" for MIFARE Ultralight.
	PICC_CMD_MF_DECREMENT	= 0xC0,		// Decrements the contents of a block and stores the result in the internal data register.
	PICC_CMD_MF_INCREMENT	= 0xC1,		// Increments the contents of a block and stores the result in the internal data register.
	PICC_CMD_MF_RESTORE		= 0xC2,		// Reads the contents of a block into the internal data register.
	PICC_CMD_MF_TRANSFER	= 0xB0,		// Writes the contents of the internal data register to a block.
	// The commands used for MIFARE Ultralight (from http://www.nxp.com/documents/data_sheet/MF0ICU1.pdf, Section 8.6)
	// The PICC_CMD_MF_READ and PICC_CMD_MF_WRITE can also be used for MIFARE Ultralight.
	PICC_CMD_UL_WRITE		= 0xA2		// Writes one 4 byte page to the PICC.
};

	// Return codes from the functions in this class. Remember to update GetStatusCodeName() if you add more.
	// last value set to 0xff, then compiler uses less ram, it seems some optimisations are triggered
	enum gb_MFRC522_statusCodes : byte {
		STATUS_OK				,	// Success
		STATUS_ERROR			,	// Error in communication
		STATUS_COLLISION		= 90,	// Collission detected
		STATUS_TIMEOUT			,	// Timeout in communication.
		STATUS_NO_ROOM			,	// A buffer is not big enough.
		STATUS_INTERNAL_ERROR	,	// Internal error in the code. Should not happen ;-)
		STATUS_INVALID			,	// Invalid argument.
		STATUS_CRC_WRONG		,	// The CRC_A does not match
		STATUS_MIFARE_NACK		= 0xff	// A MIFARE PICC responded with NAK.
	};

/*
Writes a byte to the specified register in the MFRC522 chip
*/
void GB_MFRC522_WriteRegister(PCD_Register GB_reg, uint8_t value);

void GB_MFRC522_WriteRegister(PCD_Register GB_reg, uint8_t count, uint8_t *value);


/*
Reads a byte from the specified register in the MFRC522 chip
*/
uint8_t GB_MFRC522_ReadRegister(PCD_Register GB_reg);

void GB_MFRC522_ClearRegisterBitMask(PCD_Register gb_reg, byte mask);

void GB_MFRC522_SetRegisterBitmask( PCD_Register gb_reg, byte mask);

gb_MFRC522_statusCodes PCD_CalculateCRC(	byte *data,		///< In: Pointer to the data to transfer to the FIFO for CRC calculation.\
int length,	///< In: The number of bytes to transfer.
byte *result	///< Out: Pointer to result buffer. Result is written to result[0..1], low byte first.
);
/*
shows the MFRC522 software version
*/
void GB_MFRC522Version();


/* 
Initialize the MFRC522 chip
*/
void MFRC522_init();

void GB_MFRC522_AnteenaOn();

gb_MFRC522_statusCodes GB_MFRC522_CommunicateWithPICC(byte command,   //The command to execute
byte waitIRQ,
byte *sendData,
byte sendLen,
byte *backdata,
byte *backlen,
byte *validbits,
byte rxalign,
bool checkCRC
);

gb_MFRC522_statusCodes GB_MFRC522_TransceiveData( byte *senddata,  //Pointer to the data to transfer to the FIFO
byte sendlen,       //Number of bytes to transfer to FIFO
byte *backdata,     //nullptr or pointer to buffer if data should be read back after executing the command
byte *backlen,      //In: Max no of bytes to write to *backdata. Out: The no of bytes returned.
byte *validbits,    //In/Out: The number of valid bits in the last byte
byte rxalign,
bool checkCRC       //In: True => The last 2 bytes of the response is assumed to be a CRC_A that must be validated
);

	// A struct used for passing the UID of a PICC.
	typedef struct {
		byte		size;			// Number of bytes in the UID. 4, 7 or 10.
		byte		uidByte[10];
		byte		sak;			// The SAK (Select acknowledge) byte returned from the PICC after successful selection.
	} Uid;

	// Member variables
	Uid uid;								// Used by PICC_ReadCardSerial().
	
gb_MFRC522_statusCodes GB_PICC_REQA_OR_WUPA(byte command, byte *gb_bufferATQA, byte *gb_buffersize);


gb_MFRC522_statusCodes GB_PICC_RequestA(byte * gb_bufferATQ, byte *gb_buffersize);




bool GB_PICC_IsNewCardPresent();

bool GB_PICC_ReadCardSerial();
void GB_PICCDetails(Uid *uid);

#include "GB_MFRC522.cpp"


#endif
				
			

GB_MFRC522.c

				
					void GB_MFRC522_WriteRegister(PCD_Register GB_reg, uint8_t value)
{
gb_MFRC522_CE_pin_low;
GB_MA_SPI0_send_byte_conti(GB_reg);
GB_MA_SPI0_send_byte_conti(value);
gb_MFRC522_CE_pin_high;
}
void GB_MFRC522_WriteRegister(PCD_Register GB_reg, uint8_t count, uint8_t *value)
{
gb_MFRC522_CE_pin_low;
GB_MA_SPI0_send_byte_conti(GB_reg);
for (uint8_t i =0;i<count;i++){
GB_MA_SPI0_send_byte_conti(value[i]);
}
gb_MFRC522_CE_pin_high;
}

uint8_t GB_MFRC522_ReadRegister(PCD_Register GB_reg)
{
uint8_t gb_x = 0;
gb_MFRC522_CE_pin_low;

GB_MA_SPI0_exchange_byte((0x80 | GB_reg));
// GB_MA_SPI0_send_byte_conti(0x80 | GB_reg);
gb_x = GB_MA_SPI0_exchange_byte(0);
// gb_x = GB_MA_SPI0_read_byte();
gb_MFRC522_CE_pin_high;
return gb_x;
}
void GB_MFRC522_ReadRegister(PCD_Register reg, byte count, byte *values, byte rxalign)
{
if (count == 0) {
return;
}
byte address = 0x80 | reg; // MSB == 1 is for reading. LSB is not used in address. Datasheet section 8.1.2.3.
byte index = 0;
gb_MFRC522_CE_pin_low;
count--; // One read is performed outside of the loop
GB_MA_SPI0_exchange_byte(address); // Tell MFRC522 which address we want to read
if (rxalign) { // Only update bit positions rxAlign..7 in values[0]
// Create bit mask for bit positions rxAlign..7
byte mask = (0xFF << rxalign) & 0xFF;
// Read value and tell that we want to read the same address again.
byte value = GB_MA_SPI0_exchange_byte(address);
// Apply mask to both current value of values[0] and the new data in value.
values[0] = (values[0] & ~mask) | (value & mask);
index++;
}
while (index < count) {
values[index] = GB_MA_SPI0_exchange_byte(address); // Read value and tell that we want to read the same address again.
index++;
}
values[index] = GB_MA_SPI0_exchange_byte(0); // Read the final byte. Send 0 to stop reading.

gb_MFRC522_CE_pin_high;

}
void GB_MFRC522_ClearRegisterBitMask(PCD_Register gb_reg, byte mask)
{
byte tmp;
tmp = GB_MFRC522_ReadRegister(gb_reg);
GB_MFRC522_WriteRegister(gb_reg, tmp & (~mask)); //clear bit mask
}
void GB_MFRC522_SetRegisterBitmask( PCD_Register gb_reg, byte mask)
{
byte tmp;
tmp = GB_MFRC522_ReadRegister(gb_reg);
GB_MFRC522_WriteRegister(gb_reg, tmp | (mask)); //clear bit mask
}
void GB_MFRC522Version()
{
uint8_t v = GB_MFRC522_ReadRegister(VersionReg);
GB_printString0("Firmware Version: 0d");
GB_decimel0(v);
switch(v) 
{
case 0x88: GB_printString0(" = (clone)\n"); break;
case 0x90: GB_printString0(" = v0.0\n"); break;
case 0x91: GB_printString0(" = v1.0\n"); break;
case 0x92: GB_printString0(" = v2.0\n"); break;
case 0x12: GB_printString0(" = counterfeit chip\n"); break;
default: GB_printString0(" = (unknown)\n");
} 
}
void MFRC522_init()
{
GB_MFRC522_WriteRegister(TxModeReg, 0x00);
GB_MFRC522_WriteRegister(RxModeReg, 0x00);

GB_MFRC522_WriteRegister(ModWidthReg, 0x26);

// When communicating with a PICC we need a timeout if something goes wrong.
// f_timer = 13.56 MHz / (2*TPreScaler+1) where TPreScaler = [TPrescaler_Hi:TPrescaler_Lo].
// TPrescaler_Hi are the four low bits in TModeReg. TPrescaler_Lo is TPrescalerReg.
GB_MFRC522_WriteRegister(TModeReg, 0x80); // TAuto=1; timer starts automatically at the end of the transmission in all communication modes at all speeds
GB_MFRC522_WriteRegister(TPrescalerReg, 0xA9); // TPreScaler = TModeReg[3..0]:TPrescalerReg, ie 0x0A9 = 169 => f_timer=40kHz, ie a timer period of 25μs.
GB_MFRC522_WriteRegister(TReloadRegH, 0x03); // Reload timer with 0x3E8 = 1000, ie 25ms before timeout.
GB_MFRC522_WriteRegister(TReloadRegL, 0xE8);


GB_MFRC522_WriteRegister(TxASKReg, 0x40);// Default 0x00. Force a 100 % ASK modulation independent of the ModGsPReg register setting
GB_MFRC522_WriteRegister(ModeReg, 0x3D); // Default 0x3F. Set the preset value for the CRC co processor for the CalcCRC command to 0x6363 (ISO 14443-3 part 6.2.4) // Enable the antenna driver pins TX1 and TX2 (they were disabled by the reset)

GB_MFRC522_AnteenaOn(); //Enable the Antenna Driver pins TX1 & TX2(They are disabled by reset)

}
void GB_MFRC522_AnteenaOn()
{
uint8_t gb_x = GB_MFRC522_ReadRegister(TxControlReg);
if((gb_x & 0x03) != 0x03)
{
GB_MFRC522_WriteRegister(TxControlReg, (gb_x | 0x03));
}
}
gb_MFRC522_statusCodes PCD_CalculateCRC( byte *data, byte length, byte *result) ///< In: Pointer to the data to transfer to the FIFO for CRC calculation.\
) 
{
GB_MFRC522_WriteRegister(CommandReg, PCD_Idle); // Stop any active command.
GB_MFRC522_WriteRegister(DivIrqReg, 0x04); // Clear the CRCIRq interrupt request bit
GB_MFRC522_WriteRegister(FIFOLevelReg, 0x80); // FlushBuffer = 1, FIFO initialization
GB_MFRC522_WriteRegister(FIFODataReg, length, data); // Write data to the FIFO
GB_MFRC522_WriteRegister(CommandReg, PCD_CalcCRC); // Start the calculation
// Wait for the CRC calculation to complete. Check for the register to
// indicate that the CRC calculation is complete in a loop. If the
// calculation is not indicated as complete in ~90ms, then time out
// the operation.
const uint32_t deadline = GB_millis() + 89;
do {
// DivIrqReg[7..0] bits are: Set2 reserved reserved MfinActIRq reserved CRCIRq reserved reserved
byte n = GB_MFRC522_ReadRegister(DivIrqReg);
if (n & 0x04) { // CRCIRq bit set - calculation done
GB_MFRC522_WriteRegister(CommandReg, PCD_Idle); // Stop calculating CRC for new content in the FIFO.
// Transfer the result from the registers to the result buffer
result[0] = GB_MFRC522_ReadRegister(CRCResultRegL);
result[1] = GB_MFRC522_ReadRegister(CRCResultRegH);
return STATUS_OK;
}
yield();
}
while (static_cast<uint32_t> (GB_millis()) < deadline);
// 89ms passed and nothing happened. Communication with the MFRC522 might be down.
return STATUS_TIMEOUT;
} // End PCD_CalculateCRC()

gb_MFRC522_statusCodes GB_MFRC522_CommunicateWithPICC(byte command, //The command to execute
byte waitIRQ,
byte *sendData,
byte sendLen,
byte *backdata,
byte *backlen,
byte *validbits,
byte rxalign,
bool checkCRC
)
{
byte txLastBits = validbits ? *validbits :0;
byte bitFraming = (rxalign <<4) + txLastBits; //RxAlign = BitFramingReg[6..4]. TxLastBits = BitFramingReg[2..0]

GB_MFRC522_WriteRegister(CommandReg, PCD_Idle); // Stop any active command.
GB_MFRC522_WriteRegister(ComIrqReg, 0x7F); // Clear all seven interrupt request bits

// For PCD to PICC Communication!!
GB_MFRC522_WriteRegister(FIFOLevelReg, 0x80); // FlushBuffer = 1, FIFO initialization
GB_MFRC522_WriteRegister(FIFODataReg, sendLen, sendData); // Write sendData to the FIFO
GB_MFRC522_WriteRegister(BitFramingReg, bitFraming); // Bit adjustments
GB_MFRC522_WriteRegister(CommandReg, command); // Execute the command
if(command = PCD_Transceive){
GB_MFRC522_SetRegisterBitmask(BitFramingReg, 0x80); //StartSend=1, transmission of data starts
}

const uint32_t deadline = GB_millis()+36;
bool completed = false;
do {
byte n = GB_MFRC522_ReadRegister(ComIrqReg); // ComIrqReg[7..0] bits are: Set1 TxIRq RxIRq IdleIRq HiAlertIRq LoAlertIRq ErrIRq TimerIRq
if (n & waitIRQ) { // One of the interrupts that signal success has been set.
// GB_printString0("signal success\n");
completed = true;
break;
}
if (n & 0x01) { // Timer interrupt - nothing received in 25ms
// GB_printString0("Timeout\n");
return STATUS_TIMEOUT;
}
//yield();
}
while (static_cast<uint32_t> (GB_millis()) < deadline);
// _delay_ms(30);
//36ms and nothing happened. Communication with the MFRC522 might be down.
if (!completed) {
return STATUS_TIMEOUT;
}
//Stop now if any errors except collisions were detected.
byte errorRegValue = GB_MFRC522_ReadRegister(ErrorReg); // ErrorReg[7..0] bits are: WrErr TempErr reserved BufferOvfl CollErr CRCErr ParityErr ProtocolErr
if (errorRegValue & 0x13) { // BufferOvfl ParityErr ProtocolErr
GB_printString0("Some error \n");
return STATUS_ERROR;
}
byte _validbits = 0;
//If the caller wants data back, get it from the MFRC522.
if(backdata && backlen) {
byte n = GB_MFRC522_ReadRegister(FIFOLevelReg);
// GB_printString0("FIFO len");
//GB_decimel0(n);
//GB_printString0("\n");
if(n > *backlen){
return STATUS_NO_ROOM;
}

*backlen = n;
GB_MFRC522_ReadRegister(FIFODataReg, n, backdata, rxalign);
// GB_printString0("FIFO len");
// GB_decimel0(*backdata);
// GB_printString0("\n");
_validbits = GB_MFRC522_ReadRegister(ControlReg) & 0x07;
if(validbits){
*validbits = _validbits;
}
}
// Tell about collisions
if (errorRegValue & 0x08) { // CollErr
return STATUS_COLLISION;
}
// Perform CRC_A validation if requested.
if (backdata && backlen && checkCRC) {
// In this case a MIFARE Classic NAK is not OK.
if (*backlen == 1 && _validbits == 4) {
return STATUS_MIFARE_NACK;
}
// We need at least the CRC_A value and all 8 bits of the last byte must be received.
if (*backlen < 2 || _validbits != 0) {
return STATUS_CRC_WRONG;
}
// Verify CRC_A - do our own calculation and store the control in controlBuffer.
byte controlBuffer[2];
gb_MFRC522_statusCodes status = PCD_CalculateCRC(&backdata[0], *backlen - 2, &controlBuffer[0]);
if (status != STATUS_OK) {
return status;
}
if ((backdata[*backlen - 2] != controlBuffer[0]) || (backdata[*backlen - 1] != controlBuffer[1])) {
return STATUS_CRC_WRONG;
}
}
return STATUS_OK;
}//return STATUS_OK;
gb_MFRC522_statusCodes GB_MFRC522_TransceiveData( byte *senddata, //Pointer to the data to transfer to the FIFO
byte sendlen, //Number of bytes to transfer to FIFO
byte *backdata, //nullptr or pointer to buffer if data should be read back after executing the command
byte *backlen, //In: Max no of bytes to write to *backdata. Out: The no of bytes returned.
byte *validbits, //In/Out: The number of valid bits in the last byte
byte rxalign,
bool checkCRC //In: True => The last 2 bytes of the response is assumed to be a CRC_A that must be validated
)
{
byte waitIRQ = 0x30;
// GB_printString0("uy\n");
// GB_decimel0(rxalign);
// GB_printString0("\n");
// GB_decimel0(checkCRC);
// GB_printString0("\n");

_delay_ms(100);
return GB_MFRC522_CommunicateWithPICC(PCD_Transceive, waitIRQ, senddata, sendlen, backdata, backlen, validbits, rxalign, checkCRC);
}

gb_MFRC522_statusCodes GB_PICC_REQA_OR_WUPA(byte command, byte *gb_bufferATQA, byte *gb_buffersize)
{
gb_MFRC522_statusCodes status;
byte gb_validbits;
if(gb_bufferATQA == 0 || *gb_buffersize < 2) { // As gb_bufferATQA is a buffer to store the Answer to request, when command REQ is send by PCD.
return STATUS_NO_ROOM; //So this buffer should be pointing to some valid pointer and not to null pointer. And buffer 
} //size should be greater then 2 bytes, ATQA is of 2 bytes.

GB_MFRC522_ClearRegisterBitMask(CollReg,0x80);
gb_validbits = 7;

status = GB_MFRC522_TransceiveData(&command, 1, gb_bufferATQA, gb_buffersize, &gb_validbits, 0, 0);
// GB_printString0("status -->");
// GB_decimel0(status);
// GB_printString0("\n");
if( status != STATUS_OK);
return status;

if(*gb_buffersize !=2 || gb_validbits != 0){
return STATUS_ERROR;
}

return STATUS_OK;

}
gb_MFRC522_statusCodes GB_PICC_RequestA(byte * bufferATQ, byte *buffersize)
{
return GB_PICC_REQA_OR_WUPA(PICC_CMD_REQA, bufferATQ, buffersize);
}
bool GB_PICC_IsNewCardPresent()
{
byte gb_bufferATQ[2]; // We will be sending the Request command. That is in order to detect the PICCs which are in the operating field 
// PCD shall send repeated request commands. PCD will send REQ or WUP in any sequence to detect the PICCs.
//REQ commands are transmitted via short frame If PICC is in energizing field for PCD and gets powered up,
//it will start listening for valid REQ command. And transmits its ATQ(Answer to request). 
//This answer to Request is stored in this buffer. ATQA is a 2 byte number that is returned by PICC.
byte gb_buffersize = sizeof(gb_bufferATQ);
// Reset baud rates
GB_MFRC522_WriteRegister(TxModeReg, 0x00);
GB_MFRC522_WriteRegister(RxModeReg, 0x00);
// Reset ModWidthReg
GB_MFRC522_WriteRegister(ModWidthReg, 0x26);//38 in decimal

gb_MFRC522_statusCodes result = GB_PICC_RequestA(gb_bufferATQ, &gb_buffersize);
// GB_decimel0(result);
// GB_printString0("\n");
return (result == STATUS_OK || result == STATUS_COLLISION);

}
 
/**
* Transmits SELECT/ANTICOLLISION commands to select a single PICC.
* Before calling this function the PICCs must be placed in the READY(*) state by calling PICC_RequestA() or PICC_WakeupA().
* On success:
* - The chosen PICC is in state ACTIVE(*) and all other PICCs have returned to state IDLE/HALT. (Figure 7 of the ISO/IEC 14443-3 draft.)
* - The UID size and value of the chosen PICC is returned in *uid along with the SAK.
* 
* A PICC UID consists of 4, 7 or 10 bytes.
* Only 4 bytes can be specified in a SELECT command, so for the longer UIDs two or three iterations are used:
* UID size Number of UID bytes Cascade levels Example of PICC
* ======== =================== ============== ===============
* single 4 1 MIFARE Classic
* double 7 2 MIFARE Ultralight
* triple 10 3 Not currently in use?
* 
* @return STATUS_OK on success, STATUS_??? otherwise.
*/
gb_MFRC522_statusCodes GB_PICC_Select( Uid *uid, ///< Pointer to Uid struct. Normally output, but can also be used to supply a known UID.
byte validBits ///< The number of known UID bits supplied in *uid. Normally 0. If set you must also supply uid->size.
) {
bool uidComplete;
bool selectDone;
bool useCascadeTag;
byte cascadeLevel = 1;
gb_MFRC522_statusCodes result;
byte count;
byte checkBit;
byte index;
byte uidIndex; // The first index in uid->uidByte[] that is used in the current Cascade Level.
int8_t currentLevelKnownBits; // The number of known UID bits in the current Cascade Level.
byte buffer[9]; // The SELECT/ANTICOLLISION commands uses a 7 byte standard frame + 2 bytes CRC_A
byte bufferUsed; // The number of bytes used in the buffer, ie the number of bytes to transfer to the FIFO.
byte rxAlign; // Used in BitFramingReg. Defines the bit position for the first bit received.
byte txLastBits; // Used in BitFramingReg. The number of valid bits in the last transmitted byte. 
byte *responseBuffer;
byte responseLength;

// Description of buffer structure:
// Byte 0: SEL Indicates the Cascade Level: PICC_CMD_SEL_CL1, PICC_CMD_SEL_CL2 or PICC_CMD_SEL_CL3
// Byte 1: NVB Number of Valid Bits (in complete command, not just the UID): High nibble: complete bytes, Low nibble: Extra bits. 
// Byte 2: UID-data or CT See explanation below. CT means Cascade Tag.
// Byte 3: UID-data
// Byte 4: UID-data
// Byte 5: UID-data
// Byte 6: BCC Block Check Character - XOR of bytes 2-5
// Byte 7: CRC_A
// Byte 8: CRC_A
// The BCC and CRC_A are only transmitted if we know all the UID bits of the current Cascade Level.
//
// Description of bytes 2-5: (Section 6.5.4 of the ISO/IEC 14443-3 draft: UID contents and cascade levels)
// UID size Cascade level Byte2 Byte3 Byte4 Byte5
// ======== ============= ===== ===== ===== =====
// 4 bytes 1 uid0 uid1 uid2 uid3
// 7 bytes 1 CT uid0 uid1 uid2
// 2 uid3 uid4 uid5 uid6
// 10 bytes 1 CT uid0 uid1 uid2
// 2 CT uid3 uid4 uid5
// 3 uid6 uid7 uid8 uid9

// Sanity checks
if (validBits > 80) {
return STATUS_INVALID;
}

// Prepare MFRC522
GB_MFRC522_ClearRegisterBitMask(CollReg, 0x80); // ValuesAfterColl=1 => Bits received after collision are cleared.

// Repeat Cascade Level loop until we have a complete UID.
uidComplete = false;
while (!uidComplete) {
// Set the Cascade Level in the SEL byte, find out if we need to use the Cascade Tag in byte 2.
switch (cascadeLevel) {
case 1:
buffer[0] = PICC_CMD_SEL_CL1;
uidIndex = 0;
useCascadeTag = validBits && uid->size > 4; // When we know that the UID has more than 4 bytes
break;

case 2:
buffer[0] = PICC_CMD_SEL_CL2;
uidIndex = 3;
useCascadeTag = validBits && uid->size > 7; // When we know that the UID has more than 7 bytes
break;

case 3:
buffer[0] = PICC_CMD_SEL_CL3;
uidIndex = 6;
useCascadeTag = false; // Never used in CL3.
break;

default:
return STATUS_INTERNAL_ERROR;
break;
}

// GB_decimel0(validBits);
// GB_printString0("\n");
// GB_decimel0(uidIndex);
// GB_printString0("\n");
// GB_decimel0(useCascadeTag);
// GB_printString0("\n");
// How many UID bits are known in this Cascade Level?
currentLevelKnownBits = validBits - (8 * uidIndex);
if (currentLevelKnownBits < 0) {
currentLevelKnownBits = 0;
}
// Copy the known bits from uid->uidByte[] to buffer[]
index = 2; // destination index in buffer[]
if (useCascadeTag) {
buffer[index++] = PICC_CMD_CT; // buffer[3]
}
byte bytesToCopy = currentLevelKnownBits / 8 + (currentLevelKnownBits % 8 ? 1 : 0); // The number of bytes needed to represent the known bits for this level.
// GB_decimel0(bytesToCopy);
// GB_printString0("\n");
if (bytesToCopy) {
byte maxBytes = useCascadeTag ? 3 : 4; // Max 4 bytes in each Cascade Level. Only 3 left if we use the Cascade Tag
if (bytesToCopy > maxBytes) {
bytesToCopy = maxBytes;
}
for (count = 0; count < bytesToCopy; count++) {
buffer[index++] = uid->uidByte[uidIndex + count];
}
}
// Now that the data has been copied we need to include the 8 bits in CT in currentLevelKnownBits
if (useCascadeTag) {
currentLevelKnownBits += 8;
}

// Repeat anti collision loop until we can transmit all UID bits + BCC and receive a SAK - max 32 iterations.
selectDone = false;
while (!selectDone) {
// Find out how many bits and bytes to send and receive.
if (currentLevelKnownBits >= 32) { // All UID bits in this Cascade Level are known. This is a SELECT.
//Serial.print(F("SELECT: currentLevelKnownBits=")); Serial.println(currentLevelKnownBits, DEC);
// GB_decimel0(buffer[1]);
// GB_printString0("o\n");
buffer[1] = 0x70; // NVB - Number of Valid Bits: Seven whole bytes

// GB_decimel0(buffer[1]);
// GB_printString0("\n");
// Calculate BCC - Block Check Character
buffer[6] = buffer[2] ^ buffer[3] ^ buffer[4] ^ buffer[5];
// GB_decimel0(buffer[6]);
// GB_printString0("o\n");
// Calculate CRC_A
result = PCD_CalculateCRC(buffer, 7, &buffer[7]);
// GB_decimel0(result);
// GB_printString0("\n");
if (result != STATUS_OK) {
return result;
}
// GB_printString0("z\n");
txLastBits = 0; // 0 => All 8 bits are valid.
bufferUsed = 9;
// Store response in the last 3 bytes of buffer (BCC and CRC_A - not needed after tx)
responseBuffer = &buffer[6];
responseLength = 3;
}
else { // This is an ANTICOLLISION/SELECT
//Serial.print(F("ANTICOLLISION: currentLevelKnownBits=")); Serial.println(currentLevelKnownBits, DEC);
txLastBits = currentLevelKnownBits % 8;
count = currentLevelKnownBits / 8; // Number of whole bytes in the UID part.
index = 2 + count; // Number of whole bytes: SEL + NVB + UIDs
buffer[1] = (index << 4) + txLastBits; // NVB - Number of Valid Bits
// GB_decimel0(buffer[1]);
// GB_printString0("\n");
bufferUsed = index + (txLastBits ? 1 : 0);
// Store response in the unused part of buffer
responseBuffer = &buffer[index];
responseLength = sizeof(buffer) - index;
}

// Set bit adjustments
rxAlign = txLastBits; // Having a separate variable is overkill. But it makes the next line easier to read.
GB_MFRC522_WriteRegister(BitFramingReg, (rxAlign << 4) + txLastBits); // RxAlign = BitFramingReg[6..4]. TxLastBits = BitFramingReg[2..0]

// for (int i =0; i<bufferUsed; i++)
// { GB_decimel0(buffer[i]);
// GB_printString0(" ");
// }
// GB_printString0("\n");
// GB_decimel0(bufferUsed);
// GB_printString0("\n");
// Transmit the buffer and receive the response.
result = GB_MFRC522_TransceiveData(buffer, bufferUsed, responseBuffer, &responseLength, &txLastBits, rxAlign, 0);
// GB_decimel0(result);
// GB_printString0("\n");
//GB_decimel0(selectDone);
// for (int i =0; i<responseLength; i++)
// {
// GB_decimel0(responseBuffer[i]);
// GB_printString0(" ");
// }
if (result == STATUS_COLLISION) { // More than one PICC in the field => collision.
byte valueOfCollReg = GB_MFRC522_ReadRegister(CollReg); // CollReg[7..0] bits are: ValuesAfterColl reserved CollPosNotValid CollPos[4:0]
if (valueOfCollReg & 0x20) { // CollPosNotValid
return STATUS_COLLISION; // Without a valid collision position we cannot continue
}
byte collisionPos = valueOfCollReg & 0x1F; // Values 0-31, 0 means bit 32.
if (collisionPos == 0) {
collisionPos = 32;
}
if (collisionPos <= currentLevelKnownBits) { // No progress - should not happen 
return STATUS_INTERNAL_ERROR;
}
// Choose the PICC with the bit set.
currentLevelKnownBits = collisionPos;
count = currentLevelKnownBits % 8; // The bit to modify
checkBit = (currentLevelKnownBits - 1) % 8;
index = 1 + (currentLevelKnownBits / 8) + (count ? 1 : 0); // First byte is index 0.
buffer[index] |= (1 << checkBit);
}
else if (result != STATUS_OK) {
return result;
}
else { // STATUS_OK
if (currentLevelKnownBits >= 32) { // This was a SELECT.
selectDone = true; // No more anticollision 
// GB_decimel0(currentLevelKnownBits);
// GB_printString0("2)");
// We continue below outside the while.
}
else { // This was an ANTICOLLISION.
// We now have all 32 bits of the UID in this Cascade Level
// GB_printString0("\n");
// GB_decimel0(currentLevelKnownBits);
// GB_printString0("\n");
// GB_printString0("1)");
currentLevelKnownBits = 32;
// Run loop again to do the SELECT.
}
}
} // End of while (!selectDone)

// We do not check the CBB - it was constructed by us above.

// GB_printString0("3");
// Copy the found UID bytes from buffer[] to uid->uidByte[]
index = (buffer[2] == PICC_CMD_CT) ? 3 : 2; // source index in buffer[]
bytesToCopy = (buffer[2] == PICC_CMD_CT) ? 3 : 4;
for (count = 0; count < bytesToCopy; count++) {
uid->uidByte[uidIndex + count] = buffer[index++];
}

// Check response SAK (Select Acknowledge)
if (responseLength != 3 || txLastBits != 0) { // SAK must be exactly 24 bits (1 byte + CRC_A).
return STATUS_ERROR;
}
// Verify CRC_A - do our own calculation and store the control in buffer[2..3] - those bytes are not needed anymore.
result = PCD_CalculateCRC(responseBuffer, 1, &buffer[2]);
if (result != STATUS_OK) {
return result;
}
if ((buffer[2] != responseBuffer[1]) || (buffer[3] != responseBuffer[2])) {
return STATUS_CRC_WRONG;
}
if (responseBuffer[0] & 0x04) { // Cascade bit set - UID not complete yes
cascadeLevel++;
}
else {
uidComplete = true;
uid->sak = responseBuffer[0];
}
} // End of while (!uidComplete)

// Set correct uid->size
uid->size = 3 * cascadeLevel + 1;
return STATUS_OK;
} // End PICC_Select()
bool GB_PICC_ReadCardSerial()
{
gb_MFRC522_statusCodes result = GB_PICC_Select(&uid, 0);
return (result == STATUS_OK);
}

void GB_PICCDetails(Uid *uid)
{
// UID
GB_printString0("Card UID:\n");
for (byte i = 0; i < uid->size; i++) {
if(uid->uidByte[i] < 0x10)
GB_printString0("0");
else
GB_printString0(" ");
GB_decimel0(uid->uidByte[i]);
}
GB_printString0("\n");

// SAK
GB_printString0("Card SAK: \n");
if(uid->sak < 0x10)
GB_printString0("0");
GB_decimel0(uid->sak);

// (suggested) PICC type
// PICC_Type piccType = PICC_GetType(uid->sak);
// Serial.print(F("PICC type: "));
// Serial.println(PICC_GetTypeName(piccType));
} // End PICC_DumpDetailsToSerial()
Proposed Demo
Demo Explained

Project Download
NXP-S32K144-MCU/S32K114_RFID_Module at main · gkunalupta/NXP-S32K144-MCU (github.com)

 

AVR_BareMetal_Firmwares/SPI/Examples/Atmega256_RFID_BareMetal at master · gkunalupta/AVR_BareMetal_Firmwares (github.com)

Prev
PREVIOUS
ISO14443-A: RFID Standard Protocol
NEXT
GPIO Peripheral in S32K144 MCU
Next
Leave a Reply
Logged in as Rohit Chauhan. Edit your profile. Log out? Required fields are marked *

Comment * 
				
			

Proposed Demo

STM32F103
NXP S32K144
AVR MCU

Project Download

Author

Kunal

Leave a comment

Stay Updated With Us

Error: Contact form not found.

      Blog