STM32H7上实现AD5758驱动

目录

概述

1 下载ADI 5758 Demo

2 AD5758驱动的移植

2.1 使用STM32CubeMX创建工程 

2.2 接口函数实现

2.2.1 驱动接口列表

2.2.2 函数实现

2.2.3 修正ad5758驱动

3 AD5758应用程序

3.1 编写测试程序

3.1.1 配置参数结构

3.1.2 配置参数函数

3.1.3 读取参数函数

3.2 接口调用

4 测试代码


源代码下载地址:

stm32-h750-proj资源-CSDN文库

概述

本文主要介绍使用ADI官方提供的AD5758驱动代码,使用STM32H7驱动该芯片,实现寄存器的配置和读取功能。ADI官方提供的AD5758驱动代码采用阻塞模式配置和读取寄存器信息,在实际使用中,可以可能要对其做相应的调整,本文提供的代码可供参考。

1 下载ADI 5758 Demo

登录如下网址,下载Demo:

https://wiki.analog.com/resources/eval/user-guides/ad5758

该软件包挂载在github上,可使用git命令直接下载,下载命令为:

git clone https://github.com/analogdevicesinc/no-OS/tree/main/projects/ad5758-sdz

下载完成后,打开代码:

2 AD5758驱动的移植

2.1 使用STM32CubeMX创建工程 

使用STM32CubeMX创建工程,创建完成后,使用Keil打开工程

添加ad5758.c 和ad5758.h到项目,并创建接口函数文件:ad5758_io.c

2.2 接口函数实现

2.2.1 驱动接口列表

函数名功能描述
no_os_spi_write_and_readSPI读写数据
ad5758_cs_LOWAD5758芯片片选LOW
ad5758_cs_HIGHTAD5758芯片片选HIGH
reset_chip_LOWAD5758芯片复位LOW
reset_chip_HIGHAD5758芯片复位HIGH
ldac_chip_LOW加载数据引脚置LOW
ldac_chip_HIGH加载数据引脚置HIGH
fault_chip_statusError状态引脚
pwr_status_chipPower状态引脚

2.2.2 函数实现

step- 1: 定义IO接口列表

static const Stru_ad5758Port stru_ad5758PortList[1] =
{
    {
			0x00,
			&hspi2,
			DAC_SYNC_0_GPIO_Port,
			DAC_SYNC_0_Pin,

			DAC_RESET_0_GPIO_Port,
			DAC_RESET_0_Pin,

			DAC_LDAC_0_1_GPIO_Port,
			DAC_LDAC_0_1_Pin,

			DAC_FAULT_0_GPIO_Port,
			DAC_FAULT_0_Pin,

			DAC_PWR_STATUS_0_GPIO_Port,
			DAC_PWR_STATUS_0_Pin,
    },  //ad57578 chip-1
};

step-2: 实现接口

详细代码如下:

bool no_os_spi_write_and_read( uint8_t *buff, int len)
{	
	int i = 0;
  uint8_t rbuff[len];
	
	const Stru_ad5758Port *pAD5758_Port = &stru_ad5758PortList[chip_index];
	
	for( i = 0;  i<len; i++  )
	{
		rbuff[i] = spi_readWriteByte( pAD5758_Port->spi, buff[i]);
	}	
	
	for( i = 0;  i<len; i++  )
	{
		buff[i] = rbuff[i];
	}	
	
	return true;
}

void ad5758_cs_LOW( void )
{
	const Stru_ad5758Port *pAD5758_Port = &stru_ad5758PortList[chip_index];

	HAL_GPIO_WritePin(pAD5758_Port->SpiCsGPIOx, pAD5758_Port->SpiCsPin, GPIO_PIN_RESET);
}

void ad5758_cs_HIGHT( void )
{
	const Stru_ad5758Port *pAD5758_Port = &stru_ad5758PortList[chip_index];

	HAL_GPIO_WritePin(pAD5758_Port->SpiCsGPIOx, pAD5758_Port->SpiCsPin, GPIO_PIN_SET); 
}

void reset_chip_LOW( void )
{
	const Stru_ad5758Port *pAD5758_Port = &stru_ad5758PortList[chip_index];

	HAL_GPIO_WritePin(pAD5758_Port->ResetGPIOx, pAD5758_Port->ResetPin, GPIO_PIN_RESET);
}

void reset_chip_HIGH( void )
{
	const Stru_ad5758Port *pAD5758_Port = &stru_ad5758PortList[chip_index];

	HAL_GPIO_WritePin(pAD5758_Port->ResetGPIOx, pAD5758_Port->ResetPin, GPIO_PIN_SET); 
}

void ldac_chip_LOW( void )
{
	const Stru_ad5758Port *pAD5758_Port = &stru_ad5758PortList[chip_index];

	HAL_GPIO_WritePin(pAD5758_Port->DacLoadGPIOx, pAD5758_Port->DacLoadPin, GPIO_PIN_RESET);
}

void ldac_chip_HIGH( void )
{
	const Stru_ad5758Port *pAD5758_Port = &stru_ad5758PortList[chip_index];

	HAL_GPIO_WritePin(pAD5758_Port->DacLoadGPIOx, pAD5758_Port->DacLoadPin, GPIO_PIN_SET); 
}

uint8_t fault_chip_status( void )
{
	const Stru_ad5758Port *pAD5758_Port = &stru_ad5758PortList[chip_index];

	return HAL_READ_DAC_PIN(pAD5758_Port->FaultGPIOx, pAD5758_Port->FaultPin); 
}

uint8_t pwr_status_chip( void )
{
	const Stru_ad5758Port *pAD5758_Port = &stru_ad5758PortList[chip_index];

	return HAL_READ_DAC_PIN(pAD5758_Port->PwrOkGPIOx, pAD5758_Port->PwrOkPin); 
}

2.2.3 修正ad5758驱动

在ad5758.c文件找那个,主要重写调用no_os_spi_write_and_read()函数的接口参数。

修正前该函数调用参数原型为:

修正之后

完整代码如下:

#include "ad5758.h"
#include "ad5758_io.h"

/**
 * Compute CRC8 checksum.
 * @param data - The data buffer.
 * @param data_size - The size of the data buffer.
 * @return CRC8 checksum.
 */
