Re: [PATCH 4/5] iio: imu: adis16550: add adis16550 support

[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]

 



On Mon, 28 Oct 2024 14:35:44 +0200
Robert Budai <robert.budai@xxxxxxxxxx> wrote:

> From: Nuno Sá <nuno.sa@xxxxxxxxxx>
> 
> The ADIS16550 is a complete inertial system that includes a triaxis
> gyroscope and a triaxis accelerometer. Each inertial sensor in
> the ADIS16550 combines industry leading MEMS only technology
> with signal conditioning that optimizes dynamic performance. The
> factory calibration characterizes each sensor for sensitivity, bias,
> and alignment. As a result, each sensor has its own dynamic com-
> pensation formulas that provide accurate sensor measurements
> 
> Co-developed-by: Ramona Gradinariu <ramona.gradinariu@xxxxxxxxxx>
> Signed-off-by: Ramona Gradinariu <ramona.gradinariu@xxxxxxxxxx>
> Co-developed-by: Antoniu Miclaus <antoniu.miclaus@xxxxxxxxxx>
> Signed-off-by: Antoniu Miclaus <antoniu.miclaus@xxxxxxxxxx>
> Co-developed-by: Robert Budai <robert.budai@xxxxxxxxxx>
> Signed-off-by: Robert Budai <robert.budai@xxxxxxxxxx>
> Signed-off-by: Nuno Sá <nuno.sa@xxxxxxxxxx>

Various minor things inline.

Robert, as sender your SoB should come last. (just move down your two
lines and it is fine).

> diff --git a/drivers/iio/imu/adis16550.c b/drivers/iio/imu/adis16550.c
> new file mode 100644
> index 000000000000..204d72c9f442
> --- /dev/null
> +++ b/drivers/iio/imu/adis16550.c
> @@ -0,0 +1,1228 @@
> +// SPDX-License-Identifier: GPL-2.0
> +/*
> + * ADIS16550 IMU driver
> + *
> + * Copyright 2024 Analog Devices Inc.
> + */
> +#include <linux/bitfield.h>
> +#include <linux/bitops.h>
> +#include <linux/clk.h>
> +#include <linux/crc32.h>
> +#include <linux/debugfs.h>
> +#include <linux/iio/buffer.h>
> +#include <linux/iio/iio.h>
> +#include <linux/iio/imu/adis.h>
> +#include <linux/iio/sysfs.h>
> +#include <linux/iio/trigger_consumer.h>
> +#include <linux/interrupt.h>
> +#include <linux/kernel.h>
> +#include <linux/lcm.h>
> +#include <linux/math.h>
> +#include <linux/module.h>
> +#include <linux/mod_devicetable.h>
> +#include <linux/regulator/consumer.h>
> +#include <linux/spi/spi.h>
> +#include <linux/swab.h>
> +
> +#include <asm/unaligned.h>
Moved. Now linux/unaligned.h (rc2 onwards)


