GD32F303应用笔记(二) 驱动TLE5012B/TLI5012B

简介

  • TLI5012B 是英飞凌(Infineon)出品的一款高精度角度传感器芯片,基于霍尔技术,常用于电机控制、角度编码器等场景。
  • 本文基于GD32F303CCT6平台,使用SPI进行数据传输。

引脚配置

  • 引脚配置如下:
  • 此处使用软件片选,因为硬件片选不支持CPOL=0,CPHA=1下的自动操作。

使用了SPI0,配置如下

接口信号MCU 引脚复用模式
(GPIO 模式)
方向*备注
SPI0
(全remap)
NSSPA15GPIO_MODE_OUT_PP输出软件片选
SCKPB3GPIO_MODE_AF_PP输出时钟:CPOL0 / CPHA1
MISOPB4GPIO_MODE_IN_FLOATING输入16bit 数据输入
MOSIPB5GPIO_MODE_AF_PP输出16bit 数据输出

代码如下:

#include "gd32f30x.h"

#define SPI0_INST	 	 SPI0
#define SPI0_SCK_PORT	 GPIOB
#define SPI0_SCK_PIN	 GPIO_PIN_3
#define SPI0_SCK_FUNC	 GPIO_MODE_AF_PP
#define SPI0_MOSI_PORT	 GPIOB
#define SPI0_MOSI_PIN	 GPIO_PIN_5
#define SPI0_MOSI_FUNC	 GPIO_MODE_AF_PP
#define SPI0_MISO_PORT	 GPIOB
#define SPI0_MISO_PIN	 GPIO_PIN_4
#define SPI0_MISO_FUNC	 GPIO_MODE_IN_FLOATING
#define SPI0_NSS_PORT	 GPIOA
#define SPI0_NSS_PIN	 GPIO_PIN_15
#define SPI0_NSS_FUNC	 GPIO_MODE_OUT_PP

void gpio_init(void)
{
    rcu_periph_clock_enable(RCU_SPI0);
    rcu_periph_clock_enable(RCU_SPI1);
    /* 关闭 JTAG,仅保留 SWD(释放 PA15、PB3、PB4) */
    gpio_pin_remap_config(GPIO_SWJ_SWDPENABLE_REMAP, ENABLE);

    /* -------- SPI0 全 remap:PB3/4/5 + PA15 -------- */
    gpio_pin_remap_config(GPIO_SPI0_REMAP, ENABLE);
    /* PA15 → NSS, 推挽输出 */
    gpio_init(SPI0_NSS_PORT, SPI0_NSS_FUNC, GPIO_OSPEED_50MHZ, SPI0_NSS_PIN);
    /* PB3 → SCK, PB5 → MOSI, 推挽输出 */
    gpio_init(SPI0_SCK_PORT, SPI1_SCK_FUNC, GPIO_OSPEED_50MHZ, SPI0_SCK_PIN | SPI0_MOSI_PIN);
    /* PB4 → MISO, 浮空输入 */
    gpio_init(SPI0_MISO_PORT, SPI0_MISO_FUNC, GPIO_OSPEED_50MHZ, SPI0_MISO_PIN);

}

SPI配置

SPI配置如下:

/**
 * @brief Initialize SPI module
 * 
 * @details Configures SPI hardware and initializes necessary settings
 */
void spi_init(void)
{
    spi_parameter_struct spi_init_str;
    spi_struct_para_init(&spi_init_str);

    /* SPI参数:16bit, 主机, 全双工, CPOL=0 CPHA=1, MSB first */
    spi_init_str.device_mode          = SPI_MASTER;
    spi_init_str.trans_mode           = SPI_TRANSMODE_FULLDUPLEX;
    spi_init_str.frame_size           = SPI_FRAMESIZE_16BIT;
    spi_init_str.clock_polarity_phase = SPI_CK_PL_LOW_PH_2EDGE;
    spi_init_str.nss                  = SPI_NSS_SOFT;      
    spi_init_str.endian               = SPI_ENDIAN_MSB;

    spi_init_str.prescale = SPI_PSC_16;
    spi_init(SPI0_INST, &spi_init_str);
    spi_nss_output_enable(SPI0_INST);  
    spi_nssp_mode_enable(SPI0_INST);
    spi_enable(SPI0_INST); 
}

/**
 * @brief Send or read half word through SPI
 * 
 * @param[in] spi_periph SPI peripheral
 * @param[in] i_HalfWord data
 */