static uint8_t ad5758_compute_crc8(uint8_t *data,
				   uint8_t data_size)
{
	uint8_t i;
	uint8_t crc = 0;

	while (data_size) {
		for (i = 0x80; i != 0; i >>= 1) {
			if (((crc & 0x80) != 0) != ((*data & i) != 0)) {
				crc <<= 1;
				crc ^= AD5758_CRC8_POLY;
			} else {
				crc <<= 1;
			}
		}
		data++;
		data_size--;
	}

	return crc;
}

/**
 * Read from device.
 * @param dev - The device structure.
 * @param reg_addr - The register address.
 * @param reg_data - The register data.
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_spi_reg_read(struct ad5758_dev *dev,
			    uint8_t reg_addr,
			    uint16_t *reg_data)
{
	Stru_dataRegister st_dataRegister;
	uint8_t buf[4];
	int32_t ret;
	uint8_t rd_reg_addr;

	buf[0] = AD5758_REG_WRITE(AD5758_REG_TWO_STAGE_READBACK_SELECT);
	buf[1] = 0x00;
	buf[2] = reg_addr;

	if (dev->crc_en)
		buf[3] = ad5758_compute_crc8(buf, 3);
	else
		buf[3] = 0x00;

	ret = no_os_spi_write_and_read( buf, 4);
	if (ret < 0)
		goto spi_err;

	buf[0] = AD5758_REG_WRITE(AD5758_REG_NOP);
	buf[1] = 0x00;
	buf[2] = 0x00;

	if (dev->crc_en)
		buf[3] = ad5758_compute_crc8(buf, 3);
	else
		buf[3] = 0x00;

	ret = no_os_spi_write_and_read( buf, 4);
	if (ret < 0)
		goto spi_err;

	if ((dev->crc_en) &&
	    (ad5758_compute_crc8(buf, 3) != buf[3]))
		goto error;

	*reg_data = (buf[1] << 8) | buf[2];
	 // parser register address
   rd_reg_addr = buf[0]&0x1f;
	
#if DEBUG_LOG_AD5758  
		// update the data structure
		st_dataRegister.AddressStatus_bit.regiterAddress = rd_reg_addr;
		st_dataRegister.AddressStatus_bit.FaultStatus = (buf[0]&0x20)>>5;
		st_dataRegister.AddressStatus_bit.reserved = (buf[0]&0xc0)>>6;	
	  st_dataRegister.crc_8 = buf[3];
	
		printf("[no_os_spi_write_and_read]: \r\n");
		for ( int i = 0; i < 4; i++ )
		{
				printf("byte-%d : 0x%02x  \r\n",i, buf[i]);
		}
		
    printf("\r\n\r\n");
    printf("[parser the data register]: \r\n");
    printf("reserved:    0x%02x  \r\n",st_dataRegister.AddressStatus_bit.reserved);
    printf("reg_addr:    0x%02x  \r\n", st_dataRegister.AddressStatus_bit.regiterAddress);
    printf("FaultStatus: 0x%02x  \r\n",st_dataRegister.AddressStatus_bit.FaultStatus);
    printf("reg_data:    0x%04x  \r\n",st_dataRegister.data);
    printf("crc_8:       0x%02x  \r\n",st_dataRegister.crc_8);
    printf("\r\n\r\n");		
#endif   

	return 0;

spi_err:
	printf("%s: Failed spi comm with code: %"PRIi32".\n", __func__, ret);
	return -1;
error:
	printf("%s: Failed CRC with code: %"PRIi32".\n", __func__, ret);
	return -1;
}

/**
 * Write to device.
 * @param dev - The device structure.
 * @param reg_addr - The register address.
 * @param reg_data - The register data.
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_spi_reg_write(struct ad5758_dev *dev,
			     uint8_t reg_addr,
			     uint16_t reg_data)
{
	uint8_t buf[4];

	buf[0] = AD5758_REG_WRITE(reg_addr);
	buf[1] = (reg_data >> 8);
	buf[2] = (reg_data & 0xFF);
	buf[3] = ad5758_compute_crc8(buf, 3);

	return no_os_spi_write_and_read( buf, 4);
}

/**
 * SPI write to device using a mask.
 * @param dev - The device structure.
 * @param reg_addr - The register address.
 * @param mask - The mask.
 * @param data - The register data.
 * @return 0 in case of success, negative error code otherwise.
 */
static int32_t ad5758_spi_write_mask(struct ad5758_dev *dev,
				     uint8_t reg_addr,
				     uint32_t mask,
				     uint16_t data)
{
	uint16_t reg_data;
	int32_t ret;

	ret = ad5758_spi_reg_read(dev, reg_addr, &reg_data);
	if (ret < 0)
		return -1;

	reg_data &= ~mask;
	reg_data |= data;

	return ad5758_spi_reg_write(dev, reg_addr, reg_data);
}

/**
 * Enable/disable SPI CRC function.
 * @param dev - The device structure.
 * @param crc_en - CRC status
 * Accepted values: 0 - disabled
 *					1 - enabled
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_set_crc(struct ad5758_dev *dev, uint8_t crc_en)
{
	int32_t ret;

	ret = ad5758_spi_write_mask(dev, AD5758_REG_DIGITAL_DIAG_CONFIG,
				    AD5758_DIG_DIAG_CONFIG_SPI_CRC_EN_MSK,
				    AD5758_DIG_DIAG_CONFIG_SPI_CRC_EN_MODE(crc_en));

	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return -1;
	}
	dev->crc_en = crc_en;

	return 0;
}

/**
 * Busy wait until CAL_MEM_UNREFRESHED bit in the DIGITAL_DIAG_RESULTS clears
 * @param dev - The device structure.
 * @return 0 in case of success
 */
int32_t ad5758_wait_for_refresh_cycle(struct ad5758_dev *dev)
{
	uint16_t reg_data;
	/*
	 * Wait until the CAL_MEM_UNREFRESHED bit in the DIGITAL_DIAG_RESULTS
	 * register returns to 0.
	 */
	do {
		ad5758_spi_reg_read(dev, AD5758_REG_DIGITAL_DIAG_RESULTS,
				    &reg_data);
	} while (reg_data & AD5758_DIG_DIAG_RESULTS_CAL_MEM_UNREFRESHED_MSK);

	return 0;
}

