[Revised] Working with STM32 and RC522 RFID reader: SPI based module

In this article, we will took at the RFID and how it does work and use RC522 to read RFID tag and display the tag ID on I2C LCD.

In this article, we will cover the following:

  • What is RFID.
  • RC522 RFID module.
  • Connection with STM32.
  • Code.
  • Demo.

1. What is RFID:

RFID (radio frequency identification) is a form of wireless communication that incorporates the use of electromagnetic or electrostatic coupling in the radio frequency portion of the electromagnetic spectrum to uniquely identify an object, animal or person.

How does RFID work?

Every RFID system consists of three components: a scanning antenna, a transceiver and a transponder. When the scanning antenna and transceiver are combined, they are referred to as an RFID reader or interrogator. There are two types of RFID readers — fixed readers and mobile readers. The RFID reader is a network-connected device that can be portable or permanently attached. It uses radio waves to transmit signals that activate the tag. Once activated, the tag sends a wave back to the antenna, where it is translated into data.

The transponder is in the RFID tag itself. The read range for RFID tags varies based on factors including the type of tag, type of reader, RFID frequency and interference in the surrounding environment or from other RFID tags and readers. Tags that have a stronger power source also have a longer read range.

For more information, please check this youtube video (here).

2.1 RC522 RFID module:

The RC522 RFID module based on MFRC522 IC from NXP is one of the most inexpensive RFID options that you can get online for less than four dollars. It usually comes with a RFID card tag and key fob tag having 1KB memory. And best of all, it can write a tag, so you can store your some sort of secret message in it.

he RC522 RFID Reader module is designed to create a 13.56MHz electromagnetic field that it uses to communicate with the RFID tags (ISO 14443A standard tags). The reader can communicate with a microcontroller over a 4-pin Serial Peripheral Interface (SPI) with a maximum data rate of 10Mbps. It also supports communication over I2C and UART protocols.

The module comes with an interrupt pin. It is handy because instead of constantly asking the RFID module “is there a card in view yet? “, the module will alert us when a tag comes into its vicinity.

The operating voltage of the module is from 2.5 to 3.3V, but the good news is that the logic pins are 5-volt tolerant, so we can easily connect it to any 5V logic microcontroller without using any logic level converter.

Here are complete specifications:

Frequency Range13.56 MHz ISM Band
Host InterfaceSPI / I2C / UART
Operating Supply Voltage2.5 V to 3.3 V
Max. Operating Current13-26mA
Min. Current(Power down)10µA
Logic Inputs5V Tolerant
Read Range5 cm

2.2 RC522 pinout:

The RC522 module has total 8 pins that interface it to the outside world. The connections are as follows:

PinDescription 
VCCsupplies power for the module. This can be anywhere from 2.5 to 3.3 volts. You can connect it to 3.3V output. Remember connecting it to 5V pin will likely destroy your module!
RSTan input for Reset and power-down. When this pin goes low, hard power-down is enabled. This turns off all internal current sinks including the oscillator and the input pins are disconnected from the outside world. On the rising edge, the module is reset.
GNDthe Ground Pin and needs to be connected to GND pin on the Arduino.
IRQpin acts as Master-In-Slave-Out when SPI interface is enabled, acts as serial clock when I2C interface is enabled and acts as serial data output when UART interface is enabled.
MISOis SPI input to the RC522 module.
MOSI is SPI input to the RC522 module.
SCKaccepts clock pulses provided by the SPI bus Master.
SSpin acts as Signal input when SPI interface is enabled, acts as serial data when I2C interface is enabled and acts as serial data input when UART interface is enabled. This pin is usually marked by encasing the pin in a square so it can be used as a reference for identifying the other pins.

3. Connection with STM32F411RE Nucleo:

RC522STM32F446 Nucleo
Vcc3V3
RSTPA8 (D7)
GNDGND
MOSIPA7 (D11)
MISOPA6 (D12)
SCKPA5 (D13)
CSPB0 (A3)
IRQNot connected

4. Code:

We start off by configuring SPI as following:

