Post Go back to editing

Help with AD74413R SPI Initialisation on STM32

Category: Software
Product Number: AD74412R
Software Version: https://github.com/analogdevicesinc/no-OS/blob/main/drivers/adc-dac/ad74413r/ad74413r.h

Hello everyone,

I’m working on bringing up an EV-AD74412R (quad‐channel software configurable I/O) with an STM32 MCU, and I’m seeing some odd behavior on the SPI MISO line. Hoping someone can spot what I’m missing or sense check my approach please!

Hardware setup:

STM32H7S7-DK - configured SPI channel 4 as a full duplex master.

I've powered the EV-AD74412RSDZ with 24V DC into the AVDD port and have checked with a multimeter that I have 3.3V at DVCC and IOVDD and also the 5V board probe point has the correct voltage. 

Wiring:

SPI SCLK → AD74413R SCLK pin
SPI MOSI → AD74413R SDI pin
SPI MISO ← AD74413R SDO pin
SPI Chip Select (GPIO) → AD74413R SYNC pin
RESET (GPIO) → AD74413R RESET pin

I'm going into the PMOD connector of the STM32 as this was the only available SPI channel:


pin 4 saying SPI5 is a mistake (I think) as within CubeMX it is correctly mapped as SPI4:


SPI Configuration on STM32: 
Clock polarity (CPOL): Low (rising edge first)

Clock phase (CPHA): 1Edge or 2Edge – tested both
Baud Rate Prescaler: 64 (so SCLK is not very fast)
8‐bit data size in the STM32 HAL
NSS: Software managed (GPIO toggling for SYNC pin)
First bit: MSB first


HAL SPI calls:
HAL_SPI_Transmit() for writes.
HAL_SPI_TransmitReceive() for reads.

When I run the ad74413r_init() the scratch test is failing every time as I just read back 0's when I'm expecting to get the test val back 0x1234. 

MOSI & SCLK look OK on the scope: 

CLK:

MOSI:

Chip select also seems to be toggling correctly:

However MISO  toggles but the amplitude is lower than I expect, or decoding as garbage:

The no_os example ported to STM32 environment: 

/*
 * ad74413r.c
 *
 *  Created on: Feb 21, 2025
 *      Author: chris.flello
 */


/***************************************************************************//**
 *   @file   ad74413r.c
 *   @brief  Source file of AD74413r Driver.
 *   @author Ciprian Regus (ciprian.regus@analog.com)
********************************************************************************
 * Copyright 2022(c) Analog Devices, Inc.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions are met:
 *
 * 1. Redistributions of source code must retain the above copyright notice,
 *    this list of conditions and the following disclaimer.
 *
 * 2. Redistributions in binary form must reproduce the above copyright notice,
 *    this list of conditions and the following disclaimer in the documentation
 *    and/or other materials provided with the distribution.
 *
 * 3. Neither the name of Analog Devices, Inc. nor the names of its
 *    contributors may be used to endorse or promote products derived from this
 *    software without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY ANALOG DEVICES, INC. “AS IS” AND ANY EXPRESS OR
 * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
 * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO
 * EVENT SHALL ANALOG DEVICES, INC. BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
 * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
 * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
 * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
 * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*******************************************************************************/

/******************************************************************************/
/***************************** Include Files **********************************/
/******************************************************************************/
#include "ad74413r.h"
#include "errno.h"
#include <stdint.h>

//#include "no_os_crc8.h"
//#include "no_os_delay.h"
//#include "no_os_error.h"
//#include "no_os_util.h"
//#include "no_os_alloc.h"

/******************************************************************************/
/********************** Macros and Constants Definitions **********************/
/******************************************************************************/
#define AD74413R_FRAME_SIZE 		4
#define AD74413R_CRC_POLYNOMIAL 	0x7
#define AD74413R_DIN_DEBOUNCE_LEN 32

/******************************************************************************/
/************************ Variable Declarations ******************************/
/******************************************************************************/
//Commented as now using STM32 CRC library
//NO_OS_DECLARE_CRC8_TABLE(_crc_table);

static const unsigned int ad74413r_debounce_map[AD74413R_DIN_DEBOUNCE_LEN] = {
	0,     13,    18,    24,    32,    42,    56,    75,
	100,   130,   180,   240,   320,   420,   560,   750,
	1000,  1300,  1800,  2400,  3200,  4200,  5600,  7500,
	10000, 13000, 18000, 24000, 32000, 42000, 56000, 75000,
};

/** The time required for an ADC conversion by rejection (us) */
static const uint32_t conv_times_ad74413r[] = { 50000, 208, 100000, 833 };
static const uint32_t conv_times_ad74412r[] = { 50000, 208};

/******************************************************************************/
/************************ Functions Definitions *******************************/
/******************************************************************************/
/******************************************************************************/

// Standard CRC-8 with poly=0x07, initial=0, no reflection, no final xor.
uint8_t ad74413r_crc8(const uint8_t *data, uint32_t len)
{
    uint8_t crc = 0x00; // start remainder
    const uint8_t poly = 0x07;

    while (len--) {
        crc ^= *data++;
        for (int i = 0; i < 8; i++) {
            if (crc & 0x80)
                crc = (uint8_t)((crc << 1) ^ poly);
            else
                crc <<= 1;
        }
    }
    return crc;
}


/**
 * @brief Set the rejection value based on the selected sample rate
 * @param rate - ADC sample rate
 * @param rejection - Rejection register value
 * @return 0 in case of success, -EINVAL otherwise
 */
static int ad74413r_rate_to_rejection(enum ad74413r_adc_sample rate,
				      enum ad74413r_rejection *rejection)
{
	switch (rate) {
	case AD74413R_ADC_SAMPLE_20HZ:
		*rejection = AD74413R_REJECTION_50_60;
		break;
	case AD74413R_ADC_SAMPLE_4800HZ:
		*rejection = AD74413R_REJECTION_NONE;
		break;
	case AD74413R_ADC_SAMPLE_10HZ:
		*rejection = AD74413R_REJECTION_50_60_HART;
		break;
	case AD74413R_ADC_SAMPLE_1200HZ:
		*rejection = AD74413R_REJECTION_HART;
		break;
	default:
		return -EINVAL;
	}

	return 0;
}

/**
 * @brief Set the sample rate based on the selected rejection value
 * @param rate - ADC sample rate
 * @param rejection - Rejection register value
 * @return 0 in case of success, -EINVAL otherwise
 */
static int ad74413r_rejection_to_rate(enum ad74413r_rejection rejection,
				      enum ad74413r_adc_sample *rate)
{
	switch (rejection) {
	case AD74413R_REJECTION_50_60:
		*rate = AD74413R_ADC_SAMPLE_20HZ;
		break;
	case AD74413R_REJECTION_NONE:
		*rate = AD74413R_ADC_SAMPLE_4800HZ;
		break;
	case AD74413R_REJECTION_50_60_HART:
		*rate = AD74413R_ADC_SAMPLE_10HZ;
		break;
	case AD74413R_REJECTION_HART:
		*rate = AD74413R_ADC_SAMPLE_1200HZ;
		break;
	default:
		return -EINVAL;
	}

	return 0;
}

/**
 * @brief Convert the measuring range of the ADC from range enum values to millivolts.
 * @param range - ADC sample rate
 * @param val - Rejection register value
 * @return 0 in case of success, -EINVAL otherwise
 */
int ad74413r_range_to_voltage_range(enum ad74413r_adc_range range,
				    uint32_t *val)
{
	switch (range) {
	case AD74413R_ADC_RANGE_10V:
		*val = 10000;
		break;
	case AD74413R_ADC_RANGE_2P5V_EXT_POW:
	case AD74413R_ADC_RANGE_2P5V_INT_POW:
		*val = 2500;
		break;
	case AD74413R_ADC_RANGE_5V_BI_DIR:
		*val = 5000;
		break;
	default:
		return -EINVAL;
	}

	return 0;
}

/**
 * @brief Convert the measuring range of the ADC from range enum values to millivolts.
 * @param range - ADC sample rate
 * @param val - Rejection register value
 * @return 0 in case of success, -EINVAL otherwise
 */