> +
> +#define ADIS16550_REG_BURST_GYRO_ACCEL		0x0a
> +#define ADIS16550_REG_BURST_DELTA_ANG_VEL	0x0b
> +#define ADIS16550_BURST_DATA_GYRO_ACCEL_MASK	GENMASK(5, 0)
> +#define ADIS16550_BURST_DATA_DELTA_ANG_VEL_MASK	GENMASK(12, 7)
> +
> +#define ADIS16550_REG_STATUS		0x0e
> +#define ADIS16550_REG_TEMP		0x10
> +#define ADIS16550_REG_X_GYRO		0x12
> +#define ADIS16550_REG_Y_GYRO		0x14
> +#define ADIS16550_REG_Z_GYRO		0x16
> +#define ADIS16550_REG_X_ACCEL		0x18
> +#define ADIS16550_REG_Y_ACCEL		0x1a
> +#define ADIS16550_REG_Z_ACCEL		0x1c
> +#define ADIS16550_REG_X_DELTANG_L	0x1E
> +#define ADIS16550_REG_Y_DELTANG_L	0x20
> +#define ADIS16550_REG_Z_DELTANG_L	0x22
> +#define ADIS16550_REG_X_DELTVEL_L	0x24
> +#define ADIS16550_REG_Y_DELTVEL_L	0x26
> +#define ADIS16550_REG_Z_DELTVEL_L	0x28
> +#define ADIS16550_REG_X_GYRO_SCALE	0x30
> +#define ADIS16550_REG_Y_GYRO_SCALE	0x32
> +#define ADIS16550_REG_Z_GYRO_SCALE	0x34
> +#define ADIS16550_REG_X_ACCEL_SCALE	0x36
> +#define ADIS16550_REG_Y_ACCEL_SCALE	0x38
> +#define ADIS16550_REG_Z_ACCEL_SCALE	0x3a
> +#define ADIS16550_REG_X_GYRO_BIAS	0x40
> +#define ADIS16550_REG_Y_GYRO_BIAS	0x42
> +#define ADIS16550_REG_Z_GYRO_BIAS	0x44
> +#define ADIS16550_REG_X_ACCEL_BIAS	0x46
> +#define ADIS16550_REG_Y_ACCEL_BIAS	0x48
> +#define ADIS16550_REG_Z_ACCEL_BIAS	0x4a
> +#define ADIS16550_REG_COMMAND		0x50
> +#define ADIS16550_REG_CONFIG		0x52
> +#define ADIS16550_GYRO_FIR_EN_MASK	BIT(3)
> +#define ADIS16550_ACCL_FIR_EN_MASK	BIT(2)
> +#define ADIS16550_SYNC_MASK	\
> +			(ADIS16550_SYNC_EN_MASK | ADIS16550_SYNC_MODE_MASK)
> +#define ADIS16550_SYNC_MODE_MASK	BIT(1)
> +#define ADIS16550_SYNC_EN_MASK		BIT(0)
> +/* max of 4000 SPS in scale sync */
> +#define ADIS16550_SYNC_SCALE_MAX_RATE	(4000 * 1000)
> +#define ADIS16550_REG_DEC_RATE		0x54
> +#define ADIS16550_REG_SYNC_SCALE	0x56
> +#define ADIS16550_REG_SERIAL_NUM	0x76
> +#define ADIS16550_REG_FW_REV		0x7A
> +#define ADIS16550_REG_FW_DATE		0x7C
> +#define ADIS16550_REG_PROD_ID		0x7E
> +#define ADIS16550_REG_FLASH_CNT		0x72
> +/* spi protocol*/
> +#define ADIS16550_SPI_DATA_MASK		GENMASK(31, 16)
> +#define ADIS16550_SPI_REG_MASK		GENMASK(14, 8)
> +#define ADIS16550_SPI_R_W_MASK		BIT(7)
> +#define ADIS16550_SPI_CRC_MASK		GENMASK(3, 0)
> +#define ADIS16550_SPI_SV_MASK		GENMASK(7, 6)
> +/* burst read */
> +#define ADIS16550_BURST_N_ELEM		12
> +#define ADIS16550_BURST_DATA_LEN	(ADIS16550_BURST_N_ELEM * 4)
> +#define ADIS16550_MAX_SCAN_DATA		12

> +static int adis16550_set_freq(struct adis16550 *st, u32 freq)
name freq to indicate the units.