void SPI1_Pins_Init()
{
	RCC->AHB1ENR|=RCC_AHB1ENR_GPIOAEN; //enable clock for GPIOA
	GPIOA->MODER|=GPIO_MODER_MODE5_1|GPIO_MODER_MODE6_1|GPIO_MODER_MODE7_1; //set PA5, PA6 and PA7 to alternate function mode
	GPIOA->MODER &=~(GPIO_MODER_MODE5_0|GPIO_MODER_MODE6_0|GPIO_MODER_MODE7_0);
	GPIOA->AFR[0]|=(0x05<<20)|(0x05<<24)|(0x05<<28);
}



void SPI1_Init()
{
	/*Enable clock access to SPI1 module*/
		RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;

		/*Set clock to fPCLK/4*/
		SPI1->CR1 |=(1U<<3);
		SPI1->CR1 &=~(1U<<4);
		SPI1->CR1 &=~(1U<<5);

		/*Enable full duplex*/
		SPI1->CR1 &=~(1U<<10);

		/*Set MSB first*/
		SPI1->CR1 &= ~(1U<<7);

		/*Set mode to MASTER*/
		SPI1->CR1 |= (1U<<2);

		/*Set 8 bit data mode*/
		SPI1->CR1 &= ~(1U<<11);

		/*Select software slave management by
		 * setting SSM=1 and SSI=1*/
		SPI1->CR1 |= (1<<8);
		SPI1->CR1 |= (1<<9);

		/*Enable SPI module*/
		SPI1->CR1 |= (1<<6);
}

Then SPI transmit as following:

void spi1_transmit(uint8_t *data,uint32_t size)
{
	uint32_t i=0;

	while(i<size)
	{
		/*Wait until TXE is set*/
		while(!(SPI1->SR & (SPI_SR_TXE))){}

		/*Write the data to the data register*/
		SPI1->DR = data[i];
		i++;
	}
	/*Wait until TXE is set*/
	while(!(SPI1->SR & (SPI_SR_TXE))){}

	/*Wait for BUSY flag to reset*/
	while((SPI1->SR & (SPI_SR_BSY))){}

	/*Clear OVR flag*/
	(void)SPI1->DR;
	(void)SPI1->SR;
}

SPI receive function:

void spi1_receive(uint8_t *data,uint32_t size)
{
	while(size)
	{
		/*Send dummy data*/
		SPI1->DR =0;

		/*Wait for RXNE flag to be set*/
		while(!(SPI1->SR & (SPI_SR_RXNE))){}

		/*Read data from data register*/
		*data++ = (SPI1->DR);
		size--;
	}
}

Now for the RC522 initializing function as following:

Create new source file with name of rfid.c as put the following:

void rc522_init(void)
{
	/*
	 * STM32 ->RFID
	 * SPI  -> SPI
	 * PA8  ->RST
	 * PB0  ->CS
	 * */
  SPI1_Pins_Init();
  SPI1_Init();
  GPIOA->MODER|=GPIO_MODER_MODE8_0;
  GPIOA->MODER&=~GPIO_MODER_MODE8_1;

  RCC->AHB1ENR|=RCC_AHB1ENR_GPIOBEN;

  GPIOB->MODER|=GPIO_MODER_MODE0_0;
  GPIOB->MODER&=~GPIO_MODER_MODE0_1;
  GPIOA->BSRR=GPIO_BSRR_BR8;
  for(volatile int i=0;i<100000;i++);
  GPIOA->BSRR=GPIO_BSRR_BS8;
  for(volatile int i=0;i<100000;i++);
  rc522_reset();

  rc522_regWrite8(MFRC522_REG_T_MODE, 0x80);
  rc522_regWrite8(MFRC522_REG_T_PRESCALER, 0xA9);
  rc522_regWrite8(MFRC522_REG_T_RELOAD_L, 0xE8);
  rc522_regWrite8(MFRC522_REG_T_RELOAD_H, 0x03);


  rc522_regWrite8(MFRC522_REG_TX_AUTO, 0x40);
  rc522_regWrite8(MFRC522_REG_MODE, 0x3D);

  rc522_antennaON();   //Open the antenna
}

Register read and write:

uint8_t rc522_regRead8(uint8_t reg)
{
  spi_cs_rfid_write(0);
  reg = ((reg << 1) & 0x7E) | 0x80;
  spi1_transmit(&reg, 1);
  uint8_t dataRd=0;
  spi1_receive(&dataRd, 1);
  spi_cs_rfid_write(1);
  return dataRd;
}

/**
 * @brief write register
 */