int ad74413r_range_to_voltage_offset(enum ad74413r_adc_range range,
				     int32_t *val)
{
	switch (range) {
	case AD74413R_ADC_RANGE_10V:
	case AD74413R_ADC_RANGE_2P5V_EXT_POW:
	case AD74413R_ADC_RANGE_2P5V_INT_POW:
		*val = 0;
		break;
	case AD74413R_ADC_RANGE_5V_BI_DIR:
		*val = (-(int)AD74413R_ADC_MAX_VALUE / 2);
		break;
	default:
		return -EINVAL;
	}

	return 0;
}

/**
 * @brief Converts a millivolt value in the corresponding DAC 13 bit code.
 * @param mvolts - The millivolts value.
 * @param code - The resulting DAC code.
 * @return 0 in case of success, -EINVAL otherwise
 */
int ad74413r_dac_voltage_to_code(uint32_t mvolts, uint32_t *code)
{
	if (mvolts > AD74413R_DAC_RANGE)
		return -EINVAL;

	*code = mvolts * NO_OS_BIT(AD74413R_DAC_RESOLUTION) / AD74413R_DAC_RANGE;

	return 0;
}

/**
 * @brief Load the address and value in a communication buffer using
 * the format that the device expects.
 * @param reg - Register address.
 * @param val - Register value.
 * @param buff - The communication buffer.
 */

static inline void put_unaligned_be16(uint16_t val, uint8_t *buf)
{
    buf[0] = (val >> 8) & 0xFF;  // High byte first
    buf[1] = val & 0xFF;         // Low byte
}

static void ad74413r_format_reg_write(uint8_t reg, uint16_t val, uint8_t *buff)
{
    buff[0] = reg;
    put_unaligned_be16(val, &buff[1]);  // Use our new function to store val

    // Compute CRC-8 using STM32 HAL CRC
    uint8_t crc = ad74413r_crc8(buff, 3);
    buff[3] = (uint8_t)crc;
}
/**
 * @brief Read a raw communication frame
 * @param desc - The device structure.
 * @param addr - The register's address.
 * @param val - A raw comm frame.
 * @return 0 in case of success, negative error otherwise.
 */
int ad74413r_reg_read_raw(struct ad74413r_desc *desc, uint32_t addr, uint8_t *val)
{
    HAL_StatusTypeDef status;

    // STEP 1: Write the ADDR into the READ_SELECT register (4-byte frame: cmd + 2 data bytes + CRC).
    //         That tells the AD74412R/13R which register we want to read next.
    ad74413r_format_reg_write(AD74413R_READ_SELECT, addr, desc->comm_buff);

    // Pull CS low, transmit 4 bytes, then CS high
    HAL_GPIO_WritePin(desc->cs_gpio_port, desc->cs_gpio_pin, GPIO_PIN_RESET);
    status = HAL_SPI_Transmit(desc->hspi, desc->comm_buff, AD74413R_FRAME_SIZE, HAL_MAX_DELAY);
    HAL_GPIO_WritePin(desc->cs_gpio_port, desc->cs_gpio_pin, GPIO_PIN_SET);

    if (status != HAL_OK)
        return -EIO;  // I/O error

    // STEP 2: Send a “NOP” frame while simultaneously reading back the register content from MISO.
    //         The device drives MISO with the actual data only while you clock out these bytes on MOSI.
    uint8_t tx_buff[AD74413R_FRAME_SIZE];
    uint8_t rx_buff[AD74413R_FRAME_SIZE];

    // Format a NOP write (AD74413R_NOP, 0x0000), plus CRC
    ad74413r_format_reg_write(AD74413R_NOP, AD74413R_NOP, tx_buff);

    // Pull CS low, do Transmit+Receive of 4 bytes, then CS high
    HAL_GPIO_WritePin(desc->cs_gpio_port, desc->cs_gpio_pin, GPIO_PIN_RESET);
    status = HAL_SPI_TransmitReceive(desc->hspi, tx_buff, rx_buff, AD74413R_FRAME_SIZE, HAL_MAX_DELAY);
    HAL_GPIO_WritePin(desc->cs_gpio_port, desc->cs_gpio_pin, GPIO_PIN_SET);

    if (status != HAL_OK)
        return -EIO;

    // Return the 4 received bytes to the caller (comm_buff[0..3])
    val[0] = rx_buff[0];  // echo of command or readback info
    val[1] = rx_buff[1];  // high byte of data
    val[2] = rx_buff[2];  // low byte of data
    val[3] = rx_buff[3];  // device-generated CRC
    return 0;
}


/**
 * @brief Write a register's value
 * @param desc  - The device structure.
 * @param addr - The register's address.
 * @param val - The register's value.
 * @return 0 in case of success, negative error otherwise
 */
int ad74413r_reg_write(struct ad74413r_desc *desc, uint32_t addr, uint16_t val)
{
	// Format data into SPI buffer
	ad74413r_format_reg_write(addr, val, desc->comm_buff);

	// Transmit data via SPI
	int ret = HAL_SPI_Transmit(desc->hspi, desc->comm_buff, AD74413R_FRAME_SIZE, HAL_MAX_DELAY);
	if (ret != HAL_OK)
		return -EIO;

	return 0;
}

/**
 * @brief Read a register's value
 * @param desc  - The device structure.
 * @param addr - The register's address.
 * @param val - The register's read value.
 * @return 0 in case of success, negative error otherwise
 */
int ad74413r_reg_read(struct ad74413r_desc *desc, uint32_t addr, uint16_t *val)
{
	int ret;
	uint8_t expected_crc;

	// Read raw register value
	ret = ad74413r_reg_read_raw(desc, addr, desc->comm_buff);
	if (ret)
		return ret;

	// Compute CRC-8 using software function
	expected_crc = ad74413r_crc8(desc->comm_buff, 3);

	// Compare computed CRC with received CRC byte
	if (expected_crc != desc->comm_buff[3])
		return -EINVAL;

	// Extract 16-bit value from the buffer (Big-Endian format)
	*val = (desc->comm_buff[1] << 8) | desc->comm_buff[2];  // Replacing no_os_get_unaligned_be16()

	return 0;
}

/**
 * @brief Update a register's field.
 * @param desc  - The device structure.
 * @param addr - The register's address.
 * @param val - The register's value.
 * @param mask - The mask for a specific register field.
 * @return 0 in case of success, negative error otherwise.
 */
int ad74413r_reg_update(struct ad74413r_desc *desc, uint32_t addr,
			uint16_t mask,
			uint16_t val)
{
	int ret;
	uint16_t c_val;

	ret = ad74413r_reg_read(desc, addr, &c_val);
	if (ret)
		return ret;

	c_val &= ~mask;
	c_val |= no_os_field_prep(mask, val);

	return ad74413r_reg_write(desc, addr, c_val);
}

/**
 * @brief Get the number of active channels.
 * @param desc - The device structure.
 * @param nb_channels - The number of active channels
 * @return 0 in case of success, negative error otherwise.
 */
int ad74413r_nb_active_channels(struct ad74413r_desc *desc,
				uint8_t *nb_channels)
{
	int ret;
	uint16_t reg_val;

	ret = ad74413r_reg_read(desc, AD74413R_ADC_CONV_CTRL, &reg_val);
	if (ret)
		return ret;

	reg_val = no_os_field_get(NO_OS_GENMASK(7, 0), reg_val);
	*nb_channels = no_os_hweight8((uint8_t)reg_val);

	return 0;
}

/**
 * @brief Clear the ALERT_STATUS register.
 * @param desc - The device structure.
 * @return 0 in case of success, negative error otherwise.
 */
int ad74413r_clear_errors(struct ad74413r_desc *desc)
{
	return ad74413r_reg_write(desc, AD74413R_ALERT_STATUS, AD74413R_ERR_CLR_MASK);
}

/**
 * @brief Select which information the device will respond with (in the readback field)
 * when a read operation is performed.
 * @param desc - The device structure.
 * @param mode - Possible values:
 * 			0 - Respond with the readback address.
 * 			1 - Respond with status bits.
 * @return 0 in case of success, negative error otherwise.
 */