> +{
> +	u16 dec;
> +	int ret;
> +	u32 sample_rate = st->clk_freq;
> +	/*
> +	 * The optimal sample rate for the supported IMUs is between
> +	 * int_clk - 1000 and int_clk + 500.
> +	 */
> +	u32 max_sample_rate =  st->info->int_clk * 1000 + 500000;
> +	u32 min_sample_rate =  st->info->int_clk * 1000 - 1000000;
> +
> +	if (!freq)
> +		return -EINVAL;
> +
> +	adis_dev_lock(&st->adis);
adis_dev_auto_lock() here and in similar places
then you can directly return from error paths.


> +
> +	if (st->sync_mode == ADIS16550_SYNC_MODE_SCALED) {
> +		unsigned long scaled_rate = lcm(st->clk_freq, freq);
> +		int sync_scale;
> +
> +		if (scaled_rate > max_sample_rate)
> +			scaled_rate = max_sample_rate / st->clk_freq * st->clk_freq;
> +		else
> +			scaled_rate = max_sample_rate / scaled_rate * scaled_rate;
> +
> +		if (scaled_rate < min_sample_rate)
> +			scaled_rate = roundup(min_sample_rate, st->clk_freq);
> +
> +		sync_scale = scaled_rate / st->clk_freq;
> +		ret = __adis_write_reg_16(&st->adis, ADIS16550_REG_SYNC_SCALE,
> +					  sync_scale);
> +		if (ret)
> +			goto error;
> +
> +		sample_rate = scaled_rate;
> +	}
> +
> +	dec = DIV_ROUND_CLOSEST(sample_rate, freq);
> +
> +	if (dec)
> +		dec--;
> +
> +	if (dec > st->info->max_dec)
> +		dec = st->info->max_dec;

dec = min(dec, st->info->max_dec)

> +
> +	ret = __adis_write_reg_16(&st->adis, ADIS16550_REG_DEC_RATE, dec);
> +	if (ret)
> +		goto error;
> +
> +	adis_dev_unlock(&st->adis);
> +
> +	return 0;
> +
> +error:
> +	adis_dev_unlock(&st->adis);
> +	return ret;
> +}