void rc522_regWrite8(uint8_t reg, uint8_t data8)
{
  spi_cs_rfid_write(0);
  uint8_t txData[2] = {0x7E&(reg << 1), data8};
  spi1_transmit(txData, 2);
  spi_cs_rfid_write(1);
}

Other functions required:

bool rc522_toCard(
    uint8_t command,
    uint8_t* sendData,
    uint8_t sendLen,
    uint8_t* backData,
    uint16_t* backLen);

bool rc522_request(uint8_t reqMode, uint8_t *tagType);

bool rc522_antiColl(uint8_t* serNum);

void spi_cs_rfid_write(bool state)
{
	if(state)
	  {
	    GPIOB->ODR |= (1UL << 0);
	  }
	  else
	  {
	    GPIOB->ODR &= ~(1UL << 0);
	  }
}

/**
 * @brief set bit
 */
void rc522_setBit(uint8_t reg, uint8_t mask)
{
  rc522_regWrite8(reg, rc522_regRead8(reg)|mask);
}

/**
 * @brief clear bit
 */
void rc522_clearBit(uint8_t reg, uint8_t mask)
{
  rc522_regWrite8(reg, rc522_regRead8(reg)&(~mask));
}

/**
 * @brief reset function
 */
void rc522_reset(void)
{
  rc522_regWrite8(0x01, 0x0F);
}

/**
 * @brief Antenna ON
 */
void rc522_antennaON(void)
{
  uint8_t temp;

  temp = rc522_regRead8(MFRC522_REG_TX_CONTROL);
  if (!(temp & 0x03)) {
    rc522_setBit(MFRC522_REG_TX_CONTROL, 0x03);
  }
}

/**
 * @brief Check card
 */
bool rc522_checkCard(uint8_t *id)
{
  bool status=false;
  //Find cards, return card type
    status = rc522_request(PICC_REQIDL, id);
    if (status == true) {
      //Card detected
      //Anti-collision, return card serial number 4 bytes
      status = rc522_antiColl(id);
    }
    rc522_halt();      //Command card into hibernation

    return status;
}

/**
 * @brief Request function
 */
bool rc522_request(uint8_t reqMode, uint8_t *tagType)
{
  bool status=false;
  uint16_t backBits;
  rc522_regWrite8(MFRC522_REG_BIT_FRAMING, 0x07);
  tagType[0] = reqMode;
  status = rc522_toCard(PCD_TRANSCEIVE, tagType, 1, tagType, &backBits);
  if ((status != true) || (backBits != 0x10)) {
    status = false;
  }
  return status;
}

/**
 * @brief to Card
 */
bool rc522_toCard(
    uint8_t command,
    uint8_t* sendData,
    uint8_t sendLen,
    uint8_t* backData,
    uint16_t* backLen)
{
  bool status = false;
  uint8_t irqEn = 0x00;
  uint8_t waitIRq = 0x00;
  uint8_t lastBits;
  uint8_t n;
  uint16_t i;

  switch (command) {
    case PCD_AUTHENT: {
      irqEn = 0x12;
      waitIRq = 0x10;
      break;
    }
    case PCD_TRANSCEIVE: {
      irqEn = 0x77;
      waitIRq = 0x30;
      break;
    }
    default:
      break;
  }

  rc522_regWrite8(MFRC522_REG_COMM_IE_N, irqEn | 0x80);
  rc522_clearBit(MFRC522_REG_COMM_IRQ, 0x80);
  rc522_setBit(MFRC522_REG_FIFO_LEVEL, 0x80);

  rc522_regWrite8(MFRC522_REG_COMMAND, PCD_IDLE);

  //Writing data to the FIFO
  for (i = 0; i < sendLen; i++) {
    rc522_regWrite8(MFRC522_REG_FIFO_DATA, sendData[i]);
  }

  //Execute the command
  rc522_regWrite8(MFRC522_REG_COMMAND, command);
  if (command == PCD_TRANSCEIVE) {
    rc522_setBit(MFRC522_REG_BIT_FRAMING, 0x80);   //StartSend=1,transmission of data starts
  }

  //Waiting to receive data to complete
  i = 100;  //i according to the clock frequency adjustment, the operator M1 card maximum waiting time 25ms???
  do {
    //CommIrqReg[7..0]
    //Set1 TxIRq RxIRq IdleIRq HiAlerIRq LoAlertIRq ErrIRq TimerIRq
    n = rc522_regRead8(MFRC522_REG_COMM_IRQ);
    i--;
  } while ((i!=0) && !(n&0x01) && !(n&waitIRq));

  rc522_clearBit(MFRC522_REG_BIT_FRAMING, 0x80);     //StartSend=0

  if (i != 0)  {
    if (!(rc522_regRead8(MFRC522_REG_ERROR) & 0x1B)) {
      status = true;
      if (n & irqEn & 0x01) {
        status = false;
      }

      if (command == PCD_TRANSCEIVE) {
        n = rc522_regRead8(MFRC522_REG_FIFO_LEVEL);
        uint8_t l = n;
        lastBits = rc522_regRead8(MFRC522_REG_CONTROL) & 0x07;
        if (lastBits) {
          *backLen = (n - 1) * 8 + lastBits;
        } else {
          *backLen = n * 8;
        }

        if (n == 0) {
          n = 1;
        }
        if (n > MFRC522_MAX_LEN) {
          n = MFRC522_MAX_LEN;
        }

        //Reading the received data in FIFO
        for (i = 0; i < n; i++) {
          uint8_t d = rc522_regRead8(MFRC522_REG_FIFO_DATA);
          if (l == 4)
            printf("%02x ", d);
          backData[i] = d;
        }
        if (l==4)
          printf("\r\n");
        return status;
      }
    } else {
      printf("error\r\n");
      status = false;
    }
  }

  return status;
}