int ad74413r_set_info(struct ad74413r_desc *desc, uint16_t mode)
{
	return ad74413r_reg_update(desc, AD74413R_READ_SELECT,
				   AD74413R_SPI_RD_RET_INFO_MASK, mode);
}

/**
 * @brief Comm test function
 * @param desc - The device structure.
 * @return 0 in case of success, negative error code otherwise.
 */
static int ad74413r_scratch_test(struct ad74413r_desc *desc)
{
	int ret;
	uint16_t val;
	uint16_t test_val = 0x1234;

	ret = ad74413r_reg_write(desc, AD74413R_SCRATCH, test_val);
	if (ret)
		return ret;

	ret = ad74413r_reg_read(desc, AD74413R_SCRATCH, &val);
	if (ret)
		return ret;

	if (val != test_val)
		return -EINVAL;

	return 0;
}

/**
 * @brief Perform either a software or hardware reset and wait for device reset time.
 * @param desc - The device structure.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_reset(struct ad74413r_desc *desc)
{
	if (desc->reset_gpio_port) {
		// Set reset pin low
		HAL_GPIO_WritePin(desc->reset_gpio_port, desc->reset_gpio_pin, GPIO_PIN_RESET);

		// Minimum RESET signal pulse duration (50 µs)
		HAL_Delay(1);  // Use DWT_Delay(50) if microsecond precision needed

		// Set reset pin high
		HAL_GPIO_WritePin(desc->reset_gpio_port, desc->reset_gpio_pin, GPIO_PIN_SET);
	} else {
		// Perform software reset using register writes
		int ret = ad74413r_reg_write(desc, AD74413R_CMD_KEY, AD74413R_CMD_KEY_RESET_1);
		if (ret)
			return ret;

		ret = ad74413r_reg_write(desc, AD74413R_CMD_KEY, AD74413R_CMD_KEY_RESET_2);
		if (ret)
			return ret;
	}

	// Device reset time (datasheet value = 1ms)
	HAL_Delay(1);

	return 0;
}

/**
 * @brief Set the operation mode for a specific channel
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param ch_func - The operation mode.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_channel_function(struct ad74413r_desc *desc,
				  uint32_t ch, enum ad74413r_op_mode ch_func)
{
	int ret;

	ret = ad74413r_set_channel_dac_code(desc, ch, 0);
	if (ret)
		return ret;

	ret = ad74413r_reg_update(desc, AD74413R_CH_FUNC_SETUP(ch),
				  AD74413R_CH_FUNC_SETUP_MASK, AD74413R_HIGH_Z);
	if (ret)
		return ret;

	/* Each function should be selected for at least 130 us. */
	no_os_udelay(130);
	ret = ad74413r_reg_update(desc, AD74413R_CH_FUNC_SETUP(ch),
				  AD74413R_CH_FUNC_SETUP_MASK, ch_func);
	if (ret)
		return ret;

	ret = ad74413r_reg_update(desc, AD74413R_ADC_CONFIG(ch),
				  AD74413R_CH_200K_TO_GND_MASK, 1);
	if (ret)
		return ret;

	/* No writes to the DACx registers may be done for 150 us after changing function */
	no_os_udelay(150);

	desc->channel_configs[ch].function = ch_func;

	return 0;
}

/**
 * @brief Read the raw ADC raw conversion value.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param val - The ADC raw conversion value.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_get_raw_adc_result(struct ad74413r_desc *desc, uint32_t ch,
				uint16_t *val)
{
	return ad74413r_reg_read(desc, AD74413R_ADC_RESULT(ch), val);
}

/**
 * @brief Enable/disable a specific ADC channel
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param status - Enabled or disabled status.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_adc_channel_enable(struct ad74413r_desc *desc, uint32_t ch,
				    bool status)
{
	int ret;

	ret = ad74413r_reg_update(desc, AD74413R_ADC_CONV_CTRL,
				  AD74413R_CH_EN_MASK(ch), status);
	if (ret)
		return ret;

	desc->channel_configs[ch].enabled = status;

	return 0;
}

/**
 * @brief Enable conversions on a diagnostic register
 * @param desc - The device structure.
 * @param ch - Diagnostic channel index.
 * @param status - Enabled or disabled status.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_diag_channel_enable(struct ad74413r_desc *desc, uint32_t ch,
				     bool status)
{
	return ad74413r_reg_update(desc, AD74413R_ADC_CONV_CTRL,
				   AD74413R_DIAG_EN_MASK(ch), status);
}

/**
 * @brief Get the ADC measurement range for a specific channel
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param val - The ADC range value.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_get_adc_range(struct ad74413r_desc *desc, uint32_t ch,
			   uint16_t *val)
{
	int ret;

	ret = ad74413r_reg_read(desc, AD74413R_ADC_CONFIG(ch), val);
	if (ret)
		return ret;

	*val = no_os_field_get(AD74413R_ADC_RANGE_MASK, *val);

	return 0;
}

/**
 * @brief Get the rejection setting for a specific channel.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param val - The ADC rejection setting.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_get_adc_rejection(struct ad74413r_desc *desc, uint32_t ch,
			       enum ad74413r_rejection *val)
{
	int ret;
	uint16_t rejection_val;

	ret = ad74413r_reg_read(desc, AD74413R_ADC_CONFIG(ch), &rejection_val);
	if (ret)
		return ret;

	*val = no_os_field_get(AD74413R_ADC_REJECTION_MASK, rejection_val);

	return 0;
}

/**
 * @brief Get the rejection setting for a specific channel.
 * @param desc - The device structure.
 * @param val - The ADC rejection setting.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_get_adc_diag_rejection(struct ad74413r_desc *desc,
				    enum ad74413r_rejection *val)
{
	int ret;
	uint16_t reg_val;

	ret = ad74413r_reg_read(desc, AD74413R_ADC_CONV_CTRL, &reg_val);
	if (ret)
		return ret;

	reg_val = no_os_field_get(AD74413R_EN_REJ_DIAG_MASK, reg_val);
	if (reg_val)
		*val = AD74413R_REJECTION_50_60;
	else
		*val = AD74413R_REJECTION_NONE;

	return 0;
}

/**
 * @brief Set the rejection setting for a specific channel.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param val - The ADC rejection setting.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_adc_rejection(struct ad74413r_desc *desc, uint32_t ch,
			       enum ad74413r_rejection val)
{
	return ad74413r_reg_update(desc, AD74413R_ADC_CONFIG(ch),
				   AD74413R_ADC_REJECTION_MASK, val);
}

/**
 * @brief Get the ADC sample rate.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param val - The ADC sample rate value.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_get_adc_rate(struct ad74413r_desc *desc, uint32_t ch,
			  enum ad74413r_adc_sample *val)
{
	int ret;
	enum ad74413r_rejection rejection;

	ret = ad74413r_get_adc_rejection(desc, ch, &rejection);
	if (ret)
		return ret;

	return ad74413r_rejection_to_rate(rejection, val);
}

/**
 * @brief Set the ADC sample rate.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param val - The ADC sample rate value.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_adc_rate(struct ad74413r_desc *desc, uint32_t ch,
			  enum ad74413r_adc_sample val)
{
	int ret;
	enum ad74413r_rejection rejection;

	ret = ad74413r_rate_to_rejection(val, &rejection);
	if (ret)
		return ret;

	return ad74413r_set_adc_rejection(desc, ch, rejection);
}

/**
 * @brief Get the ADC sample rate for the diagnostics channels.
 * @param desc - The device structure.
 * @param ch - The diagnostics channel index.
 * @param val - The ADC sample rate value.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_get_adc_diag_rate(struct ad74413r_desc *desc, uint32_t ch,
			       enum ad74413r_adc_sample *val)
{
	enum ad74413r_rejection rejection;
	int ret;

	ret = ad74413r_get_adc_diag_rejection(desc, &rejection);
	if (ret)
		return ret;

	return ad74413r_rejection_to_rate(rejection, val);
}

/**
 * @brief Set the ADC sample rate for the diagnostics channels.
 * @param desc - The device structure.
 * @param ch - The diagnostics channel index.
 * @param val - The ADC sample rate value.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_adc_diag_rate(struct ad74413r_desc *desc, uint32_t ch,
			       enum ad74413r_adc_sample val)
{
	uint16_t reg_val;

	switch (val) {
	case AD74413R_ADC_SAMPLE_20HZ:
		reg_val = 1;
		break;
	case AD74413R_ADC_SAMPLE_4800HZ:
		reg_val = 0;
		break;
	default:
		return -EINVAL;
	}

	return ad74413r_reg_update(desc, AD74413R_ADC_CONV_CTRL,
				   AD74413R_EN_REJ_DIAG_MASK, reg_val);
}

/**
 * @brief Start or stop ADC conversions.
 * @param desc - The device structure.
 * @param status - The ADC conversion sequence.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_adc_conv_seq(struct ad74413r_desc *desc,
			      enum ad74413r_conv_seq status)
{
	int ret;

	ret = ad74413r_reg_update(desc, AD74413R_ADC_CONV_CTRL,
				  AD74413R_CONV_SEQ_MASK, status);
	if (ret)
		return ret;
	/**
	 * The write to CONV_SEQ powers up the ADC. If the ADC was powered down, the user must wait
	 * for 100us before the ADC starts doing conversions.
	 */
	no_os_udelay(100);

	return 0;
}