> +static int adis16550_read_raw(struct iio_dev *indio_dev,
> +			      const struct iio_chan_spec *chan,
> +			      int *val, int *val2, long info)
> +{
> +	struct adis16550 *st = iio_priv(indio_dev);
> +	int ret;
> +	const int idx = chan->scan_index;
> +	u32 tmp;
> +	u16 scale;
reverse xmas tree.

> +
> +	switch (info) {
> +	case IIO_CHAN_INFO_RAW:
> +		return adis_single_conversion(indio_dev, chan, 0, val);
> +	case IIO_CHAN_INFO_SCALE:
> +		switch (chan->type) {
> +		case IIO_ANGL_VEL:
> +			*val = st->info->gyro_max_val;
> +			*val2 = st->info->gyro_max_scale;
This level of flexibility only makes sense if you are very soon
going to send additional support for devices where these change.
If you are, state that in the patch description.

> +			return IIO_VAL_FRACTIONAL;
> +		case IIO_ACCEL:
> +			*val = st->info->accel_max_val;
> +			*val2 = st->info->accel_max_scale;
> +			return IIO_VAL_FRACTIONAL;
> +		case IIO_TEMP:
> +			*val = st->info->temp_scale;
> +			return IIO_VAL_INT;
> +		case IIO_DELTA_ANGL:
> +			*val = st->info->deltang_max_val;
> +			*val2 = 31;
> +			return IIO_VAL_FRACTIONAL_LOG2;
> +		case IIO_DELTA_VELOCITY:
> +			*val = st->info->deltvel_max_val;
> +			*val2 = 31;
> +			return IIO_VAL_FRACTIONAL_LOG2;
> +		default:
> +			return -EINVAL;
> +		}
> +	case IIO_CHAN_INFO_OFFSET:
> +		/* temperature centered at 25°C */
> +		*val = DIV_ROUND_CLOSEST(25000, st->info->temp_scale);
> +		return IIO_VAL_INT;
> +	case IIO_CHAN_INFO_CALIBBIAS:
> +		ret = adis_read_reg_32(&st->adis,
> +				       adis16550_calib_bias[idx], val);
> +		if (ret)
> +			return ret;
> +
> +		return IIO_VAL_INT;
> +	case IIO_CHAN_INFO_CALIBSCALE:
> +		ret = adis_read_reg_16(&st->adis,
> +				       adis16550_calib_scale[idx], &scale);
> +		if (ret)
> +			return ret;
> +
> +		*val = scale;
> +		return IIO_VAL_INT;
> +	case IIO_CHAN_INFO_SAMP_FREQ:
> +		ret = adis16550_get_freq(st, &tmp);
> +		if (ret)
> +			return ret;
> +
> +		*val = tmp / 1000;
> +		*val2 = (tmp % 1000) * 1000;
> +		return IIO_VAL_INT_PLUS_MICRO;
> +	case IIO_CHAN_INFO_LOW_PASS_FILTER_3DB_FREQUENCY:
> +		switch (chan->type) {
> +		case IIO_ANGL_VEL:
> +			ret = adis16550_get_accl_filter_freq(st, val);
> +			if (ret)
> +				return ret;
> +			return IIO_VAL_INT;
> +		case IIO_ACCEL:
> +			ret = adis16550_get_gyro_filter_freq(st, val);
> +			if (ret)
> +				return ret;
> +			return IIO_VAL_INT;
> +		default:
> +			return -EINVAL;
> +		}
> +	default:
> +		return -EINVAL;
> +	}
> +}
> +
> +static int adis16550_write_raw(struct iio_dev *indio_dev,
> +			       const struct iio_chan_spec *chan,
> +			       int val, int val2, long info)
> +{
> +	struct adis16550 *st = iio_priv(indio_dev);
> +	u32 tmp;
> +	const int idx = chan->scan_index;
> +
> +	switch (info) {
> +	case IIO_CHAN_INFO_SAMP_FREQ:
> +		tmp = val * 1000 + val2 / 1000;
> +		return adis16550_set_freq(st, tmp);
> +	case IIO_CHAN_INFO_CALIBBIAS:
> +		return adis_write_reg_32(&st->adis, adis16550_calib_bias[idx],
> +					 val);
> +	case IIO_CHAN_INFO_CALIBSCALE:
> +		return adis_write_reg_16(&st->adis, adis16550_calib_scale[idx],
> +					 val);
> +	case IIO_CHAN_INFO_LOW_PASS_FILTER_3DB_FREQUENCY:
> +		switch (chan->type) {
> +		case IIO_ANGL_VEL:
> +			return adis16550_set_accl_filter_freq(st, val);
> +		case IIO_ACCEL:
> +			return adis16550_set_gyro_filter_freq(st, val);
> +		default:
> +			return -EINVAL;
> +		}
> +	default:
> +		return -EINVAL;
> +	}
> +}
> +
> +#define ADIS16550_MOD_CHAN(_type, _mod, _address, _si, _r_bits, _s_bits) \
> +	{ \
> +		.type = (_type), \
> +		.modified = 1, \
> +		.channel2 = (_mod), \
> +		.info_mask_separate = BIT(IIO_CHAN_INFO_RAW) | \
> +			BIT(IIO_CHAN_INFO_CALIBBIAS) | \
> +			BIT(IIO_CHAN_INFO_CALIBSCALE), \
> +		.info_mask_shared_by_type = BIT(IIO_CHAN_INFO_SCALE) | \
> +					    BIT(IIO_CHAN_INFO_LOW_PASS_FILTER_3DB_FREQUENCY), \
> +		.info_mask_shared_by_all = BIT(IIO_CHAN_INFO_SAMP_FREQ), \
> +		.address = (_address), \
> +		.scan_index = (_si), \
> +		.scan_type = { \
> +			.sign = 's', \
> +			.realbits = (_r_bits), \
> +			.storagebits = (_s_bits), \
As below. These are always 32 , so just fix that for now.

> +			.endianness = IIO_BE, \
> +		}, \
> +	}
> +
> +#define ADIS16550_GYRO_CHANNEL(_mod) \
> +	ADIS16550_MOD_CHAN(IIO_ANGL_VEL, IIO_MOD_ ## _mod, \
> +	ADIS16550_REG_ ## _mod ## _GYRO, ADIS16550_SCAN_GYRO_ ## _mod, 32, \
> +	32)
> +
> +#define ADIS16550_ACCEL_CHANNEL(_mod) \
> +	ADIS16550_MOD_CHAN(IIO_ACCEL, IIO_MOD_ ## _mod, \
> +	ADIS16550_REG_ ## _mod ## _ACCEL, ADIS16550_SCAN_ACCEL_ ## _mod, 32, \
> +	32)
> +
> +#define ADIS16550_TEMP_CHANNEL() { \
> +		.type = IIO_TEMP, \
> +		.indexed = 1, \
> +		.channel = 0, \
> +		.info_mask_separate = BIT(IIO_CHAN_INFO_RAW) | \
> +			BIT(IIO_CHAN_INFO_SCALE) | BIT(IIO_CHAN_INFO_OFFSET), \
> +		.info_mask_shared_by_all = BIT(IIO_CHAN_INFO_SAMP_FREQ), \
> +		.address = ADIS16550_REG_TEMP, \
> +		.scan_index = ADIS16550_SCAN_TEMP, \
> +		.scan_type = { \
> +			.sign = 's', \
> +			.realbits = 16, \
Add a comment here on why you aren't storing it in a be16
(I assume because it requires special casing and no one is ever going to
run this device as just a thermometer!

> +			.storagebits = 32, \
> +			.endianness = IIO_BE, \
> +		}, \
> +	}
> +
> +#define ADIS16550_MOD_CHAN_DELTA(_type, _mod, _address, _si, _r_bits, _s_bits) { \
> +		.type = (_type), \
> +		.modified = 1, \
> +		.channel2 = (_mod), \
> +		.info_mask_separate = BIT(IIO_CHAN_INFO_RAW), \
> +		.info_mask_shared_by_type = BIT(IIO_CHAN_INFO_SCALE), \
> +		.info_mask_shared_by_all = BIT(IIO_CHAN_INFO_SAMP_FREQ), \
> +		.address = (_address), \
> +		.scan_index = _si, \
> +		.scan_type = { \
> +			.sign = 's', \
> +			.realbits = (_r_bits), \
> +			.storagebits = (_s_bits), \
If they are always 32, encode them as that and we can revisit when you add
more parts that aren't. 

> +			.endianness = IIO_BE, \
> +		}, \
> +	}
> +
> +#define ADIS16550_DELTANG_CHAN(_mod) \
> +	ADIS16550_MOD_CHAN_DELTA(IIO_DELTA_ANGL, IIO_MOD_ ## _mod, \
> +			   ADIS16550_REG_ ## _mod ## _DELTANG_L, ADIS16550_SCAN_DELTANG_ ## _mod, 32, 32)
> +
> +#define ADIS16550_DELTVEL_CHAN(_mod) \
> +	ADIS16550_MOD_CHAN_DELTA(IIO_DELTA_VELOCITY, IIO_MOD_ ## _mod, \
> +			   ADIS16550_REG_ ## _mod ## _DELTVEL_L, ADIS16550_SCAN_DELTVEL_ ## _mod, 32, 32)
> +
> +#define ADIS16550_DELTANG_CHAN_NO_SCAN(_mod) \
> +	ADIS16550_MOD_CHAN_DELTA(IIO_DELTA_ANGL, IIO_MOD_ ## _mod, \
> +			   ADIS16550_REG_ ## _mod ## _DELTANG_L, -1, 32, 32)
> +
> +#define ADIS16550_DELTVEL_CHAN_NO_SCAN(_mod) \
> +	ADIS16550_MOD_CHAN_DELTA(IIO_DELTA_VELOCITY, IIO_MOD_ ## _mod, \
> +			   ADIS16550_REG_ ## _mod ## _DELTVEL_L, -1, 32, 32)

> +
> +#define ADIS16550_CHIP_INFO(_name) \
> +	{ \
> +		.num_channels = ARRAY_SIZE(adis16550_channels), \
> +		.channels = adis16550_channels, \
> +		.name = # _name, \

If only the name differs, then use a fallback compatible in DT.
Also do we care about the normal vs w variant?


> +		.gyro_max_val = 1, \
> +		.gyro_max_scale = IIO_RAD_TO_DEGREE(80 << 16), \
> +		.accel_max_val = 1, \
> +		.accel_max_scale = IIO_M_S_2_TO_G(102400000), \
> +		.temp_scale = 4, \
> +		.deltang_max_val = IIO_DEGREE_TO_RAD(720), \
> +		.deltvel_max_val = 125, \
> +		.int_clk = 4000, \
> +		.max_dec = 4095, \
> +		.sync_mode = adis16550_sync_modes, \
> +		.num_sync = ARRAY_SIZE(adis16550_sync_modes), \
> +	}
> +
> +static const struct adis16550_chip_info adis16550_chip_info[] = {
> +	[ADIS16550] =
> +		ADIS16550_CHIP_INFO(adis16550),
> +	[ADIS16550W] =
> +		ADIS16550_CHIP_INFO(adis16550w),
> +};

We've generally stopped using arrays of chip info structures because
it's easier to read
&adis16550_chip_info, &adis16550w_chip_info

So split this.  Note lots of older drivers do what you have here
so this is more of a 'new' best practice thing than anything
thing else.


> +
> +static u32 adis16550_validate_crc(const u32 *buf, const u8 n_elem,
> +				  const u32 crc)
> +{
> +	u32 crc_calc;
> +	u32 crc_buf[ADIS16550_BURST_N_ELEM - 2];
> +	int j;
> +	/*
> +	 * The crc calculation of the data is done in little endian. Hence, we
> +	 * always swap the 32bit elements making sure that the data LSB is
> +	 * always on address 0...
> +	 */
> +	for (j = 0; j < n_elem; j++)
> +		crc_buf[j] = swab32(buf[j]);
> +
> +	crc_calc = crc32(~0, crc_buf, n_elem * 4);
> +	crc_calc ^= ~0;
> +
> +	return (crc_calc == crc);
Drop the ()

> +}
> +
> +static irqreturn_t adis16550_trigger_handler(int irq, void *p)
> +{
> +	struct iio_poll_func *pf = p;
> +	struct iio_dev *indio_dev = pf->indio_dev;
> +	struct adis *adis = iio_device_get_drvdata(indio_dev);
> +	struct adis16550 *st = iio_priv(indio_dev);
> +	__be32 *buffer = adis->buffer, data[ADIS16550_MAX_SCAN_DATA];

Separate lines for those two. This is very hard to read.

> +	u32 crc;
> +	u16 dummy;
> +	int ret, bit, i = 0;
> +	u8 data_offset = 4;
> +	u8 buff_offset = 0;
> +	bool valid;
> +
> +	ret = spi_sync(adis->spi, &adis->msg);
> +	if (ret)
> +		goto done;
> +	/*
> +	 * Validate the header. The header is a normal spi reply with state
> +	 * vector and crc4.
> +	 */
> +	ret = adis16550_spi_validate(&st->adis, buffer[0], &dummy);
> +	if (ret)
> +		goto done;
> +
> +	crc = be32_to_cpu(buffer[ADIS16550_BURST_N_ELEM - 1]);
> +	/* the header is not included in the crc */
> +	valid = adis16550_validate_crc((u32 *)&buffer[1],
> +				       ADIS16550_BURST_N_ELEM - 2, crc);
> +	if (!valid) {
> +		dev_err(&adis->spi->dev, "Burst Invalid crc!\n");
> +		goto done;
> +	}
> +
> +	for_each_set_bit(bit, indio_dev->active_scan_mask,
> +			 indio_dev->masklength) {
> +		switch (bit) {
> +		case ADIS16550_SCAN_TEMP:
> +			data[i++] = buffer[data_offset - 1];
> +			break;
> +		case ADIS16550_SCAN_DELTANG_X ... ADIS16550_SCAN_DELTVEL_Z:
> +			buff_offset = ADIS16550_SCAN_DELTANG_X;

I assume these are contiguous and give available masks you will have
them all if any are set. Use memcpy()
This probably wants to be a bunch of if statements given you should just
check for an indicative element then copy in blocks.


> +			fallthrough;

Just repeat the assignment. The fallthrough makes this harder to read.

> +		case ADIS16550_SCAN_GYRO_X ... ADIS16550_SCAN_ACCEL_Z:
> +			data[i++] = buffer[bit + data_offset - buff_offset];
> +			break;
> +		}
> +	}
> +
> +	iio_push_to_buffers_with_timestamp(indio_dev, data, pf->timestamp);
> +done:
> +	iio_trigger_notify_done(indio_dev->trig);
> +	return IRQ_HANDLED;
> +}
> +
> +static const unsigned long adis16550_channel_masks[] = {
> +	ADIS16550_BURST_DATA_GYRO_ACCEL_MASK | BIT(ADIS16550_SCAN_TEMP) | BIT(13),
> +	ADIS16550_BURST_DATA_DELTA_ANG_VEL_MASK | BIT(ADIS16550_SCAN_TEMP) | BIT(13),

IIRC timestamp is handled separately so shouldn't need to be in here.
I think this is going to end up allocating larger storage than you need
because the timestamp will get counted twice when computing that buffer.

> +	0,
> +};
> +
> +static int adis16550_update_scan_mode(struct iio_dev *indio_dev,
> +				      const unsigned long *scan_mask)
> +{
> +	struct adis *adis = iio_device_get_drvdata(indio_dev);
> +	u8 *tx;

If no other reason for ordering, pick something like reverse xmas
tree and make the code consistent.

> +	u16 burst_length = ADIS16550_BURST_DATA_LEN;
> +	u8 burst_cmd;
> +
> +	if (*scan_mask & ADIS16550_BURST_DATA_GYRO_ACCEL_MASK)
> +		burst_cmd = ADIS16550_REG_BURST_GYRO_ACCEL;
> +	else
> +		burst_cmd = ADIS16550_REG_BURST_DELTA_ANG_VEL;
> +
> +	kfree(adis->xfer);
> +	kfree(adis->buffer);
> +
> +	adis->xfer = kcalloc(2, sizeof(*adis->xfer), GFP_KERNEL);
> +	if (!adis->xfer)
> +		return -ENOMEM;

Always the same size?  Why reallocate it in here - just do it once
at probe, or possibly embed it in the iio_priv() with appropriate
handling to make it dma safe.


> +
> +	adis->buffer = kzalloc(burst_length + sizeof(u32), GFP_KERNEL);
Use a local variable to set this up + __free() to clean it up and
finally no_free_ptr() to 'steal' the ownership after all opportunities
for error have passed.

> +	if (!adis->buffer) {
> +		kfree(adis->xfer);
> +		adis->xfer = NULL;
> +		return -ENOMEM;
> +	}
> +
> +	tx = adis->buffer + burst_length;
> +	tx[0] = 0x00;
> +	tx[1] = 0x00;
> +	tx[2] = burst_cmd;
> +	/* crc4 is 0 on burst command */
> +	tx[3] = spi_crc4(get_unaligned_le32(tx));
> +
> +	adis->xfer[0].tx_buf = tx;
> +	adis->xfer[0].len = 4;
> +	adis->xfer[0].cs_change = 1;
> +	adis->xfer[0].delay.value = 8;
> +	adis->xfer[0].delay.unit = SPI_DELAY_UNIT_USECS;
> +	adis->xfer[1].rx_buf = adis->buffer;
> +	adis->xfer[1].len = burst_length;
> +
> +	spi_message_init_with_transfers(&adis->msg, adis->xfer, 2);
> +
> +	return 0;
> +}

> +static int adis16550_config_sync(struct adis16550 *st)
> +{
> +	int ret;
> +	const struct adis16550_sync *sync;
> +	struct device *dev = &st->adis.spi->dev;
> +	u32 sync_mode;
> +	struct clk *clk;
> +	u16 mode;

I left a comment on the DT binding on this. I'm not sure why we need to explicitly
add a binding for it as opposed to picking right choice based on input clock
frequency and presence or not of the clock.

Maybe you can always pick based just on the clock frequency.
I've not checked the ranges.

> +
> +	if (!device_property_present(dev, "adi,sync-mode")) {
> +		st->clk_freq = st->info->int_clk * 1000;
> +		return 0;
> +	}
> +
> +	if (!device_property_match_string(dev, "adi,sync-mode", "direct_sync"))
> +		sync_mode = 0;
> +	else if (!device_property_match_string(dev, "adi,sync-mode", "scaled_sync"))
> +		sync_mode = 1;
> +	else
> +		return -EINVAL;
> +
> +	sync = &st->info->sync_mode[sync_mode];
> +	st->sync_mode = sync->sync_mode;
> +
> +	clk = devm_clk_get_enabled(dev, NULL);
> +	if (IS_ERR(clk))
> +		return PTR_ERR(clk);
> +
> +	st->clk_freq = clk_get_rate(clk);
> +	if (st->clk_freq > sync->max_rate || st->clk_freq < sync->min_rate)
> +		return dev_err_probe(dev, -EINVAL,
> +				     "Clk rate: %lu not in a valid range:[%u %u]\n",
> +				     st->clk_freq, sync->min_rate, sync->max_rate);
> +
> +	if (sync->sync_mode == ADIS16550_SYNC_MODE_SCALED) {
> +		u16 sync_scale;
> +		u32 scaled_freq = 0;
> +		/*
> +		 * In pps scaled sync we must scale the input clock to a range
> +		 * of [3000 45000].
> +		 */
> +		ret = device_property_read_u32(dev, "adi,scaled-output-hz",
> +					       &scaled_freq);
> +		if (ret)
> +			return dev_err_probe(dev, ret,
> +					     "adi,scaled-output-hz property not found");
> +

Not in the binding Docs that I can see..

> +		if (scaled_freq < 3000 || scaled_freq > 4500)
> +			return dev_err_probe(dev, -EINVAL,
> +					     "Invalid value:%u for adi,scaled-output-hz",
> +					     scaled_freq);
> +
> +		sync_scale = DIV_ROUND_CLOSEST(scaled_freq, st->clk_freq);
> +
> +		ret = adis_write_reg_16(&st->adis, ADIS16550_REG_SYNC_SCALE,
> +					sync_scale);
> +		if (ret)
> +			return ret;
> +
> +		st->clk_freq = scaled_freq;
> +	}
> +
> +	st->clk_freq *= 1000;
change clk_freq to include a unit.
clk_freq_hz or similar then it should be obvious why the multiplier is needed.


> +
> +	/* set sync mode */

Obvious from the field name. I'd drop the comment as it doesn't add
much.

> +	mode = FIELD_PREP(ADIS16550_SYNC_MODE_MASK, sync->sync_mode);
> +	mode |= FIELD_PREP(ADIS16550_SYNC_EN_MASK, true);
	mode = FIELD_PREP() |
	       FIELD_PREP();

cleaner if it's only two lines like this.

> +
> +	return __adis_update_bits(&st->adis, ADIS16550_REG_CONFIG,
> +				  ADIS16550_SYNC_MASK, mode);
> +}

> +static int adis16550_probe(struct spi_device *spi)
> +{
struct device *dev = &spi->dev;
will shorten just enough paths to be worth adding I think.
> +	struct iio_dev *indio_dev;
> +	struct adis16550 *st;
> +	int ret;
> +
> +	indio_dev = devm_iio_device_alloc(&spi->dev, sizeof(*st));
> +	if (!indio_dev)
> +		return -ENOMEM;
> +
> +	st = iio_priv(indio_dev);
> +
> +	st->info =  device_get_match_data(&spi->dev);

Extra space before device

> +	if (!st->info)
> +		return -EINVAL;
> +
> +	indio_dev->name = st->info->name;
> +	indio_dev->channels = st->info->channels;
> +	indio_dev->num_channels = st->info->num_channels;
> +	indio_dev->available_scan_masks = adis16550_channel_masks;
> +	indio_dev->info = &adis16550_info;
> +	indio_dev->modes = INDIO_DIRECT_MODE;
> +
> +	st->adis.ops = &adis16550_ops;
> +
> +	ret = devm_regulator_get_enable(&spi->dev, "vdd");
> +	if (ret)
> +		return dev_err_probe(&spi->dev, ret,
> +				     "Failed to get vdd regulator\n");
> +
> +	ret = adis_init(&st->adis, indio_dev, spi, &adis16550_data);
> +	if (ret)
> +		return ret;
> +
> +	ret = __adis_initial_startup(&st->adis);
> +	if (ret)
> +		return ret;
> +
> +	ret = adis16550_config_sync(st);
> +	if (ret)
> +		return ret;
> +
> +	ret = devm_adis_setup_buffer_and_trigger(&st->adis, indio_dev,
> +						 adis16550_trigger_handler);
> +	if (ret)
> +		return ret;
> +
> +	ret = devm_iio_device_register(&spi->dev, indio_dev);
> +	if (ret)
> +		return ret;
> +
> +	adis16550_debugfs_init(indio_dev);
> +
> +	return 0;
> +}






[Index of Archives]     [Kernel Newbies]     [Security]     [Netfilter]     [Bugtraq]     [Linux FS]     [Yosemite Forum]     [MIPS Linux]     [ARM Linux]     [Linux Security]     [Linux RAID]     [Samba]     [Video 4 Linux]     [Device Mapper]     [Linux Resources]

  Powered by Linux