bool rc522_antiColl(uint8_t* serNum)
{
  bool status;
  uint8_t i;
  uint8_t serNumCheck = 0;
  uint16_t unLen;
  //for (i = 0; i < 4; i++)
//    printf("Anticoll In %d: 0x%02x\r\n", i, serNum[i]);


  rc522_regWrite8(MFRC522_REG_BIT_FRAMING, 0x00);    //TxLastBists = BitFramingReg[2..0]

  serNum[0] = PICC_ANTICOLL;
  serNum[1] = 0x20;
  status = rc522_toCard(PCD_TRANSCEIVE, serNum, 2, serNum, &unLen);

  //for (i = 0; i < 4; i++)
//      printf("Anticoll ToCard %d: 0x%02x\r\n", i, serNum[i]);

  if (status == true) {
    //Check card serial number
    for (i = 0; i < 4; i++) {
      serNumCheck ^= serNum[i];
    }
    if (serNumCheck != serNum[i]) {
      status = false;
    }
  }
  return status;
}

void rc522_halt(void)
{
  uint16_t unLen;
  uint8_t buff[4];

  buff[0] = PICC_HALT;
  buff[1] = 0;
  rc522_calculateCRC(buff, 2, &buff[2]);

  rc522_toCard(PCD_TRANSCEIVE, buff, 4, buff, &unLen);
}

void rc522_calculateCRC(uint8_t*  pIndata, uint8_t len, uint8_t* pOutData)
{
  uint8_t i, n;

  rc522_clearBit(MFRC522_REG_DIV_IRQ, 0x04);     //CRCIrq = 0
  rc522_setBit(MFRC522_REG_FIFO_LEVEL, 0x80);      //Clear the FIFO pointer
  //Write_MFRC522(CommandReg, PCD_IDLE);

  //Writing data to the FIFO
  for (i = 0; i < len; i++) {
    rc522_regWrite8(MFRC522_REG_FIFO_DATA, *(pIndata+i));
  }
  rc522_regWrite8(MFRC522_REG_COMMAND, PCD_CALCCRC);

  //Wait CRC calculation is complete
  i = 0xFF;
  do {
    n = rc522_regRead8(MFRC522_REG_DIV_IRQ);
    i--;
  } while ((i!=0) && !(n&0x04));      //CRCIrq = 1

  //Read CRC calculation result
  pOutData[0] = rc522_regRead8(MFRC522_REG_CRC_RESULT_L);
  pOutData[1] = rc522_regRead8(MFRC522_REG_CRC_RESULT_M);
}

/**
 * @brief compare IDs
 */
bool rc522_compareIds(uint8_t *idCurrent, uint8_t *idReference)
{
  uint8_t i;
  for(i=0; i<4;i++)
  {
    if(idCurrent[i] != idReference[i])
    {
      return false;
    }
  }
  return true;
}

