diff --git a/drivers/sensor/CMakeLists.txt b/drivers/sensor/CMakeLists.txt index 0d3cec2a13d60..bdd188f68d309 100644 --- a/drivers/sensor/CMakeLists.txt +++ b/drivers/sensor/CMakeLists.txt @@ -38,6 +38,7 @@ add_subdirectory(wsen) # zephyr-keep-sorted-stop add_subdirectory_ifdef(CONFIG_A01NYUB a01nyub) +add_subdirectory_ifdef(CONFIG_ALS31300 als31300) add_subdirectory_ifdef(CONFIG_AMD_SB_TSI amd_sb_tsi) add_subdirectory_ifdef(CONFIG_AMG88XX amg88xx) add_subdirectory_ifdef(CONFIG_APDS9253 apds9253) diff --git a/drivers/sensor/Kconfig b/drivers/sensor/Kconfig index 338329cc91d61..288b41f0cfa43 100644 --- a/drivers/sensor/Kconfig +++ b/drivers/sensor/Kconfig @@ -88,6 +88,7 @@ comment "Device Drivers" # zephyr-keep-sorted-start source "drivers/sensor/adi/Kconfig" +source "drivers/sensor/als31300/Kconfig" source "drivers/sensor/ams/Kconfig" source "drivers/sensor/aosong/Kconfig" source "drivers/sensor/asahi_kasei/Kconfig" diff --git a/drivers/sensor/als31300/CMakeLists.txt b/drivers/sensor/als31300/CMakeLists.txt new file mode 100644 index 0000000000000..a87e1a88cef6a --- /dev/null +++ b/drivers/sensor/als31300/CMakeLists.txt @@ -0,0 +1,7 @@ +# Copyright (c) 2025 Croxel +# SPDX-License-Identifier: Apache-2.0 + +zephyr_library() + +zephyr_library_sources(als31300.c) +zephyr_library_sources_ifdef(CONFIG_SENSOR_ASYNC_API als31300_async.c als31300_decoder.c) diff --git a/drivers/sensor/als31300/Kconfig b/drivers/sensor/als31300/Kconfig new file mode 100644 index 0000000000000..7475fcf64348d --- /dev/null +++ b/drivers/sensor/als31300/Kconfig @@ -0,0 +1,14 @@ +# Copyright (c) 2025 Croxel +# SPDX-License-Identifier: Apache-2.0 + +# ALS31300 3D Linear Hall-Effect Sensor configuration options + +config ALS31300 + bool "ALS31300 3D Linear Hall-Effect Sensor" + default y + depends on DT_HAS_ALLEGRO_ALS31300_ENABLED + select I2C + help + Enable driver for ALS31300 3D Linear Hall-Effect Sensor. + This sensor provides 12-bit magnetic field measurements + on X, Y, and Z axes via I2C interface. diff --git a/drivers/sensor/als31300/als31300.c b/drivers/sensor/als31300/als31300.c new file mode 100644 index 0000000000000..47dbeafa10250 --- /dev/null +++ b/drivers/sensor/als31300/als31300.c @@ -0,0 +1,279 @@ +/* + * Copyright (c) 2025 Croxel + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT allegro_als31300 + +#include "als31300.h" + +#include +#include +#include +#include +#include +#include + +LOG_MODULE_REGISTER(als31300, CONFIG_SENSOR_LOG_LEVEL); + +/** + * @brief Convert 12-bit two's complement value to signed 16-bit + * @param value 12-bit value to convert (bits 11:0) + * @return Signed 16-bit value + */ +int16_t als31300_convert_12bit_to_signed(uint16_t value) +{ + return (int16_t)sign_extend(value, ALS31300_12BIT_SIGN_BIT_INDEX); +} + +/** + * @brief Parse raw register data from 8-byte buffer + * @param buf 8-byte buffer containing register 0x28 and 0x29 data + * @param readings Pointer to readings structure to store parsed data + */ +void als31300_parse_registers(const uint8_t *buf, struct als31300_readings *readings) +{ + uint32_t reg28_data, reg29_data; + uint16_t x_msb, y_msb, z_msb; + uint8_t x_lsb, y_lsb, z_lsb; + uint8_t temp_msb, temp_lsb; + + /* Convert 8 bytes to two 32-bit values (MSB first) */ + reg28_data = ((uint32_t)buf[0] << 24) | ((uint32_t)buf[1] << 16) | ((uint32_t)buf[2] << 8) | + ((uint32_t)buf[3]); + reg29_data = ((uint32_t)buf[4] << 24) | ((uint32_t)buf[5] << 16) | ((uint32_t)buf[6] << 8) | + ((uint32_t)buf[7]); + + /* Extract fields from register 0x28 */ + temp_msb = (reg28_data & ALS31300_REG28_TEMP_MSB_MASK) >> ALS31300_REG28_TEMP_MSB_SHIFT; + z_msb = (reg28_data & ALS31300_REG28_Z_AXIS_MSB_MASK) >> ALS31300_REG28_Z_AXIS_MSB_SHIFT; + y_msb = (reg28_data & ALS31300_REG28_Y_AXIS_MSB_MASK) >> ALS31300_REG28_Y_AXIS_MSB_SHIFT; + x_msb = (reg28_data & ALS31300_REG28_X_AXIS_MSB_MASK) >> ALS31300_REG28_X_AXIS_MSB_SHIFT; + + /* Extract fields from register 0x29 */ + temp_lsb = (reg29_data & ALS31300_REG29_TEMP_LSB_MASK) >> ALS31300_REG29_TEMP_LSB_SHIFT; + z_lsb = (reg29_data & ALS31300_REG29_Z_AXIS_LSB_MASK) >> ALS31300_REG29_Z_AXIS_LSB_SHIFT; + y_lsb = (reg29_data & ALS31300_REG29_Y_AXIS_LSB_MASK) >> ALS31300_REG29_Y_AXIS_LSB_SHIFT; + x_lsb = (reg29_data & ALS31300_REG29_X_AXIS_LSB_MASK) >> ALS31300_REG29_X_AXIS_LSB_SHIFT; + + /* Combine MSB and LSB to form 12-bit values */ + const uint16_t x_raw = (x_msb << 4) | x_lsb; + const uint16_t y_raw = (y_msb << 4) | y_lsb; + const uint16_t z_raw = (z_msb << 4) | z_lsb; + const uint16_t temp_raw = (temp_msb << 6) | temp_lsb; + + /* Convert to signed values (proper 12-bit two's complement) */ + readings->x = als31300_convert_12bit_to_signed(x_raw); + readings->y = als31300_convert_12bit_to_signed(y_raw); + readings->z = als31300_convert_12bit_to_signed(z_raw); + readings->temp = temp_raw; +} + +/** + * @brief Convert raw magnetic field value to microgauss + * This function converts the 12-bit signed raw magnetic field value to + * microgauss units + * Formula: microgauss = (raw_value * 500 * 1000000) / 4096 + * @param raw_value Signed 12-bit magnetic field value + * @return Magnetic field in microgauss + */ +int32_t als31300_convert_to_gauss(int16_t raw_value) +{ + /* Convert to microgauss + * For 500G full scale: (raw_value * 500 * 1000000) / 4096 + * This gives us the fractional part in microgauss + */ + return ((int64_t)raw_value * ALS31300_FULL_SCALE_RANGE_GAUSS * 1000000) / + ALS31300_12BIT_RESOLUTION; +} + +/** + * @brief Convert raw temperature value to celsius + * Based on datasheet formula: T(°C) = 302 * (raw_temp - 1708) / 4096 + * @param raw_temp 12-bit raw temperature value + * @return Temperature in microcelsius + */ +int32_t als31300_convert_temperature(uint16_t raw_temp) +{ + /* Convert to microcelsius + * Formula: microcelsius = (302 * (raw_temp - 1708) * 1000000) / 4096 + */ + return ((int64_t)ALS31300_TEMP_SCALE_FACTOR * ((int32_t)raw_temp - ALS31300_TEMP_OFFSET) * + 1000000) / + ALS31300_TEMP_DIVISOR; +} + +/** + * @brief Read and parse sensor data from ALS31300 + * This function performs an 8-byte I2C burst read from registers 0x28 and 0x29 + * to get magnetic field and temperature data. The data is parsed according to + * the datasheet bit field layout and stored in the provided readings structure. + * @param dev Pointer to the device structure + * @param readings Pointer to readings structure to store data + * @return 0 on success, negative error code on failure + */ +static int als31300_read_sensor_data(const struct device *dev, enum sensor_channel chan, + struct als31300_readings *readings) +{ + const struct als31300_config *cfg = dev->config; + struct als31300_data *data = dev->data; + uint8_t buf[8]; + int ret; + + /* Read both data registers in a single 8-byte transaction for consistency */ + ret = i2c_burst_read_dt(&cfg->i2c, ALS31300_REG_DATA_28, buf, sizeof(buf)); + if (ret < 0) { + LOG_ERR("Failed to read sensor data: %d", ret); + return ret; + } + + /* Parse the register data using common helper */ + als31300_parse_registers(buf, readings); + + /* Also update local data structure for compatibility */ + data->x_raw = readings->x; + data->y_raw = readings->y; + data->z_raw = readings->z; + data->temp_raw = readings->temp; + + return 0; +} + +static int als31300_sample_fetch(const struct device *dev, enum sensor_channel chan) +{ + struct als31300_readings readings; + + return als31300_read_sensor_data(dev, chan, &readings); +} + +static int als31300_channel_get(const struct device *dev, enum sensor_channel chan, + struct sensor_value *val) +{ + struct als31300_data *data = dev->data; + int32_t raw_val; + int32_t converted_val; + + switch (chan) { + case SENSOR_CHAN_MAGN_X: + raw_val = data->x_raw; + break; + case SENSOR_CHAN_MAGN_Y: + raw_val = data->y_raw; + break; + case SENSOR_CHAN_MAGN_Z: + raw_val = data->z_raw; + break; + case SENSOR_CHAN_AMBIENT_TEMP: + /* Temperature conversion */ + converted_val = als31300_convert_temperature(data->temp_raw); + sensor_value_from_micro(val, converted_val); + return 0; + default: + return -ENOTSUP; + } + + /* Convert raw magnetic data to gauss */ + converted_val = als31300_convert_to_gauss(raw_val); + sensor_value_from_micro(val, converted_val); + + return 0; +} + +static DEVICE_API(sensor, als31300_api) = { + .sample_fetch = als31300_sample_fetch, + .channel_get = als31300_channel_get, +#ifdef CONFIG_SENSOR_ASYNC_API + .submit = als31300_submit, + .get_decoder = als31300_get_decoder, +#endif +}; + +/** + * @brief Configure ALS31300 to Active Mode + * This function sets the device to Active Mode by writing to the volatile + * register 0x27. This register can be written without customer access mode. + * @param dev Pointer to the device structure + * @return 0 on success, negative error code on failure + */ +static int als31300_configure_device(const struct device *dev) +{ + const struct als31300_config *cfg = dev->config; + uint32_t reg27_value = 0x00000000; /* All bits to 0 = Active Mode */ + int ret; + + LOG_INF("Configuring ALS31300 to Active Mode..."); + + /* Write 0x00000000 to register 0x27 to set Active Mode + * Bits [1:0] = 0 → Active Mode + * Bits [3:2] = 0 → Single read mode (default I2C mode) + * Bits [6:4] = 0 → Low-power count = 0.5ms (doesn't matter in Active Mode) + * Bits [31:7] = 0 → Reserved (should be 0) + */ + ret = i2c_burst_write_dt(&cfg->i2c, ALS31300_REG_VOLATILE_27, (uint8_t *)®27_value, + sizeof(reg27_value)); + if (ret < 0) { + LOG_ERR("Failed to write to register 0x27: %d", ret); + return ret; + } + + return 0; +} + +/** + * @brief Initialize ALS31300 device + */ +static int als31300_init(const struct device *dev) +{ + const struct als31300_config *cfg = dev->config; + int ret; + + if (!i2c_is_ready_dt(&cfg->i2c)) { + LOG_ERR("I2C device not ready"); + return -ENODEV; + } + + /* Wait for power-on delay as specified in datasheet */ + k_usleep(ALS31300_POWER_ON_DELAY_US); + + /* Test communication by reading a register (can be done without customer access) */ + uint8_t test_val; + + ret = i2c_reg_read_byte_dt(&cfg->i2c, ALS31300_REG_VOLATILE_27, &test_val); + if (ret < 0) { + LOG_ERR("Failed to communicate with sensor: %d", ret); + return ret; + } + + /* Configure device to Active Mode */ + ret = als31300_configure_device(dev); + if (ret < 0) { + LOG_ERR("Failed to configure device: %d", ret); + return ret; + } + + /* Wait a bit more for the sensor to be fully ready in Active Mode */ + k_msleep(ALS31300_REG_WRITE_DELAY_MS); + + return 0; +} + +#define ALS31300_INIT(inst) \ + RTIO_DEFINE(als31300_rtio_ctx_##inst, 16, 16); \ + I2C_DT_IODEV_DEFINE(als31300_bus_##inst, DT_DRV_INST(inst)); \ + \ + static struct als31300_data als31300_data_##inst; \ + \ + static const struct als31300_config als31300_config_##inst = { \ + .i2c = I2C_DT_SPEC_INST_GET(inst), \ + .bus = \ + { \ + .ctx = &als31300_rtio_ctx_##inst, \ + .iodev = &als31300_bus_##inst, \ + }, \ + }; \ + \ + SENSOR_DEVICE_DT_INST_DEFINE(inst, als31300_init, NULL, &als31300_data_##inst, \ + &als31300_config_##inst, POST_KERNEL, \ + CONFIG_SENSOR_INIT_PRIORITY, &als31300_api) + +DT_INST_FOREACH_STATUS_OKAY(ALS31300_INIT); diff --git a/drivers/sensor/als31300/als31300.h b/drivers/sensor/als31300/als31300.h new file mode 100644 index 0000000000000..cca8d5ae05240 --- /dev/null +++ b/drivers/sensor/als31300/als31300.h @@ -0,0 +1,202 @@ +/* + * Copyright (c) 2025 Croxel + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef ZEPHYR_DRIVERS_SENSOR_ALS31300_H_ +#define ZEPHYR_DRIVERS_SENSOR_ALS31300_H_ + +#include +#include +#include +#include + +/* ALS31300 Register Definitions */ +#define ALS31300_REG_EEPROM_02 0x02 +#define ALS31300_REG_EEPROM_03 0x03 +#define ALS31300_REG_VOLATILE_27 0x27 +#define ALS31300_REG_DATA_28 0x28 +#define ALS31300_REG_DATA_29 0x29 + +/* Customer Access Code */ +#define ALS31300_ACCESS_ADDR 0x35 +#define ALS31300_ACCESS_CODE 0x2C413534 + +/* Register 0x02 bit definitions */ +#define ALS31300_BW_SELECT_MASK GENMASK(23, 21) +#define ALS31300_BW_SELECT_SHIFT 21 +#define ALS31300_HALL_MODE_MASK GENMASK(20, 19) +#define ALS31300_HALL_MODE_SHIFT 19 +#define ALS31300_CHAN_Z_EN BIT(8) +#define ALS31300_CHAN_Y_EN BIT(7) +#define ALS31300_CHAN_X_EN BIT(6) + +/* Register 0x27 bit definitions */ +#define ALS31300_SLEEP_MASK GENMASK(1, 0) +#define ALS31300_SLEEP_ACTIVE 0 +#define ALS31300_SLEEP_MODE 1 +#define ALS31300_SLEEP_LPDCM 2 + +/* Register 0x28 bit fields */ +#define ALS31300_REG28_TEMP_MSB_MASK GENMASK(5, 0) /* Bits 5:0 */ +#define ALS31300_REG28_TEMP_MSB_SHIFT 0 + +#define ALS31300_REG28_INTERRUPT_MASK GENMASK(6, 6) /* Bit 6 */ +#define ALS31300_REG28_INTERRUPT_SHIFT 6 + +#define ALS31300_REG28_NEW_DATA_MASK GENMASK(7, 7) /* Bit 7 */ +#define ALS31300_REG28_NEW_DATA_SHIFT 7 + +#define ALS31300_REG28_Z_AXIS_MSB_MASK GENMASK(15, 8) /* Bits 15:8 */ +#define ALS31300_REG28_Z_AXIS_MSB_SHIFT 8 + +#define ALS31300_REG28_Y_AXIS_MSB_MASK GENMASK(23, 16) /* Bits 23:16 */ +#define ALS31300_REG28_Y_AXIS_MSB_SHIFT 16 + +#define ALS31300_REG28_X_AXIS_MSB_MASK GENMASK(31, 24) /* Bits 31:24 */ +#define ALS31300_REG28_X_AXIS_MSB_SHIFT 24 + +/* Register 0x29 bit fields */ +#define ALS31300_REG29_TEMP_LSB_MASK GENMASK(5, 0) /* Bits 5:0 */ +#define ALS31300_REG29_TEMP_LSB_SHIFT 0 + +#define ALS31300_REG29_HALL_MODE_STATUS_MASK GENMASK(7, 6) /* Bits 7:6 */ +#define ALS31300_REG29_HALL_MODE_STATUS_SHIFT 6 + +#define ALS31300_REG29_Z_AXIS_LSB_MASK GENMASK(11, 8) /* Bits 11:8 */ +#define ALS31300_REG29_Z_AXIS_LSB_SHIFT 8 + +#define ALS31300_REG29_Y_AXIS_LSB_MASK GENMASK(15, 12) /* Bits 15:12 */ +#define ALS31300_REG29_Y_AXIS_LSB_SHIFT 12 + +#define ALS31300_REG29_X_AXIS_LSB_MASK GENMASK(19, 16) /* Bits 19:16 */ +#define ALS31300_REG29_X_AXIS_LSB_SHIFT 16 + +#define ALS31300_REG29_INTERRUPT_WRITE_MASK GENMASK(20, 20) /* Bit 20 */ +#define ALS31300_REG29_INTERRUPT_WRITE_SHIFT 20 + +#define ALS31300_REG29_RESERVED_MASK GENMASK(31, 21) /* Bits 31:21 */ +#define ALS31300_REG29_RESERVED_SHIFT 21 + +/* ALS31300 sensitivity and conversion constants */ +#define ALS31300_FULL_SCALE_RANGE_GAUSS 500 /* 500 gauss full scale */ +#define ALS31300_12BIT_RESOLUTION 4096 /* 2^12 for 12-bit resolution */ +#define ALS31300_12BIT_SIGN_BIT_INDEX 11 /* Sign bit position for 12-bit values (0-based) */ + +/* ALS31300 EEPROM Register 0x02 bit field definitions */ +#define ALS31300_EEPROM_CUSTOMER_EE_MASK GENMASK(4, 0) /* Bits 4:0 */ +#define ALS31300_EEPROM_CUSTOMER_EE_SHIFT 0 + +#define ALS31300_EEPROM_INT_LATCH_EN_MASK BIT(5) /* Bit 5 */ +#define ALS31300_EEPROM_INT_LATCH_EN_SHIFT 5 + +#define ALS31300_EEPROM_CHANNEL_X_EN_MASK BIT(6) /* Bit 6 */ +#define ALS31300_EEPROM_CHANNEL_X_EN_SHIFT 6 + +#define ALS31300_EEPROM_CHANNEL_Y_EN_MASK BIT(7) /* Bit 7 */ +#define ALS31300_EEPROM_CHANNEL_Y_EN_SHIFT 7 + +#define ALS31300_EEPROM_CHANNEL_Z_EN_MASK BIT(8) /* Bit 8 */ +#define ALS31300_EEPROM_CHANNEL_Z_EN_SHIFT 8 + +#define ALS31300_EEPROM_I2C_THRESHOLD_MASK BIT(9) /* Bit 9 */ +#define ALS31300_EEPROM_I2C_THRESHOLD_SHIFT 9 + +#define ALS31300_EEPROM_SLAVE_ADDR_MASK GENMASK(16, 10) /* Bits 16:10 */ +#define ALS31300_EEPROM_SLAVE_ADDR_SHIFT 10 + +#define ALS31300_EEPROM_DISABLE_SLAVE_ADC_MASK BIT(17) /* Bit 17 */ +#define ALS31300_EEPROM_DISABLE_SLAVE_ADC_SHIFT 17 + +#define ALS31300_EEPROM_I2C_CRC_EN_MASK BIT(18) /* Bit 18 */ +#define ALS31300_EEPROM_I2C_CRC_EN_SHIFT 18 + +#define ALS31300_EEPROM_HALL_MODE_MASK GENMASK(20, 19) /* Bits 20:19 */ +#define ALS31300_EEPROM_HALL_MODE_SHIFT 19 + +#define ALS31300_EEPROM_BW_SELECT_MASK GENMASK(23, 21) /* Bits 23:21 */ +#define ALS31300_EEPROM_BW_SELECT_SHIFT 21 + +#define ALS31300_EEPROM_RESERVED_MASK GENMASK(31, 24) /* Bits 31:24 */ +#define ALS31300_EEPROM_RESERVED_SHIFT 24 + +/* Timing constants */ +#define ALS31300_POWER_ON_DELAY_US 600 +#define ALS31300_REG_WRITE_DELAY_MS 50 + +/* Fixed-point conversion constants */ +#define ALS31300_TEMP_SCALE_FACTOR 302 /* Temperature scale factor */ +#define ALS31300_TEMP_OFFSET 1708 /* Temperature offset */ +#define ALS31300_TEMP_DIVISOR 4096 /* Temperature divisor */ + +/* RTIO-specific constants */ +#define ALS31300_MAGN_SHIFT 16 /* Q31 shift for magnetic field values */ +#define ALS31300_TEMP_SHIFT 16 /* Q31 shift for temperature values */ + +/* Sensor readings structure */ +struct als31300_readings { + int16_t x; + int16_t y; + int16_t z; + uint16_t temp; +}; + +/* Bus abstraction structure */ +struct als31300_bus { + struct rtio *ctx; + struct rtio_iodev *iodev; +}; + +/* RTIO encoded data structures */ +struct als31300_encoded_header { + uint8_t channels; + uint8_t reserved[3]; + uint64_t timestamp; +} __attribute__((__packed__)); + +struct als31300_encoded_data { + struct als31300_encoded_header header; + uint8_t payload[8]; /* Raw I2C data from registers 0x28-0x29 */ +} __attribute__((__packed__)); + +/* Forward declarations for structures used in multiple files */ +struct als31300_data { + int16_t x_raw; + int16_t y_raw; + int16_t z_raw; + int16_t temp_raw; +}; + +struct als31300_config { + struct i2c_dt_spec i2c; + struct als31300_bus bus; +}; + +/* Common helper functions shared between sync and async implementations */ +int16_t als31300_convert_12bit_to_signed(uint16_t value); +void als31300_parse_registers(const uint8_t *buf, struct als31300_readings *readings); +int32_t als31300_convert_to_gauss(int16_t raw_value); +int32_t als31300_convert_temperature(uint16_t raw_temp); + +#ifdef CONFIG_SENSOR_ASYNC_API +#include + +struct rtio_sqe; +struct rtio_iodev_sqe; +struct sensor_read_config; +struct sensor_decoder_api; + +/* Async I2C helper function */ +int als31300_prep_i2c_read_async(const struct als31300_config *cfg, uint8_t reg, uint8_t *buf, + size_t size, struct rtio_sqe **out); + +/* Encode function for async API */ +int als31300_encode(const struct device *dev, const struct sensor_read_config *read_config, + uint8_t trigger_status, uint8_t *buf); + +/* Async API functions */ +void als31300_submit(const struct device *dev, struct rtio_iodev_sqe *iodev_sqe); +int als31300_get_decoder(const struct device *dev, const struct sensor_decoder_api **decoder); +#endif + +#endif /* ZEPHYR_DRIVERS_SENSOR_ALS31300_H_ */ diff --git a/drivers/sensor/als31300/als31300_async.c b/drivers/sensor/als31300/als31300_async.c new file mode 100644 index 0000000000000..0e6285f0098d7 --- /dev/null +++ b/drivers/sensor/als31300/als31300_async.c @@ -0,0 +1,205 @@ +/* + * Copyright (c) 2025 Croxel + * SPDX-License-Identifier: Apache-2.0 + */ + +#include "als31300.h" + +#include +#include +#include +#include +#include +#include +#include + +LOG_MODULE_DECLARE(als31300, CONFIG_SENSOR_LOG_LEVEL); + +/** + * @brief Encode channel flags for the given sensor channel + */ +static uint8_t als31300_encode_channel(enum sensor_channel chan) +{ + uint8_t encode_bmask = 0; + + switch (chan) { + case SENSOR_CHAN_MAGN_X: + encode_bmask |= BIT(0); + break; + case SENSOR_CHAN_MAGN_Y: + encode_bmask |= BIT(1); + break; + case SENSOR_CHAN_MAGN_Z: + encode_bmask |= BIT(2); + break; + case SENSOR_CHAN_MAGN_XYZ: + encode_bmask |= BIT(0) | BIT(1) | BIT(2); + break; + case SENSOR_CHAN_AMBIENT_TEMP: + encode_bmask |= BIT(3); + break; + case SENSOR_CHAN_ALL: + encode_bmask |= BIT(0) | BIT(1) | BIT(2) | BIT(3); + break; + default: + break; + } + + return encode_bmask; +} + +/** + * @brief Prepare async I2C read operation + */ +int als31300_prep_i2c_read_async(const struct als31300_config *cfg, uint8_t reg, uint8_t *buf, + size_t size, struct rtio_sqe **out) +{ + struct rtio *ctx = cfg->bus.ctx; + struct rtio_iodev *iodev = cfg->bus.iodev; + struct rtio_sqe *write_reg_sqe = rtio_sqe_acquire(ctx); + struct rtio_sqe *read_buf_sqe = rtio_sqe_acquire(ctx); + + if (!write_reg_sqe || !read_buf_sqe) { + rtio_sqe_drop_all(ctx); + return -ENOMEM; + } + + rtio_sqe_prep_tiny_write(write_reg_sqe, iodev, RTIO_PRIO_NORM, ®, 1, NULL); + write_reg_sqe->flags |= RTIO_SQE_TRANSACTION; + + rtio_sqe_prep_read(read_buf_sqe, iodev, RTIO_PRIO_NORM, buf, size, NULL); + read_buf_sqe->iodev_flags |= RTIO_IODEV_I2C_STOP | RTIO_IODEV_I2C_RESTART; + + if (out) { + *out = read_buf_sqe; + } + + return 0; +} + +/** + * @brief Completion callback for async operations + */ +static void als31300_complete_result(struct rtio *ctx, const struct rtio_sqe *sqe, int result, + void *arg) +{ + ARG_UNUSED(result); + struct rtio_iodev_sqe *iodev_sqe = (struct rtio_iodev_sqe *)sqe->userdata; + struct rtio_cqe *cqe; + int err = 0; + + do { + cqe = rtio_cqe_consume(ctx); + if (cqe != NULL) { + err = cqe->result; + rtio_cqe_release(ctx, cqe); + } + } while (cqe != NULL); + + if (err != 0) { + rtio_iodev_sqe_err(iodev_sqe, err); + } else { + rtio_iodev_sqe_ok(iodev_sqe, 0); + } +} + +/** + * @brief Encode sensor metadata for async API + */ +int als31300_encode(const struct device *dev, const struct sensor_read_config *read_config, + uint8_t trigger_status, uint8_t *buf) +{ + struct als31300_encoded_data *edata = (struct als31300_encoded_data *)buf; + uint64_t cycles; + int err; + + ARG_UNUSED(dev); + + edata->header.channels = 0; + + if (trigger_status) { + /* For triggers, encode all channels */ + edata->header.channels |= als31300_encode_channel(SENSOR_CHAN_ALL); + } else { + /* For normal reads, encode requested channels */ + const struct sensor_chan_spec *const channels = read_config->channels; + size_t num_channels = read_config->count; + + for (size_t i = 0; i < num_channels; i++) { + edata->header.channels |= als31300_encode_channel(channels[i].chan_type); + } + } + + /* Get timestamp */ + err = sensor_clock_get_cycles(&cycles); + if (err != 0) { + return err; + } + + edata->header.timestamp = sensor_clock_cycles_to_ns(cycles); + + return 0; +} + +/** + * @brief RTIO submit function using chained SQE approach + */ +static void als31300_submit_one_shot(const struct device *dev, struct rtio_iodev_sqe *iodev_sqe) +{ + const struct sensor_read_config *cfg = iodev_sqe->sqe.iodev->data; + uint32_t min_buf_len = sizeof(struct als31300_encoded_data); + int err; + uint8_t *buf; + uint32_t buf_len; + struct als31300_encoded_data *edata; + const struct als31300_config *conf = dev->config; + + err = rtio_sqe_rx_buf(iodev_sqe, min_buf_len, min_buf_len, &buf, &buf_len); + if (err < 0 || buf_len < min_buf_len || !buf) { + LOG_ERR("Failed to get a read buffer of size %u bytes", min_buf_len); + rtio_iodev_sqe_err(iodev_sqe, err); + return; + } + + edata = (struct als31300_encoded_data *)buf; + + err = als31300_encode(dev, cfg, 0, buf); + if (err != 0) { + LOG_ERR("Failed to encode sensor data"); + rtio_iodev_sqe_err(iodev_sqe, err); + return; + } + + struct rtio_sqe *read_sqe; + + err = als31300_prep_i2c_read_async(conf, ALS31300_REG_DATA_28, edata->payload, + sizeof(edata->payload), &read_sqe); + if (err < 0) { + LOG_ERR("Failed to prepare async read operation"); + rtio_iodev_sqe_err(iodev_sqe, err); + return; + } + read_sqe->flags |= RTIO_SQE_CHAINED; + + struct rtio_sqe *complete_sqe = rtio_sqe_acquire(conf->bus.ctx); + + if (!complete_sqe) { + LOG_ERR("Failed to acquire completion SQE"); + rtio_iodev_sqe_err(iodev_sqe, -ENOMEM); + rtio_sqe_drop_all(conf->bus.ctx); + return; + } + + rtio_sqe_prep_callback_no_cqe(complete_sqe, &als31300_complete_result, (void *)dev, + iodev_sqe); + + rtio_submit(conf->bus.ctx, 0); +} + +/** + * @brief RTIO submit function + */ +void als31300_submit(const struct device *dev, struct rtio_iodev_sqe *iodev_sqe) +{ + als31300_submit_one_shot(dev, iodev_sqe); +} diff --git a/drivers/sensor/als31300/als31300_decoder.c b/drivers/sensor/als31300/als31300_decoder.c new file mode 100644 index 0000000000000..1ac18fa0ac14a --- /dev/null +++ b/drivers/sensor/als31300/als31300_decoder.c @@ -0,0 +1,193 @@ +/* + * Copyright (c) 2025 Croxel + * SPDX-License-Identifier: Apache-2.0 + */ + +#include "als31300.h" + +#include +#include +#include +#include + +LOG_MODULE_DECLARE(als31300, CONFIG_SENSOR_LOG_LEVEL); + +/** + * @brief Encode channel flags for the given sensor channel + */ +static uint8_t als31300_encode_channel(enum sensor_channel chan) +{ + uint8_t encode_bmask = 0; + + switch (chan) { + case SENSOR_CHAN_MAGN_X: + encode_bmask |= BIT(0); + break; + case SENSOR_CHAN_MAGN_Y: + encode_bmask |= BIT(1); + break; + case SENSOR_CHAN_MAGN_Z: + encode_bmask |= BIT(2); + break; + case SENSOR_CHAN_MAGN_XYZ: + encode_bmask |= BIT(0) | BIT(1) | BIT(2); + break; + case SENSOR_CHAN_AMBIENT_TEMP: + encode_bmask |= BIT(3); + break; + case SENSOR_CHAN_ALL: + encode_bmask |= BIT(0) | BIT(1) | BIT(2) | BIT(3); + break; + default: + break; + } + + return encode_bmask; +} + +/** + * @brief Convert raw magnetic field value to Q31 format + * @param raw_value Signed 12-bit magnetic field value + * @param q31_out Pointer to store Q31 value + */ +static void als31300_convert_raw_to_q31_magn(int16_t raw_value, q31_t *q31_out) +{ + /* Convert to microgauss using integer arithmetic */ + int32_t microgauss = als31300_convert_to_gauss(raw_value); + + /* Convert to Q31 format: Q31 = (value * 2^shift) / 1000000 + * For magnetic field, we use shift=16, so the full scale is ±2^(31-16) = ±32768 gauss + * This gives us good resolution for the ±500G range of the ALS31300 + * microgauss * 2^16 / 1000000 = microgauss * 65536 / 1000000 + */ + *q31_out = (q31_t)(((int64_t)microgauss << ALS31300_MAGN_SHIFT) / 1000000); +} + +/** + * @brief Convert raw temperature value to Q31 format + * @param raw_temp 12-bit raw temperature value + * @param q31_out Pointer to store Q31 value + */ +static void als31300_convert_temp_to_q31(uint16_t raw_temp, q31_t *q31_out) +{ + /* Convert to microcelsius using integer arithmetic */ + int32_t microcelsius = als31300_convert_temperature(raw_temp); + + /* Convert to Q31 format: Q31 = (value * 2^shift) / 1000000 + * For temperature, we use shift=16, so the full scale is ±2^(31-16) = ±32768°C + * This gives us good resolution for typical temperature ranges (-40°C to +125°C) + * microcelsius * 2^16 / 1000000 = microcelsius * 65536 / 1000000 + */ + *q31_out = (q31_t)(((int64_t)microcelsius << ALS31300_TEMP_SHIFT) / 1000000); +} + +/** + * @brief Get frame count for decoder + */ +static int als31300_decoder_get_frame_count(const uint8_t *buffer, + struct sensor_chan_spec chan_spec, + uint16_t *frame_count) +{ + const struct als31300_encoded_data *edata = (const struct als31300_encoded_data *)buffer; + + if (chan_spec.chan_idx != 0) { + return -ENOTSUP; + } + + uint8_t channel_request = als31300_encode_channel(chan_spec.chan_type); + + /* Filter unknown channels and having no data */ + if ((edata->header.channels & channel_request) != channel_request) { + return -ENODATA; + } + + *frame_count = 1; + return 0; +} + +/** + * @brief Get size info for decoder + */ +static int als31300_decoder_get_size_info(struct sensor_chan_spec chan_spec, size_t *base_size, + size_t *frame_size) +{ + switch (chan_spec.chan_type) { + case SENSOR_CHAN_MAGN_X: + case SENSOR_CHAN_MAGN_Y: + case SENSOR_CHAN_MAGN_Z: + case SENSOR_CHAN_MAGN_XYZ: + *base_size = sizeof(struct sensor_three_axis_data); + *frame_size = sizeof(struct sensor_three_axis_sample_data); + return 0; + case SENSOR_CHAN_AMBIENT_TEMP: + *base_size = sizeof(struct sensor_q31_data); + *frame_size = sizeof(struct sensor_q31_sample_data); + return 0; + default: + return -ENOTSUP; + } +} + +/** + * @brief Decode function for RTIO + */ +static int als31300_decoder_decode(const uint8_t *buffer, struct sensor_chan_spec chan_spec, + uint32_t *fit, uint16_t max_count, void *data_out) +{ + const struct als31300_encoded_data *edata = (const struct als31300_encoded_data *)buffer; + + if (*fit != 0) { + return 0; + } + + /* Parse raw payload data using common helper */ + struct als31300_readings readings; + + als31300_parse_registers(edata->payload, &readings); + + switch (chan_spec.chan_type) { + case SENSOR_CHAN_MAGN_X: + case SENSOR_CHAN_MAGN_Y: + case SENSOR_CHAN_MAGN_Z: + case SENSOR_CHAN_MAGN_XYZ: { + struct sensor_three_axis_data *out = data_out; + + out->header.base_timestamp_ns = edata->header.timestamp; + out->header.reading_count = 1; + out->shift = ALS31300_MAGN_SHIFT; + + /* Convert raw readings to Q31 format */ + als31300_convert_raw_to_q31_magn(readings.x, &out->readings[0].x); + als31300_convert_raw_to_q31_magn(readings.y, &out->readings[0].y); + als31300_convert_raw_to_q31_magn(readings.z, &out->readings[0].z); + *fit = 1; + return 1; + } + case SENSOR_CHAN_AMBIENT_TEMP: { + struct sensor_q31_data *out = data_out; + + out->header.base_timestamp_ns = edata->header.timestamp; + out->header.reading_count = 1; + out->shift = ALS31300_TEMP_SHIFT; + + als31300_convert_temp_to_q31(readings.temp, &out->readings[0].temperature); + *fit = 1; + return 1; + } + default: + return -ENOTSUP; + } +} + +SENSOR_DECODER_API_DT_DEFINE() = { + .get_frame_count = als31300_decoder_get_frame_count, + .get_size_info = als31300_decoder_get_size_info, + .decode = als31300_decoder_decode, +}; + +int als31300_get_decoder(const struct device *dev, const struct sensor_decoder_api **decoder) +{ + ARG_UNUSED(dev); + *decoder = &SENSOR_DECODER_NAME(); + return 0; +} diff --git a/dts/bindings/sensor/allegro,als31300.yaml b/dts/bindings/sensor/allegro,als31300.yaml new file mode 100644 index 0000000000000..2469517429d9e --- /dev/null +++ b/dts/bindings/sensor/allegro,als31300.yaml @@ -0,0 +1,7 @@ +# ALS31300 Device Tree Binding + +description: Allegro ALS31300 3D Linear Hall Effect Sensor + +compatible: "allegro,als31300" + +include: [sensor-device.yaml, i2c-device.yaml] diff --git a/tests/drivers/build_all/sensor/i2c.dtsi b/tests/drivers/build_all/sensor/i2c.dtsi index eb505c663f7ff..cf21635773b54 100644 --- a/tests/drivers/build_all/sensor/i2c.dtsi +++ b/tests/drivers/build_all/sensor/i2c.dtsi @@ -1417,3 +1417,8 @@ test_i2c_ina7xx: ina7xx@bc { tct = <5>; avg = <3>; }; + +test_i2c_als31300: als31300@bd { + compatible = "allegro,als31300"; + reg = <0xbd>; +};