/**
 * Initiate a software reset
 * @param dev - The device structure.
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_soft_reset(struct ad5758_dev *dev)
{
	int32_t ret;

	ret = ad5758_spi_reg_write(dev, AD5758_REG_KEY,
				   AD5758_KEY_CODE_RESET_1);
	if (ret < 0)
		goto error;

	ret = ad5758_spi_reg_write(dev, AD5758_REG_KEY,
				   AD5758_KEY_CODE_RESET_2);
	if (ret < 0)
		goto error;
	/* Wait 100 us */
	no_os_udelay(100);

	return 0;

error:
	printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
	return -1;
}

/**
 * Initiate a calibration memory refresh to the shadow registers
 * @param dev - The device structure.
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_calib_mem_refresh(struct ad5758_dev *dev)
{
	int32_t ret;

	ret = ad5758_spi_reg_write(dev, AD5758_REG_KEY,
				   AD5758_KEY_CODE_CALIB_MEM_REFRESH);
	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return -1;
	}

	/* Wait to allow time for the internal calibrations to complete */
	return ad5758_wait_for_refresh_cycle(dev);
}

/**
 * Configure the dc-to-dc controller mode
 * @param dev - The device structure.
 * @param mode - Mode[1:0] bits.
 * Accepted values: DC_DC_POWER_OFF
 *		    DPC_CURRENT_MODE
 *		    DPC_VOLTAGE_MODE
 *		    PPC_CURRENT_MODE
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_set_dc_dc_conv_mode(struct ad5758_dev *dev,
				   enum ad5758_dc_dc_mode mode)
{
	uint16_t reg_data;
	int32_t ret;

	/*
	 * The ENABLE_PPC_BUFFERS bit must be set prior to enabling PPC current
	 * mode.
	 */
	if (mode == PPC_CURRENT_MODE) {
		ret  = ad5758_spi_write_mask(dev, AD5758_REG_ADC_CONFIG,
					     AD5758_ADC_CONFIG_PPC_BUF_MSK,
					     AD5758_ADC_CONFIG_PPC_BUF_EN(1));
		if (ret < 0)
			goto error;
	}

	ret = ad5758_spi_write_mask(dev, AD5758_REG_DCDC_CONFIG1,
				    AD5758_DCDC_CONFIG1_DCDC_MODE_MSK,
				    AD5758_DCDC_CONFIG1_DCDC_MODE_MODE(mode));

	if (ret < 0)
		goto error;
	/*
	 * Poll the BUSY_3WI bit in the DCDC_CONFIG2 register until it is 0.
	 * This allows the 3-wire interface communication to complete.
	 */
	do {
		ad5758_spi_reg_read(dev, AD5758_REG_DCDC_CONFIG2, &reg_data);
	} while (reg_data & AD5758_DCDC_CONFIG2_BUSY_3WI_MSK);
	dev->dc_dc_mode = mode;

	return 0;

error:
	printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
	return -1;
}

/**
 * Set the dc-to-dc converter current limit.
 * @param dev - The device structure.
 * @param ilimit - current limit in mA
 * Accepted values: ILIMIT_150_mA
 *		    ILIMIT_200_mA
 *		    ILIMIT_250_mA
 *		    ILIMIT_300_mA
 *		    ILIMIT_350_mA
 *		    ILIMIT_400_mA
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_set_dc_dc_ilimit(struct ad5758_dev *dev,
				enum ad5758_dc_dc_ilimt ilimit)
{
	uint16_t reg_data;
	int32_t ret;

	ret = ad5758_spi_write_mask(dev, AD5758_REG_DCDC_CONFIG2,
				    AD5758_DCDC_CONFIG2_ILIMIT_MSK,
				    AD5758_DCDC_CONFIG2_ILIMIT_MODE(ilimit));

	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return -1;
	}

	/*
	 * Poll the BUSY_3WI bit in the DCDC_CONFIG2 register until it is 0.
	 * This allows the 3-wire interface communication to complete.
	 */
	do {
		ad5758_spi_reg_read(dev, AD5758_REG_DCDC_CONFIG2, &reg_data);
	} while (reg_data & AD5758_DCDC_CONFIG2_BUSY_3WI_MSK);
	dev->dc_dc_ilimit = ilimit;

	return 0;
}

/**
 * Enable/disable Enable Internal Buffers.
 * @param dev - The device structure.
 * @param enable - enable or disable
 * Accepted values: 0: disable
 * 		    1: enable
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_internal_buffers_en(struct ad5758_dev *dev, uint8_t enable)
{
	int32_t ret;

	ret = ad5758_spi_write_mask(dev, AD5758_REG_DAC_CONFIG,
				    AD5758_DAC_CONFIG_INT_EN_MSK,
				    AD5758_DAC_CONFIG_INT_EN_MODE(enable));
	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return -1;
	}

	/* Wait to allow time for the internal calibrations to complete */
	return ad5758_wait_for_refresh_cycle(dev);
}

/**
 * Select Output Range.
 * @param dev - The device structure.
 * @param range - output range
 * Accepted values: RANGE_0V_5V
 *		    RANGE_0V_10V
 *		    RANGE_M5V_5V
 *		    RANGE_M10V_10V
 *		    RANGE_0mA_20mA
 *		    RANGE_0mA_24mA
 *		    RANGE_4mA_24mA
 *		    RANGE_M20mA_20mA
 *		    RANGE_M24mA_24mA
 *		    RANGE_M1mA_22mA
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_set_out_range(struct ad5758_dev *dev,
			     enum ad5758_output_range range)
{
	int32_t ret;

	ret = ad5758_spi_write_mask(dev, AD5758_REG_DAC_CONFIG,
				    AD5758_DAC_CONFIG_RANGE_MSK,
				    AD5758_DAC_CONFIG_RANGE_MODE(range));

	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return -1;
	}
	dev->output_range = range;

	/* Modifying the RANGE bits in the DAC_CONFIG register also initiates
	 * a calibration memory refresh and, therefore, a subsequent SPI write
	 * must not be performed until the CAL_MEM_UNREFRESHED bit in the
	 * DIGITAL_DIAG_RESULTS register returns to 0.
	 */
	return ad5758_wait_for_refresh_cycle(dev);
}

/**
 * Configure the slew rate by setting the clock and enable/disable the control
 * @param dev - The device structure.
 * @param clk - Slew rate clock.
 * Accepted values: SR_CLOCK_240_KHZ
 *		    SR_CLOCK_200_KHZ
 *		    SR_CLOCK_150_KHZ
 *		    SR_CLOCK_128_KHZ
 *		    SR_CLOCK_64_KHZ
 *		    SR_CLOCK_32_KHZ
 *		    SR_CLOCK_16_KHZ
 *		    SR_CLOCK_8_KHZ
 *		    SR_CLOCK_4_KHZ
 *		    SR_CLOCK_2_KHZ
 *		    SR_CLOCK_1_KHZ
 *		    SR_CLOCK_512_HZ
 *		    SR_CLOCK_256_HZ
 *		    SR_CLOCK_128_HZ
 *		    SR_CLOCK_64_HZ
 *		    SR_CLOCK_16_HZ
 * @param enable - enable or disable the sr coontrol
 * Accepted values: 0: disable
 * 		    1: enable
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_slew_rate_config(struct ad5758_dev *dev,
				enum ad5758_slew_rate_clk clk,
				uint8_t enable)
{
	int32_t ret;

	ret = ad5758_spi_write_mask(dev, AD5758_REG_DAC_CONFIG,
				    AD5758_DAC_CONFIG_SR_EN_MSK,
				    AD5758_DAC_CONFIG_SR_EN_MODE(enable));
	if(ret)
		goto error;

	ret = ad5758_spi_write_mask(dev, AD5758_REG_DAC_CONFIG,
				    AD5758_DAC_CONFIG_SR_CLOCK_MSK,
				    AD5758_DAC_CONFIG_SR_CLOCK_MODE(clk));

	if (ret < 0)
		goto error;

	dev->slew_rate_clk = clk;

	/* Wait to allow time for the internal calibrations to complete */
	return ad5758_wait_for_refresh_cycle(dev);

error:
	printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
	return -1;
}

/**
 * Write DAC data to the input register
 * @param dev - The device structure.
 * @param code - DAC input data of 16 bits
 * Accepted values: 0x00 to 0xFFFF
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_dac_input_write(struct ad5758_dev *dev, uint16_t code)
{
	int32_t ret;

	ret = ad5758_spi_reg_write(dev, AD5758_REG_DAC_INPUT, code);

	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return -1;
	}

	return 0;
}

/**
 * Enable/disable VIOUT.
 * @param dev - The device structure.
 * @param enable - enable or disable VIOUT output
 * Accepted values: 0: disable
 * 		    1: enable
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_dac_output_en(struct ad5758_dev *dev, uint8_t enable)
{
	int32_t ret;

	ret = ad5758_spi_write_mask(dev, AD5758_REG_DAC_CONFIG,
				    AD5758_DAC_CONFIG_OUT_EN_MSK,
				    AD5758_DAC_CONFIG_OUT_EN_MODE(enable));

	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return -1;
	}
	no_os_mdelay(1);

	return 0;
}

/**
 * Clear the error flags for the on-chip digital diagnostic features
 * @param dev - The device structure.
 * @param flag - which flag to clear
 * Accepted values: DIAG_SPI_CRC_ERR
 * 		    DIAG_SLIPBIT_ERR
 * 		    DIAG_SCLK_COUNT_ERR
 * 		    DIAG_INVALID_SPI_ACCESS_ERR
 * 		    DIAG_CAL_MEM_CRC_ERR
 * 		    DIAG_INVERSE_DAC_CHECK_ERR
 * 		    DIAG_DAC_LATCH_MON_ERR
 * 		    DIAG_THREE_WI_RC_ERR
 * 		    DIAG_WDT_ERR
 * 		    DIAG_ERR_3WI
 * 		    DIAG_RESET_OCCURRED
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_clear_dig_diag_flag(struct ad5758_dev *dev,
				   enum ad5758_dig_diag_flags flag)
{
	int32_t ret;

	/*
	 * Flags require a 1 to be written to them to update them to their
	 * current value
	 */
	ret = ad5758_spi_write_mask(dev, AD5758_REG_DIGITAL_DIAG_RESULTS,
				    NO_OS_BIT(flag), NO_OS_BIT(flag));

	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return -1;
	}

	return 0;
}