And now, create new header file with name of rfid.h and the following is the content of the header file:

#ifndef RFID_H_
#define RFID_H_


#include "stdbool.h"
#include "stdint.h"


#define MFRC522_CS_LOW          MFRC522_CS_PORT->BSRRH = MFRC522_CS_PIN;
#define MFRC522_CS_HIGH         MFRC522_CS_PORT->BSRRL = MFRC522_CS_PIN;

/* MFRC522 Commands */
#define PCD_IDLE            0x00   //NO action; Cancel the current command
#define PCD_AUTHENT           0x0E   //Authentication Key
#define PCD_RECEIVE           0x08   //Receive Data
#define PCD_TRANSMIT          0x04   //Transmit data
#define PCD_TRANSCEIVE          0x0C   //Transmit and receive data,
#define PCD_RESETPHASE          0x0F   //Reset
#define PCD_CALCCRC           0x03   //CRC Calculate

/* Mifare_One card command word */
#define PICC_REQIDL           0x26   // find the antenna area does not enter hibernation
#define PICC_REQALL           0x52   // find all the cards antenna area
#define PICC_ANTICOLL         0x93   // anti-collision
#define PICC_SElECTTAG          0x93   // election card
#define PICC_AUTHENT1A          0x60   // authentication key A
#define PICC_AUTHENT1B          0x61   // authentication key B
#define PICC_READ           0x30   // Read Block
#define PICC_WRITE            0xA0   // write block
#define PICC_DECREMENT          0xC0   // debit
#define PICC_INCREMENT          0xC1   // recharge
#define PICC_RESTORE          0xC2   // transfer block data to the buffer
#define PICC_TRANSFER         0xB0   // save the data in the buffer
#define PICC_HALT           0x50   // Sleep

/* MFRC522 Registers */
//Page 0: Command and Status
#define MFRC522_REG_RESERVED00      0x00
#define MFRC522_REG_COMMAND       0x01
#define MFRC522_REG_COMM_IE_N     0x02
#define MFRC522_REG_DIV1_EN       0x03
#define MFRC522_REG_COMM_IRQ      0x04
#define MFRC522_REG_DIV_IRQ       0x05
#define MFRC522_REG_ERROR       0x06
#define MFRC522_REG_STATUS1       0x07
#define MFRC522_REG_STATUS2       0x08
#define MFRC522_REG_FIFO_DATA     0x09
#define MFRC522_REG_FIFO_LEVEL      0x0A
#define MFRC522_REG_WATER_LEVEL     0x0B
#define MFRC522_REG_CONTROL       0x0C
#define MFRC522_REG_BIT_FRAMING     0x0D
#define MFRC522_REG_COLL        0x0E
#define MFRC522_REG_RESERVED01      0x0F
//Page 1: Command
#define MFRC522_REG_RESERVED10      0x10
#define MFRC522_REG_MODE        0x11
#define MFRC522_REG_TX_MODE       0x12
#define MFRC522_REG_RX_MODE       0x13
#define MFRC522_REG_TX_CONTROL      0x14
#define MFRC522_REG_TX_AUTO       0x15
#define MFRC522_REG_TX_SELL       0x16
#define MFRC522_REG_RX_SELL       0x17
#define MFRC522_REG_RX_THRESHOLD    0x18
#define MFRC522_REG_DEMOD       0x19
#define MFRC522_REG_RESERVED11      0x1A
#define MFRC522_REG_RESERVED12      0x1B
#define MFRC522_REG_MIFARE        0x1C
#define MFRC522_REG_RESERVED13      0x1D
#define MFRC522_REG_RESERVED14      0x1E
#define MFRC522_REG_SERIALSPEED     0x1F
//Page 2: CFG
#define MFRC522_REG_RESERVED20      0x20
#define MFRC522_REG_CRC_RESULT_M    0x21
#define MFRC522_REG_CRC_RESULT_L    0x22
#define MFRC522_REG_RESERVED21      0x23
#define MFRC522_REG_MOD_WIDTH     0x24
#define MFRC522_REG_RESERVED22      0x25
#define MFRC522_REG_RF_CFG        0x26
#define MFRC522_REG_GS_N        0x27
#define MFRC522_REG_CWGS_PREG     0x28
#define MFRC522_REG__MODGS_PREG     0x29
#define MFRC522_REG_T_MODE        0x2A
#define MFRC522_REG_T_PRESCALER     0x2B
#define MFRC522_REG_T_RELOAD_H      0x2C
#define MFRC522_REG_T_RELOAD_L      0x2D
#define MFRC522_REG_T_COUNTER_VALUE_H 0x2E
#define MFRC522_REG_T_COUNTER_VALUE_L 0x2F
//Page 3:TestRegister
#define MFRC522_REG_RESERVED30      0x30
#define MFRC522_REG_TEST_SEL1     0x31
#define MFRC522_REG_TEST_SEL2     0x32
#define MFRC522_REG_TEST_PIN_EN     0x33
#define MFRC522_REG_TEST_PIN_VALUE    0x34
#define MFRC522_REG_TEST_BUS      0x35
#define MFRC522_REG_AUTO_TEST     0x36
#define MFRC522_REG_VERSION       0x37
#define MFRC522_REG_ANALOG_TEST     0x38
#define MFRC522_REG_TEST_ADC1     0x39
#define MFRC522_REG_TEST_ADC2     0x3A
#define MFRC522_REG_TEST_ADC0     0x3B
#define MFRC522_REG_RESERVED31      0x3C
#define MFRC522_REG_RESERVED32      0x3D
#define MFRC522_REG_RESERVED33      0x3E
#define MFRC522_REG_RESERVED34      0x3F
//Dummy byte
#define MFRC522_DUMMY         0x00