uint16_t spi_rw_half_word(uint32_t spi_periph, const uint16_t i_HalfWord)
{
    uint32_t to;
    uint16_t data = 0xFFFF;      
    bool     ok   = true;

    /* ---------- Send data ---------- */
    to = 200;
    while ((RESET == spi_i2s_flag_get(spi_periph, SPI_FLAG_TBE)) && --to);
    if (to == 0) ok = false;

    if (ok)
    {
        if(RESET == spi_i2s_flag_get(spi_periph, SPI_FLAG_RBNE)) 
        {
            (void)spi_i2s_data_receive(spi_periph);   /* throw Dummy */               
        }
        spi_i2s_data_transmit(spi_periph, i_HalfWord);
        /* wait rx succ*/
        to = 200;
        while ((RESET == spi_i2s_flag_get(spi_periph, SPI_FLAG_RBNE)) && --to);
        if (to == 0) ok = false;
        else
            data = spi_i2s_data_receive(spi_periph);   /* throw Dummy */
    }

    /* ---------- wait bsu idle ---------- */
    if (ok)
    {
        to = 200;
        while ((SET == spi_i2s_flag_get(spi_periph, SPI_FLAG_TRANS))  \
        && SET == spi_i2s_flag_get(spi_periph, SPI_FLAG_RBNE) && --to);
        if (to == 0) ok = false;
    }

    return ok ? data : 0xFFFF;
}

TLI5012B相关函数

函数功能:初始化,获取传感器数据等。

/**
 * @brief Initialize TLI5012B magnetic angle sensor
 * @note This function configures the sensor registers for proper operation
 * @return None
 */