/**
 * Configure CLKOUT by setting the frequency and enabling/disabling the option
 * @param dev - The device structure.
 * @param config - Enable or disable
 * Accepted values: CLKOUT_DISABLE
 * 		    CLKOUT_ENABLE
 * @param freq - configure the frequency of CLKOUT.
 * Accepted values: CLKOUT_FREQ_416_KHZ
 * 		    CLKOUT_FREQ_435_KHZ
 * 		    CLKOUT_FREQ_454_KHZ
 * 		    CLKOUT_FREQ_476_KHZ
 * 		    CLKOUT_FREQ_500_KHZ
 * 		    CLKOUT_FREQ_526_KHZ
 * 		    CLKOUT_FREQ_555_KHZ
 * 		    CLKOUT_FREQ_588_KHZ
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_set_clkout_config(struct ad5758_dev *dev,
				 enum ad5758_clkout_config config,
				 enum ad5758_clkout_freq freq)
{
	int32_t ret;

	ret = ad5758_spi_write_mask(dev, AD5758_REG_GP_CONFIG1,
				    AD5758_GP_CONFIG1_CLKOUT_FREQ_MSK,
				    AD5758_GP_CONFIG1_CLKOUT_FREQ_MODE(freq));
	if(ret < 0)
		goto error;

	ret = ad5758_spi_write_mask(dev, AD5758_REG_GP_CONFIG1,
				    AD5758_GP_CONFIG1_CLKOUT_CONFIG_MSK,
				    AD5758_GP_CONFIG1_CLKOUT_CONFIG_MODE(config));
	if(ret < 0)
		goto error;

	dev->clkout_config = config;
	dev->clkout_freq = freq;

	return 0;

error:
	printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
	return -1;
}

/**
 * Select which node to multiplex to the ADC.
 * @param dev - The device structure.
 * @param adc_ip_sel - diagnostic select
 * Accepted values: ADC_IP_MAIN_DIE_TEMP
 * 		    ADC_IP_DCDC_DIE_TEMP
 * 		    ADC_IP_REFIN
 * 		    ADC_IP_REF2
 * 		    ADC_IP_VSENSE
 * 		    ADC_IP_MVSENSE
 * 		    ADC_IP_INT_AVCC
 * 		    ADC_IP_REGOUT
 * 		    ADC_IP_VLOGIC
 * 		    ADC_IP_INT_CURR_MON_VOUT
 * 		    ADC_IP_REFGND
 * 		    ADC_IP_AGND
 * 		    ADC_IP_DGND
 * 		    ADC_IP_VDPC
 * 		    ADC_IP_AVDD2
 * 		    ADC_IP_AVSS
 * 		    ADC_IP_DCDC_DIE_NODE
 * 		    ADC_IP_REFOUT
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_select_adc_ip(struct ad5758_dev *dev,
			     enum ad5758_adc_ip adc_ip_sel)
{
	int32_t ret;

	ret = ad5758_spi_write_mask(dev, AD5758_REG_ADC_CONFIG,
				    AD5758_ADC_CONFIG_ADC_IP_SELECT_MSK,
				    AD5758_ADC_CONFIG_ADC_IP_SELECT_MODE(adc_ip_sel));

	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return -1;
	}

	return 0;
}

/**
 * Set depth of the sequencer.
 * @param dev - The device structure.
 * @param num_of_channels - depth of the sequencer 1 to 8 channels
 * Accepted values: 1 channel, 2 channels ... 8 channels
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_select_adc_depth(struct ad5758_dev *dev,
				uint8_t num_of_channels)
{
	int32_t ret = -1;

	if ((num_of_channels == 0) || (num_of_channels > 8)) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);

		return ret;
	}

	num_of_channels -= 1;
	ret = ad5758_spi_reg_write(dev, AD5758_REG_ADC_CONFIG,
				   AD5758_ADC_CONFIG_SEQUENCE_DATA_MODE(num_of_channels));

	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return ret;
	}

	return 0;
}

/**
 * Load the desired channel into the sequencer with the adc input
 * @param dev - The device structure.
 * @param channel - Desired channel
 * Accepted values: 0 = channel 1, 1 = channel 2... 7 = channel 8
 * @param adc_ip_sel - diagnostic select
 * Accepted values: ADC_IP_MAIN_DIE_TEMP
 * 		    ADC_IP_DCDC_DIE_TEMP
 * 		    ADC_IP_REFIN
 * 		    ADC_IP_REF2
 * 		    ADC_IP_VSENSE
 * 		    ADC_IP_MVSENSE
 * 		    ADC_IP_INT_AVCC
 * 		    ADC_IP_REGOUT
 * 		    ADC_IP_VLOGIC
 * 		    ADC_IP_INT_CURR_MON_VOUT
 * 		    ADC_IP_REFGND
 * 		    ADC_IP_AGND
 * 		    ADC_IP_DGND
 * 		    ADC_IP_VDPC
 * 		    ADC_IP_AVDD2
 * 		    ADC_IP_AVSS
 * 		    ADC_IP_DCDC_DIE_NODE
 * 		    ADC_IP_REFOUT
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_set_adc_channel_input(struct ad5758_dev *dev,
				     uint8_t channel,
				     enum ad5758_adc_ip adc_ip_sel)
{
	uint16_t cmd;
	int32_t ret;

	cmd = (AD5758_ADC_CONFIG_SEQUENCE_COMMAND_MODE(0x01) |
	       AD5758_ADC_CONFIG_SEQUENCE_DATA_MODE(channel) |
	       AD5758_ADC_CONFIG_ADC_IP_SELECT_MODE(adc_ip_sel));

	ret = ad5758_spi_reg_write(dev, AD5758_REG_ADC_CONFIG, cmd);

	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return -1;
	}

	return 0;
}

/**
 * Configure the ADC into one of four modes of operation
 * @param dev - The device structure.
 * @param adc_mode - ADC mode of operation
 * Accepted values: ADC_MODE_KEY_SEQ
 * 		    ADC_MODE_AUTO_SEQ
 * 		    ADC_MODE_SINGLE_CONV
 * 		    ADC_MODE_SINGLE_KEY_CONV
 * @param enable - enable or disable the selected mode
 * Accepted values: 0: disable
 * 		    1: enable
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_set_adc_mode(struct ad5758_dev *dev,
			    enum ad5758_adc_mode adc_mode,
			    uint8_t enable)
{
	uint16_t cmd;
	int32_t ret;

	cmd = (AD5758_ADC_CONFIG_SEQUENCE_COMMAND_MODE(adc_mode) |
	       AD5758_ADC_CONFIG_SEQUENCE_DATA_MODE(enable));

	ret = ad5758_spi_reg_write(dev, AD5758_REG_ADC_CONFIG, cmd);

	if (ret < 0) {
		printf("%s: Failed with code: %"PRIi32".\n", __func__, ret);
		return -1;
	}

	return 0;
}

/**
 * Configure the dc-to-dc controller mode
 * @param dev - The device structure.
 * @param mode - Mode[1:0] bits.
 * Accepted values: DC_DC_POWER_OFF
 *                  DPC_CURRENT_MODE
 *                  DPC_VOLTAGE_MODE
 *                  PPC_CURRENT_MODE
 * @return 0 in case of success, negative error code otherwise.
 */
int32_t ad5758_set_dc_dc_conv_mode_ext(struct ad5758_dev *pdev, enum ad5758_dc_dc_mode mode)
{
    uint16_t reg_data;
    int32_t ret;

#if DEBUG_LOG_AD5758
     printf("ad5758_set_dc_dc_conv_mode_ext: \r\n\r\n\r\n");
#endif

    /*
     * The ENABLE_PPC_BUFFERS bit must be set prior to enabling PPC current
     * mode.
     */
    if (mode == PPC_CURRENT_MODE) {
        ret  = ad5758_spi_write_mask(pdev, AD5758_REG_ADC_CONFIG,
                                           AD5758_ADC_CONFIG_PPC_BUF_MSK,
                                           AD5758_ADC_CONFIG_PPC_BUF_EN(1));
        if (ret < 0)
           goto error;
    }

    ret = ad5758_spi_write_mask(pdev, AD5758_REG_DCDC_CONFIG1,
                                      AD5758_DCDC_CONFIG1_DCDC_MODE_MSK,
                                      AD5758_DCDC_CONFIG1_DCDC_MODE_MODE(mode));

    if (ret < 0)
        goto error;
    /*
     * Poll the BUSY_3WI bit in the DCDC_CONFIG2 register until it is 0.
     * This allows the 3-wire interface communication to complete.
     */
    do {
            ad5758_spi_reg_read(pdev, AD5758_REG_DCDC_CONFIG2, &reg_data);
    } while (reg_data & AD5758_DCDC_CONFIG2_BUSY_3WI_MSK);

    return 0;

error:
    printf("Failed with code: %d\n",ret);
    return -1;
}