/**
 * @brief Get a single ADC raw value for a specific channel, then power down the ADC.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param val - The ADC raw result.
 * @param is_diag - Select which channel type does the index refer to (I/O or diagnostics).
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_get_adc_single(struct ad74413r_desc *desc, uint32_t ch,
			    uint16_t *val, bool is_diag)
{
	int ret;
	uint32_t delay;
	uint8_t nb_active_channels;
	enum ad74413r_rejection rejection;

	if (is_diag)
		ret = ad74413r_set_diag_channel_enable(desc, ch, true);
	else
		ret = ad74413r_set_adc_channel_enable(desc, ch, true);
	if (ret)
		return ret;

	ret = ad74413r_nb_active_channels(desc, &nb_active_channels);
	if (ret)
		return ret;

	ret = ad74413r_set_adc_conv_seq(desc, AD74413R_START_SINGLE);
	if (ret)
		return ret;

	if (is_diag)
		ret = ad74413r_get_adc_diag_rejection(desc, &rejection);
	else
		ret = ad74413r_get_adc_rejection(desc, ch, &rejection);
	if (ret)
		return ret;

	if (desc->chip_id == AD74413R)
		delay = conv_times_ad74413r[rejection];
	else
		delay = conv_times_ad74412r[rejection];

	/** Wait for all channels to complete the conversion. */
	if (delay < 1000)
		no_os_udelay(delay * nb_active_channels);
	else
		no_os_mdelay((delay * nb_active_channels) / 1000);

	if (is_diag)
		ret = ad74413r_get_diag(desc, ch, val);
	else
		ret = ad74413r_get_raw_adc_result(desc, ch, val);
	if (ret)
		return ret;

	ret = ad74413r_set_adc_conv_seq(desc, AD74413R_STOP_PWR_DOWN);
	if (ret)
		return ret;

	if (is_diag)
		return ad74413r_set_diag_channel_enable(desc, ch, false);

	return ad74413r_set_adc_channel_enable(desc, ch, false);
}

/**
 * @brief Get the ADC real value, according to the operation mode.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param val - The ADC real measurement value (the unit depends on
 * the operation mode).
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_adc_get_value(struct ad74413r_desc *desc, uint32_t ch,
			   struct ad74413r_decimal *val)
{
	int ret;
	uint16_t adc_code;

	ret = ad74413r_get_adc_single(desc, ch, &adc_code, false);
	if (ret)
		return ret;

	switch (desc->channel_configs[ch].function) {
	case AD74413R_HIGH_Z:
		val->integer = no_os_div_u64_rem(adc_code * AD74413R_RANGE_10V_SCALE,
						 AD74413R_RANGE_10V_SCALE_DIV,
						 (uint32_t *)&val->decimal);
		break;
	case AD74413R_VOLTAGE_OUT:
		/**
		 * I_Rsense = (Vmin + (ADC_CODE/65535) * range) / Rsense
		 */
		val->integer = no_os_div_s64_rem((adc_code + AD74413R_RANGE_5V_OFFSET) *
						 AD74413R_RANGE_5V_SCALE,
						 AD74413R_RSENSE * AD74413R_RANGE_5V_SCALE_DIV,
						 &val->decimal);
		break;
	case AD74413R_CURRENT_OUT:
	case AD74413R_VOLTAGE_IN:
		val->integer = no_os_div_u64_rem(adc_code * AD74413R_RANGE_10V_SCALE,
						 AD74413R_RANGE_10V_SCALE_DIV,
						 (uint32_t *)&val->decimal);
		break;
	case AD74413R_CURRENT_IN_EXT_HART:
		if (desc->chip_id == AD74412R)
			return -ENOTSUP;
	/* fallthrough */
	case AD74413R_CURRENT_IN_LOOP_HART:
		if (desc->chip_id == AD74412R)
			return -ENOTSUP;
	/* fallthrough */
	case AD74413R_CURRENT_IN_EXT:
	case AD74413R_CURRENT_IN_LOOP:
		val->integer = no_os_div_u64_rem(adc_code * AD74413R_RANGE_2V5_SCALE,
						 AD74413R_RANGE_2V5_SCALE_DIV * AD74413R_RSENSE,
						 (uint32_t *)&val->decimal);
		break;
	case AD74413R_RESISTANCE:
		val->integer = no_os_div_u64_rem(adc_code * AD74413R_RTD_PULL_UP,
						 AD74413R_ADC_MAX_VALUE - adc_code,
						 (uint32_t *)&val->decimal);
		break;
	case AD74413R_DIGITAL_INPUT:
	case AD74413R_DIGITAL_INPUT_LOOP:
		val->integer = no_os_div_u64_rem(adc_code * AD74413R_RANGE_10V_SCALE,
						 AD74413R_RANGE_10V_SCALE_DIV,
						 (uint32_t *)&val->decimal);
		break;
	default:
		return -EINVAL;
	}

	return 0;
}

/**
 * @brief Read the die's temperature from the diagnostic register.
 * @param desc - The device structure.
 * @param ch - The diagnostic channel on which the temperature reading
 * is assigned and enabled.
 * @param temp - The measured temperature (in degrees Celsius).
 * @return 0 in case of success, -EINVAL otherwise.
 */
int ad74413r_get_temp(struct ad74413r_desc *desc, uint32_t ch, uint16_t *temp)
{
	int ret;

	ret = ad74413r_get_diag(desc, ch, temp);
	if (ret)
		return ret;

	*temp = (*temp + AD74413R_TEMP_OFFSET) * AD74413R_TEMP_SCALE_DIV /
		AD74413R_TEMP_SCALE;

	return 0;
}

