The AD8460 is a “bits in, power out” high voltage, high-power,
high-speed driver optimized for large output current (up to ±1 A)
and high slew rate (up to ±1800 V/μs) at high voltage (up to ±40 V)
into capacitive loads.
A digital engine implements user-configurable features: modes for
digital input, programmable supply current, and fault monitoring
and programmable protection settings for output current,
output voltage, and junction temperature. The AD8460 operates on
high voltage dual supplies up to ±55 V and a single low voltage
supply of 5 V.
Signed-off-by: Mariel Tinaco <Mariel.Tinaco@analog.com>
---
MAINTAINERS | 1 +
drivers/iio/dac/Kconfig | 13 +
drivers/iio/dac/Makefile | 1 +
drivers/iio/dac/ad8460.c | 976 +++++++++++++++++++++++++++++++++++++++
4 files changed, 991 insertions(+)
create mode 100644 drivers/iio/dac/ad8460.c
diff --git a/MAINTAINERS b/MAINTAINERS
index dae93df2a..6134cac65 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -1240,6 +1240,7 @@ L: linux-iio@vger.kernel.org
S: Supported
W: https://ez.analog.com/linux-software-drivers
F: Documentation/devicetree/bindings/iio/dac/adi,ad8460.yaml
+F: drivers/iio/dac/ad8460.c
ANALOG DEVICES INC AD9739a DRIVER
M: Nuno Sa <nuno.sa@analog.com>
diff --git a/drivers/iio/dac/Kconfig b/drivers/iio/dac/Kconfig
index 3c2bf620f..8da5cfe4f 100644
--- a/drivers/iio/dac/Kconfig
+++ b/drivers/iio/dac/Kconfig
@@ -300,6 +300,19 @@ config AD7303
To compile this driver as module choose M here: the module will be called
ad7303.
+config AD8460
+ tristate "Analog Devices AD8460 DAC driver"
+ depends on SPI
+ select REGMAP_SPI
+ select IIO_BUFFER
+ select IIO_BUFFER_DMAENGINE
+ help
+ Say yes here to build support for Analog Devices AD8460 Digital to
+ Analog Converters (DAC).
+
+ To compile this driver as a module choose M here: the module will be called
+ ad8460.
+
config AD8801
tristate "Analog Devices AD8801/AD8803 DAC driver"
depends on SPI_MASTER
diff --git a/drivers/iio/dac/Makefile b/drivers/iio/dac/Makefile
index 8432a81a1..0fa2849e1 100644
--- a/drivers/iio/dac/Makefile
+++ b/drivers/iio/dac/Makefile
@@ -28,6 +28,7 @@ obj-$(CONFIG_AD5686_SPI) += ad5686-spi.o
obj-$(CONFIG_AD5696_I2C) += ad5696-i2c.o
obj-$(CONFIG_AD7293) += ad7293.o
obj-$(CONFIG_AD7303) += ad7303.o
+obj-$(CONFIG_AD8460) += ad8460.o
obj-$(CONFIG_AD8801) += ad8801.o
obj-$(CONFIG_AD9739A) += ad9739a.o
obj-$(CONFIG_ADI_AXI_DAC) += adi-axi-dac.o
diff --git a/drivers/iio/dac/ad8460.c b/drivers/iio/dac/ad8460.c
new file mode 100644
index 000000000..a94fa4526
--- /dev/null
+++ b/drivers/iio/dac/ad8460.c
@@ -0,0 +1,976 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * AD8460 Waveform generator DAC Driver
+ *
+ * Copyright (C) 2024 Analog Devices, Inc.
+ */
+
+#include <linux/bitfield.h>
+#include <linux/cleanup.h>
+#include <linux/clk.h>
+#include <linux/debugfs.h>
+#include <linux/delay.h>
+#include <linux/dmaengine.h>
+#include <linux/gpio/consumer.h>
+#include <linux/iio/buffer.h>
+#include <linux/iio/buffer-dma.h>
+#include <linux/iio/buffer-dmaengine.h>
+#include <linux/iio/consumer.h>
+#include <linux/iio/events.h>
+#include <linux/iio/iio.h>
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/mod_devicetable.h>
+#include <linux/regmap.h>
+#include <linux/regulator/consumer.h>
+#include <linux/spi/spi.h>
+
+#define AD8460_CTRL_REG(x) (x)
+#define AD8460_HVDAC_DATA_WORD_LOW(x) (0x60 + (2 * (x)))
+#define AD8460_HVDAC_DATA_WORD_HIGH(x) (0x61 + (2 * (x)))
+
+#define AD8460_HV_RESET_MSK BIT(7)
+#define AD8460_HV_SLEEP_MSK BIT(4)
+#define AD8460_WAVE_GEN_MODE_MSK BIT(0)
+
+#define AD8460_HVDAC_SLEEP_MSK BIT(3)
+
+#define AD8460_FAULT_ARM_MSK BIT(7)
+#define AD8460_FAULT_LIMIT_MSK GENMASK(6, 0)
+
+#define AD8460_APG_MODE_ENABLE_MSK BIT(5)
+#define AD8460_PATTERN_DEPTH_MSK GENMASK(3, 0)
+
+#define AD8460_SET_QUIESCENT_CURRENT_MSK GENMASK(7, 0)
+
+#define AD8460_SHUTDOWN_FLAG_MSK BIT(7)
+
+#define AD8460_DATA_BYTE_LOW_MSK GENMASK(7, 0)
+#define AD8460_DATA_BYTE_HIGH_MSK GENMASK(5, 0)
+
+#define AD8460_DATA_BYTE_WORD_LENGTH 2
+#define AD8460_NUM_DATA_WORDS 16
+#define AD8460_NOMINAL_VOLTAGE_SPAN 80
+#define AD8460_MIN_RSET_OHMS 2000
+#define AD8460_MAX_RSET_OHMS 20000
+#define AD8460_MIN_VREFIO_UV 120000
+#define AD8460_MAX_VREFIO_UV 1200000
+#define AD8460_CURRENT_LIMIT_CONV(x) ((x) / 15625)
+#define AD8460_VOLTAGE_LIMIT_CONV(x) ((x) / 1953000)
+#define AD8460_TEMP_LIMIT_CONV(x) (((x) + 266640) / 6510)
+
+enum ad8460_fault_type {
+ AD8460_OVERCURRENT_SRC,
+ AD8460_OVERCURRENT_SNK,
+ AD8460_OVERVOLTAGE_POS,
+ AD8460_OVERVOLTAGE_NEG,
+ AD8460_OVERTEMPERATURE,
+};
+
+struct ad8460_state {
+ struct spi_device *spi;
+ struct regmap *regmap;
+ struct iio_channel *tmp_adc_channel;
+ struct clk *sync_clk;
+ /* lock to protect against multiple access to the device and shared data */
+ struct mutex lock;
+ int refio_1p2v_mv;
+ u32 rset_ohms;
+ /*
+ * DMA (thus cache coherency maintenance) requires the
+ * transfer buffers to live in their own cache lines.
+ */
+ u8 spi_tx_buf[2] __aligned(IIO_DMA_MINALIGN);
+};
+
+static int ad8460_hv_reset(struct ad8460_state *state)
+{
+ int ret;
+
+ ret = regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x00),
+ AD8460_HV_RESET_MSK,
+ FIELD_PREP(AD8460_HV_RESET_MSK, 1));
+ if (ret)
+ return ret;
+
+ fsleep(20);
+
+ return regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x00),
+ AD8460_HV_RESET_MSK,
+ FIELD_PREP(AD8460_HV_RESET_MSK, 0));
+}
+
+static int ad8460_reset(const struct ad8460_state *state)
+{
+ struct device *dev = &state->spi->dev;
+ struct gpio_desc *reset;
+
+ reset = devm_gpiod_get_optional(dev, "reset", GPIOD_OUT_LOW);
+ if (IS_ERR(reset))
+ return dev_err_probe(dev, PTR_ERR(reset),
+ "Failed to get reset gpio");
+ if (reset) {
+ /* minimum duration of 10ns */
+ ndelay(10);
+ gpiod_set_value_cansleep(reset, 1);
+ return 0;
+ }
+
+ /* bring all registers to their default state */
+ return regmap_write(state->regmap, AD8460_CTRL_REG(0x03), 1);
+}
+
+static int ad8460_enable_apg_mode(struct ad8460_state *state, int val)
+{
+ int ret;
+
+ ret = regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x02),
+ AD8460_APG_MODE_ENABLE_MSK,
+ FIELD_PREP(AD8460_APG_MODE_ENABLE_MSK, val));
+ if (ret)
+ return ret;
+
+ return regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x00),
+ AD8460_WAVE_GEN_MODE_MSK,
+ FIELD_PREP(AD8460_WAVE_GEN_MODE_MSK, val));
+}
+
+static int ad8460_read_shutdown_flag(struct ad8460_state *state, u64 *flag)
+{
+ int ret, val;
+
+ ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x0E), &val);
+ if (ret)
+ return ret;
+
+ *flag = FIELD_GET(AD8460_SHUTDOWN_FLAG_MSK, val);
+ return 0;
+}
+
+static ssize_t ad8460_dac_input_read(struct iio_dev *indio_dev,
+ uintptr_t private,
+ const struct iio_chan_spec *chan,
+ char *buf)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ unsigned int reg;
+ int ret;
+
+ ret = ad8460_get_hvdac_word(state, private, ®);
+ if (ret)
+ return ret;
+
+ return sysfs_emit(buf, "%ld\n", reg);
+}
+
+static ssize_t ad8460_dac_input_write(struct iio_dev *indio_dev,
+ uintptr_t private,
+ const struct iio_chan_spec *chan,
+ const char *buf,
+ size_t len)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ unsigned int reg;
+ int ret;
+
+ ret = kstrtou32(buf, ®);
+ if (ret)
+ return ret;
+
+ guard(mutex)(&state->lock);
+
+ return ad8460_set_hvdac_word(state, private, reg);
+}
+
+static ssize_t ad8460_read_symbol(struct iio_dev *indio_dev,
+ uintptr_t private,
+ const struct iio_chan_spec *chan,
+ char *buf)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ unsigned int reg;
+ int ret;
+
+ ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x02), ®);
+ if (ret)
+ return ret;
+
+ return sysfs_emit(buf, "%ld\n", FIELD_GET(AD8460_PATTERN_DEPTH_MSK, reg));
+}
+
+static ssize_t ad8460_write_symbol(struct iio_dev *indio_dev,
+ uintptr_t private,
+ const struct iio_chan_spec *chan,
+ const char *buf,
+ size_t len)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ bool sym;
+ int ret;
+
+ ret = kstrtou16(buf, &sym);
+ if (ret)
+ return ret;
+
+ guard(mutex)(&state->lock);
+
+ return regmap_update_bits(state->regmap,
+ AD8460_CTRL_REG(0x02),
+ AD8460_PATTERN_DEPTH_MSK,
+ FIELD_PREP(AD8460_PATTERN_DEPTH_MSK, sym));
+}
+
+static ssize_t ad8460_read_toggle_en(struct iio_dev *indio_dev,
+ uintptr_t private,
+ const struct iio_chan_spec *chan,
+ char *buf)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ unsigned int reg;
+ int ret;
+
+ ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x02), ®);
+ if (ret)
+ return ret;
+
+ return sysfs_emit(buf, "%ld\n", FIELD_GET(AD8460_APG_MODE_ENABLE_MSK, reg));
+}
+
+static ssize_t ad8460_write_toggle_en(struct iio_dev *indio_dev,
+ uintptr_t private,
+ const struct iio_chan_spec *chan,
+ const char *buf,
+ size_t len)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ bool toggle_en;
+ int ret;
+
+ ret = kstrtou16(buf, &toggle_en);
+ if (ret)
+ return ret;
+
+ iio_device_claim_direct_scoped(return -EBUSY, indio_dev)
+ return ad8460_enable_apg_mode(state, toggle_en);
+ unreachable();
+}
+
+static ssize_t ad8460_read_powerdown(struct iio_dev *indio_dev,
+ uintptr_t private,
+ const struct iio_chan_spec *chan,
+ char *buf)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ unsigned int reg;
+ int ret;
+
+ ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x01), ®);
+ if (ret)
+ return ret;
+
+ return sysfs_emit(buf, "%ld\n", FIELD_GET(AD8460_HVDAC_SLEEP_MSK, reg));
+}
+
+static ssize_t ad8460_write_powerdown(struct iio_dev *indio_dev,
+ uintptr_t private,
+ const struct iio_chan_spec *chan,
+ const char *buf,
+ size_t len)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ bool pwr_down;
+ u64 sdn_flag;
+ int ret;
+
+ ret = kstrtobool(buf, &pwr_down);
+ if (ret)
+ return ret;
+
+ guard(mutex)(&state->lock);
+
+ ret = regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x01),
+ AD8460_HVDAC_SLEEP_MSK,
+ FIELD_PREP(AD8460_HVDAC_SLEEP_MSK, pwr_down));
+ if (ret)
+ return ret;
+
+ if (!pwr_down) {
+ ret = ad8460_read_shutdown_flag(state, &sdn_flag);
+ if (ret)
+ return ret;
+
+ if (sdn_flag) {
+ ret = ad8460_hv_reset(state);
+ if (ret)
+ return ret;
+ }
+ }
+
+ ret = regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x00),
+ AD8460_HV_SLEEP_MSK,
+ FIELD_PREP(AD8460_HV_SLEEP_MSK, !pwr_down));
+ if (ret)
+ return ret;
+
+ return len;
+}
+
+static const char * const ad8460_powerdown_modes[] = {
+ "three_state",
+};
+
+static int ad8460_get_powerdown_mode(struct iio_dev *indio_dev,
+ const struct iio_chan_spec *chan)
+{
+ return 0;
+}
+
+static int ad8460_set_powerdown_mode(struct iio_dev *indio_dev,
+ const struct iio_chan_spec *chan,
+ unsigned int type)
+{
+ return 0;
+}
+
+static int ad8460_get_hvdac_word(struct ad8460_state *state,
+ int index,
+ int *val)
+{
+ int ret;
+
+ ret = regmap_bulk_read(state->regmap, AD8460_HVDAC_DATA_WORD_LOW(index),
+ &state->spi_tx_buf, AD8460_DATA_BYTE_WORD_LENGTH);
+ if (ret)
+ return ret;
+
+ *val = get_unaligned_le16(state->spi_tx_buf);
+
+ return ret;
+}
+
+static int ad8460_set_hvdac_word(struct ad8460_state *state,
+ int index,
+ int val)
+{
+ put_unaligned_le16(val & 0x3FFF, &state->spi_tx_buf);
+
+ return regmap_bulk_write(state->regmap, AD8460_HVDAC_DATA_WORD_LOW(index),
+ state->spi_tx_buf, AD8460_DATA_BYTE_WORD_LENGTH);
+}
+
+static int ad8460_set_sample(struct ad8460_state *state, int val)
+{
+ int ret;
+
+ ret = ad8460_enable_apg_mode(state, 1);
+ if (ret)
+ return ret;
+
+ guard(mutex)(&state->lock);
+ ret = ad8460_set_hvdac_word(state, 0, val);
+ if (ret)
+ return ret;
+
+ return regmap_update_bits(state->regmap,
+ AD8460_CTRL_REG(0x02),
+ AD8460_PATTERN_DEPTH_MSK,
+ FIELD_PREP(AD8460_PATTERN_DEPTH_MSK, 0));
+}
+
+static int ad8460_set_fault_threshold(struct ad8460_state *state,
+ enum ad8460_fault_type fault,
+ unsigned int threshold)
+{
+ return regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x08 + fault),
+ AD8460_FAULT_LIMIT_MSK,
+ FIELD_PREP(AD8460_FAULT_LIMIT_MSK, threshold));
+}
+
+static int ad8460_get_fault_threshold(struct ad8460_state *state,
+ enum ad8460_fault_type fault,
+ unsigned int *threshold)
+{
+ unsigned int val;
+ int ret;
+
+ ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x08 + fault), &val);
+ if (ret)
+ return ret;
+
+ *threshold = FIELD_GET(AD8460_FAULT_LIMIT_MSK, val);
+
+ return ret;
+}
+
+static int ad8460_set_fault_threshold_en(struct ad8460_state *state,
+ enum ad8460_fault_type fault,
+ bool en)
+{
+ return regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x08 + fault),
+ AD8460_FAULT_ARM_MSK,
+ FIELD_PREP(AD8460_FAULT_ARM_MSK, en));
+}
+
+static int ad8460_get_fault_threshold_en(struct ad8460_state *state,
+ enum ad8460_fault_type fault,
+ bool *en)
+{
+ unsigned int val;
+ int ret;
+
+ ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x08 + fault), &val);
+ if (ret)
+ return ret;
+
+ *en = FIELD_GET(AD8460_FAULT_ARM_MSK, val);
+
+ return 0;
+}
+
+static int ad8460_write_raw(struct iio_dev *indio_dev,
+ struct iio_chan_spec const *chan,
+ int val,
+ int val2,
+ long mask)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+
+ switch (mask) {
+ case IIO_CHAN_INFO_RAW:
+ switch (chan->type) {
+ case IIO_VOLTAGE:
+ iio_device_claim_direct_scoped(return -EBUSY, indio_dev)
+ return ad8460_set_sample(state, val);
+ unreachable();
+ case IIO_CURRENT:
+ return regmap_write(state->regmap, AD8460_CTRL_REG(0x04),
+ FIELD_PREP(AD8460_SET_QUIESCENT_CURRENT_MSK, val));
+ default:
+ return -EINVAL;
+ }
+ default:
+ return -EINVAL;
+ }
+}
+
+static int ad8460_read_raw(struct iio_dev *indio_dev,
+ struct iio_chan_spec const *chan,
+ int *val,
+ int *val2,
+ long mask)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ int data, ret;
+
+ switch (mask) {
+ case IIO_CHAN_INFO_RAW:
+ switch (chan->type) {
+ case IIO_VOLTAGE:
+ scoped_guard(mutex, &state->lock) {
+ ret = ad8460_get_hvdac_word(state, 0, &data);
+ if (ret)
+ return ret;
+ }
+ *val = data;
+ return IIO_VAL_INT;
+ case IIO_CURRENT:
+ ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x04), &data);
+ if (ret)
+ return ret;
+ *val = data;
+ return IIO_VAL_INT;
+ case IIO_TEMP:
+ ret = iio_read_channel_raw(state->tmp_adc_channel, &data);
+ if (ret)
+ return ret;
+ *val = data;
+ return IIO_VAL_INT;
+ default:
+ return -EINVAL;
+ }
+ case IIO_CHAN_INFO_SAMP_FREQ:
+ *val = clk_get_rate(state->sync_clk);
+ return IIO_VAL_INT;
+ case IIO_CHAN_INFO_SCALE:
+ /* vCONV = vNOMINAL_SPAN * (DAC_CODE / 2**14) - 40V
+ * vMAX = vNOMINAL_SPAN * (2**14 / 2**14) - 40V
+ * vMIN = vNOMINAL_SPAN * (0 / 2**14) - 40V
+ * vADJ = vCONV * (2000 / rSET) * (vREF / 1.2)
+ * vSPAN = vADJ_MAX - vADJ_MIN
+ * See datasheet page 49, section FULL-SCALE REDUCTION
+ */
+ *val = AD8460_NOMINAL_VOLTAGE_SPAN * 2000 * state->refio_1p2v_mv;
+ *val2 = state->rset_ohms * 1200;
+ return IIO_VAL_FRACTIONAL;
+ default:
+ return -EINVAL;
+ }
+}
+
+static int ad8460_select_fault_type(int chan_type, enum iio_event_direction dir)
+{
+ switch (chan_type) {
+ case IIO_VOLTAGE:
+ switch (dir) {
+ case IIO_EV_DIR_RISING:
+ return AD8460_OVERVOLTAGE_POS;
+ case IIO_EV_DIR_FALLING:
+ return AD8460_OVERVOLTAGE_NEG;
+ default:
+ return -EINVAL;
+ }
+ break;
+ case IIO_CURRENT:
+ switch (dir) {
+ case IIO_EV_DIR_RISING:
+ return AD8460_OVERCURRENT_SRC;
+ case IIO_EV_DIR_FALLING:
+ return AD8460_OVERCURRENT_SNK;
+ default:
+ return -EINVAL;
+ }
+ break;
+ case IIO_TEMP:
+ switch (dir) {
+ case IIO_EV_DIR_RISING:
+ return AD8460_OVERTEMPERATURE;
+ default:
+ return -EINVAL;
+ }
+ default:
+ return -EINVAL;
+ }
+}
+
+static int ad8460_write_event_value(struct iio_dev *indio_dev,
+ const struct iio_chan_spec *chan,
+ enum iio_event_type type,
+ enum iio_event_direction dir,
+ enum iio_event_info info, int val, int val2)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ unsigned int fault;
+
+ if (type != IIO_EV_TYPE_THRESH)
+ return -EINVAL;
+
+ if (info != IIO_EV_INFO_VALUE)
+ return -EINVAL;
+
+ fault = ad8460_select_fault_type(chan->type, dir);
+ if (fault < 0)
+ return fault;
+
+ return ad8460_set_fault_threshold(state, fault, val);
+}
+
+static int ad8460_read_event_value(struct iio_dev *indio_dev,
+ const struct iio_chan_spec *chan,
+ enum iio_event_type type,
+ enum iio_event_direction dir,
+ enum iio_event_info info, int *val, int *val2)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ unsigned int fault;
+
+ if (type != IIO_EV_TYPE_THRESH)
+ return -EINVAL;
+
+ if (info != IIO_EV_INFO_VALUE)
+ return -EINVAL;
+
+ fault = ad8460_select_fault_type(chan->type, dir);
+ if (fault < 0)
+ return fault;
+
+ return ad8460_get_fault_threshold(state, fault, val);
+}
+
+static int ad8460_write_event_config(struct iio_dev *indio_dev,
+ const struct iio_chan_spec *chan,
+ enum iio_event_type type,
+ enum iio_event_direction dir, int val)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ unsigned int fault;
+
+ if (type != IIO_EV_TYPE_THRESH)
+ return -EINVAL;
+
+ fault = ad8460_select_fault_type(chan->type, dir);
+ if (fault < 0)
+ return fault;
+
+ return ad8460_set_fault_threshold_en(state, fault, val);
+}
+
+static int ad8460_read_event_config(struct iio_dev *indio_dev,
+ const struct iio_chan_spec *chan,
+ enum iio_event_type type,
+ enum iio_event_direction dir)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+ unsigned int fault;
+ bool en;
+ int ret;
+
+ if (type != IIO_EV_TYPE_THRESH)
+ return -EINVAL;
+
+ fault = ad8460_select_fault_type(chan->type, dir);
+ if (fault < 0)
+ return fault;
+
+ ret = ad8460_get_fault_threshold_en(state, fault, &en);
+ return ret ?: en;
+}
+
+static int ad8460_reg_access(struct iio_dev *indio_dev,
+ unsigned int reg, unsigned int writeval,
+ unsigned int *readval)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+
+ if (readval)
+ return regmap_read(state->regmap, reg, readval);
+
+ return regmap_write(state->regmap, reg, writeval);
+}
+
+static int ad8460_buffer_preenable(struct iio_dev *indio_dev)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+
+ return ad8460_enable_apg_mode(state, 0);
+}
+
+static int ad8460_buffer_postdisable(struct iio_dev *indio_dev)
+{
+ struct ad8460_state *state = iio_priv(indio_dev);
+
+ return ad8460_enable_apg_mode(state, 1);
+}
+
+static const struct iio_buffer_setup_ops ad8460_buffer_setup_ops = {
+ .preenable = &ad8460_buffer_preenable,
+ .postdisable = &ad8460_buffer_postdisable,
+};
+
+static const struct iio_info ad8460_info = {
+ .read_raw = &ad8460_read_raw,
+ .write_raw = &ad8460_write_raw,
+ .write_event_value = &ad8460_write_event_value,
+ .read_event_value = &ad8460_read_event_value,
+ .write_event_config = &ad8460_write_event_config,
+ .read_event_config = &ad8460_read_event_config,
+ .debugfs_reg_access = &ad8460_reg_access,
+};
+
+static const struct iio_enum ad8460_powerdown_mode_enum = {
+ .items = ad8460_powerdown_modes,
+ .num_items = ARRAY_SIZE(ad8460_powerdown_modes),
+ .get = ad8460_get_powerdown_mode,
+ .set = ad8460_set_powerdown_mode,
+};
+
+#define AD8460_CHAN_EXT_INFO(_name, _what, _shared, _read, _write) { \
+ .name = _name, \
+ .read = (_read), \
+ .write = (_write), \
+ .private = (_what), \
+ .shared = (_shared), \
+}
+
+static struct iio_chan_spec_ext_info ad8460_ext_info[] = {
+ AD8460_CHAN_EXT_INFO("raw0", 0, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw1", 1, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw2", 2, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw3", 3, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw4", 4, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw5", 5, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw6", 6, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw7", 7, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw8", 8, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw9", 9, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw10", 10, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw11", 11, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw12", 12, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw13", 13, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw14", 14, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("raw15", 15, IIO_SEPARATE,
+ ad8460_dac_input_read, ad8460_dac_input_write),
+ AD8460_CHAN_EXT_INFO("toggle_en", 0, IIO_SEPARATE,
+ ad8460_read_toggle_en,
+ ad8460_write_toggle_en),
+ AD8460_CHAN_EXT_INFO("symbol", 0, IIO_SEPARATE,
+ ad8460_read_symbol,
+ ad8460_write_symbol),
+ AD8460_CHAN_EXT_INFO("powerdown", 0, IIO_SEPARATE,
+ ad8460_read_powerdown, ad8460_write_powerdown),
+ IIO_ENUM("powerdown_mode", IIO_SEPARATE, &ad8460_powerdown_mode_enum),
+ IIO_ENUM_AVAILABLE("powerdown_mode", IIO_SHARED_BY_TYPE,
+ &ad8460_powerdown_mode_enum),
+ {}
+};
+
+static const struct iio_event_spec ad8460_events[] = {
+ {
+ .type = IIO_EV_TYPE_THRESH,
+ .dir = IIO_EV_DIR_RISING,
+ .mask_separate = BIT(IIO_EV_INFO_VALUE) |
+ BIT(IIO_EV_INFO_ENABLE),
+ },
+ {
+ .type = IIO_EV_TYPE_THRESH,
+ .dir = IIO_EV_DIR_FALLING,
+ .mask_separate = BIT(IIO_EV_INFO_VALUE) |
+ BIT(IIO_EV_INFO_ENABLE),
+ },
+};
+
+#define AD8460_VOLTAGE_CHAN(_chan) { \
+ .type = IIO_VOLTAGE, \
+ .info_mask_separate = BIT(IIO_CHAN_INFO_SAMP_FREQ) | \
+ BIT(IIO_CHAN_INFO_RAW) | \
+ BIT(IIO_CHAN_INFO_SCALE), \
+ .output = 1, \
+ .indexed = 1, \
+ .channel = (_chan), \
+ .scan_index = 0, \
+ .scan_type = { \
+ .sign = 'u', \
+ .realbits = 14, \
+ .storagebits = 16, \
+ .endianness = IIO_LE, \
+ }, \
+ .ext_info = ad8460_ext_info, \
+ .event_spec = ad8460_events, \
+ .num_event_specs = ARRAY_SIZE(ad8460_events), \
+}
+
+#define AD8460_CURRENT_CHAN(_chan) { \
+ .type = IIO_CURRENT, \
+ .info_mask_separate = BIT(IIO_CHAN_INFO_RAW), \
+ .output = 0, \
+ .indexed = 1, \
+ .channel = (_chan), \
+ .scan_index = 1, \
+ .scan_type = { \
+ .sign = 'u', \
+ .realbits = 8, \
+ .storagebits = 8, \
+ .endianness = IIO_LE, \
+ }, \
+ .event_spec = ad8460_events, \
+ .num_event_specs = ARRAY_SIZE(ad8460_events), \
+}
+
+#define AD8460_TEMP_CHAN(_chan) { \
+ .type = IIO_TEMP, \
+ .info_mask_separate = BIT(IIO_CHAN_INFO_RAW), \
+ .output = 1, \
+ .indexed = 1, \
+ .channel = (_chan), \
+ .scan_index = 2, \
+ .scan_type = { \
+ .sign = 'u', \
+ .endianness = IIO_LE, \
+ }, \
+ .event_spec = ad8460_events, \
+ .num_event_specs = 1, \
+}
+
+static const struct iio_chan_spec ad8460_channels[] = {
+ AD8460_VOLTAGE_CHAN(0),
+ AD8460_CURRENT_CHAN(0),
+};
+
+static const struct iio_chan_spec ad8460_channels_with_tmp_adc[] = {
+ AD8460_VOLTAGE_CHAN(0),
+ AD8460_CURRENT_CHAN(0),
+ AD8460_TEMP_CHAN(0),
+};
+
+static const struct regmap_config ad8460_regmap_config = {
+ .reg_bits = 8,
+ .val_bits = 8,
+ .max_register = 0x7F,
+};
+
+static int ad8460_probe(struct spi_device *spi)
+{
+ struct ad8460_state *state;
+ struct iio_dev *indio_dev;
+ struct regulator *refio_1p2v;
+ u32 tmp[2], temp;
+ int ret;
+
+ indio_dev = devm_iio_device_alloc(&spi->dev, sizeof(*state));
+ if (!indio_dev)
+ return -ENOMEM;
+
+ state = iio_priv(indio_dev);
+ mutex_init(&state->lock);
+
+ indio_dev->name = "ad8460";
+ indio_dev->info = &ad8460_info;
+
+ state->spi = spi;
+
+ state->regmap = devm_regmap_init_spi(spi, &ad8460_regmap_config);
+ if (IS_ERR(state->regmap))
+ return dev_err_probe(&spi->dev, PTR_ERR(state->regmap),
+ "Failed to initialize regmap");
+
+ state->sync_clk = devm_clk_get_enabled(&spi->dev, NULL);
+ if (IS_ERR(state->sync_clk))
+ return dev_err_probe(&spi->dev, PTR_ERR(state->sync_clk),
+ "Failed to get sync clk\n");
+
+ state->tmp_adc_channel = devm_iio_channel_get(&spi->dev, "ad8460-tmp");
+ if (IS_ERR_OR_NULL(state->tmp_adc_channel)) {
+ indio_dev->channels = ad8460_channels;
+ indio_dev->num_channels = ARRAY_SIZE(ad8460_channels);
+ } else {
+ indio_dev->channels = ad8460_channels_with_tmp_adc;
+ indio_dev->num_channels = ARRAY_SIZE(ad8460_channels_with_tmp_adc);
+ dev_info(&spi->dev, "Found ADC channel to read TMP pin\n");
+ }
+
+ ret = devm_regulator_get_enable_read_voltage(&spi->dev, "refio_1p2v");
+ if (ret == -ENODEV) {
+ state->refio_1p2v_mv = 1200;
+ } else if (ret < 0) {
+ return dev_err_probe(&spi->dev, PTR_ERR(vrefio),
+ "Failed to get reference voltage\n");
+ } else {
+ state->refio_1p2v_mv = ret / 1000;
+ }
+
+ if (!in_range(ret, AD8460_MIN_VREFIO_UV, AD8460_MAX_VREFIO_UV))
+ return dev_err_probe(&spi->dev, -EINVAL,
+ "Invalid ref voltage range(%u mV) [%u mV, %u mV]\n",
+ ret, AD8460_MIN_VREFIO_UV / 1000,
+ AD8460_MAX_VREFIO_UV / 1000);
+
+ ret = device_property_read_u32(&spi->dev, "adi,rset-ohms", &state->rset_ohms);
+ if (ret) {
+ state->rset_ohms = 2000;
+ } else {
+ if (!in_range(state->rset_ohms, AD8460_MIN_RSET_OHMS,
+ AD8460_MAX_RSET_OHMS))
+ return dev_err_probe(&spi->dev, -EINVAL,
+ "Invalid resistor set range(%u) [%u, %u]\n",
+ state->rset_ohms,
+ AD8460_MIN_RSET_OHMS,
+ AD8460_MAX_RSET_OHMS);
+ }
+
+ /* Arm the device by default */
+ ret = device_property_read_u32_array(&spi->dev, "adi,range-microamp",
+ tmp, ARRAY_SIZE(tmp));
+ if (!ret) {
+ ret = regmap_write(state->regmap, AD8460_CTRL_REG(0x08),
+ (1 << 7) | AD8460_CURRENT_LIMIT_CONV(tmp[1]));
+ if (ret)
+ return dev_err_probe(&spi->dev, -EINVAL,
+ "overcurrent src not valid: %d uA",
+ tmp[1]);
+
+ ret = regmap_write(state->regmap, AD8460_CTRL_REG(0x09),
+ (1 << 7) | AD8460_CURRENT_LIMIT_CONV(abs(tmp[0])));
+ if (ret)
+ return dev_err_probe(&spi->dev, -EINVAL,
+ "overcurrent snk not valid: %d uA",
+ tmp[0]);
+ }
+
+ ret = device_property_read_u32_array(&spi->dev, "adi,range-microvolt",
+ tmp, ARRAY_SIZE(tmp));
+ if (!ret) {
+ ret = regmap_write(state->regmap, AD8460_CTRL_REG(0x0A),
+ (1 << 7) | AD8460_VOLTAGE_LIMIT_CONV(tmp[1]));
+ if (ret)
+ return dev_err_probe(&spi->dev, -EINVAL,
+ "positive overvoltage not valid: %d uV",
+ tmp[1]);
+
+ ret = regmap_write(state->regmap, AD8460_CTRL_REG(0x0B),
+ (1 << 7) | AD8460_VOLTAGE_LIMIT_CONV(abs(tmp[0])));
+ if (ret)
+ return dev_err_probe(&spi->dev, -EINVAL,
+ "negative overvoltage not valid: %d uV",
+ tmp[0]);
+ }
+
+ ret = device_property_read_u32(&spi->dev, "adi,temp-max-millicelsius", &temp);
+ if (!ret) {
+ ret = regmap_write(state->regmap, AD8460_CTRL_REG(0x0C),
+ (1 << 7) | AD8460_TEMP_LIMIT_CONV(abs(temp)));
+ if (ret)
+ return dev_err_probe(&spi->dev, -EINVAL,
+ "overtemperature not valid: %d",
+ temp);
+ }
+
+ ret = ad8460_reset(state);
+ if (ret)
+ return ret;
+
+ /* Enables DAC by default */
+ ret = regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x01),
+ AD8460_HVDAC_SLEEP_MSK,
+ FIELD_PREP(AD8460_HVDAC_SLEEP_MSK, 0));
+ if (ret)
+ return ret;
+
+ indio_dev->modes = INDIO_DIRECT_MODE;
+ indio_dev->setup_ops = &ad8460_buffer_setup_ops;
+
+ ret = devm_iio_dmaengine_buffer_setup_ext(&spi->dev, indio_dev, "tx",
+ IIO_BUFFER_DIRECTION_OUT);
+ if (ret)
+ return dev_err_probe(&spi->dev, ret,
+ "Failed to get DMA buffer\n");
+
+ ret = devm_iio_device_register(&spi->dev, indio_dev);
+ if (ret)
+ return ret;
+
+ return 0;
+}
+
+static const struct of_device_id ad8460_of_match[] = {
+ { .compatible = "adi, ad8460" },
+ { }
+};
+MODULE_DEVICE_TABLE(of, ad8460_of_match);
+
+static struct spi_driver ad8460_driver = {
+ .driver = {
+ .name = "ad8460",
+ .of_match_table = ad8460_of_match,
+ },
+ .probe = ad8460_probe,
+};
+module_spi_driver(ad8460_driver);
+
+MODULE_AUTHOR("Mariel Tinaco <mariel.tinaco@analog.com");
+MODULE_DESCRIPTION("AD8460 DAC driver");
+MODULE_LICENSE("GPL");
+MODULE_IMPORT_NS(IIO_DMAENGINE_BUFFER);
--
2.34.1
On Tue, 30 Jul 2024 11:05:09 +0800
Mariel Tinaco <Mariel.Tinaco@analog.com> wrote:
> The AD8460 is a “bits in, power out” high voltage, high-power,
> high-speed driver optimized for large output current (up to ±1 A)
> and high slew rate (up to ±1800 V/μs) at high voltage (up to ±40 V)
> into capacitive loads.
>
> A digital engine implements user-configurable features: modes for
> digital input, programmable supply current, and fault monitoring
> and programmable protection settings for output current,
> output voltage, and junction temperature. The AD8460 operates on
> high voltage dual supplies up to ±55 V and a single low voltage
> supply of 5 V.
>
> Signed-off-by: Mariel Tinaco <Mariel.Tinaco@analog.com>
Hi Mariel,
The test bot detected problems don't give me a high degree of confidence
in this driver in general. Please be much more careful and thorough in
build tests for v3.
Various minor comments inline
Jonathan
> diff --git a/drivers/iio/dac/ad8460.c b/drivers/iio/dac/ad8460.c
> new file mode 100644
> index 000000000..a94fa4526
> --- /dev/null
> +++ b/drivers/iio/dac/ad8460.c
> @@ -0,0 +1,976 @@
> +static int ad8460_set_hvdac_word(struct ad8460_state *state,
> + int index,
> + int val)
> +{
> + put_unaligned_le16(val & 0x3FFF, &state->spi_tx_buf);
GENMASK for that constant.
> +
> + return regmap_bulk_write(state->regmap, AD8460_HVDAC_DATA_WORD_LOW(index),
> + state->spi_tx_buf, AD8460_DATA_BYTE_WORD_LENGTH);
> +}
> +
> +static int ad8460_write_raw(struct iio_dev *indio_dev,
> + struct iio_chan_spec const *chan,
> + int val,
> + int val2,
> + long mask)
Aim for wrapping to below 80 chars, not much shorter.
Feel free to group parameters though if you want to.
> +{
> + struct ad8460_state *state = iio_priv(indio_dev);
> +
> + switch (mask) {
> + case IIO_CHAN_INFO_RAW:
> + switch (chan->type) {
> + case IIO_VOLTAGE:
> + iio_device_claim_direct_scoped(return -EBUSY, indio_dev)
> + return ad8460_set_sample(state, val);
> + unreachable();
> + case IIO_CURRENT:
> + return regmap_write(state->regmap, AD8460_CTRL_REG(0x04),
> + FIELD_PREP(AD8460_SET_QUIESCENT_CURRENT_MSK, val));
> + default:
> + return -EINVAL;
> + }
> + default:
> + return -EINVAL;
> + }
> +}
> +
> +static int ad8460_read_raw(struct iio_dev *indio_dev,
> + struct iio_chan_spec const *chan,
> + int *val,
> + int *val2,
> + long mask)
> +{
> + struct ad8460_state *state = iio_priv(indio_dev);
> + int data, ret;
> +
> + switch (mask) {
> + case IIO_CHAN_INFO_RAW:
> + switch (chan->type) {
> + case IIO_VOLTAGE:
> + scoped_guard(mutex, &state->lock) {
> + ret = ad8460_get_hvdac_word(state, 0, &data);
> + if (ret)
> + return ret;
> + }
> + *val = data;
> + return IIO_VAL_INT;
> + case IIO_CURRENT:
> + ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x04), &data);
> + if (ret)
> + return ret;
> + *val = data;
> + return IIO_VAL_INT;
> + case IIO_TEMP:
> + ret = iio_read_channel_raw(state->tmp_adc_channel, &data);
> + if (ret)
> + return ret;
> + *val = data;
> + return IIO_VAL_INT;
> + default:
> + return -EINVAL;
> + }
> + case IIO_CHAN_INFO_SAMP_FREQ:
> + *val = clk_get_rate(state->sync_clk);
> + return IIO_VAL_INT;
> + case IIO_CHAN_INFO_SCALE:
> + /* vCONV = vNOMINAL_SPAN * (DAC_CODE / 2**14) - 40V
/*
* vCONV ...
for IIO multiline comment syntax.
> + * vMAX = vNOMINAL_SPAN * (2**14 / 2**14) - 40V
> + * vMIN = vNOMINAL_SPAN * (0 / 2**14) - 40V
> + * vADJ = vCONV * (2000 / rSET) * (vREF / 1.2)
> + * vSPAN = vADJ_MAX - vADJ_MIN
> + * See datasheet page 49, section FULL-SCALE REDUCTION
> + */
> + *val = AD8460_NOMINAL_VOLTAGE_SPAN * 2000 * state->refio_1p2v_mv;
> + *val2 = state->rset_ohms * 1200;
> + return IIO_VAL_FRACTIONAL;
> + default:
> + return -EINVAL;
> + }
> +}
> +
> +static int ad8460_select_fault_type(int chan_type, enum iio_event_direction dir)
> +{
> + switch (chan_type) {
> + case IIO_VOLTAGE:
> + switch (dir) {
> + case IIO_EV_DIR_RISING:
> + return AD8460_OVERVOLTAGE_POS;
> + case IIO_EV_DIR_FALLING:
> + return AD8460_OVERVOLTAGE_NEG;
> + default:
> + return -EINVAL;
> + }
> + break;
as below.
> + case IIO_CURRENT:
> + switch (dir) {
> + case IIO_EV_DIR_RISING:
> + return AD8460_OVERCURRENT_SRC;
> + case IIO_EV_DIR_FALLING:
> + return AD8460_OVERCURRENT_SNK;
> + default:
> + return -EINVAL;
> + }
> + break;
Can't get here. So drop the break.
> + case IIO_TEMP:
> + switch (dir) {
> + case IIO_EV_DIR_RISING:
> + return AD8460_OVERTEMPERATURE;
> + default:
> + return -EINVAL;
> + }
> + default:
> + return -EINVAL;
> + }
> +}
> +static int ad8460_read_event_config(struct iio_dev *indio_dev,
> + const struct iio_chan_spec *chan,
> + enum iio_event_type type,
> + enum iio_event_direction dir)
> +{
> + struct ad8460_state *state = iio_priv(indio_dev);
> + unsigned int fault;
> + bool en;
> + int ret;
> +
> + if (type != IIO_EV_TYPE_THRESH)
> + return -EINVAL;
> +
> + fault = ad8460_select_fault_type(chan->type, dir);
> + if (fault < 0)
> + return fault;
> +
> + ret = ad8460_get_fault_threshold_en(state, fault, &en);
> + return ret ?: en;
Keep to simpler to read
if (ret)
return ret;
return en;
> +}
> +
> +static struct iio_chan_spec_ext_info ad8460_ext_info[] = {
> + AD8460_CHAN_EXT_INFO("raw0", 0, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw1", 1, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw2", 2, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw3", 3, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw4", 4, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw5", 5, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw6", 6, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw7", 7, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw8", 8, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw9", 9, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw10", 10, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw11", 11, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw12", 12, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw13", 13, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw14", 14, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("raw15", 15, IIO_SEPARATE,
> + ad8460_dac_input_read, ad8460_dac_input_write),
> + AD8460_CHAN_EXT_INFO("toggle_en", 0, IIO_SEPARATE,
> + ad8460_read_toggle_en,
> + ad8460_write_toggle_en),
> + AD8460_CHAN_EXT_INFO("symbol", 0, IIO_SEPARATE,
> + ad8460_read_symbol,
> + ad8460_write_symbol),
Wrap closer to 80 chars.
> + AD8460_CHAN_EXT_INFO("powerdown", 0, IIO_SEPARATE,
> + ad8460_read_powerdown, ad8460_write_powerdown),
> + IIO_ENUM("powerdown_mode", IIO_SEPARATE, &ad8460_powerdown_mode_enum),
> + IIO_ENUM_AVAILABLE("powerdown_mode", IIO_SHARED_BY_TYPE,
> + &ad8460_powerdown_mode_enum),
> + {}
> +};
> +
> +static const struct iio_event_spec ad8460_events[] = {
> + {
> + .type = IIO_EV_TYPE_THRESH,
> + .dir = IIO_EV_DIR_RISING,
> + .mask_separate = BIT(IIO_EV_INFO_VALUE) |
> + BIT(IIO_EV_INFO_ENABLE),
> + },
> + {
> + .type = IIO_EV_TYPE_THRESH,
> + .dir = IIO_EV_DIR_FALLING,
> + .mask_separate = BIT(IIO_EV_INFO_VALUE) |
> + BIT(IIO_EV_INFO_ENABLE),
> + },
> +};
> +
> +#define AD8460_VOLTAGE_CHAN(_chan) { \
> + .type = IIO_VOLTAGE, \
> + .info_mask_separate = BIT(IIO_CHAN_INFO_SAMP_FREQ) | \
> + BIT(IIO_CHAN_INFO_RAW) | \
> + BIT(IIO_CHAN_INFO_SCALE), \
> + .output = 1, \
> + .indexed = 1, \
> + .channel = (_chan), \
> + .scan_index = 0, \
> + .scan_type = { \
> + .sign = 'u', \
> + .realbits = 14, \
> + .storagebits = 16, \
> + .endianness = IIO_LE, \
> + }, \
> + .ext_info = ad8460_ext_info, \
> + .event_spec = ad8460_events, \
> + .num_event_specs = ARRAY_SIZE(ad8460_events), \
> +}
> +
> +#define AD8460_CURRENT_CHAN(_chan) { \
> + .type = IIO_CURRENT, \
> + .info_mask_separate = BIT(IIO_CHAN_INFO_RAW), \
> + .output = 0, \
I'm guessing this is also not used with the buffer.
set scan_index = -1 if so.
> + .indexed = 1, \
> + .channel = (_chan), \
> + .scan_index = 1, \
> + .scan_type = { \
> + .sign = 'u', \
> + .realbits = 8, \
> + .storagebits = 8, \
> + .endianness = IIO_LE, \
Generally don't provide these if you aren't using them for buffered
capture. It's just unnecessary noise in the driver.
> + }, \
> + .event_spec = ad8460_events, \
> + .num_event_specs = ARRAY_SIZE(ad8460_events), \
> +}
> +
> +#define AD8460_TEMP_CHAN(_chan) { \
> + .type = IIO_TEMP, \
> + .info_mask_separate = BIT(IIO_CHAN_INFO_RAW), \
> + .output = 1, \
> + .indexed = 1, \
> + .channel = (_chan), \
> + .scan_index = 2, \
> + .scan_type = { \
No sizing?
I suspect you don't want to present this for the buffered interface.
If so, set .scan_index = -1
> + .sign = 'u', \
> + .endianness = IIO_LE, \
> + }, \
> + .event_spec = ad8460_events, \
> + .num_event_specs = 1, \
> +}
> +
> +static const struct iio_chan_spec ad8460_channels[] = {
> + AD8460_VOLTAGE_CHAN(0),
> + AD8460_CURRENT_CHAN(0),
> +};
> +
> +static const struct iio_chan_spec ad8460_channels_with_tmp_adc[] = {
> + AD8460_VOLTAGE_CHAN(0),
> + AD8460_CURRENT_CHAN(0),
> + AD8460_TEMP_CHAN(0),
> +};
Unless you plan to very soon add support for devices with more channels,
drop the parameter and hardcode 0 in the definitions.
Chances are that if you do get a more complex device with more channels
you will need more than just a channel number anyway so this code
will change either way. Hence better to keep it simple for now.
> +static int ad8460_probe(struct spi_device *spi)
> +{
> + struct ad8460_state *state;
> + struct iio_dev *indio_dev;
> + struct regulator *refio_1p2v;
> + u32 tmp[2], temp;
> + int ret;
> +
> + indio_dev = devm_iio_device_alloc(&spi->dev, sizeof(*state));
> + if (!indio_dev)
> + return -ENOMEM;
> +
> + state = iio_priv(indio_dev);
> + mutex_init(&state->lock);
> +
> + indio_dev->name = "ad8460";
> + indio_dev->info = &ad8460_info;
> +
> + state->spi = spi;
> +
> + state->regmap = devm_regmap_init_spi(spi, &ad8460_regmap_config);
> + if (IS_ERR(state->regmap))
> + return dev_err_probe(&spi->dev, PTR_ERR(state->regmap),
> + "Failed to initialize regmap");
> +
> + state->sync_clk = devm_clk_get_enabled(&spi->dev, NULL);
Lots of use of spi->dev, I'd suggest
struct device *dev = &spi->dev;
then replace all these instances with that local variable.
> + if (IS_ERR(state->sync_clk))
> + return dev_err_probe(&spi->dev, PTR_ERR(state->sync_clk),
> + "Failed to get sync clk\n");
> +
> + state->tmp_adc_channel = devm_iio_channel_get(&spi->dev, "ad8460-tmp");
> + if (IS_ERR_OR_NULL(state->tmp_adc_channel)) {
> + indio_dev->channels = ad8460_channels;
> + indio_dev->num_channels = ARRAY_SIZE(ad8460_channels);
> + } else {
> + indio_dev->channels = ad8460_channels_with_tmp_adc;
> + indio_dev->num_channels = ARRAY_SIZE(ad8460_channels_with_tmp_adc);
> + dev_info(&spi->dev, "Found ADC channel to read TMP pin\n");
That will be apparent anyway once driver is registered, so don't fill the log
with messages like this. dev_dbg() perhaps or drop it entirely.
> + }
> +
> + ret = devm_regulator_get_enable_read_voltage(&spi->dev, "refio_1p2v");
> + if (ret == -ENODEV) {
> + state->refio_1p2v_mv = 1200;
> + } else if (ret < 0) {
> + return dev_err_probe(&spi->dev, PTR_ERR(vrefio),
> + "Failed to get reference voltage\n");
> + } else {
> + state->refio_1p2v_mv = ret / 1000;
> + }
> +
> + if (!in_range(ret, AD8460_MIN_VREFIO_UV, AD8460_MAX_VREFIO_UV))
> + return dev_err_probe(&spi->dev, -EINVAL,
> + "Invalid ref voltage range(%u mV) [%u mV, %u mV]\n",
> + ret, AD8460_MIN_VREFIO_UV / 1000,
Why print ret rather than state->refio_1p2v_mv?
Having a dev_err_probe() with ret as a later parameter is rather confusing
if nothing else.
> + AD8460_MAX_VREFIO_UV / 1000);
> +
> + ret = device_property_read_u32(&spi->dev, "adi,rset-ohms", &state->rset_ohms);
> + if (ret) {
> + state->rset_ohms = 2000;
> + } else {
> + if (!in_range(state->rset_ohms, AD8460_MIN_RSET_OHMS,
> + AD8460_MAX_RSET_OHMS))
Might as well combine as
else if (!...
Then can also drop some brackets as single statements in each leg.
> + return dev_err_probe(&spi->dev, -EINVAL,
> + "Invalid resistor set range(%u) [%u, %u]\n",
> + state->rset_ohms,
> + AD8460_MIN_RSET_OHMS,
> + AD8460_MAX_RSET_OHMS);
> + }
> +
> + /* Arm the device by default */
> + ret = device_property_read_u32_array(&spi->dev, "adi,range-microamp",
> + tmp, ARRAY_SIZE(tmp));
> + if (!ret) {
> + ret = regmap_write(state->regmap, AD8460_CTRL_REG(0x08),
> + (1 << 7) | AD8460_CURRENT_LIMIT_CONV(tmp[1]));
What is the (1 << 7)? Feels like a magic number that should have a define.
> + if (ret)
> + return dev_err_probe(&spi->dev, -EINVAL,
ret not -EINVAL;
> + "overcurrent src not valid: %d uA",
> + tmp[1]);
> +
> + ret = regmap_write(state->regmap, AD8460_CTRL_REG(0x09),
> + (1 << 7) | AD8460_CURRENT_LIMIT_CONV(abs(tmp[0])));
> + if (ret)
> + return dev_err_probe(&spi->dev, -EINVAL,
same here and everywhere else where you are eating a potentially more meaningful error
value.
> + "overcurrent snk not valid: %d uA",
> + tmp[0]);
> + }
> +
> + ret = device_property_read_u32_array(&spi->dev, "adi,range-microvolt",
> + tmp, ARRAY_SIZE(tmp));
> + if (!ret) {
This is currently documented in the binding as only taking one set of values.
Seems a lot more flexible here.
> + ret = regmap_write(state->regmap, AD8460_CTRL_REG(0x0A),
> + (1 << 7) | AD8460_VOLTAGE_LIMIT_CONV(tmp[1]));
> + if (ret)
> + return dev_err_probe(&spi->dev, -EINVAL,
> + "positive overvoltage not valid: %d uV",
> + tmp[1]);
> +
> + ret = regmap_write(state->regmap, AD8460_CTRL_REG(0x0B),
> + (1 << 7) | AD8460_VOLTAGE_LIMIT_CONV(abs(tmp[0])));
> + if (ret)
> + return dev_err_probe(&spi->dev, -EINVAL,
> + "negative overvoltage not valid: %d uV",
> + tmp[0]);
> + }
> +
> + ret = device_property_read_u32(&spi->dev, "adi,temp-max-millicelsius", &temp);
I'd handled as a default of whatever is already in that
register. Just write temp = default; before this call.
That way you just don't check ret for the property query. If it's there the
value in temp will be updated, if not we'll have the default.
Consider similar for the other cases.
It will make it easier to tell from the driver what happens if a property is not
provided. Also document defaults in the dt binding.
> + if (!ret) {
> + ret = regmap_write(state->regmap, AD8460_CTRL_REG(0x0C),
> + (1 << 7) | AD8460_TEMP_LIMIT_CONV(abs(temp)));
> + if (ret)
> + return dev_err_probe(&spi->dev, -EINVAL,
> + "overtemperature not valid: %d",
> + temp);
> + }
> +
> + ret = ad8460_reset(state);
> + if (ret)
> + return ret;
> +
> + /* Enables DAC by default */
> + ret = regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x01),
> + AD8460_HVDAC_SLEEP_MSK,
> + FIELD_PREP(AD8460_HVDAC_SLEEP_MSK, 0));
> + if (ret)
> + return ret;
> +
> + indio_dev->modes = INDIO_DIRECT_MODE;
> + indio_dev->setup_ops = &ad8460_buffer_setup_ops;
> +
> + ret = devm_iio_dmaengine_buffer_setup_ext(&spi->dev, indio_dev, "tx",
> + IIO_BUFFER_DIRECTION_OUT);
> + if (ret)
> + return dev_err_probe(&spi->dev, ret,
> + "Failed to get DMA buffer\n");
> +
> + ret = devm_iio_device_register(&spi->dev, indio_dev);
return devm_iio_device_register()
> + if (ret)
> + return ret;
> +
> + return 0;
> +}
Hi Mariel,
kernel test robot noticed the following build errors:
[auto build test ERROR on 9900e7a54764998ba3a22f06ec629f7b5fe0b422]
url: https://github.com/intel-lab-lkp/linux/commits/Mariel-Tinaco/dt-bindings-iio-dac-add-docs-for-ad8460/20240730-112724
base: 9900e7a54764998ba3a22f06ec629f7b5fe0b422
patch link: https://lore.kernel.org/r/20240730030509.57834-3-Mariel.Tinaco%40analog.com
patch subject: [PATCH v2 2/2] iio: dac: support the ad8460 Waveform DAC
config: i386-allyesconfig (https://download.01.org/0day-ci/archive/20240802/202408021737.KMIdEjmt-lkp@intel.com/config)
compiler: gcc-13 (Ubuntu 13.2.0-4ubuntu3) 13.2.0
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20240802/202408021737.KMIdEjmt-lkp@intel.com/reproduce)
If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <lkp@intel.com>
| Closes: https://lore.kernel.org/oe-kbuild-all/202408021737.KMIdEjmt-lkp@intel.com/
All errors (new ones prefixed by >>):
drivers/iio/dac/ad8460.c: In function 'ad8460_dac_input_read':
>> drivers/iio/dac/ad8460.c:159:15: error: implicit declaration of function 'ad8460_get_hvdac_word' [-Werror=implicit-function-declaration]
159 | ret = ad8460_get_hvdac_word(state, private, ®);
| ^~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c:163:35: warning: format '%ld' expects argument of type 'long int', but argument 3 has type 'unsigned int' [-Wformat=]
163 | return sysfs_emit(buf, "%ld\n", reg);
| ~~^ ~~~
| | |
| | unsigned int
| long int
| %d
drivers/iio/dac/ad8460.c: In function 'ad8460_dac_input_write':
drivers/iio/dac/ad8460.c:176:30: warning: passing argument 2 of 'kstrtou32' makes integer from pointer without a cast [-Wint-conversion]
176 | ret = kstrtou32(buf, ®);
| ^~~~
| |
| unsigned int *
In file included from include/linux/kernel.h:25,
from include/linux/clk.h:13,
from drivers/iio/dac/ad8460.c:10:
include/linux/kstrtox.h:84:70: note: expected 'unsigned int' but argument is of type 'unsigned int *'
84 | static inline int __must_check kstrtou32(const char *s, unsigned int base, u32 *res)
| ~~~~~~~~~~~~~^~~~
>> drivers/iio/dac/ad8460.c:176:15: error: too few arguments to function 'kstrtou32'
176 | ret = kstrtou32(buf, ®);
| ^~~~~~~~~
include/linux/kstrtox.h:84:32: note: declared here
84 | static inline int __must_check kstrtou32(const char *s, unsigned int base, u32 *res)
| ^~~~~~~~~
>> drivers/iio/dac/ad8460.c:182:16: error: implicit declaration of function 'ad8460_set_hvdac_word' [-Werror=implicit-function-declaration]
182 | return ad8460_set_hvdac_word(state, private, reg);
| ^~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c: In function 'ad8460_write_symbol':
drivers/iio/dac/ad8460.c:211:30: warning: passing argument 2 of 'kstrtou16' makes integer from pointer without a cast [-Wint-conversion]
211 | ret = kstrtou16(buf, &sym);
| ^~~~
| |
| bool * {aka _Bool *}
include/linux/kstrtox.h:94:56: note: expected 'unsigned int' but argument is of type 'bool *' {aka '_Bool *'}
94 | int __must_check kstrtou16(const char *s, unsigned int base, u16 *res);
| ~~~~~~~~~~~~~^~~~
>> drivers/iio/dac/ad8460.c:211:15: error: too few arguments to function 'kstrtou16'
211 | ret = kstrtou16(buf, &sym);
| ^~~~~~~~~
include/linux/kstrtox.h:94:18: note: declared here
94 | int __must_check kstrtou16(const char *s, unsigned int base, u16 *res);
| ^~~~~~~~~
drivers/iio/dac/ad8460.c: In function 'ad8460_write_toggle_en':
drivers/iio/dac/ad8460.c:249:30: warning: passing argument 2 of 'kstrtou16' makes integer from pointer without a cast [-Wint-conversion]
249 | ret = kstrtou16(buf, &toggle_en);
| ^~~~~~~~~~
| |
| bool * {aka _Bool *}
include/linux/kstrtox.h:94:56: note: expected 'unsigned int' but argument is of type 'bool *' {aka '_Bool *'}
94 | int __must_check kstrtou16(const char *s, unsigned int base, u16 *res);
| ~~~~~~~~~~~~~^~~~
drivers/iio/dac/ad8460.c:249:15: error: too few arguments to function 'kstrtou16'
249 | ret = kstrtou16(buf, &toggle_en);
| ^~~~~~~~~
include/linux/kstrtox.h:94:18: note: declared here
94 | int __must_check kstrtou16(const char *s, unsigned int base, u16 *res);
| ^~~~~~~~~
drivers/iio/dac/ad8460.c: At top level:
>> drivers/iio/dac/ad8460.c:335:12: error: static declaration of 'ad8460_get_hvdac_word' follows non-static declaration
335 | static int ad8460_get_hvdac_word(struct ad8460_state *state,
| ^~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c:159:15: note: previous implicit declaration of 'ad8460_get_hvdac_word' with type 'int()'
159 | ret = ad8460_get_hvdac_word(state, private, ®);
| ^~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c: In function 'ad8460_get_hvdac_word':
>> drivers/iio/dac/ad8460.c:346:16: error: implicit declaration of function 'get_unaligned_le16' [-Werror=implicit-function-declaration]
346 | *val = get_unaligned_le16(state->spi_tx_buf);
| ^~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c: At top level:
>> drivers/iio/dac/ad8460.c:351:12: error: static declaration of 'ad8460_set_hvdac_word' follows non-static declaration
351 | static int ad8460_set_hvdac_word(struct ad8460_state *state,
| ^~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c:182:16: note: previous implicit declaration of 'ad8460_set_hvdac_word' with type 'int()'
182 | return ad8460_set_hvdac_word(state, private, reg);
| ^~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c: In function 'ad8460_set_hvdac_word':
>> drivers/iio/dac/ad8460.c:355:9: error: implicit declaration of function 'put_unaligned_le16' [-Werror=implicit-function-declaration]
355 | put_unaligned_le16(val & 0x3FFF, &state->spi_tx_buf);
| ^~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c: In function 'ad8460_probe':
>> drivers/iio/dac/ad8460.c:855:15: error: implicit declaration of function 'devm_regulator_get_enable_read_voltage'; did you mean 'devm_regulator_get_enable_optional'? [-Werror=implicit-function-declaration]
855 | ret = devm_regulator_get_enable_read_voltage(&spi->dev, "refio_1p2v");
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
| devm_regulator_get_enable_optional
>> drivers/iio/dac/ad8460.c:859:57: error: 'vrefio' undeclared (first use in this function)
859 | return dev_err_probe(&spi->dev, PTR_ERR(vrefio),
| ^~~~~~
drivers/iio/dac/ad8460.c:859:57: note: each undeclared identifier is reported only once for each function it appears in
drivers/iio/dac/ad8460.c:819:27: warning: unused variable 'refio_1p2v' [-Wunused-variable]
819 | struct regulator *refio_1p2v;
| ^~~~~~~~~~
cc1: some warnings being treated as errors
vim +/ad8460_get_hvdac_word +159 drivers/iio/dac/ad8460.c
149
150 static ssize_t ad8460_dac_input_read(struct iio_dev *indio_dev,
151 uintptr_t private,
152 const struct iio_chan_spec *chan,
153 char *buf)
154 {
155 struct ad8460_state *state = iio_priv(indio_dev);
156 unsigned int reg;
157 int ret;
158
> 159 ret = ad8460_get_hvdac_word(state, private, ®);
160 if (ret)
161 return ret;
162
163 return sysfs_emit(buf, "%ld\n", reg);
164 }
165
166 static ssize_t ad8460_dac_input_write(struct iio_dev *indio_dev,
167 uintptr_t private,
168 const struct iio_chan_spec *chan,
169 const char *buf,
170 size_t len)
171 {
172 struct ad8460_state *state = iio_priv(indio_dev);
173 unsigned int reg;
174 int ret;
175
> 176 ret = kstrtou32(buf, ®);
177 if (ret)
178 return ret;
179
180 guard(mutex)(&state->lock);
181
> 182 return ad8460_set_hvdac_word(state, private, reg);
183 }
184
185 static ssize_t ad8460_read_symbol(struct iio_dev *indio_dev,
186 uintptr_t private,
187 const struct iio_chan_spec *chan,
188 char *buf)
189 {
190 struct ad8460_state *state = iio_priv(indio_dev);
191 unsigned int reg;
192 int ret;
193
194 ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x02), ®);
195 if (ret)
196 return ret;
197
198 return sysfs_emit(buf, "%ld\n", FIELD_GET(AD8460_PATTERN_DEPTH_MSK, reg));
199 }
200
201 static ssize_t ad8460_write_symbol(struct iio_dev *indio_dev,
202 uintptr_t private,
203 const struct iio_chan_spec *chan,
204 const char *buf,
205 size_t len)
206 {
207 struct ad8460_state *state = iio_priv(indio_dev);
208 bool sym;
209 int ret;
210
> 211 ret = kstrtou16(buf, &sym);
212 if (ret)
213 return ret;
214
215 guard(mutex)(&state->lock);
216
217 return regmap_update_bits(state->regmap,
218 AD8460_CTRL_REG(0x02),
219 AD8460_PATTERN_DEPTH_MSK,
220 FIELD_PREP(AD8460_PATTERN_DEPTH_MSK, sym));
221 }
222
223 static ssize_t ad8460_read_toggle_en(struct iio_dev *indio_dev,
224 uintptr_t private,
225 const struct iio_chan_spec *chan,
226 char *buf)
227 {
228 struct ad8460_state *state = iio_priv(indio_dev);
229 unsigned int reg;
230 int ret;
231
232 ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x02), ®);
233 if (ret)
234 return ret;
235
236 return sysfs_emit(buf, "%ld\n", FIELD_GET(AD8460_APG_MODE_ENABLE_MSK, reg));
237 }
238
239 static ssize_t ad8460_write_toggle_en(struct iio_dev *indio_dev,
240 uintptr_t private,
241 const struct iio_chan_spec *chan,
242 const char *buf,
243 size_t len)
244 {
245 struct ad8460_state *state = iio_priv(indio_dev);
246 bool toggle_en;
247 int ret;
248
249 ret = kstrtou16(buf, &toggle_en);
250 if (ret)
251 return ret;
252
253 iio_device_claim_direct_scoped(return -EBUSY, indio_dev)
254 return ad8460_enable_apg_mode(state, toggle_en);
255 unreachable();
256 }
257
258 static ssize_t ad8460_read_powerdown(struct iio_dev *indio_dev,
259 uintptr_t private,
260 const struct iio_chan_spec *chan,
261 char *buf)
262 {
263 struct ad8460_state *state = iio_priv(indio_dev);
264 unsigned int reg;
265 int ret;
266
267 ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x01), ®);
268 if (ret)
269 return ret;
270
271 return sysfs_emit(buf, "%ld\n", FIELD_GET(AD8460_HVDAC_SLEEP_MSK, reg));
272 }
273
274 static ssize_t ad8460_write_powerdown(struct iio_dev *indio_dev,
275 uintptr_t private,
276 const struct iio_chan_spec *chan,
277 const char *buf,
278 size_t len)
279 {
280 struct ad8460_state *state = iio_priv(indio_dev);
281 bool pwr_down;
282 u64 sdn_flag;
283 int ret;
284
285 ret = kstrtobool(buf, &pwr_down);
286 if (ret)
287 return ret;
288
289 guard(mutex)(&state->lock);
290
291 ret = regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x01),
292 AD8460_HVDAC_SLEEP_MSK,
293 FIELD_PREP(AD8460_HVDAC_SLEEP_MSK, pwr_down));
294 if (ret)
295 return ret;
296
297 if (!pwr_down) {
298 ret = ad8460_read_shutdown_flag(state, &sdn_flag);
299 if (ret)
300 return ret;
301
302 if (sdn_flag) {
303 ret = ad8460_hv_reset(state);
304 if (ret)
305 return ret;
306 }
307 }
308
309 ret = regmap_update_bits(state->regmap, AD8460_CTRL_REG(0x00),
310 AD8460_HV_SLEEP_MSK,
311 FIELD_PREP(AD8460_HV_SLEEP_MSK, !pwr_down));
312 if (ret)
313 return ret;
314
315 return len;
316 }
317
318 static const char * const ad8460_powerdown_modes[] = {
319 "three_state",
320 };
321
322 static int ad8460_get_powerdown_mode(struct iio_dev *indio_dev,
323 const struct iio_chan_spec *chan)
324 {
325 return 0;
326 }
327
328 static int ad8460_set_powerdown_mode(struct iio_dev *indio_dev,
329 const struct iio_chan_spec *chan,
330 unsigned int type)
331 {
332 return 0;
333 }
334
> 335 static int ad8460_get_hvdac_word(struct ad8460_state *state,
336 int index,
337 int *val)
338 {
339 int ret;
340
341 ret = regmap_bulk_read(state->regmap, AD8460_HVDAC_DATA_WORD_LOW(index),
342 &state->spi_tx_buf, AD8460_DATA_BYTE_WORD_LENGTH);
343 if (ret)
344 return ret;
345
> 346 *val = get_unaligned_le16(state->spi_tx_buf);
347
348 return ret;
349 }
350
> 351 static int ad8460_set_hvdac_word(struct ad8460_state *state,
352 int index,
353 int val)
354 {
> 355 put_unaligned_le16(val & 0x3FFF, &state->spi_tx_buf);
356
357 return regmap_bulk_write(state->regmap, AD8460_HVDAC_DATA_WORD_LOW(index),
358 state->spi_tx_buf, AD8460_DATA_BYTE_WORD_LENGTH);
359 }
360
--
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki
Hi Mariel,
kernel test robot noticed the following build warnings:
[auto build test WARNING on 9900e7a54764998ba3a22f06ec629f7b5fe0b422]
url: https://github.com/intel-lab-lkp/linux/commits/Mariel-Tinaco/dt-bindings-iio-dac-add-docs-for-ad8460/20240730-112724
base: 9900e7a54764998ba3a22f06ec629f7b5fe0b422
patch link: https://lore.kernel.org/r/20240730030509.57834-3-Mariel.Tinaco%40analog.com
patch subject: [PATCH v2 2/2] iio: dac: support the ad8460 Waveform DAC
config: x86_64-allyesconfig (https://download.01.org/0day-ci/archive/20240802/202408021509.ug75TMoS-lkp@intel.com/config)
compiler: clang version 18.1.5 (https://github.com/llvm/llvm-project 617a15a9eac96088ae5e9134248d8236e34b91b1)
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20240802/202408021509.ug75TMoS-lkp@intel.com/reproduce)
If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <lkp@intel.com>
| Closes: https://lore.kernel.org/oe-kbuild-all/202408021509.ug75TMoS-lkp@intel.com/
All warnings (new ones prefixed by >>):
drivers/iio/dac/ad8460.c:159:8: error: call to undeclared function 'ad8460_get_hvdac_word'; ISO C99 and later do not support implicit function declarations [-Wimplicit-function-declaration]
159 | ret = ad8460_get_hvdac_word(state, private, ®);
| ^
>> drivers/iio/dac/ad8460.c:163:34: warning: format specifies type 'long' but the argument has type 'unsigned int' [-Wformat]
163 | return sysfs_emit(buf, "%ld\n", reg);
| ~~~ ^~~
| %u
drivers/iio/dac/ad8460.c:176:27: error: too few arguments to function call, expected 3, have 2
176 | ret = kstrtou32(buf, ®);
| ~~~~~~~~~ ^
include/linux/kstrtox.h:84:32: note: 'kstrtou32' declared here
84 | static inline int __must_check kstrtou32(const char *s, unsigned int base, u32 *res)
| ^ ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c:182:9: error: call to undeclared function 'ad8460_set_hvdac_word'; ISO C99 and later do not support implicit function declarations [-Wimplicit-function-declaration]
182 | return ad8460_set_hvdac_word(state, private, reg);
| ^
drivers/iio/dac/ad8460.c:211:27: error: too few arguments to function call, expected 3, have 2
211 | ret = kstrtou16(buf, &sym);
| ~~~~~~~~~ ^
include/linux/kstrtox.h:94:18: note: 'kstrtou16' declared here
94 | int __must_check kstrtou16(const char *s, unsigned int base, u16 *res);
| ^ ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c:249:33: error: too few arguments to function call, expected 3, have 2
249 | ret = kstrtou16(buf, &toggle_en);
| ~~~~~~~~~ ^
include/linux/kstrtox.h:94:18: note: 'kstrtou16' declared here
94 | int __must_check kstrtou16(const char *s, unsigned int base, u16 *res);
| ^ ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c:335:12: error: static declaration of 'ad8460_get_hvdac_word' follows non-static declaration
335 | static int ad8460_get_hvdac_word(struct ad8460_state *state,
| ^
drivers/iio/dac/ad8460.c:159:8: note: previous implicit declaration is here
159 | ret = ad8460_get_hvdac_word(state, private, ®);
| ^
drivers/iio/dac/ad8460.c:346:9: error: call to undeclared function 'get_unaligned_le16'; ISO C99 and later do not support implicit function declarations [-Wimplicit-function-declaration]
346 | *val = get_unaligned_le16(state->spi_tx_buf);
| ^
drivers/iio/dac/ad8460.c:351:12: error: static declaration of 'ad8460_set_hvdac_word' follows non-static declaration
351 | static int ad8460_set_hvdac_word(struct ad8460_state *state,
| ^
drivers/iio/dac/ad8460.c:182:9: note: previous implicit declaration is here
182 | return ad8460_set_hvdac_word(state, private, reg);
| ^
drivers/iio/dac/ad8460.c:355:2: error: call to undeclared function 'put_unaligned_le16'; ISO C99 and later do not support implicit function declarations [-Wimplicit-function-declaration]
355 | put_unaligned_le16(val & 0x3FFF, &state->spi_tx_buf);
| ^
drivers/iio/dac/ad8460.c:855:8: error: call to undeclared function 'devm_regulator_get_enable_read_voltage'; ISO C99 and later do not support implicit function declarations [-Wimplicit-function-declaration]
855 | ret = devm_regulator_get_enable_read_voltage(&spi->dev, "refio_1p2v");
| ^
drivers/iio/dac/ad8460.c:855:8: note: did you mean 'devm_regulator_get_enable_optional'?
include/linux/regulator/consumer.h:166:5: note: 'devm_regulator_get_enable_optional' declared here
166 | int devm_regulator_get_enable_optional(struct device *dev, const char *id);
| ^
drivers/iio/dac/ad8460.c:859:43: error: use of undeclared identifier 'vrefio'
859 | return dev_err_probe(&spi->dev, PTR_ERR(vrefio),
| ^
1 warning and 11 errors generated.
vim +163 drivers/iio/dac/ad8460.c
149
150 static ssize_t ad8460_dac_input_read(struct iio_dev *indio_dev,
151 uintptr_t private,
152 const struct iio_chan_spec *chan,
153 char *buf)
154 {
155 struct ad8460_state *state = iio_priv(indio_dev);
156 unsigned int reg;
157 int ret;
158
159 ret = ad8460_get_hvdac_word(state, private, ®);
160 if (ret)
161 return ret;
162
> 163 return sysfs_emit(buf, "%ld\n", reg);
164 }
165
--
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki
Hi Mariel,
kernel test robot noticed the following build warnings:
[auto build test WARNING on 9900e7a54764998ba3a22f06ec629f7b5fe0b422]
url: https://github.com/intel-lab-lkp/linux/commits/Mariel-Tinaco/dt-bindings-iio-dac-add-docs-for-ad8460/20240730-112724
base: 9900e7a54764998ba3a22f06ec629f7b5fe0b422
patch link: https://lore.kernel.org/r/20240730030509.57834-3-Mariel.Tinaco%40analog.com
patch subject: [PATCH v2 2/2] iio: dac: support the ad8460 Waveform DAC
config: i386-allyesconfig (https://download.01.org/0day-ci/archive/20240802/202408021321.uic81edY-lkp@intel.com/config)
compiler: gcc-13 (Ubuntu 13.2.0-4ubuntu3) 13.2.0
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20240802/202408021321.uic81edY-lkp@intel.com/reproduce)
If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <lkp@intel.com>
| Closes: https://lore.kernel.org/oe-kbuild-all/202408021321.uic81edY-lkp@intel.com/
All warnings (new ones prefixed by >>):
drivers/iio/dac/ad8460.c: In function 'ad8460_dac_input_read':
drivers/iio/dac/ad8460.c:159:15: error: implicit declaration of function 'ad8460_get_hvdac_word' [-Werror=implicit-function-declaration]
159 | ret = ad8460_get_hvdac_word(state, private, ®);
| ^~~~~~~~~~~~~~~~~~~~~
>> drivers/iio/dac/ad8460.c:163:35: warning: format '%ld' expects argument of type 'long int', but argument 3 has type 'unsigned int' [-Wformat=]
163 | return sysfs_emit(buf, "%ld\n", reg);
| ~~^ ~~~
| | |
| | unsigned int
| long int
| %d
drivers/iio/dac/ad8460.c: In function 'ad8460_dac_input_write':
>> drivers/iio/dac/ad8460.c:176:30: warning: passing argument 2 of 'kstrtou32' makes integer from pointer without a cast [-Wint-conversion]
176 | ret = kstrtou32(buf, ®);
| ^~~~
| |
| unsigned int *
In file included from include/linux/kernel.h:25,
from include/linux/clk.h:13,
from drivers/iio/dac/ad8460.c:10:
include/linux/kstrtox.h:84:70: note: expected 'unsigned int' but argument is of type 'unsigned int *'
84 | static inline int __must_check kstrtou32(const char *s, unsigned int base, u32 *res)
| ~~~~~~~~~~~~~^~~~
drivers/iio/dac/ad8460.c:176:15: error: too few arguments to function 'kstrtou32'
176 | ret = kstrtou32(buf, ®);
| ^~~~~~~~~
include/linux/kstrtox.h:84:32: note: declared here
84 | static inline int __must_check kstrtou32(const char *s, unsigned int base, u32 *res)
| ^~~~~~~~~
drivers/iio/dac/ad8460.c:182:16: error: implicit declaration of function 'ad8460_set_hvdac_word' [-Werror=implicit-function-declaration]
182 | return ad8460_set_hvdac_word(state, private, reg);
| ^~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c: In function 'ad8460_write_symbol':
>> drivers/iio/dac/ad8460.c:211:30: warning: passing argument 2 of 'kstrtou16' makes integer from pointer without a cast [-Wint-conversion]
211 | ret = kstrtou16(buf, &sym);
| ^~~~
| |
| bool * {aka _Bool *}
include/linux/kstrtox.h:94:56: note: expected 'unsigned int' but argument is of type 'bool *' {aka '_Bool *'}
94 | int __must_check kstrtou16(const char *s, unsigned int base, u16 *res);
| ~~~~~~~~~~~~~^~~~
drivers/iio/dac/ad8460.c:211:15: error: too few arguments to function 'kstrtou16'
211 | ret = kstrtou16(buf, &sym);
| ^~~~~~~~~
include/linux/kstrtox.h:94:18: note: declared here
94 | int __must_check kstrtou16(const char *s, unsigned int base, u16 *res);
| ^~~~~~~~~
drivers/iio/dac/ad8460.c: In function 'ad8460_write_toggle_en':
drivers/iio/dac/ad8460.c:249:30: warning: passing argument 2 of 'kstrtou16' makes integer from pointer without a cast [-Wint-conversion]
249 | ret = kstrtou16(buf, &toggle_en);
| ^~~~~~~~~~
| |
| bool * {aka _Bool *}
include/linux/kstrtox.h:94:56: note: expected 'unsigned int' but argument is of type 'bool *' {aka '_Bool *'}
94 | int __must_check kstrtou16(const char *s, unsigned int base, u16 *res);
| ~~~~~~~~~~~~~^~~~
drivers/iio/dac/ad8460.c:249:15: error: too few arguments to function 'kstrtou16'
249 | ret = kstrtou16(buf, &toggle_en);
| ^~~~~~~~~
include/linux/kstrtox.h:94:18: note: declared here
94 | int __must_check kstrtou16(const char *s, unsigned int base, u16 *res);
| ^~~~~~~~~
drivers/iio/dac/ad8460.c: At top level:
drivers/iio/dac/ad8460.c:335:12: error: static declaration of 'ad8460_get_hvdac_word' follows non-static declaration
335 | static int ad8460_get_hvdac_word(struct ad8460_state *state,
| ^~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c:159:15: note: previous implicit declaration of 'ad8460_get_hvdac_word' with type 'int()'
159 | ret = ad8460_get_hvdac_word(state, private, ®);
| ^~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c: In function 'ad8460_get_hvdac_word':
drivers/iio/dac/ad8460.c:346:16: error: implicit declaration of function 'get_unaligned_le16' [-Werror=implicit-function-declaration]
346 | *val = get_unaligned_le16(state->spi_tx_buf);
| ^~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c: At top level:
drivers/iio/dac/ad8460.c:351:12: error: static declaration of 'ad8460_set_hvdac_word' follows non-static declaration
351 | static int ad8460_set_hvdac_word(struct ad8460_state *state,
| ^~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c:182:16: note: previous implicit declaration of 'ad8460_set_hvdac_word' with type 'int()'
182 | return ad8460_set_hvdac_word(state, private, reg);
| ^~~~~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c: In function 'ad8460_set_hvdac_word':
drivers/iio/dac/ad8460.c:355:9: error: implicit declaration of function 'put_unaligned_le16' [-Werror=implicit-function-declaration]
355 | put_unaligned_le16(val & 0x3FFF, &state->spi_tx_buf);
| ^~~~~~~~~~~~~~~~~~
drivers/iio/dac/ad8460.c: In function 'ad8460_probe':
drivers/iio/dac/ad8460.c:855:15: error: implicit declaration of function 'devm_regulator_get_enable_read_voltage'; did you mean 'devm_regulator_get_enable_optional'? [-Werror=implicit-function-declaration]
855 | ret = devm_regulator_get_enable_read_voltage(&spi->dev, "refio_1p2v");
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
| devm_regulator_get_enable_optional
drivers/iio/dac/ad8460.c:859:57: error: 'vrefio' undeclared (first use in this function)
859 | return dev_err_probe(&spi->dev, PTR_ERR(vrefio),
| ^~~~~~
drivers/iio/dac/ad8460.c:859:57: note: each undeclared identifier is reported only once for each function it appears in
>> drivers/iio/dac/ad8460.c:819:27: warning: unused variable 'refio_1p2v' [-Wunused-variable]
819 | struct regulator *refio_1p2v;
| ^~~~~~~~~~
cc1: some warnings being treated as errors
vim +163 drivers/iio/dac/ad8460.c
149
150 static ssize_t ad8460_dac_input_read(struct iio_dev *indio_dev,
151 uintptr_t private,
152 const struct iio_chan_spec *chan,
153 char *buf)
154 {
155 struct ad8460_state *state = iio_priv(indio_dev);
156 unsigned int reg;
157 int ret;
158
159 ret = ad8460_get_hvdac_word(state, private, ®);
160 if (ret)
161 return ret;
162
> 163 return sysfs_emit(buf, "%ld\n", reg);
164 }
165
166 static ssize_t ad8460_dac_input_write(struct iio_dev *indio_dev,
167 uintptr_t private,
168 const struct iio_chan_spec *chan,
169 const char *buf,
170 size_t len)
171 {
172 struct ad8460_state *state = iio_priv(indio_dev);
173 unsigned int reg;
174 int ret;
175
> 176 ret = kstrtou32(buf, ®);
177 if (ret)
178 return ret;
179
180 guard(mutex)(&state->lock);
181
182 return ad8460_set_hvdac_word(state, private, reg);
183 }
184
185 static ssize_t ad8460_read_symbol(struct iio_dev *indio_dev,
186 uintptr_t private,
187 const struct iio_chan_spec *chan,
188 char *buf)
189 {
190 struct ad8460_state *state = iio_priv(indio_dev);
191 unsigned int reg;
192 int ret;
193
194 ret = regmap_read(state->regmap, AD8460_CTRL_REG(0x02), ®);
195 if (ret)
196 return ret;
197
198 return sysfs_emit(buf, "%ld\n", FIELD_GET(AD8460_PATTERN_DEPTH_MSK, reg));
199 }
200
201 static ssize_t ad8460_write_symbol(struct iio_dev *indio_dev,
202 uintptr_t private,
203 const struct iio_chan_spec *chan,
204 const char *buf,
205 size_t len)
206 {
207 struct ad8460_state *state = iio_priv(indio_dev);
208 bool sym;
209 int ret;
210
> 211 ret = kstrtou16(buf, &sym);
212 if (ret)
213 return ret;
214
215 guard(mutex)(&state->lock);
216
217 return regmap_update_bits(state->regmap,
218 AD8460_CTRL_REG(0x02),
219 AD8460_PATTERN_DEPTH_MSK,
220 FIELD_PREP(AD8460_PATTERN_DEPTH_MSK, sym));
221 }
222
--
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki
© 2016 - 2025 Red Hat, Inc.