int32_t ad5758_set_clkout_config_ext( struct ad5758_dev *pdev, enum ad5758_clkout_config config,enum ad5758_clkout_freq freq)
{
    int32_t ret;

#if DEBUG_LOG_AD5758
    printf("ad5758_set_clkout_config_ext: \r\n\r\n\r\n");
#endif
    
    ret = ad5758_spi_write_mask( pdev, AD5758_REG_GP_CONFIG1,
                                       AD5758_GP_CONFIG1_CLKOUT_FREQ_MSK,
                                       AD5758_GP_CONFIG1_CLKOUT_FREQ_MODE(freq));
    if(ret < 0)
            goto error;

    ret = ad5758_spi_write_mask( pdev, AD5758_REG_GP_CONFIG1,
                                       AD5758_GP_CONFIG1_CLKOUT_CONFIG_MSK,
                                       AD5758_GP_CONFIG1_CLKOUT_CONFIG_MODE(config));
    if(ret < 0)
            goto error;

    return 0;

error:
    printf("Failed with code: %d\n",ret);
    return -1;
}

int32_t ad5758_reg_AutostatusReadbackMode(struct ad5758_dev *pdev,uint8_t reg_addr,uint16_t *reg_data)
{
    uint8_t buf[4];
	  uint8_t _read_buff[4];
    int32_t ret;
    uint8_t cal_crc = 0;
    uint8_t r_reg_addr = 0;
    uint8_t reserved = 0;
		Stru_dataRegister st_dataRegister;
    
    do{             
        buf[0] = AD5758_REG_WRITE(AD5758_REG_TWO_STAGE_READBACK_SELECT);
        buf[1] = 0x00;
        buf[2] = reg_addr;
        buf[3] = ad5758_compute_crc8(buf, 3);

        ret = no_os_spi_write_and_read(buf, 4);
        buf[0] = AD5758_REG_WRITE(AD5758_REG_NOP);
        buf[1] = 0x00;
        buf[2] = 0x00;
        buf[3] = ad5758_compute_crc8(buf, 3);

        ret = no_os_spi_write_and_read( buf, 4);

        // handle the result here
        cal_crc = ad5758_compute_crc8(_read_buff, 3);
        
        // parser register address
        r_reg_addr = _read_buff[0]&0x1f;
        
        // reserved falg
        reserved = (_read_buff[0]&0xc0)>>6;
        
#if DEBUG_LOG_AD5758  
        printf("[read register bytes]: \r\n");
        for ( int i = 0; i < 4; i++ )
        {
            printf("byte-%d : 0x%02x  \r\n",i, _read_buff[i]);
        }
#endif   
        // update the data structure
        st_dataRegister.AddressStatus_bit.regiterAddress = r_reg_addr;
        st_dataRegister.AddressStatus_bit.FaultStatus = (_read_buff[0]&0x20)>>5;
        st_dataRegister.AddressStatus_bit.reserved = reserved;
        
        *reg_data = (_read_buff[1] << 8) | _read_buff[2];
        st_dataRegister.data = *reg_data;
        st_dataRegister.crc_8 = _read_buff[3];
        
#if DEBUG_LOG_AD5758  
				printf("\r\n\r\n");
				printf("[parser the data register]: \r\n");
				printf("reserved:    0x%02x  \r\n",st_dataRegister.AddressStatus_bit.reserved);
				printf("reg_addr:    0x%02x  \r\n", st_dataRegister.AddressStatus_bit.regiterAddress);
				printf("FaultStatus: 0x%02x  \r\n",st_dataRegister.AddressStatus_bit.FaultStatus);
				printf("reg_data:    0x%04x  \r\n",st_dataRegister.data);
				printf("crc_8:       0x%02x  \r\n",st_dataRegister.crc_8);
				printf("\r\n\r\n");
#endif        
        
   }while(reserved != AD5758_RESERVED);

   return 0;

spi_err:
		printf("- Failed spi comm with code\n");
		return -1;
error:
		printf("- Failed CRC with code: %d \n",ret);
		return -1;
}

3 AD5758应用程序

3.1 编写测试程序

调用ad5758.c和ad5758_io.c中的接口,实现测试程序,该程序要实现的任务如下:

1)配置参数

2)使能输出属性(电流/电压)

3)读出配置参数

3.1.1 配置参数结构

代码第7行: 配置电压模式输出

代码第11行:电压输出范围为:0 ~ 10V

3.1.2 配置参数函数

该函数主要实现初始化参数功能,配置方法严格遵守AD5758 data sheet 上给出的流程