/**
 * @brief Set and load a code for the DAC on a specific channel.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param dac_code - The code for the DAC.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_channel_dac_code(struct ad74413r_desc *desc, uint32_t ch,
				  uint16_t dac_code)
{
	int ret;

	ret = ad74413r_reg_write(desc, AD74413R_DAC_CODE(ch), dac_code);
	if (ret)
		return ret;

	return ad74413r_reg_write(desc, AD74413R_CMD_KEY, AD74413R_CMD_KEY_LDAC);
}

/**
 * @brief Set which diagnostic value to be loaded in the DIAG_RESULT register
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param diag_code - The diagnostic setting.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_diag(struct ad74413r_desc *desc, uint32_t ch,
		      enum ad74413r_diag_mode diag_code)
{
	return ad74413r_reg_update(desc, AD74413R_DIAG_ASSIGN,
				   AD74413R_DIAG_ASSIGN_MASK(ch), diag_code);
}

/**
 * @brief Get the diagnostic value for a specific channel.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param diag_code - The diagnostic setting.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_get_diag(struct ad74413r_desc *desc, uint32_t ch,
		      uint16_t *diag_code)
{
	int ret;

	ret = ad74413r_reg_read(desc, AD74413R_DIAG_RESULT(ch), diag_code);
	if (ret)
		return ret;

	*diag_code = no_os_field_get(AD74413R_DIAG_RESULT_MASK, *diag_code);

	return ret;
}

/**
 * @brief Set the debounce mode for the IOx inputs when the ADC is running in digital
 * input mode.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param mode - The debounce mode.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_debounce_mode(struct ad74413r_desc *desc, uint32_t ch,
			       enum ad74413r_debounce_mode mode)
{
	return ad74413r_reg_update(desc, AD74413R_DIN_CONFIG(ch),
				   AD74413R_DEBOUNCE_MODE_MASK, mode);
}

/**
 * @brief Set the debounce settle time for the IOx inputs when the ADC is
 * running in digital input mode.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param time - The debounce time.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_debounce_time(struct ad74413r_desc *desc, uint32_t ch,
			       uint32_t time)
{
	uint32_t val = AD74413R_DIN_DEBOUNCE_LEN - 1;

	for (uint32_t i = 0; i < AD74413R_DIN_DEBOUNCE_LEN; i++)
		if (time <= ad74413r_debounce_map[i]) {
			val = i;
			break;
		}

	return ad74413r_reg_update(desc, AD74413R_DIN_CONFIG(ch),
				   AD74413R_DEBOUNCE_TIME_MASK, val);
}

/**
 * @brief Get the GPO value for a specific channel.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param val - The debounce time.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_gpo_get(struct ad74413r_desc *desc, uint32_t ch, uint8_t *val)
{
	int ret;
	uint16_t reg;

	ret = ad74413r_reg_read(desc, AD74413R_DIN_COMP_OUT, &reg);
	if (ret)
		return ret;

	*val = no_os_field_get(NO_OS_BIT(ch), reg);

	return 0;
}

/**
 * @brief Set the GPO operation mode.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param config - The configuration setting.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_gpo_config(struct ad74413r_desc *desc, uint32_t ch,
			    enum ad74413r_gpo_select config)
{
	return ad74413r_reg_update(desc, AD74413R_GPO_CONFIG(ch),
				   AD74413R_GPO_SELECT_MASK, config);
}

/**
 * @brief Set the threshold, for which a signal would be considered high,
 * when the ADC is running in digital input mode.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param threshold - The threshold value (in millivolts). The actual threshold
 * set might not match this value (~500mV max. error), since it's fairly
 * low resolution (29 possible values).
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_threshold(struct ad74413r_desc *desc, uint32_t ch,
			   uint32_t threshold)
{
	int ret;
	uint32_t dac_threshold;

	if (threshold > AD74413R_THRESHOLD_RANGE)
		return -EINVAL;

	/** Set a fixed range (0 - 16 V) for the threshold, so it would not depend on Vadd. */
	ret = ad74413r_reg_update(desc, AD74413R_DIN_THRESH,
				  AD74413R_DIN_THRESH_MODE_MASK, 1);
	if (ret)
		return ret;

	dac_threshold = AD74413R_THRESHOLD_DAC_RANGE * threshold /
			AD74413R_THRESHOLD_RANGE;

	return ad74413r_reg_update(desc, AD74413R_DIN_THRESH,
				   AD74413R_COMP_THRESH_MASK, dac_threshold);
}

/**
 * @brief Set the logic value of a GPO pin
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param val - The output logic state.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_gpo_set(struct ad74413r_desc *desc, uint32_t ch, uint8_t val)
{
	int ret;

	ret = ad74413r_set_gpo_config(desc, ch, AD74413R_GPO_CONFIG_DATA);
	if (ret)
		return ret;

	return ad74413r_reg_update(desc, AD74413R_GPO_CONFIG(ch),
				   AD74413R_GPO_DATA_MASK, val);
}

/**
 * @brief Set multiple GPO values at once.
 * @param desc - The device structure.
 * @param mask - Active channels mask.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_gpo_set_multiple(struct ad74413r_desc *desc, uint32_t mask)
{
	int ret;
	uint32_t bit;

	ret = ad74413r_reg_write(desc, AD74413R_GPO_PARALLEL, mask);
	if (ret)
		return ret;

	while (mask) {
		bit = no_os_find_first_set_bit(mask);

		ret = ad74413r_set_gpo_config(desc, bit, AD74413R_GPO_CONFIG_PAR_DATA);
		if (ret)
			return ret;

		mask >>= bit + 1;
	}

	return 0;
}

/**
 * @brief Read the live status bits.
 * @param desc - The device structure.
 * @param status - The register's value.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_get_live(struct ad74413r_desc *desc,
		      union ad74413r_live_status *status)
{
	return ad74413r_reg_read(desc, AD74413R_LIVE_STATUS, &status->value);
}

/**
 * @brief The code value will be loaded into the DACs when the CLR_EN bit in the
 * OUTPUT_CONFIGx registers is asserted and the DAC clear key is written
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param code - The DAC code to be loaded
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_dac_clear_code(struct ad74413r_desc *desc, uint32_t ch,
				uint16_t code)
{
	return ad74413r_reg_write(desc, AD74413R_DAC_CLR_CODE(ch), code);
}

/**
 * @brief Clear the DAC (to the code in DAC_CLR_CODE register)
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_clear_dac(struct ad74413r_desc *desc, uint32_t ch)
{
	int ret;

	ret = ad74413r_reg_update(desc, AD74413R_OUTPUT_CONFIG(ch),
				  AD74413R_CLR_EN_MASK, 1);
	if (ret)
		return ret;

	ret = ad74413r_reg_write(desc, AD74413R_CMD_KEY, AD74413R_CMD_KEY_DAC_CLEAR);
	if (ret)
		return ret;

	return ad74413r_reg_update(desc, AD74413R_OUTPUT_CONFIG(ch),
				   AD74413R_CLR_EN_MASK, 0);
}

/**
 * @brief Configure and enable slew rate control for a DAC on a specific channel
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @param step - Number of codes per increment.
 * @param rate - Number of increments per second.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_dac_slew_enable(struct ad74413r_desc *desc, uint32_t ch,
			     enum ad74413r_slew_lin_step step,
			     enum ad74413r_lin_rate rate)
{
	int ret;

	ret = ad74413r_reg_update(desc, AD74413R_OUTPUT_CONFIG(ch),
				  AD74413R_SLEW_LIN_STEP_MASK, step);
	if (ret)
		return ret;

	ret = ad74413r_reg_update(desc, AD74413R_OUTPUT_CONFIG(ch),
				  AD74413R_SLEW_LIN_RATE_MASK, rate);
	if (ret)
		return ret;

	return ad74413r_reg_update(desc, AD74413R_OUTPUT_CONFIG(ch),
				   AD74413R_SLEW_EN_MASK, 1);
}

/**
 * @brief Disable the slew rate control.
 * @param desc - The device structure.
 * @param ch - The channel index.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_dac_slew_disable(struct ad74413r_desc *desc, uint32_t ch)
{
	return ad74413r_reg_update(desc, AD74413R_OUTPUT_CONFIG(ch),
				   AD74413R_SLEW_EN_MASK, 0);
}

/**
 * @brief Enable or disable the higher thermal reset.
 * @param desc - The device structure.
 * @param enable - The thermal reset status.
 * 			false: reset at 110 deg. Celsius.
 * 			true: reset at 140 deg. Celsius.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_set_therm_rst(struct ad74413r_desc *desc, bool enable)
{
	return ad74413r_reg_write(desc, AD74413R_THERM_RST, enable);
}

/**
 * @brief Initialize the device structure.
 * @param desc - The device structure to be initialized.
 * @param init_param - Initialization parameter for the device descriptor.
 * @return 0 in case of success, negative error code otherwise.
 */
