diff --git a/drivers/adc-dac/ad5592r/ad5592r-base.c b/drivers/adc-dac/ad5592r/ad5592r-base.c index dd31a558ec2..7ffaf1f6b78 100644 --- a/drivers/adc-dac/ad5592r/ad5592r-base.c +++ b/drivers/adc-dac/ad5592r/ad5592r-base.c @@ -3,7 +3,7 @@ * @brief Implementation of AD5592R Base Driver. * @author Mircea Caprioru (mircea.caprioru@analog.com) ******************************************************************************** - * Copyright 2018, 2020(c) Analog Devices, Inc. + * Copyright 2018, 2020, 2025(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: @@ -320,3 +320,174 @@ int32_t ad5592r_reset_channel_modes(struct ad5592r_dev *dev) return ad5592r_set_channel_modes(dev); } + +/** + * Register update + * + * @param dev - The device structure. + * @param reg_addr - The Register address + * @param data - The data to be written + * @param mask - The mask + * @return 0 in case of success, negative error code otherwise + */ +int32_t ad5592r_base_reg_update(struct ad5592r_dev *dev, uint16_t reg_addr, + uint16_t data, uint16_t mask) +{ + + uint16_t temp_reg_val; + int32_t ret; + + if (!dev) + return -1; + + ret = ad5592r_base_reg_read(dev, reg_addr, &temp_reg_val); + if (ret < 0) + return ret; + + temp_reg_val &= ~mask; + temp_reg_val |= data; + + ret = ad5592r_base_reg_write(dev, reg_addr, temp_reg_val); + if (ret < 0) + return ret; + + return 0; +} + +/** + * Set ADC Range of the device + * + * @param dev - The device structure. + * @param adc_range - ADC Range + * @return 0 in case of success, negative error code otherwise + */ +int32_t ad5592r_set_adc_range(struct ad5592r_dev *dev, + enum ad559xr_range adc_range) +{ + int32_t ret; + uint16_t status = 0; + + if (!dev) + return -1; + + status = adc_range ? AD5592R_REG_CTRL_ADC_RANGE : 0; + + ret = ad5592r_base_reg_update(dev, AD5592R_REG_CTRL, status, + AD5592R_REG_CTRL_ADC_RANGE); + if (ret < 0) + return ret; + + dev->adc_range = adc_range; + + return 0; +} + +/** + * Set DAC Range of the device + * + * @param dev - The device structure. + * @param dac_range - DAC Range + * @return 0 in case of success, negative error code otherwise + */ +int32_t ad5592r_set_dac_range(struct ad5592r_dev *dev, + enum ad559xr_range dac_range) +{ + int32_t ret; + uint16_t status = 0; + + if (!dev) + return -1; + + status = dac_range ? AD5592R_REG_CTRL_DAC_RANGE : 0; + + ret = ad5592r_base_reg_update(dev, AD5592R_REG_CTRL, status, + AD5592R_REG_CTRL_DAC_RANGE); + if (ret < 0) + return ret; + + dev->dac_range = dac_range; + + return 0; +} + +/** + * Set Power Down DAC Channel of the device + * + * @param dev - The device structure. + * @param chan - The channel number. + * @param enable - Status to enable/disable power down. + * @return 0 in case of success, negative error code otherwise + */ +int32_t ad5592r_power_down(struct ad5592r_dev *dev, uint8_t chan, bool enable) +{ + int ret; + uint16_t temp_reg_val = 0; + + if (!dev) + return -1; + + temp_reg_val = enable ? NO_OS_BIT(chan) : 0; + + ret = ad5592r_base_reg_update(dev, AD5592R_REG_PD, temp_reg_val, + NO_OS_BIT(chan)); + if (ret < 0) + return ret; + + dev->power_down[chan] = enable; + + return 0; +} + +/** + * Set Reference Select option for the device + * + * @param dev - The device structure. + * @param enable - Status to enable/disable internal reference. + * @return 0 in case of success, negative error code otherwise + */ +int32_t ad5592r_set_int_ref(struct ad5592r_dev *dev, bool enable) +{ + uint16_t temp_reg_val = 0; + int ret; + + if (!dev) + return -1; + + temp_reg_val = enable ? AD5592R_REG_PD_EN_REF : 0; + + ret = ad5592r_base_reg_update(dev, AD5592R_REG_PD, temp_reg_val, + AD5592R_REG_PD_EN_REF); + if (ret < 0) + return ret; + + dev->int_ref = enable; + + return 0; +} + +/** + * Set ADC Buffer for the device + * + * @param dev - The device structure. + * @param enable - Status to enable/disable adc buffer. + * @return 0 in case of success, negative error code otherwise + */ +int32_t ad5592r_set_adc_buffer(struct ad5592r_dev *dev, bool enable) +{ + uint16_t temp_reg_val = 0; + int ret; + + if (!dev) + return -1; + + temp_reg_val = enable ? AD5592R_REG_CTRL_ADC_BUFF_EN : 0; + + ret = ad5592r_base_reg_update(dev, AD5592R_REG_CTRL, temp_reg_val, + AD5592R_REG_CTRL_ADC_BUFF_EN); + if (ret < 0) + return ret; + + dev->adc_buf = enable; + + return 0; +} diff --git a/drivers/adc-dac/ad5592r/ad5592r-base.h b/drivers/adc-dac/ad5592r/ad5592r-base.h index c08fb839f72..f908d5aa9ed 100644 --- a/drivers/adc-dac/ad5592r/ad5592r-base.h +++ b/drivers/adc-dac/ad5592r/ad5592r-base.h @@ -3,7 +3,7 @@ * @brief Header file of AD5592R Base Driver. * @author Mircea Caprioru (mircea.caprioru@analog.com) ******************************************************************************** - * Copyright 2018, 2020(c) Analog Devices, Inc. + * Copyright 2018, 2020, 2025(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: @@ -38,6 +38,7 @@ #include "no_os_spi.h" #include "no_os_i2c.h" #include "no_os_util.h" +#include "no_os_alloc.h" #include #define CH_MODE_UNUSED 0 @@ -92,6 +93,8 @@ enum ad5592r_registers { #define INTERNAL_VREF_VOLTAGE 2.5 +#define NUM_OF_CHANNELS 8 + struct ad5592r_dev; struct ad5592r_rw_ops { @@ -108,8 +111,22 @@ struct ad5592r_rw_ops { int32_t (*gpio_read)(struct ad5592r_dev *dev, uint8_t *value); }; +enum ad559xr_range { + ZERO_TO_VREF, + ZERO_TO_2VREF +}; + struct ad5592r_init_param { bool int_ref; + struct no_os_spi_init_param *spi_init; + struct no_os_i2c_init_param *i2c_init; + uint8_t channel_modes[8]; + uint8_t channel_offstate[8]; + enum ad559xr_range adc_range; + enum ad559xr_range dac_range; + bool adc_buf; + uint16_t cached_dac[8]; + uint8_t power_down[8]; }; struct ad5592r_dev { @@ -126,6 +143,11 @@ struct ad5592r_dev { uint8_t gpio_in; uint8_t gpio_val; uint8_t ldac_mode; + enum ad559xr_range adc_range; + enum ad559xr_range dac_range; + bool int_ref; + uint8_t power_down[8]; + bool adc_buf; }; int32_t ad5592r_base_reg_write(struct ad5592r_dev *dev, uint8_t reg, @@ -141,5 +163,14 @@ int32_t ad5592r_gpio_direction_output(struct ad5592r_dev *dev, int32_t ad5592r_software_reset(struct ad5592r_dev *dev); int32_t ad5592r_set_channel_modes(struct ad5592r_dev *dev); int32_t ad5592r_reset_channel_modes(struct ad5592r_dev *dev); +int32_t ad5592r_set_adc_range(struct ad5592r_dev *dev, + enum ad559xr_range adc_range); +int32_t ad5592r_set_dac_range(struct ad5592r_dev *dev, + enum ad559xr_range dac_range); +int32_t ad5592r_power_down(struct ad5592r_dev *dev, uint8_t chan, bool enable); +int32_t ad5592r_set_int_ref(struct ad5592r_dev *dev, bool enable); +int32_t ad5592r_set_adc_buffer(struct ad5592r_dev *dev, bool enable); +int32_t ad5592r_base_reg_update(struct ad5592r_dev* dev, uint16_t reg_addr, + uint16_t data, uint16_t mask); #endif /* AD5592R_BASE_H_ */ diff --git a/drivers/adc-dac/ad5592r/ad5592r.c b/drivers/adc-dac/ad5592r/ad5592r.c index 5536c6ac579..59056e26099 100644 --- a/drivers/adc-dac/ad5592r/ad5592r.c +++ b/drivers/adc-dac/ad5592r/ad5592r.c @@ -3,7 +3,7 @@ * @brief Implementation of AD5592R driver. * @author Mircea Caprioru (mircea.caprioru@analog.com) ******************************************************************************** - * Copyright 2018, 2020(c) Analog Devices, Inc. + * Copyright 2018, 2020, 2025(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: @@ -19,7 +19,7 @@ * 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 + * 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, @@ -50,7 +50,7 @@ const struct ad5592r_rw_ops ad5592r_rw_ops = { * @param buf - buffer where to read * @return 0 in case of success, negative error code otherwise */ -static int32_t ad5592r_spi_wnop_r16(struct ad5592r_dev *dev, uint16_t *buf) +int32_t ad5592r_spi_wnop_r16(struct ad5592r_dev *dev, uint16_t *buf) { int32_t ret; uint16_t spi_msg_nop = 0; /* NOP */ @@ -76,13 +76,21 @@ static int32_t ad5592r_spi_wnop_r16(struct ad5592r_dev *dev, uint16_t *buf) int32_t ad5592r_write_dac(struct ad5592r_dev *dev, uint8_t chan, uint16_t value) { + int ret; + if (!dev) return -1; dev->spi_msg = swab16(NO_OS_BIT(15) | (uint16_t)(chan << 12) | value); - return no_os_spi_write_and_read(dev->spi, (uint8_t *)&dev->spi_msg, - sizeof(dev->spi_msg)); + ret = no_os_spi_write_and_read(dev->spi, (uint8_t *)&dev->spi_msg, + sizeof(dev->spi_msg)); + if (ret) + return ret; + + dev->cached_dac[chan] = value; + + return 0; } /** @@ -126,6 +134,29 @@ int32_t ad5592r_read_adc(struct ad5592r_dev *dev, uint8_t chan, return 0; } +/** + * Enable Busy Indicator. + * + * @param dev - The device structure. + * @param enable - Enable/Disable busy Indicator. + * @return 0 in case of success, negative error code otherwise + */ +int32_t ad5592r_enable_busy(struct ad5592r_dev *dev, bool enable) +{ + uint16_t temp_reg_val = 0; + + dev->channel_modes[7] = CH_MODE_GPO; + ad5592r_set_channel_modes(dev); + + if (!dev) + return -1; + + temp_reg_val = enable ? AD5592R_REG_GPIO_OUT_EN_ADC_NOT_BUSY : 0; + + return ad5592r_base_reg_update(dev, AD5592R_REG_GPIO_OUT_EN, temp_reg_val, + AD5592R_REG_GPIO_OUT_EN_ADC_NOT_BUSY); +} + /** * Read Multiple ADC Channels. * @@ -253,37 +284,70 @@ int32_t ad5592r_gpio_read(struct ad5592r_dev *dev, uint8_t *value) /** * Initialize AD5593r device. * - * @param dev - The device structure. + * @param device - The device structure. * @param init_param - The initial parameters of the device. * @return 0 in case of success, negative error code otherwise */ -int32_t ad5592r_init(struct ad5592r_dev *dev, +int32_t ad5592r_init(struct ad5592r_dev **device, struct ad5592r_init_param *init_param) { int32_t ret; - uint16_t temp_reg_val; + struct ad5592r_dev *dev; + uint8_t i; + dev = (struct ad5592r_dev *)no_os_calloc(1, sizeof(*dev)); if (!dev) return -1; + /* Initialize the SPI communication. */ + ret = no_os_spi_init(&dev->spi, init_param->spi_init); + if (ret) + return ret; + dev->ops = &ad5592r_rw_ops; + dev->ldac_mode = 0; + dev->num_channels = NUM_OF_CHANNELS; ret = ad5592r_software_reset(dev); if (ret < 0) return ret; + for (i = 0; i < NUM_OF_CHANNELS; i++) { + dev->channel_modes[i] = init_param->channel_modes[i]; + dev->channel_offstate[i] = init_param->channel_offstate[i]; + } + + ret = ad5592r_set_adc_range(dev, init_param->adc_range); + if (ret < 0) + return ret; + + ret = ad5592r_set_dac_range(dev, init_param->dac_range); + if (ret < 0) + return ret; + + ret = ad5592r_set_adc_buffer(dev, init_param->adc_buf); + if (ret < 0) + return ret; + ret = ad5592r_set_channel_modes(dev); if (ret < 0) return ret; - if (init_param->int_ref) { - ret = ad5592r_reg_read(dev, AD5592R_REG_PD, &temp_reg_val); + ret = ad5592r_set_int_ref(dev, init_param->int_ref); + if (ret < 0) + return ret; + + for (i = 0; i < NUM_OF_CHANNELS; i++) { + ret = ad5592r_power_down(dev, i, init_param->power_down[i]); if (ret < 0) return ret; - temp_reg_val |= AD5592R_REG_PD_EN_REF; - return ad5592r_reg_write(dev, AD5592R_REG_PD, temp_reg_val); + ret = ad5592r_write_dac(dev, i, init_param->cached_dac[i]); + if (ret < 0) + return ret; } + *device = dev; + return ret; } diff --git a/drivers/adc-dac/ad5592r/ad5592r.h b/drivers/adc-dac/ad5592r/ad5592r.h index 1a3eb7de444..311b91b2b6e 100644 --- a/drivers/adc-dac/ad5592r/ad5592r.h +++ b/drivers/adc-dac/ad5592r/ad5592r.h @@ -3,7 +3,7 @@ * @brief Header file of AD5592R driver. * @author Mircea Caprioru (mircea.caprioru@analog.com) ******************************************************************************** - * Copyright 2018, 2020(c) Analog Devices, Inc. + * Copyright 2018, 2020, 2025(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: @@ -19,7 +19,7 @@ * 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 + * 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, @@ -54,7 +54,9 @@ int32_t ad5592r_reg_write(struct ad5592r_dev *dev, uint8_t reg, int32_t ad5592r_reg_read(struct ad5592r_dev *dev, uint8_t reg, uint16_t *value); int32_t ad5592r_gpio_read(struct ad5592r_dev *dev, uint8_t *value); -int32_t ad5592r_init(struct ad5592r_dev *dev, +int32_t ad5592r_init(struct ad5592r_dev **dev, struct ad5592r_init_param *init_param); +int32_t ad5592r_enable_busy(struct ad5592r_dev *dev, bool enable); +int32_t ad5592r_spi_wnop_r16(struct ad5592r_dev *dev, uint16_t *buf); #endif /* AD5592R_H_ */ diff --git a/drivers/adc-dac/ad5592r/ad5593r.c b/drivers/adc-dac/ad5592r/ad5593r.c index f2918a4bf0e..bb0fc869c17 100644 --- a/drivers/adc-dac/ad5592r/ad5593r.c +++ b/drivers/adc-dac/ad5592r/ad5593r.c @@ -3,7 +3,7 @@ * @brief Implementation of AD5593R driver. * @author Mircea Caprioru (mircea.caprioru@analog.com) ******************************************************************************** - * Copyright 2018, 2020(c) Analog Devices, Inc. + * Copyright 2018, 2020, 2025(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: @@ -19,7 +19,7 @@ * 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 + * 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, @@ -35,17 +35,6 @@ #include "no_os_error.h" #include "ad5593r.h" -#define AD5593R_MODE_CONF (0 << 4) -#define AD5593R_MODE_DAC_WRITE (1 << 4) -#define AD5593R_MODE_ADC_READBACK (4 << 4) -#define AD5593R_MODE_DAC_READBACK (5 << 4) -#define AD5593R_MODE_GPIO_READBACK (6 << 4) -#define AD5593R_MODE_REG_READBACK (7 << 4) - -#define STOP_BIT 1 -#define RESTART_BIT 0 -#define AD5593R_ADC_VALUES_BUFF_SIZE 18 - const struct ad5592r_rw_ops ad5593r_rw_ops = { .write_dac = ad5593r_write_dac, .read_adc = ad5593r_read_adc, @@ -67,6 +56,7 @@ int32_t ad5593r_write_dac(struct ad5592r_dev *dev, uint8_t chan, uint16_t value) { uint8_t data[3]; + int ret; if (!dev) return -1; @@ -75,7 +65,13 @@ int32_t ad5593r_write_dac(struct ad5592r_dev *dev, uint8_t chan, data[1] = (value >> 8) & 0xF ; data[2] = value & 0xFF; - return no_os_i2c_write(dev->i2c, data, sizeof(data), STOP_BIT); + ret = no_os_i2c_write(dev->i2c, data, sizeof(data), AD5593R_STOP_BIT); + if (ret < 0) + return ret; + + dev->cached_dac[chan] = value; + + return 0; } /** @@ -102,16 +98,16 @@ int32_t ad5593r_read_adc(struct ad5592r_dev *dev, uint8_t chan, data[1] = temp >> 8; data[2] = temp & 0xFF; - ret = no_os_i2c_write(dev->i2c, data, sizeof(data), STOP_BIT); + ret = no_os_i2c_write(dev->i2c, data, sizeof(data), AD5593R_STOP_BIT); if (ret < 0) return ret; data[0] = AD5593R_MODE_ADC_READBACK; - ret = no_os_i2c_write(dev->i2c, data, 1, STOP_BIT); + ret = no_os_i2c_write(dev->i2c, data, 1, AD5593R_STOP_BIT); if (ret < 0) return ret; - ret = no_os_i2c_read(dev->i2c, data, 2, STOP_BIT); + ret = no_os_i2c_read(dev->i2c, data, 2, AD5593R_STOP_BIT); if (ret < 0) return ret; @@ -144,16 +140,16 @@ int32_t ad5593r_multi_read_adc(struct ad5592r_dev *dev, uint16_t chans, data[1] = chans >> 8; data[2] = chans & 0xFF; - ret = no_os_i2c_write(dev->i2c, data, 3, STOP_BIT); + ret = no_os_i2c_write(dev->i2c, data, 3, AD5593R_STOP_BIT); if (ret < 0) return ret; data[0] = AD5593R_MODE_ADC_READBACK; - ret = no_os_i2c_write(dev->i2c, data, 1, RESTART_BIT); + ret = no_os_i2c_write(dev->i2c, data, 1, AD5593R_RESTART_BIT); if (ret < 0) return ret; - ret = no_os_i2c_read(dev->i2c, data, (2 * samples), STOP_BIT); + ret = no_os_i2c_read(dev->i2c, data, (2 * samples), AD5593R_STOP_BIT); if (ret < 0) return ret; @@ -185,7 +181,7 @@ int32_t ad5593r_reg_write(struct ad5592r_dev *dev, uint8_t reg, data[1] = value >> 8; data[2] = value; - ret = no_os_i2c_write(dev->i2c, data, sizeof(data), STOP_BIT); + ret = no_os_i2c_write(dev->i2c, data, sizeof(data), AD5593R_STOP_BIT); if (reg == AD5592R_REG_RESET && ret < 0) { return 0; @@ -213,11 +209,11 @@ int32_t ad5593r_reg_read(struct ad5592r_dev *dev, uint8_t reg, data[0] = AD5593R_MODE_REG_READBACK | reg; - ret = no_os_i2c_write(dev->i2c, data, 1, STOP_BIT); + ret = no_os_i2c_write(dev->i2c, data, 1, AD5593R_STOP_BIT); if (ret < 0) return ret; - ret = no_os_i2c_read(dev->i2c, data, sizeof(data), STOP_BIT); + ret = no_os_i2c_read(dev->i2c, data, sizeof(data), AD5593R_STOP_BIT); if (ret < 0) return ret; @@ -242,11 +238,11 @@ int32_t ad5593r_gpio_read(struct ad5592r_dev *dev, uint8_t *value) return -1; data[0] = AD5593R_MODE_GPIO_READBACK; - ret = no_os_i2c_write(dev->i2c, data, 1, STOP_BIT); + ret = no_os_i2c_write(dev->i2c, data, 1, AD5593R_STOP_BIT); if (ret < 0) return ret; - ret = no_os_i2c_read(dev->i2c, data, sizeof(data), STOP_BIT); + ret = no_os_i2c_read(dev->i2c, data, sizeof(data), AD5593R_STOP_BIT); if (ret < 0) return ret; @@ -258,37 +254,70 @@ int32_t ad5593r_gpio_read(struct ad5592r_dev *dev, uint8_t *value) /** * Initialize AD5593r device. * - * @param dev - The device structure. + * @param device - The device structure. * @param init_param - The initial parameters of the device. * @return 0 in case of success, negative error code otherwise */ -int32_t ad5593r_init(struct ad5592r_dev *dev, +int32_t ad5593r_init(struct ad5592r_dev **device, struct ad5592r_init_param *init_param) { int32_t ret; - uint16_t temp_reg_val; + uint8_t i; + struct ad5592r_dev *dev; + dev = (struct ad5592r_dev *)no_os_calloc(1, sizeof(*dev)); if (!dev) return -1; + /* Initialize the SPI communication. */ + ret = no_os_i2c_init(&dev->i2c, init_param->i2c_init); + if (ret < 0) + return ret; + dev->ops = &ad5593r_rw_ops; + dev->ldac_mode = 0; + dev->num_channels = NUM_OF_CHANNELS; ret = ad5592r_software_reset(dev); if (ret < 0) return ret; + for (i = 0; i < NUM_OF_CHANNELS; i++) { + dev->channel_modes[i] = init_param->channel_modes[i]; + dev->channel_offstate[i] = init_param->channel_offstate[i]; + } + + ret = ad5592r_set_adc_range(dev, init_param->adc_range); + if (ret < 0) + return ret; + + ret = ad5592r_set_dac_range(dev, init_param->dac_range); + if (ret < 0) + return ret; + + ret = ad5592r_set_adc_buffer(dev, init_param->adc_buf); + if (ret < 0) + return ret; + ret = ad5592r_set_channel_modes(dev); if (ret < 0) return ret; - if (init_param->int_ref) { - ret = ad5593r_reg_read(dev, AD5592R_REG_PD, &temp_reg_val); + ret = ad5592r_set_int_ref(dev, init_param->int_ref); + if (ret < 0) + return ret; + + for (i = 0; i < NUM_OF_CHANNELS ; i++) { + ret = ad5592r_power_down(dev, i, init_param->power_down[i]); if (ret < 0) return ret; - temp_reg_val |= AD5592R_REG_PD_EN_REF; - return ad5593r_reg_write(dev, AD5592R_REG_PD, temp_reg_val); + ret = ad5593r_write_dac(dev, i, init_param->cached_dac[i]); + if (ret < 0) + return ret; } + *device = dev; + return ret; } diff --git a/drivers/adc-dac/ad5592r/ad5593r.h b/drivers/adc-dac/ad5592r/ad5593r.h index 802b2172f63..7847ec465d2 100644 --- a/drivers/adc-dac/ad5592r/ad5593r.h +++ b/drivers/adc-dac/ad5592r/ad5593r.h @@ -3,7 +3,7 @@ * @brief Header file of AD5593R driver. * @author Mircea Caprioru (mircea.caprioru@analog.com) ******************************************************************************** - * Copyright 2018, 2020(c) Analog Devices, Inc. + * Copyright 2018, 2020, 2025(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: @@ -19,7 +19,7 @@ * 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 + * 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, @@ -36,6 +36,17 @@ #include "stdint.h" #include "ad5592r-base.h" +#define AD5593R_MODE_CONF (0 << 4) +#define AD5593R_MODE_DAC_WRITE (1 << 4) +#define AD5593R_MODE_ADC_READBACK (4 << 4) +#define AD5593R_MODE_DAC_READBACK (5 << 4) +#define AD5593R_MODE_GPIO_READBACK (6 << 4) +#define AD5593R_MODE_REG_READBACK (7 << 4) + +#define AD5593R_STOP_BIT 1 +#define AD5593R_RESTART_BIT 0 +#define AD5593R_ADC_VALUES_BUFF_SIZE 18 + int32_t ad5593r_write_dac(struct ad5592r_dev *dev, uint8_t chan, uint16_t value); int32_t ad5593r_read_adc(struct ad5592r_dev *dev, uint8_t chan, @@ -47,7 +58,7 @@ int32_t ad5593r_reg_write(struct ad5592r_dev *dev, uint8_t reg, int32_t ad5593r_reg_read(struct ad5592r_dev *dev, uint8_t reg, uint16_t *value); int32_t ad5593r_gpio_read(struct ad5592r_dev *dev, uint8_t *value); -int32_t ad5593r_init(struct ad5592r_dev *dev, +int32_t ad5593r_init(struct ad5592r_dev **dev, struct ad5592r_init_param *init_param); #endif /* AD5593R_H_ */