int32_t ad5758_init( struct ad5758_init_param *init_param )
{
	uint16_t reg_data_list[] = {0, 0x7FFF,0x6FFF, 0x5FFF,0x4FFF,0x3FFF,0x2FFF, 0x1FFF};
	struct ad5758_dev *dev = &stru_dev;
	int32_t ret;

	// select the chip 
	select_ad5758_chip(0);

	printf("debug_ad5758_init:  \r\n\r\n");
	/* Get the DAC out of reset */
	reset_chip_HIGH();

	/* Tie the LDAC pin low */
	ldac_chip_LOW();

	dev->crc_en = true;
	/* Perform a software reset */
	ret = ad5758_soft_reset(dev);
	if(ret)
		goto err;

	/* Perform a calibration memory refresh */
	ret = ad5758_calib_mem_refresh(dev);
	if(ret)
		goto err;

	/* Clear the RESET_OCCURRED flag */
	ret = ad5758_clear_dig_diag_flag(dev, DIAG_RESET_OCCURRED);
	if(ret)
		goto err;

	/* Configure CLKOUT before enabling the dc-to-dc converter */
	ret = ad5758_set_clkout_config(dev, init_param->clkout_config,
							 init_param->clkout_freq);
	if(ret)
		goto err;

	/* Set the dc-to-dc current limit */
	ret = ad5758_set_dc_dc_ilimit(dev, init_param->dc_dc_ilimit);
	if(ret)
		goto err;

	/* Set up the dc-to-dc converter mode */
	ret = ad5758_set_dc_dc_conv_mode(dev, init_param->dc_dc_mode);
	if(ret)
		goto err;

	/* Power up the DAC and internal (INT) amplifiers */
	ret = ad5758_internal_buffers_en(dev, 1);
	if(ret)
		goto err;

	/* Configure the output range */
	ret = ad5758_set_out_range(dev, init_param->output_range);
	if(ret)
		goto err;

	/* Enable Slew Rate Control and set the slew rate clock */
	ret = ad5758_slew_rate_config(dev, init_param->slew_rate_clk, 1);
	if(ret)
		goto err;

	ad5758_dac_input_write( dev ,reg_data_list[0]); 

	/* Enable VIOUT */
	ret = ad5758_dac_output_en(dev, 1);
	if(ret)
		goto err;


	printf("ad5758 successfully initialized\n");
	no_os_mdelay(1000);
	return 0;

err:
	printf("initialized ad5758 error \n");
	return -1;
}

3.1.3 读取参数函数

该函数主要实现读取配置参数,并通过串口终端打印出来

int32_t debug_ad5758_readconfig( void )
{
		int32_t ret;
		uint16_t reg_data;

		struct ad5758_dev *dev = &stru_dev;

		printf("debug_ad5758_config:  \r\n\r\n");  

		// select the chip 
		select_ad5758_chip(0);
    
    printf("debug_ad5758_config: AD5758_REG_DCDC_CONFIG1 \r\n\r\n");  
    ret = ad5758_reg_AutostatusReadbackMode( dev, AD5758_REG_DCDC_CONFIG1, &reg_data);
    if (ret < 0)
        goto err;
    
    /* read  AD5758_REG_DIGITAL_DIAG_RESULTS */
    printf("debug_ad5758_config: AD5758_REG_DIGITAL_DIAG_RESULTS \r\n\r\n");  
    ret = ad5758_reg_AutostatusReadbackMode( dev, AD5758_REG_DIGITAL_DIAG_RESULTS, &reg_data);
    if (ret < 0)
        goto err;
    
    /* read  AD5758_REG_DIGITAL_DIAG_RESULTS */
    printf("debug_ad5758_config: AD5758_REG_ANALOG_DIAG_RESULTS \r\n\r\n");  
    ret = ad5758_reg_AutostatusReadbackMode( dev, AD5758_REG_ANALOG_DIAG_RESULTS, &reg_data);
    if (ret < 0)
        goto err;
    
    /* read  AD5758_REG_FREQ_MONITOR */
    printf("debug_ad5758_config: AD5758_REG_FREQ_MONITOR \r\n\r\n");  
    ret = ad5758_reg_AutostatusReadbackMode( dev, AD5758_REG_FREQ_MONITOR, &reg_data);
    if (ret < 0)
        goto err;

    /* read  AD5758_REG_DAC_OUTPUT */
    printf("debug_ad5758_config: AD5758_REG_DAC_OUTPUT \r\n\r\n");  
    ret = ad5758_reg_AutostatusReadbackMode( dev, AD5758_REG_DAC_OUTPUT, &reg_data);
    if (ret < 0)
        goto err;
    
    /* read  AD5758_REG_DAC_CONFIG */
    printf("debug_ad5758_config: AD5758_REG_DAC_CONFIG \r\n\r\n");  
    ret = ad5758_reg_AutostatusReadbackMode( dev, AD5758_REG_DAC_CONFIG, &reg_data);
    if (ret < 0)
        goto err;
  
    printf("read config parameter: pass \r\n\r\n");
    return ret;

err:
    printf(" debug_ad5758_config: fail \r\n\r\n");
    return 0;
}

void appA5758_Init( void )
{
		ad5758_init( &init_param );
	  debug_ad5758_readconfig();
}

3.2 接口调用

编写函数appA5758_Init()调用以上接口,详细代码如下:

void appA5758_Init( void )
{
	  ad5758_init( &init_param );
	  debug_ad5758_readconfig();
}

在主函数Task中调用该函数:

4 测试代码

在ad5758_init()函数和debug_ad5758_readconfig()中分别添加两个断点

1)运行ad5758_init() 函数中的断点

 2)运行debug_ad5758_readconfig()中的断点

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:/a/547219.html

如若内容造成侵权/违法违规/事实不符,请联系我们进行投诉反馈qq邮箱809451989@qq.com,一经查实,立即删除!

相关文章

【max材质addtive叠加模式特效渲染不出通道的解决办法】

max材质addtive叠加模式特效渲染不出通道的解决办法 2021-12-22 18:15 max的scanline扫描线&#xff0c;vray渲染可以&#xff0c;红移不行(只支持它自己的材质&#xff0c;它自己的材质没有additive模式)。据说mr是可以的。 右侧的球体使用附加不透明度。 附加不透明度通过将…

CentOS:执行make命令时报错g++: Command not found

报错截图&#xff1a; 其实很简单只需要安装一下 yum -y install gcc automake autoconf libtool make yum install gcc gcc-c

​LeetCode解法汇总2924. 找到冠军 II

目录链接&#xff1a; 力扣编程题-解法汇总_分享记录-CSDN博客 GitHub同步刷题项目&#xff1a; https://github.com/September26/java-algorithms 原题链接&#xff1a;. - 力扣&#xff08;LeetCode&#xff09; 描述&#xff1a; 一场比赛中共有 n 支队伍&#xff0c;按从…

J垃圾回收

J垃圾回收 1 概述2 方法区的回收3 如何判断对象可以回收3.1 引用计数法3.2 可达性分析法 4 常见的引用对象4.1 软引用4.2 弱引用4.3 虚引用4.4 终结器引用 5 垃圾回收算法5.1 垃圾回收算法的历史和分类5.2 垃圾回收算法的评价标准5.3 标记清除算法5.4 复制算法5.5 标记整理算法…

【深入理解】width 的默认值,2024年最新面试复盘