#define MFRC522_MAX_LEN         16


/**
 * @brief initialize function
 */
void rc522_init(void);

/**
 * @brief read register
 */
uint8_t rc522_regRead8(uint8_t reg);

/**
 * @brief write register
 */
void rc522_regWrite8(uint8_t reg, uint8_t data8);

/**
 * @brief set bit
 */
void rc522_setBit(uint8_t reg, uint8_t mask);

/**
 * @brief clear bit
 */
void rc522_clearBit(uint8_t reg, uint8_t mask);

/**
 * @brief reset function
 */
void rc522_reset(void);

/**
 * @brief Antenna ON
 */
void rc522_antennaON(void);

/**
 * @brief Check card
 */
bool rc522_checkCard(uint8_t *id);

/**
 * @brief Request function
 */
bool rc522_request(uint8_t reqMode, uint8_t *tagType);

/**
 * @brief to Card
 */
bool rc522_toCard(
    uint8_t command,
    uint8_t* sendData,
    uint8_t sendLen,
    uint8_t* backData,
    uint16_t* backLen);

/**
 * @brief Anti-Collis
 */
bool rc522_antiColl(uint8_t* serNum);

/**
 * @brief Halt
 */
void rc522_halt(void);

/**
 * @brief calculate CRC
 */
void rc522_calculateCRC(uint8_t*  pIndata, uint8_t len, uint8_t* pOutData);

/**
 * @brief compare IDs
 */
bool rc522_compareIds(uint8_t *idCurrent, uint8_t *idReference);


#endif /* RFID_H_ */

In main.c file:

#include "LiquidCrystal_PCF8574.h"
#include "delay.h"
#include "stdio.h"
#include "rfid.h"


uint8_t rfid_id[4];
int main(void)
		{
		rc522_init();
		lcd_init();
		setCursor(0,0);
		lcd_send_string("RFID RC522 with");
		setCursor(7,1);
		lcd_send_string("STM32F4");
		setCursor(0,2);
		lcd_send_string("EmbeddedExperIO");
		delay(2000);
		lcd_clear();
		while(1)
				{
				if(rc522_checkCard(rfid_id))
							{

							lcd_clear();
							char data[20];
							setCursor(0,0);
							lcd_send_string("RFID code is");
							setCursor(0,1);
							sprintf(data,"0x%x 0x%x 0x%x 0x%x",rfid_id[0],rfid_id[1],rfid_id[2],rfid_id[3]);
							lcd_send_string(data);
							delay(1000);
							}
				delay(100);
				}

		}

You may download the code from here:

5. Results:

Once the code is compiled and uploaded to MCU, place a card on the module and the result shall appear as following:

Happy coding 🙂

Add Comment

Your email address will not be published. Required fields are marked *