int ad74413r_init(struct ad74413r_desc **desc, struct ad74413r_init_param *init_param)
{
	int ret;
	struct ad74413r_desc *descriptor;

	if (!init_param)
		return -EINVAL;

	// Allocate memory for descriptor
	descriptor = calloc(1, sizeof(*descriptor));
	if (!descriptor)
		return -ENOMEM;

	// Assign SPI handle from init_param
	descriptor->hspi = init_param->hspi;

	// Assign GPIO reset pin
	descriptor->reset_gpio_port = init_param->reset_gpio_port;
	descriptor->reset_gpio_pin = init_param->reset_gpio_pin;

    //Copy CS pin as well
    descriptor->cs_gpio_port = init_param->cs_gpio_port;
    descriptor->cs_gpio_pin  = init_param->cs_gpio_pin;

	// Perform hardware reset
	ret = ad74413r_reset(descriptor);
	if (ret)
		goto free_descriptor;

	// Clear any existing errors
	ret = ad74413r_clear_errors(descriptor);
	if (ret)
		goto free_descriptor;
	// Run scratch test
	ret = ad74413r_scratch_test(descriptor);
	if (ret)
		goto free_descriptor;

	// Assign chip ID
	descriptor->chip_id = init_param->chip_id;

	// Return descriptor
	*desc = descriptor;

	return 0;

free_descriptor:
	free(descriptor);
	return ret;
}
/**
 * @brief Free the device descriptor.
 * @param desc - The device structure.
 * @return 0 in case of success, -EINVAL otherwise.
 */
int ad74413r_remove(struct ad74413r_desc *desc)
{
	if (!desc)
		return -EINVAL;

	/* Perform a reset to bring the device into the default state */
	ad74413r_reset(desc);

	/* No need to remove GPIOs explicitly, STM32 HAL does not require it */
	if (desc->reset_gpio_port) {
		HAL_GPIO_WritePin(desc->reset_gpio_port, desc->reset_gpio_pin, GPIO_PIN_RESET);
	}

	/* Deinitialize SPI (if needed) */
	if (desc->hspi) {
		HAL_SPI_DeInit(desc->hspi);
	}

	/* Free memory */
	free(desc);

	return 0;
}

my main.c with SPI config:

/* USER CODE BEGIN Header */
/**
  ******************************************************************************
  * @file           : main.c
  * @brief          : Main program body
  ******************************************************************************
  * @attention
  *
  * Copyright (c) 2025 STMicroelectronics.
  * All rights reserved.
  *
  * This software is licensed under terms that can be found in the LICENSE file
  * in the root directory of this software component.
  * If no LICENSE file comes with this software, it is provided AS-IS.
  *
  ******************************************************************************
  */
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"

/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */

#include "stdio.h"
#include "stm32h7rsxx_hal.h"
#include "ad74413r.h"

/* USER CODE END Includes */

/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */

/* USER CODE END PTD */

/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */

#define AD74413R_SILICON_REV  0x46
#define AD74413R_NOP          0x00

/* USER CODE END PD */

/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */

/* USER CODE END PM */

/* Private variables ---------------------------------------------------------*/

SPI_HandleTypeDef hspi4;

/* USER CODE BEGIN PV */

/* USER CODE END PV */

/* Private function prototypes -----------------------------------------------*/
static void MX_GPIO_Init(void);
static void MX_FLASH_Init(void);
static void MX_SPI4_Init(void);
/* USER CODE BEGIN PFP */

/* USER CODE END PFP */

/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */

/* USER CODE END 0 */

/**
  * @brief  The application entry point.
  * @retval int
  */
int main(void)
{

  /* USER CODE BEGIN 1 */

  /* USER CODE END 1 */

  /* MCU Configuration--------------------------------------------------------*/

  /* Update SystemCoreClock variable according to RCC registers values. */
  SystemCoreClockUpdate();

  /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
  HAL_Init();

  /* USER CODE BEGIN Init */

  /* USER CODE END Init */

  /* USER CODE BEGIN SysInit */

  /* USER CODE END SysInit */

  /* Initialize all configured peripherals */
  MX_GPIO_Init();
  MX_FLASH_Init();
  MX_SPI4_Init();
  /* USER CODE BEGIN 2 */

//    while(1) {
//
//  		HAL_GPIO_WritePin(GPIOF, GPIO_PIN_3, GPIO_PIN_RESET);
//
//  		// Minimum RESET signal pulse duration (50 µs)
//  		HAL_Delay(100);
//
//  		// Set reset pin high
//  		HAL_GPIO_WritePin(GPIOF, GPIO_PIN_3, GPIO_PIN_SET);
//
//  		HAL_GPIO_WritePin(GPIOE, GPIO_PIN_10, GPIO_PIN_RESET);
//
//  		// Minimum RESET signal pulse duration (50 µs)
//  		HAL_Delay(100);
//
//  		// Set reset pin high
//  		HAL_GPIO_WritePin(GPIOE, GPIO_PIN_10, GPIO_PIN_SET);
//    }


    // Initialise AD74413R driver
        struct ad74413r_desc *ad744x;
        struct ad74413r_init_param p = {
          .chip_id = AD74412R,
          .hspi    = &hspi4,
  	    .reset_gpio_port = GPIOF,
  	    .reset_gpio_pin  = GPIO_PIN_3,

  		.cs_gpio_port = GPIOE,
  		.cs_gpio_pin  = GPIO_PIN_10
        };

     while(1){
        int ret = ad74413r_init(&ad744x, &p);
        if (ret) {
          printf("AD744x init failed: %d\n", ret);
        } else {
          printf("AD744x init OK\n");
        }
     }
        // Now try reading the silicon revision:
        uint16_t rev = 0;
        int ret = ad74413r_reg_read(ad744x, AD74413R_SILICON_REV, &rev);
        if (!ret) {
          printf("Silicon Rev = 0x%04X\n", rev);
        } else {
          printf("Read failed: %d\n", ret);
        }

  /* USER CODE END 2 */

  /* Infinite loop */
  /* USER CODE BEGIN WHILE */
  while (1)
  {
    /* USER CODE END WHILE */

    /* USER CODE BEGIN 3 */
  }
  /* USER CODE END 3 */
}

/**
  * @brief FLASH Initialization Function
  * @param None
  * @retval None
  */
static void MX_FLASH_Init(void)
{

  /* USER CODE BEGIN FLASH_Init 0 */

  /* USER CODE END FLASH_Init 0 */

  /* USER CODE BEGIN FLASH_Init 1 */

  /* USER CODE END FLASH_Init 1 */
  /* USER CODE BEGIN FLASH_Init 2 */

  /* USER CODE END FLASH_Init 2 */

}

/**
  * @brief SPI4 Initialization Function
  * @param None
  * @retval None
  */
static void MX_SPI4_Init(void)
{

  /* USER CODE BEGIN SPI4_Init 0 */

  /* USER CODE END SPI4_Init 0 */

  /* USER CODE BEGIN SPI4_Init 1 */

  /* USER CODE END SPI4_Init 1 */
  /* SPI4 parameter configuration*/
  hspi4.Instance = SPI4;
  hspi4.Init.Mode = SPI_MODE_MASTER;
  hspi4.Init.Direction = SPI_DIRECTION_2LINES;
  hspi4.Init.DataSize = SPI_DATASIZE_8BIT;
  hspi4.Init.CLKPolarity = SPI_POLARITY_LOW;
  hspi4.Init.CLKPhase = SPI_PHASE_2EDGE;
  hspi4.Init.NSS = SPI_NSS_SOFT;
  hspi4.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_64;
  hspi4.Init.FirstBit = SPI_FIRSTBIT_MSB;
  hspi4.Init.TIMode = SPI_TIMODE_DISABLE;
  hspi4.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
  hspi4.Init.CRCPolynomial = 0x7;
  hspi4.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
  hspi4.Init.NSSPolarity = SPI_NSS_POLARITY_LOW;
  hspi4.Init.FifoThreshold = SPI_FIFO_THRESHOLD_01DATA;
  hspi4.Init.MasterSSIdleness = SPI_MASTER_SS_IDLENESS_00CYCLE;
  hspi4.Init.MasterInterDataIdleness = SPI_MASTER_INTERDATA_IDLENESS_00CYCLE;
  hspi4.Init.MasterReceiverAutoSusp = SPI_MASTER_RX_AUTOSUSP_DISABLE;
  hspi4.Init.MasterKeepIOState = SPI_MASTER_KEEP_IO_STATE_DISABLE;
  hspi4.Init.IOSwap = SPI_IO_SWAP_DISABLE;
  hspi4.Init.ReadyMasterManagement = SPI_RDY_MASTER_MANAGEMENT_INTERNALLY;
  hspi4.Init.ReadyPolarity = SPI_RDY_POLARITY_HIGH;
  if (HAL_SPI_Init(&hspi4) != HAL_OK)
  {
    Error_Handler();
  }
  /* USER CODE BEGIN SPI4_Init 2 */

  /* USER CODE END SPI4_Init 2 */

}

/**
  * @brief GPIO Initialization Function
  * @param None
  * @retval None
  */
static void MX_GPIO_Init(void)
{
  GPIO_InitTypeDef GPIO_InitStruct = {0};
/* USER CODE BEGIN MX_GPIO_Init_1 */
/* USER CODE END MX_GPIO_Init_1 */

  /* GPIO Ports Clock Enable */
  __HAL_RCC_GPIOE_CLK_ENABLE();
  __HAL_RCC_GPIOF_CLK_ENABLE();
  __HAL_RCC_GPIOG_CLK_ENABLE();
  __HAL_RCC_GPIOM_CLK_ENABLE();
  __HAL_RCC_GPIOD_CLK_ENABLE();
  __HAL_RCC_GPIOB_CLK_ENABLE();
  __HAL_RCC_GPIOC_CLK_ENABLE();
  __HAL_RCC_GPIOA_CLK_ENABLE();

  /*Configure GPIO pin Output Level */
  HAL_GPIO_WritePin(SPI_RESET_GPIO_Port, SPI_RESET_Pin, GPIO_PIN_RESET);

  /*Configure GPIO pin Output Level */
  HAL_GPIO_WritePin(SPI_CS_GPIO_Port, SPI_CS_Pin, GPIO_PIN_SET);

  /*Configure GPIO pins : DCMI_D2_Pin DCMI_D3_Pin DCMI_D4_Pin */
  GPIO_InitStruct.Pin = DCMI_D2_Pin|DCMI_D3_Pin|DCMI_D4_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Alternate = GPIO_AF13_DCMIPP;
  HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);

  /*Configure GPIO pin : SPI_RESET_Pin */
  GPIO_InitStruct.Pin = SPI_RESET_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_MEDIUM;
  HAL_GPIO_Init(SPI_RESET_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pin : DCMI_HSYNC_Pin */
  GPIO_InitStruct.Pin = DCMI_HSYNC_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Alternate = GPIO_AF5_DCMIPP;
  HAL_GPIO_Init(DCMI_HSYNC_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pins : USB2_FS_N_Pin USB2_FS_P_Pin */
  GPIO_InitStruct.Pin = USB2_FS_N_Pin|USB2_FS_P_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS;
  HAL_GPIO_Init(GPIOM, &GPIO_InitStruct);

  /*Configure GPIO pins : USB1_HS_P_Pin USB1_HS_N_Pin */
  GPIO_InitStruct.Pin = USB1_HS_P_Pin|USB1_HS_N_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS;
  HAL_GPIO_Init(GPIOM, &GPIO_InitStruct);

  /*Configure GPIO pin : DCMI_D5_Pin */
  GPIO_InitStruct.Pin = DCMI_D5_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Alternate = GPIO_AF13_DCMIPP;
  HAL_GPIO_Init(DCMI_D5_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pin : SD_CMD_Pin */
  GPIO_InitStruct.Pin = SD_CMD_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
  GPIO_InitStruct.Alternate = GPIO_AF11_SDMMC1;
  HAL_GPIO_Init(SD_CMD_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pins : DCMI_D6_Pin DCMI_VSYNC_Pin */
  GPIO_InitStruct.Pin = DCMI_D6_Pin|DCMI_VSYNC_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Alternate = GPIO_AF13_DCMIPP;
  HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);

  /*Configure GPIO pin : MIC_CK_Pin */
  GPIO_InitStruct.Pin = MIC_CK_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF1_ADF1;
  HAL_GPIO_Init(MIC_CK_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pin : I2S_SDO_Pin */
  GPIO_InitStruct.Pin = I2S_SDO_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF8_SPI6;
  HAL_GPIO_Init(I2S_SDO_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pin : LCD_RGB_R2_Pin */
  GPIO_InitStruct.Pin = LCD_RGB_R2_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF11_LTDC;
  HAL_GPIO_Init(LCD_RGB_R2_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pin : RMII_REF_CLK_Pin */
  GPIO_InitStruct.Pin = RMII_REF_CLK_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF4_ETH;
  HAL_GPIO_Init(RMII_REF_CLK_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pins : LCD_RGB_R7_Pin LCD_HSYNC_Pin LCD_RGB_R6_Pin LCD_RGB_B1_Pin
                           LCD_CLK_Pin */
  GPIO_InitStruct.Pin = LCD_RGB_R7_Pin|LCD_HSYNC_Pin|LCD_RGB_R6_Pin|LCD_RGB_B1_Pin
                          |LCD_CLK_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF13_LTDC;
  HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);

  /*Configure GPIO pins : VCP_TX_Pin VCP_RX_Pin */
  GPIO_InitStruct.Pin = VCP_TX_Pin|VCP_RX_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF8_UART4;
  HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);

  /*Configure GPIO pin : SD_D2_Pin */
  GPIO_InitStruct.Pin = SD_D2_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
  GPIO_InitStruct.Alternate = GPIO_AF12_SDMMC1;
  HAL_GPIO_Init(SD_D2_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pins : SD_D3_Pin SD_CK_Pin SD_D0_Pin SD_D1_Pin */
  GPIO_InitStruct.Pin = SD_D3_Pin|SD_CK_Pin|SD_D0_Pin|SD_D1_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
  GPIO_InitStruct.Alternate = GPIO_AF11_SDMMC1;
  HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);

  /*Configure GPIO pins : I2C1_I3C_SDA_Pin I2C1_I3C_SCL_Pin */
  GPIO_InitStruct.Pin = I2C1_I3C_SDA_Pin|I2C1_I3C_SCL_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF4_I2C1;
  HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);

  /*Configure GPIO pins : LCD_RGB_R4_Pin LCD_RGB_R3_Pin LCD_RGB_G5_Pin LCD_DE_Pin
                           LCD_RGB_G6_Pin */
  GPIO_InitStruct.Pin = LCD_RGB_R4_Pin|LCD_RGB_R3_Pin|LCD_RGB_G5_Pin|LCD_DE_Pin
                          |LCD_RGB_G6_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF13_LTDC;
  HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);

  /*Configure GPIO pins : UCPD1_CC2_Pin UCPD1_CC1_Pin */
  GPIO_InitStruct.Pin = UCPD1_CC2_Pin|UCPD1_CC1_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  HAL_GPIO_Init(GPIOM, &GPIO_InitStruct);

  /*Configure GPIO pin : LCD_VSYNC_Pin */
  GPIO_InitStruct.Pin = LCD_VSYNC_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF11_LTDC;
  HAL_GPIO_Init(LCD_VSYNC_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pins : LCD_RGB_B2_Pin LCD_RGB_B3_Pin LCD_RGB_B6_Pin LCD_RGB_R5_Pin
                           LCD_RGB_G3_Pin LCD_RGB_G2_Pin */
  GPIO_InitStruct.Pin = LCD_RGB_B2_Pin|LCD_RGB_B3_Pin|LCD_RGB_B6_Pin|LCD_RGB_R5_Pin
                          |LCD_RGB_G3_Pin|LCD_RGB_G2_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF13_LTDC;
  HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);

  /*Configure GPIO pins : DCMI_PIXCLK_Pin DCMI_D7_Pin */
  GPIO_InitStruct.Pin = DCMI_PIXCLK_Pin|DCMI_D7_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Alternate = GPIO_AF5_DCMIPP;
  HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);

  /*Configure GPIO pins : LCD_RGB_B5_Pin LCD_RGB_B4_Pin */
  GPIO_InitStruct.Pin = LCD_RGB_B5_Pin|LCD_RGB_B4_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF14_LTDC;
  HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);

  /*Configure GPIO pins : DCMI_D0_Pin DCMI_D1_Pin */
  GPIO_InitStruct.Pin = DCMI_D0_Pin|DCMI_D1_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Alternate = GPIO_AF13_DCMIPP;
  HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);

  /*Configure GPIO pin : I2S_SDI_Pin */
  GPIO_InitStruct.Pin = I2S_SDI_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF5_SPI6;
  HAL_GPIO_Init(I2S_SDI_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pin : RMII_TX_EN_Pin */
  GPIO_InitStruct.Pin = RMII_TX_EN_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF11_ETH;
  HAL_GPIO_Init(RMII_TX_EN_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pins : LCD_RGB_G0_Pin LCD_RGB_R0_Pin LCD_RGB_G1_Pin */
  GPIO_InitStruct.Pin = LCD_RGB_G0_Pin|LCD_RGB_R0_Pin|LCD_RGB_G1_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF13_LTDC;
  HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);

  /*Configure GPIO pins : LCD_RGB_R1_Pin LCD_RGB_B0_Pin */
  GPIO_InitStruct.Pin = LCD_RGB_R1_Pin|LCD_RGB_B0_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF14_LTDC;
  HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);

  /*Configure GPIO pins : RMII_MDC_Pin RMII_RXD0_Pin RMII_RXD1_Pin */
  GPIO_InitStruct.Pin = RMII_MDC_Pin|RMII_RXD0_Pin|RMII_RXD1_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF11_ETH;
  HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);

  /*Configure GPIO pins : RMII_MDIO_Pin RMII_CRS_DV_Pin */
  GPIO_InitStruct.Pin = RMII_MDIO_Pin|RMII_CRS_DV_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF11_ETH;
  HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);

  /*Configure GPIO pins : I2S_WS_Pin I2S_CK_Pin */
  GPIO_InitStruct.Pin = I2S_WS_Pin|I2S_CK_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF8_SPI6;
  HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);

  /*Configure GPIO pins : LCD_RGB_G7_Pin LCD_RGB_G4_Pin */
  GPIO_InitStruct.Pin = LCD_RGB_G7_Pin|LCD_RGB_G4_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF10_LTDC;
  HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);

  /*Configure GPIO pin : I2S_MCK_Pin */
  GPIO_InitStruct.Pin = I2S_MCK_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF5_SPI6;
  HAL_GPIO_Init(I2S_MCK_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pin : LCD_RGB_B7_Pin */
  GPIO_InitStruct.Pin = LCD_RGB_B7_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF12_LTDC;
  HAL_GPIO_Init(LCD_RGB_B7_GPIO_Port, &GPIO_InitStruct);

  /*Configure GPIO pins : RMII_TXD0_Pin RMII_RX_ER_Pin RMII_TXD1_Pin */
  GPIO_InitStruct.Pin = RMII_TXD0_Pin|RMII_RX_ER_Pin|RMII_TXD1_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
  GPIO_InitStruct.Alternate = GPIO_AF11_ETH;
  HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);

  /*Configure GPIO pins : UCPD1_VSENSE_Pin UCPD1_ISENSE_Pin */
  GPIO_InitStruct.Pin = UCPD1_VSENSE_Pin|UCPD1_ISENSE_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  HAL_GPIO_Init(GPIOF, &GPIO_InitStruct);

  /*Configure GPIO pin : SPI_CS_Pin */
  GPIO_InitStruct.Pin = SPI_CS_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
  GPIO_InitStruct.Pull = GPIO_NOPULL;
  GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_MEDIUM;
  HAL_GPIO_Init(SPI_CS_GPIO_Port, &GPIO_InitStruct);

/* USER CODE BEGIN MX_GPIO_Init_2 */
/* USER CODE END MX_GPIO_Init_2 */
}

/* USER CODE BEGIN 4 */

/* USER CODE END 4 */

/**
  * @brief  This function is executed in case of error occurrence.
  * @retval None
  */
void Error_Handler(void)
{
  /* USER CODE BEGIN Error_Handler_Debug */
  /* User can add his own implementation to report the HAL error return state */
  __disable_irq();
  while (1)
  {
  }
  /* USER CODE END Error_Handler_Debug */
}

#ifdef  USE_FULL_ASSERT
/**
  * @brief  Reports the name of the source file and the source line number
  *         where the assert_param error has occurred.
  * @param  file: pointer to the source file name
  * @param  line: assert_param error line source number
  * @retval None
  */
void assert_failed(uint8_t *file, uint32_t line)
{
  /* USER CODE BEGIN 6 */
  /* User can add his own implementation to report the file name and line number,
     ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
  /* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */

Questions / Requests for Help:

Is my SPI mode correct? The datasheet suggests CPOL=0, CPHA=0 (so data latched on SCLK rising edge). I’ve tried CPHA=1 but it changes the timing and still doesn’t decode properly.

Could there be an issue with referencing or the AD74412R’s SDO pin drive? Should I add a pull-up resistor or test a different approach? 

Have I configured the AD74412R incorrectly? My init code does a hardware reset, writes to the SCRATCH register, and tries to read it back. I always get the wrong data.

I would appreciate any feedback or suggestions—especially from folks who’ve successfully tested the AD74412R in a simple SPI read/write scenario.

Please let me know if you see anything I’ve obviously messed up. Thank you in advance!

Kind regards,

Chris F.

Parents
  • Hi  ,

    thank you for your query, I will be happy to assist you to get your setup working.

    First think I would double check is AD74413R RESET pin, even thought you correctly accounted for it. I would double check the "EV-AD74412RSDZ " jumper settings and perhaps also measure the /RESET signal, to ensure, it is defined high to keep the DUT out of reset entire operating time. Here is snippet of jumpers configuration on the AD74413R: 

    Concerning the SPI mode and timing. Unfortunately, I am not able to review properly gathered signals on the oscilloscope, as the time domain is not set to have enough resolution to visualize the SPI signals properly. 

    Please note, that SPI data are always sampled on falling edge, this means, that AD74413R is compatible with following modes:

    (For reference: Introduction to SPI Interface | Analog Devices)

    What is SPI CLK frequency measured on the pin (AD74413R board), unfortunately I am not able to derive it from prescaler.

    The plots you have gathered, is it two transactions? (2-stage readback) As I see /SYNC pin to be toggled in the middle.

     Ensure that each transaction have 32 falling edges, otherwise the SPI frame is discarded by AD74413R as invalid frame and SPI_SCLK_CNT_ERR in ALERT_STATUS register is flagged. 

    I would also suggest to try reading ALERT_STATUS as this register should not be 0 after reset, unless cleared.

    Let me know, if any of the suggestions presented help you to resolve challenge with initialization.

    Regards,

    Arnost

  • Hi Arnost, really appreciate your advice double checked everything based on your reply and it ended up being a stupid one on my side that I wasn't toggling the CS during the write (I'm sure I put it in when modifying the noOS example driver) but the correct function below: 

    int ad74413r_reg_write(struct ad74413r_desc *desc, uint32_t addr, uint16_t val)

    {

    // 1. Format the 4-byte frame

    ad74413r_format_reg_write(addr, val, desc->comm_buff);

    // 2. Drive CS low

    HAL_GPIO_WritePin(desc->cs_gpio_port, desc->cs_gpio_pin, GPIO_PIN_RESET);

    // 3. Transmit the frame

    HAL_StatusTypeDef ret = HAL_SPI_Transmit(desc->hspi, desc->comm_buff, AD74413R_FRAME_SIZE, HAL_MAX_DELAY);

    // 4. Drive CS high

    HAL_GPIO_WritePin(desc->cs_gpio_port, desc->cs_gpio_pin, GPIO_PIN_SET);

    // 5. Check status

    if (ret != HAL_OK)

    return -EIO;

    return 0;

    }

    Anyway I am now initialising successfully and reading back the silicon ID register: 

    Thanks again both of you for your replies, very helpful! :)

  • Hi ,

    thank you for the update, I am happy that you are setup now.

    Feel free to open another EZ thread, if you will have further queries.

    Regards,

    Arnost

Reply Children
No Data