先自我介绍一下&#xff0c;小编浙江大学毕业&#xff0c;去过华为、字节跳动等大厂&#xff0c;目前阿里P7 深知大多数程序员&#xff0c;想要提升技能&#xff0c;往往是自己摸索成长&#xff0c;但自己不成体系的自学效果低效又漫长&#xff0c;而且极易碰到天花板技术停滞…

如何使用pytorch进行图像分类

如何使用pytorch进行图像分类https://featurize.cn/notebooks/5a36fa40-490e-4664-bf98-aa5ad7b2fc2f

实时传输,弹性优先——物联网通讯打造数据上传新标杆

随着信息技术的飞速发展&#xff0c;物联网技术已经成为连接物理世界和数字世界的桥梁。在物联网领域&#xff0c;数据上传的速度、稳定性和灵活性是评价通讯技术优劣的重要指标。近年来&#xff0c;物联网通讯在实时传输、弹性优先方面取得了显著进展&#xff0c;为数据上传树…

224 基于matlab的优化工具箱优化函数

基于matlab的优化工具箱优化函数&#xff0c; 此工具箱中提供的算法包括&#xff1a; 灰狼优化器&#xff08;GWO&#xff09;&#xff0c;蚂蚁狮子优化器&#xff08;ALO&#xff09;&#xff0c;多功能优化器&#xff08;MVO&#xff09;&#xff0c;蜻蜓算法&#xff08;DA&…

4.15 网络编程

思维导图 #include <stdio.h> #include <string.h> #include <unistd.h> #include <stdlib.h> #include <sys/types.h> #include <sys/stat.h> #include <fcntl.h> #include <pthread.h> #include <semaphore.h> #inclu…

定时器、PWM定时器、UART串口通信

我要成为嵌入式高手之4月15日ARM第八天&#xff01;&#xff01; ———————————————————————————— 定时器 S3C2440A 有 5 个 16 位定时器。其中定时器 0、1、2 和 3 具有脉宽调制&#xff08;PWM&#xff09;功能。定时器 4 是一个无 输出引脚的内部…

【无标题】系统思考—智慧共赢座谈会

第432期JSTO—“智慧共赢座谈会”精彩回顾 我们身处一个快速变化的世界&#xff0c;其中培训和咨询行业也不断面临新的挑战和机遇。为了紧跟这些变革&#xff0c;我们邀请了行业专家与合作伙伴深入探讨在培训、交付和销售过程中遇到的难题。 本次座谈会的亮点之一是我们科学上…

rhce day1

一 . 在系统中设定延迟任务要求如下 在系统中建立 easylee 用户&#xff0c;设定其密码为 easylee 延迟任务由 root 用户建立 要求在 5 小时后备份系统中的用户信息文件到 /backup 中 确保延迟任务是使用非交互模式建立 确保系统中只有 root 用户和 easylee 用户可以执行延…

LeetCode 热题 100 Day02

滑动窗口模块 滑动窗口类问题&#xff1a;总能找到一个窗口&#xff0c;从前往后移动来查找结果值。 这个窗口的大小可能是固定的&#xff0c;也可能是变化的。但窗口的大小一定是有限的。 https://www.cnblogs.com/huansky/p/13488234.html Leetcode 3. 无重复字符的最长子串 …

什么是分组分析法

调查数据显示&#xff0c;2019 年年末中国大陆总人口 140005 万人。从年龄构成看&#xff0c;16 至 59 周岁年末人数为 89640 万&#xff0c;占总人口的比重为 64.0%&#xff1b;60 周岁及以上人口 25388 万人&#xff0c;占总人口的 18.1%&#xff0c;其中 65 周岁及以上人口 …

leetcode-链表中间节点

876. 链表的中间结点 题目 给你单链表的头结点 head &#xff0c;请你找出并返回链表的中间结点。 如果有两个中间结点&#xff0c;则返回第二个中间结点。 示例 1&#xff1a; 输入&#xff1a;head [1,2,3,4,5] 输出&#xff1a;[3,4,5] 解释&#xff1a;链表只有一个中间…

【办公类-21-16】 20240410三级育婴师 344多选题(题目与答案合并word)

作品展示 背景需求&#xff1a; 前文将APP题库里的育婴师题目下载到EXCEL&#xff0c;并进行手动整理【办公类-21-14】 20240406三级育婴师 344道多选题 UIBOT下载整理-CSDN博客文章浏览阅读287次&#xff0c;点赞8次&#xff0c;收藏9次。【办公类-21-14】 20240406三级育婴师…

银河麒麟高级服务器操作系统adb读写缓慢问题分析

1.问题环境 处理器&#xff1a; HUAWEI Kunpeng 920 5251K 内存&#xff1a; 512 GiB 整机类型/架构&#xff1a; TaiShan 200K (Model 2280K) BIOS版本&#xff1a; Byosoft Corp. 1.81.K 内核版本 4.19.90-23.15.v2101.ky10.aarch64 第三方应用 数据库 2.问题…

基于直方图的图像阈值计算和分割算法FPGA实现,包含tb测试文件和MATLAB辅助验证

目录 1.算法运行效果图预览 2.算法运行软件版本 3.部分核心程序 4.算法理论概述 5.算法完整程序工程 1.算法运行效果图预览 2.算法运行软件版本 VIVADO2019.2 matlab2022a 3.部分核心程序 timescale 1ns / 1ps // // Company: // Engineer: // // Design Name: // …

【浪漫 罗盘时钟 Js、css实现(附源代码) 美化版本】,前端面试必问的HashMap

先自我介绍一下&#xff0c;小编浙江大学毕业&#xff0c;去过华为、字节跳动等大厂&#xff0c;目前阿里P7 深知大多数程序员&#xff0c;想要提升技能&#xff0c;往往是自己摸索成长&#xff0c;但自己不成体系的自学效果低效又漫长&#xff0c;而且极易碰到天花板技术停滞…

vue简单使用三(class样式绑定)

目录 对象的形式绑定&#xff1a; 数组的形式绑定&#xff1a; 内联样式Style 对象的形式绑定&#xff1a; 可以看到class中有两个值 数组的形式绑定&#xff1a; 可以看到也有两个值 内联样式Style style样式设置成功 完整代码&#xff1a; <!DOCTYPE html> <html…