void cdd_TLI5012_Init(void)
{
	uint16_t u16Command = 0xFFFF;
	uint16_t u16Data = 0x0000;
	uint16_t u16Safe = 0x0000;
	
	/* ---------- Step 1: Read and configure STAT register ---------- */
	/* Read STAT register to get current status */
	u16Command = READ_STAT_VALUE;
	u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
	printf("\r\n @Joe [TLI5012Init] [STAT] read u16Data: 0x%04X SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* Write STAT register, set Slave_Number = 00 */
	u16Command = 0x0001;
	u16Data &= 0x9FFF;  /* Clear bits 13-14 (Slave_Number) */
	u16Safe = cdd_TLI5012_WriteReg(u16Command, u16Data);
	printf("\r\n @Joe [TLI5012Init] [STAT] write u16Data: 0x%04X SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* Read STAT register again to verify write operation */
	u16Command = READ_STAT_VALUE;
	u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
	printf("\r\n @Joe [TLI5012Init] [STAT] read u16Data: 0x%04X SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* ---------- Step 2: Read ACSTAT register ---------- */
	u16Command = READ_ACSTAT_VALUE;
	u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
	printf("\r\n @Joe [TLI5012Init] read [ACSTAT]: 0x%04X SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* ---------- Step 3: Configure MOD1 register ---------- */
	/* Read current MOD1 register value */
	u16Command = RD_REG | WRITE_MOD1_VALUE;
	u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
	printf("\r\n @Joe [TLI5012Init] read MOD1: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* Write MOD1 register with configuration value */
	u16Command = WRITE_MOD1_VALUE;
	u16Data = MOD1_VALUE;
	u16Safe = cdd_TLI5012_WriteReg(u16Command, u16Data);
	printf("\r\n @Joe [TLI5012Init] [MOD1] write u16Data: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);    
	
	/* Verify MOD1 register write operation */
	u16Command = RD_REG | WRITE_MOD1_VALUE;
	u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
	printf("\r\n @Joe [TLI5012Init] read MOD1: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* ---------- Step 4: Configure MOD2 register ---------- */
	/* Read current MOD2 register value */
	u16Command = RD_REG | WRITE_MOD2_VALUE;
	u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
	printf("\r\n @Joe [TLI5012Init] read MOD2: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* Write MOD2 register with configuration value */
	u16Command = WRITE_MOD2_VALUE;
	u16Data = MOD2_VALUE;
	u16Safe = cdd_TLI5012_WriteReg(u16Command, u16Data);
	printf("\r\n @Joe [TLI5012Init] [MOD2] write u16Data: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* Verify MOD2 register write operation */
	u16Command = RD_REG | WRITE_MOD2_VALUE;
	u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
	printf("\r\n @Joe [TLI5012Init] read MOD2: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);    

	/* ---------- Step 5: Configure MOD3 register ---------- */
	/* Read current MOD3 register value */
	u16Command = RD_REG | WRITE_MOD3_VALUE;
	u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
	printf("\r\n @Joe [TLI5012Init] read MOD3: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* Write MOD3 register with configuration value */
	u16Command = WRITE_MOD3_VALUE;
	u16Data = MOD3_VALUE;
	u16Safe = cdd_TLI5012_WriteReg(u16Command, u16Data);
	printf("\r\n @Joe [TLI5012Init] [MOD3] write u16Data: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* Verify MOD3 register write operation */
	u16Command = RD_REG | WRITE_MOD3_VALUE;
	u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
	printf("\r\n @Joe [TLI5012Init] read MOD3: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* Optional: Configure MOD3 register with SSC_OD = 1 (commented out) */
	/*
	u16Command = 0x5091;
	u16Data |= 0x0004;  // Set SSC_OD bit
	u16Safe = cdd_TLI5012_WriteReg(u16Command, u16Data);
	printf("\r\n @Joe [TLI5012Init] [MOD3] write u16Data: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	*/
	
	/* ---------- Step 6: Configure MOD4 register ---------- */
	/* Read current MOD4 register value */
	u16Command = RD_REG | WRITE_MOD4_VALUE;
	u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
	printf("\r\n @Joe [TLI5012Init] read MOD4: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* Write MOD4 register with configuration value */
	u16Command = WRITE_MOD4_VALUE;
	u16Data = MOD4_VALUE;
	u16Safe = cdd_TLI5012_WriteReg(u16Command, u16Data);
	printf("\r\n @Joe [TLI5012Init] [MOD4] write u16Data: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);
	
	/* Verify MOD4 register write operation */
	u16Command = RD_REG | WRITE_MOD4_VALUE;
	u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
	printf("\r\n @Joe [TLI5012Init] read MOD4: 0x%04X, SafeWord: 0x%04X \r\n", u16Data, u16Safe);    
}

/**
 * @brief Write data to TLI5012B register
 * @param i_Cmd Command word to send
 * @param i_Data Data to write to register
 * @return Register response value, 0xFFFF if error
 * @note This function performs a complete SPI write transaction:
 */
uint16_t cdd_TLI5012_WriteReg(uint16_t i_Cmd, uint16_t i_Data)
{
    uint16_t result = 0xFFFF;          /* Default error code */
    SPI_CS_ENABLE();
    result = spi_rw_half_word(U1_SPI0_INST, i_Cmd);
    result = spi_rw_half_word(U1_SPI0_INST, i_Data);
    SPI_TX_OFF();  /* Configure MOSI as input to avoid conflicts */
    result = spi_rw_half_word(U1_SPI0_INST, DUMMY_BYTE);
    SPI_CS_DISABLE();
    SPI_TX_ON();  /* Restore MOSI as output */
    return result;
}

/**
 * @brief Read data from TLI5012B register
 * @param i_Cmd Command word to send
 * @param i_Data Not used in read operation (kept for compatibility)
 * @return Register data value, 0xFFFF if error
 * @note This function performs a complete SPI read transaction:
 */
uint16_t cdd_TLI5012_ReadReg(uint16_t i_Cmd, uint16_t * cosnt i_Data)
{
    uint16_t result = 0xFFFF;          /* Default error code */
    SPI_CS_ENABLE();
    *i_Data = spi_rw_half_word(U1_SPI0_INST, i_Cmd);
    SPI_TX_OFF();  /* Configure MOSI as input to avoid conflicts */
    *i_Data = spi_rw_half_word(U1_SPI0_INST, DUMMY_BYTE);    
    result = spi_rw_half_word(U1_SPI0_INST, DUMMY_BYTE);
    SPI_CS_DISABLE();
    SPI_TX_ON();  /* Restore MOSI as output */
    return result;
}

void Test_TLI5012B(void)
{
    uint16_t u16Command = 0xFFFF;
    uint16_t u16Data = 0x0000;
    uint16_t u16Safe = 0x0000;
    float angle = 0;  
    u16Command = READ_ANGLE_VALUE;
    u16Safe = cdd_TLI5012_ReadReg(u16Command, &u16Data);
    u16Data = u16Data & 0x7FFF;
    printf ( "\r\n @Joe AVAL = 0x%04X, SafeWord = 0x%04X \r\n", u16Data, u16Safe);
    //		angle = 360*( ((int16_t)(u16Data << 1)) >> 1)/32768;
    angle = ( 360*( ( (int16_t)(u16Data << 1) ) >> 1 ) ) >> 15;
    printf ( "\r\n @Joe angle = %f, AVAL = %d \r\n", angle, (((int16_t)(u16Data << 1)) >> 1));         
}

补充一些宏定义:

#define SPI_TX_OFF()                                                                                \
	do {                                                                                          \
		gpio_init(SPI0_MOSI_PORT, GPIO_MODE_IN_FLOATING, GPIO_OSPEED_50MHZ, SPI0_MOSI_PIN); \
	} while(0);
#define SPI_TX_ON()                                                                             \
	do {                                                                                      \
		gpio_init(SPI0_MOSI_PORT, SPI0_MOSI_FUNC, GPIO_OSPEED_50MHZ, SPI0_MOSI_PIN); \
	} while(0);

#define SPI_CS_ENABLE()	 gpio_bit_reset(U1_SPI0_NSS_PORT, U1_SPI0_NSS_PIN) 
#define SPI_CS_DISABLE() gpio_bit_set(U1_SPI0_NSS_PORT, U1_SPI0_NSS_PIN)  


/**
 * @brief SPI command definitions for TLI5012B sensor
 * @note All commands are 16-bit values following the TLI5012B protocol
 */

/* SPI operation types */
#define WRITE			  0 /**< SPI Write Operation */
#define READ			  1 /**< SPI Read Operation */

/* SPI communication constants */
#define DUMMY_BYTE		  0xFFFF /**< Dummy byte for SPI read operations */

#define WR_REG			  0x0000 /**< Write command - MSB is 0 */
#define RD_REG			  0x8000 /**< Read command - MSB is 1 */

#define LockValue_LADDR	  0x0000 /**< Lock value for addresses 0x00-0x04 */
#define LockValue_HADDR	  0x5000 /**< Lock value for addresses 0x05-0x11 */

/* Update buffer access command */
#define UPD_CMD			  0x0400 /**< Update command - bit 10 is 1, access update buffer */

/* Read command values */
#define READ_STAT_VALUE	  0x8001 /**< Read status register */
#define READ_ACSTAT_VALUE 0x8011 /**< Read activation status register */
#define READ_ANGLE_VALUE  0x8021 /**< Read angle value register */
#define READ_SPEED_VALUE  0x8031 /**< Read speed value register */

/* Write command values and their corresponding data */
#define WRITE_MOD1_VALUE  0x5061 /**< Write to MOD1 register (0_1010_0_000110_0001) */
#define MOD1_VALUE		  0x0001 /**< MOD1 register configuration value */

#define WRITE_MOD2_VALUE  0x5081 /**< Write to MOD2 register (0_1010_0_001000_0001) */
#define MOD2_VALUE		  0x0809 /**< MOD2 register configuration value */

#define WRITE_MOD3_VALUE  0x5091 /**< Write to MOD3 register (0_1010_0_001001_0001) */
#define MOD3_VALUE		  0x0000 /**< MOD3 register configuration value */

#define WRITE_MOD4_VALUE  0x50E1 /**< Write to MOD4 register (0_1010_0_001110_0001) */
#define MOD4_VALUE                                                               \
	0x0080 /**< MOD4 register value: 12-bit 4096, absolute count disable 0x0080; \
			enable 0x0000 */

#define WRITE_IFAB_VALUE 0x50B1 /**< Write to IFAB register */
#define IFAB_VALUE		 0x000D /**< IFAB register configuration value */

/**
 * @brief TLE5012 register address definitions
 * @note Register addresses are 4-bit values (0x00-0x11, 0x20)
 */
/* Status and data registers (0x00-0x04) */
#define STAT_ADDR		 0x00 /**< STATus register */
#define ACSTAT_ADDR		 0x01 /**< ACtivation STATus register */
#define AVAL_ADDR		 0x02 /**< Angle VALue register */
#define ASPD_ADDR		 0x03 /**< Angle SPeeD register */
#define AREV_ADDR		 0x04 /**< Angle REVolution register */

/* Configuration registers (0x05-0x0E) */
#define FSYNC_ADDR		 0x05 /**< Frame SYNChronization register */
#define MOD_1_ADDR		 0x06 /**< Interface MODe1 register */
#define SIL_ADDR		 0x07 /**< SIL register */
#define MOD_2_ADDR		 0x08 /**< Interface MODe2 register */
#define MOD_3_ADDR		 0x09 /**< Interface MODe3 register */
#define OFFX_ADDR		 0x0A /**< OFFset X register */
#define OFFY_ADDR		 0x0B /**< OFFset Y register */
#define SYNCH_ADDR		 0x0C /**< SYNCHronicity register */
#define IFAB_ADDR		 0x0D /**< IFAB register */
#define MOD_4_ADDR		 0x0E /**< Interface MODe4 register */

/* Additional registers (0x0F-0x11, 0x20) */
#define TCO_Y_ADDR		 0x0F /**< Temperature COefficient register */
#define ADC_X_ADDR		 0x10 /**< ADC X-raw value register */
#define ADC_Y_ADDR		 0x11 /**< ADC Y-raw value register */
#define IIF_CNT_ADDR	 0x20 /**< IIF CouNTer value register */

结束

测试结果如下所示: