drivers: sensor: icp201xx: Add icp201xx support

Use official TDK Invensense driver for icp201xx sensor in tdk_hal module.

Signed-off-by: Remi Buisson <remi.buisson@tdk.com>
diff --git a/drivers/sensor/tdk/CMakeLists.txt b/drivers/sensor/tdk/CMakeLists.txt
index e4b8605..09936cd 100644
--- a/drivers/sensor/tdk/CMakeLists.txt
+++ b/drivers/sensor/tdk/CMakeLists.txt
@@ -7,6 +7,7 @@
 add_subdirectory_ifdef(CONFIG_ICM42X70 icm42x70)
 add_subdirectory_ifdef(CONFIG_ICM45686 icm45686)
 add_subdirectory_ifdef(CONFIG_ICP101XX icp101xx)
+add_subdirectory_ifdef(CONFIG_ICP201XX icp201xx)
 add_subdirectory_ifdef(CONFIG_MPU6050 mpu6050)
 add_subdirectory_ifdef(CONFIG_MPU9250 mpu9250)
 # zephyr-keep-sorted-stop
diff --git a/drivers/sensor/tdk/Kconfig b/drivers/sensor/tdk/Kconfig
index 8f5d61a..2b9163a 100644
--- a/drivers/sensor/tdk/Kconfig
+++ b/drivers/sensor/tdk/Kconfig
@@ -7,6 +7,7 @@
 source "drivers/sensor/tdk/icm42x70/Kconfig"
 source "drivers/sensor/tdk/icm45686/Kconfig"
 source "drivers/sensor/tdk/icp101xx/Kconfig"
+source "drivers/sensor/tdk/icp201xx/Kconfig"
 source "drivers/sensor/tdk/mpu6050/Kconfig"
 source "drivers/sensor/tdk/mpu9250/Kconfig"
 # zephyr-keep-sorted-stop
diff --git a/drivers/sensor/tdk/icp201xx/CMakeLists.txt b/drivers/sensor/tdk/icp201xx/CMakeLists.txt
new file mode 100644
index 0000000..6bc7607
--- /dev/null
+++ b/drivers/sensor/tdk/icp201xx/CMakeLists.txt
@@ -0,0 +1,10 @@
+# SPDX-License-Identifier: Apache-2.0
+
+zephyr_library()
+
+zephyr_library_sources(icp201xx_drv.c)
+zephyr_library_sources_ifdef(CONFIG_SPI icp201xx_spi.c)
+zephyr_library_sources_ifdef(CONFIG_I2C icp201xx_i2c.c)
+
+zephyr_library_sources_ifdef(CONFIG_ICP201XX_TRIGGER icp201xx_trigger.c)
+zephyr_library_include_directories(.)
diff --git a/drivers/sensor/tdk/icp201xx/Kconfig b/drivers/sensor/tdk/icp201xx/Kconfig
new file mode 100644
index 0000000..facb97d
--- /dev/null
+++ b/drivers/sensor/tdk/icp201xx/Kconfig
@@ -0,0 +1,25 @@
+# ICP201xx High Accuracy, Low Power, Barometric Pressure and Temperature Sensor IC
+#
+# Copyright (c) 2025 TDK Invensense
+#
+# SPDX-License-Identifier: Apache-2.0
+
+menuconfig ICP201XX
+	bool "ICP201xx Barometric Pressure and Temperature Sensor"
+	default y
+	depends on DT_HAS_INVENSENSE_ICP201XX_ENABLED
+	select I2C if $(dt_compat_on_bus,$(DT_COMPAT_INVENSENSE_ICP201XX),i2c)
+	select SPI if $(dt_compat_on_bus,$(DT_COMPAT_INVENSENSE_ICP201XX),spi)
+	select USE_EMD_ICP201XX
+	select FPU if CPU_HAS_FPU
+	help
+		Enable driver for ICP101xx Barometric Pressure and Temperature Sensor.
+
+if ICP201XX
+
+module = ICP201XX
+thread_priority = 10
+thread_stack_size = 1024
+source "drivers/sensor/Kconfig.trigger_template"
+
+endif # ICP201XX
diff --git a/drivers/sensor/tdk/icp201xx/icp201xx_drv.c b/drivers/sensor/tdk/icp201xx/icp201xx_drv.c
new file mode 100644
index 0000000..26b4426
--- /dev/null
+++ b/drivers/sensor/tdk/icp201xx/icp201xx_drv.c
@@ -0,0 +1,445 @@
+/*
+ * Copyright (c) 2025 TDK Invensense
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#include <zephyr/kernel.h>
+#include <zephyr/drivers/sensor.h>
+#include <zephyr/init.h>
+#include <zephyr/drivers/gpio.h>
+#include <zephyr/pm/device.h>
+#include <zephyr/sys/byteorder.h>
+#include <zephyr/sys/__assert.h>
+
+#include <zephyr/logging/log.h>
+
+#include "icp201xx_drv.h"
+#include "Icp201xxDriver.h"
+
+LOG_MODULE_REGISTER(ICP201XX, CONFIG_SENSOR_LOG_LEVEL);
+
+#ifdef CONFIG_FPU
+#include <math.h>
+#define ATMOSPHERICAL_PRESSURE_KPA ((float)101.325)
+#define TO_KELVIN(temp_C)          (((float)273.15) + temp_C)
+/* Constant in altitude formula:
+ * M*g/R = (0,0289644 * 9,80665 / 8,31432)
+ * with M the molar mass of air.
+ * with g the gravitational force acceleration.
+ * with R the universal gaz constant.
+ */
+#define HEIGHT_TO_PRESSURE_COEFF   ((float)0.03424)
+
+/* Constant in altitude formula:
+ * R / (M*g) = 8,31432 / (0,0289644 * 9,80665)
+ * with M the molar mass of air.
+ * with g the gravitational force acceleration.
+ * with R the universal gaz constant.
+ */
+#define PRESSURE_TO_HEIGHT_COEFF   ((float)29.27127)
+/* Constant for altitude formula:
+ * logarithm of pressure at 0m
+ * ln(101.325)
+ */
+#define LOG_ATMOSPHERICAL_PRESSURE ((float)4.61833)
+#endif
+
+#define IO_DRIVE_STRENGTH_ADDR 0x0D
+
+void inv_icp201xx_sleep_us(int us)
+{
+	k_sleep(K_USEC(us));
+}
+
+static int inv_io_hal_read_reg(void *ctx, uint8_t reg, uint8_t *rbuffer, uint32_t rlen)
+{
+	struct device *dev = (struct device *)ctx;
+	const struct icp201xx_config *cfg = (const struct icp201xx_config *)dev->config;
+
+	return cfg->bus_io->read(&cfg->bus, reg, rbuffer, rlen);
+}
+
+static int inv_io_hal_write_reg(void *ctx, uint8_t reg, const uint8_t *wbuffer, uint32_t wlen)
+{
+	struct device *dev = (struct device *)ctx;
+	const struct icp201xx_config *cfg = (const struct icp201xx_config *)dev->config;
+
+	return cfg->bus_io->write(&cfg->bus, reg, (uint8_t *)wbuffer, wlen);
+}
+
+#ifdef CONFIG_FPU
+static float convertToHeight(float pressure_kp, float temperature_C)
+{
+	return PRESSURE_TO_HEIGHT_COEFF * TO_KELVIN(temperature_C) *
+	       (LOG_ATMOSPHERICAL_PRESSURE - logf(pressure_kp));
+}
+#endif
+
+/*
+ * ICP201xx warm up.
+ * If FIR filter is enabled, it will cause a settling effect on the first 14 pressure values.
+ * Therefore the first 14 pressure output values are discarded.
+ *
+ */
+void inv_icp201xx_app_warmup(inv_icp201xx_t *icp_device, icp201xx_op_mode_t op_mode,
+			     icp201xx_meas_mode_t meas_mode)
+{
+	volatile uint8_t fifo_packets = 0;
+	uint8_t fifo_packets_to_skip = 14;
+
+	do {
+		fifo_packets = 0;
+		if (!inv_icp201xx_get_fifo_count(icp_device, (uint8_t *)&fifo_packets) &&
+		    (fifo_packets >= fifo_packets_to_skip)) {
+			uint8_t i_status = 0;
+
+			inv_icp201xx_flush_fifo(icp_device);
+
+			inv_icp201xx_get_int_status(icp_device, &i_status);
+			if (i_status) {
+				inv_icp201xx_clear_int_status(icp_device, i_status);
+			}
+			break;
+		}
+		inv_icp201xx_sleep_us(2000);
+	} while (1);
+}
+
+static int icp201xx_attr_set(const struct device *dev, enum sensor_channel chan,
+			     enum sensor_attribute attr, const struct sensor_value *val)
+{
+	int err = 0;
+	struct icp201xx_data *data = (struct icp201xx_data *)dev->data;
+
+	__ASSERT_NO_MSG(val != NULL);
+	icp201xx_mutex_lock(dev);
+	if (chan == SENSOR_CHAN_PRESS) {
+		if (attr == SENSOR_ATTR_CONFIGURATION) {
+			if ((val->val1 >= ICP201XX_OP_MODE0) && (val->val1 <= ICP201XX_OP_MODE4)) {
+				data->op_mode = val->val1;
+				err = inv_icp201xx_soft_reset(&(data->icp_device));
+				err = inv_icp201xx_config(&(data->icp_device), data->op_mode,
+							  ICP201XX_FIFO_READOUT_MODE_PRES_TEMP);
+				inv_icp201xx_app_warmup(&(data->icp_device), data->op_mode,
+							ICP201XX_MEAS_MODE_CONTINUOUS);
+			} else {
+				LOG_ERR("Not supported ATTR value");
+				icp201xx_mutex_unlock(dev);
+				return -EINVAL;
+			}
+#ifdef CONFIG_ICP201XX_TRIGGER
+		} else if (attr == SENSOR_ATTR_SLOPE_TH) {
+			data->pressure_change = *val;
+		} else if ((attr == SENSOR_ATTR_LOWER_THRESH) ||
+			   (attr == SENSOR_ATTR_UPPER_THRESH)) {
+			if (val->val1 > 0) {
+				data->pressure_threshold = *val;
+			} else {
+				LOG_ERR("Not supported ATTR value");
+				icp201xx_mutex_unlock(dev);
+				return -EINVAL;
+			}
+#endif
+		} else {
+			LOG_ERR("Not supported ATTR");
+			icp201xx_mutex_unlock(dev);
+			return -EINVAL;
+		}
+	};
+	icp201xx_mutex_unlock(dev);
+	return err;
+}
+
+static int icp201xx_sample_fetch(const struct device *dev, const enum sensor_channel chan)
+{
+	struct icp201xx_data *data = (struct icp201xx_data *)dev->data;
+	uint8_t fifo_packets;
+	uint8_t fifo_data[6];
+
+	icp201xx_mutex_lock(dev);
+
+	/** Read measurements count in FIFO **/
+	if (inv_icp201xx_get_fifo_count(&(data->icp_device), &fifo_packets)) {
+		icp201xx_mutex_unlock(dev);
+		return -2;
+	}
+	if (fifo_packets == 0) {
+		icp201xx_mutex_unlock(dev);
+		return -1;
+	}
+
+	for (int i = 0; i < fifo_packets; i++) {
+		inv_icp201xx_get_fifo_data(&(data->icp_device), 1, fifo_data);
+		if (data->icp_device.serif.if_mode == ICP201XX_IF_I2C) {
+			/*
+			 * Perform dummy read to 0x00 register as last transaction after FIFO read
+			 * for I2C interface
+			 */
+			do {
+				uint8_t dummy_reg = 0;
+
+				inv_io_hal_read_reg((struct device *)dev, 0, &dummy_reg, 1);
+			} while (0);
+		}
+	}
+	inv_icp201xx_process_raw_data(&(data->icp_device), 1, fifo_data, &data->raw_pressure,
+				      &data->raw_temperature);
+	icp201xx_mutex_unlock(dev);
+	return 0;
+}
+
+static void icp201xx_convert_pressure(struct sensor_value *val, int32_t raw_val)
+{
+	/* Raw value is coded on 20-bits */
+	if (raw_val & 0x080000) {
+		raw_val |= 0xFFF00000;
+	}
+	/* P = (POUT/2^17)*40kPa + 70kPa */
+	val->val1 = (raw_val * 40) / 131072 + 70;
+	val->val2 = ((uint64_t)(raw_val * 40) % 131072) * 1000000 / 131072;
+}
+
+static void icp201xx_convert_temperature(struct sensor_value *val, int32_t raw_val)
+{
+	/* Raw value is coded on 20-bits */
+	if (raw_val & 0x080000) {
+		raw_val |= 0xFFF00000;
+	}
+	/* T = (TOUT/2^18)*65C + 25C */
+	val->val1 = (raw_val * 65) / 262144 + 25;
+	val->val2 = ((uint64_t)(raw_val * 65) % 262144) * 1000000 / 262144;
+}
+
+static int icp201xx_channel_get(const struct device *dev, enum sensor_channel chan,
+				struct sensor_value *val)
+{
+	struct icp201xx_data *data = (struct icp201xx_data *)dev->data;
+
+	if (!(chan == SENSOR_CHAN_AMBIENT_TEMP || chan == SENSOR_CHAN_PRESS ||
+	      SENSOR_CHAN_ALTITUDE)) {
+		return -ENOTSUP;
+	}
+	icp201xx_mutex_lock(dev);
+
+	if (chan == SENSOR_CHAN_PRESS) {
+		icp201xx_convert_pressure(val, data->raw_pressure);
+	} else if (chan == SENSOR_CHAN_AMBIENT_TEMP) {
+		icp201xx_convert_temperature(val, data->raw_temperature);
+#ifdef CONFIG_FPU
+	} else if (chan == SENSOR_CHAN_ALTITUDE) {
+		struct sensor_value pressure_val, temp_val;
+		float pressure, temperature, altitude;
+
+		icp201xx_convert_pressure(&pressure_val, data->raw_pressure);
+		icp201xx_convert_temperature(&temp_val, data->raw_pressure);
+		pressure = pressure_val.val1 + ((float)pressure_val.val2 / 1000000);
+		temperature = temp_val.val1 + ((float)temp_val.val2 / 1000000);
+		altitude = convertToHeight(pressure, temperature);
+		sensor_value_from_float(val, altitude);
+#endif
+	} else {
+		icp201xx_mutex_unlock(dev);
+		return -ENOTSUP;
+	}
+
+	icp201xx_mutex_unlock(dev);
+	return 0;
+}
+
+static int icp201xx_set_drive_strength(const struct device *dev, uint8_t drive)
+{
+	int rc = 0;
+	const uint8_t active_mode = 0x4;
+	const uint8_t normal_mode = 0x0;
+	const uint8_t unlock = 0x1F;
+	const uint8_t lock = 0x0;
+
+	inv_icp201xx_sleep_us(4000);
+
+	/* Set Active power mode */
+	rc |= inv_io_hal_write_reg((struct device *)dev, MPUREG_MODE_SELECT, &active_mode, 1);
+	inv_icp201xx_sleep_us(4000);
+
+	/* Unlock main register write access */
+	rc |= inv_io_hal_write_reg((struct device *)dev, MPUREG_MASTER_LOCK, &unlock, 1);
+	inv_icp201xx_sleep_us(4000);
+
+	/* Write IO drive strength */
+	rc |= inv_io_hal_write_reg((struct device *)dev, IO_DRIVE_STRENGTH_ADDR, &drive, 1);
+
+	/* Lock main register write access */
+	rc |= inv_io_hal_write_reg((struct device *)dev, MPUREG_MASTER_LOCK, &lock, 1);
+
+	/* Set Normal power mode */
+	rc |= inv_io_hal_write_reg((struct device *)dev, MPUREG_MODE_SELECT, &normal_mode, 1);
+
+	inv_icp201xx_sleep_us(4000);
+
+	return rc;
+}
+
+static int icp201xx_init(const struct device *dev)
+{
+	struct icp201xx_data *data = (struct icp201xx_data *)dev->data;
+	struct icp201xx_config *config = (struct icp201xx_config *)dev->config;
+	inv_icp201xx_serif_t icp_serif;
+	int rc = 0;
+	uint8_t who_am_i;
+	uint8_t icp_version;
+
+	icp_serif.if_mode = config->if_mode;
+
+	/* Initialize serial interface between MCU and Icp201xx */
+	icp_serif.context = (void *)dev;
+	icp_serif.read_reg = inv_io_hal_read_reg;
+	icp_serif.write_reg = inv_io_hal_write_reg;
+	icp_serif.max_read = 2048;  /* maximum number of bytes allowed per serial read */
+	icp_serif.max_write = 2048; /* maximum number of bytes allowed per serial write */
+
+	data->op_mode = config->op_mode;
+
+	rc = icp201xx_set_drive_strength(dev, config->drive_strength);
+	if (rc != INV_ERROR_SUCCESS) {
+		LOG_ERR("Drive strength error");
+		return rc;
+	}
+
+	rc = inv_icp201xx_init(&(data->icp_device), &icp_serif);
+	if (rc != INV_ERROR_SUCCESS) {
+		LOG_ERR("Init error");
+		return rc;
+	}
+
+	rc = inv_icp201xx_soft_reset(&(data->icp_device));
+	if (rc != INV_ERROR_SUCCESS) {
+		LOG_ERR("Reset error");
+		return rc;
+	}
+
+	/* Check WHOAMI */
+	rc = inv_icp201xx_get_devid_version(&(data->icp_device), &who_am_i, &icp_version);
+	if (rc != 0) {
+		LOG_ERR("Device id error");
+		return -2;
+	}
+
+	if (who_am_i != EXPECTED_DEVICE_ID) {
+		LOG_ERR("Wrong device id");
+		return -3;
+	}
+
+	/* Boot up OTP config */
+	rc = inv_icp201xx_OTP_bootup_cfg(&(data->icp_device));
+	if (rc != 0) {
+		LOG_ERR("Bootup error");
+		return rc;
+	}
+	rc = inv_icp201xx_soft_reset(&(data->icp_device));
+	if (rc != 0) {
+		LOG_ERR("Reset error");
+		return rc;
+	}
+	rc = inv_icp201xx_config(&(data->icp_device), data->op_mode,
+				 ICP201XX_FIFO_READOUT_MODE_PRES_TEMP);
+	if (rc != 0) {
+		LOG_ERR("Config error");
+		return rc;
+	}
+	inv_icp201xx_app_warmup(&(data->icp_device), data->op_mode, ICP201XX_MEAS_MODE_CONTINUOUS);
+
+	if (IS_ENABLED(CONFIG_ICP201XX_TRIGGER)) {
+		rc = icp201xx_trigger_init(dev);
+		if (rc < 0) {
+			LOG_ERR("Failed to initialize interrupt.");
+			return rc;
+		}
+	}
+
+	/* successful init, return 0 */
+	return 0;
+}
+
+void icp201xx_mutex_lock(const struct device *dev)
+{
+#ifdef CONFIG_ICP201XX_TRIGGER
+	const struct icp201xx_config *config = dev->config;
+
+	if (config->gpio_int.port) {
+		struct icp201xx_data *data = dev->data;
+
+		k_mutex_lock(&data->mutex, K_FOREVER);
+	}
+#else
+	ARG_UNUSED(dev);
+#endif
+}
+
+void icp201xx_mutex_unlock(const struct device *dev)
+{
+#ifdef CONFIG_ICP201XX_TRIGGER
+	const struct icp201xx_config *config = dev->config;
+
+	if (config->gpio_int.port) {
+		struct icp201xx_data *data = dev->data;
+
+		k_mutex_unlock(&data->mutex);
+	}
+#else
+	ARG_UNUSED(dev);
+#endif
+}
+
+static DEVICE_API(sensor, icp201xx_api_funcs) = {.sample_fetch = icp201xx_sample_fetch,
+							    .channel_get = icp201xx_channel_get,
+							    .attr_set = icp201xx_attr_set,
+#ifdef CONFIG_ICP201XX_TRIGGER
+							    .trigger_set = icp201xx_trigger_set
+#endif
+};
+
+/* Common initialization for icp201xx_config */
+#define ICP201XX_CONFIG(inst)                                              \
+	IF_ENABLED(CONFIG_ICP201XX_TRIGGER,                                  \
+		(.gpio_int = GPIO_DT_SPEC_INST_GET_OR(inst, int_gpios, {0}),)) \
+		.op_mode = DT_INST_ENUM_IDX(inst, op_mode),                    \
+		.drive_strength = DT_INST_ENUM_IDX(inst, drive_strength)
+
+/* Initializes a struct icp201xx_config for an instance on an I2C bus. */
+#define ICP201XX_CONFIG_I2C(inst)                          \
+	{                                                      \
+		.if_mode = ICP201XX_IF_I2C,                        \
+		.bus.i2c = I2C_DT_SPEC_INST_GET(inst),                 \
+		.bus_io = &icp201xx_bus_io_i2c,                    \
+		ICP201XX_CONFIG(inst)                                  \
+	}
+
+/* Initializes a struct icp201xx_config for an instance on a SPI bus. */
+#define ICP201XX_CONFIG_SPI(inst)                                  \
+	{                                                              \
+		.if_mode = ICP201XX_IF_4_WIRE_SPI,                         \
+		.bus.spi = SPI_DT_SPEC_INST_GET(inst,                      \
+			(SPI_OP_MODE_MASTER | SPI_WORD_SET(8) |    \
+			SPI_TRANSFER_MSB | SPI_FULL_DUPLEX |      \
+			SPI_MODE_CPHA | SPI_MODE_CPOL),           \
+			0),                                        \
+		.bus_io = &icp201xx_bus_io_spi,                            \
+		ICP201XX_CONFIG(inst)                                          \
+	}
+
+/*
+ * Main instantiation macro, which selects the correct bus-specific
+ * instantiation macros for the instance.
+ */
+#define ICP201XX_DEFINE(inst)                                            \
+	static struct icp201xx_data icp201xx_drv_##inst;                       \
+	static const struct icp201xx_config icp201xx_config_##inst =           \
+		COND_CODE_1(DT_INST_ON_BUS(inst, spi),                               \
+		(ICP201XX_CONFIG_SPI(inst)),	                                       \
+		(ICP201XX_CONFIG_I2C(inst)));                                        \
+	SENSOR_DEVICE_DT_INST_DEFINE(inst, icp201xx_init, NULL, &icp201xx_drv_##inst, \
+		&icp201xx_config_##inst, POST_KERNEL, CONFIG_SENSOR_INIT_PRIORITY,   \
+		&icp201xx_api_funcs);
+
+#define DT_DRV_COMPAT invensense_icp201xx
+DT_INST_FOREACH_STATUS_OKAY(ICP201XX_DEFINE)
diff --git a/drivers/sensor/tdk/icp201xx/icp201xx_drv.h b/drivers/sensor/tdk/icp201xx/icp201xx_drv.h
new file mode 100644
index 0000000..32bc029
--- /dev/null
+++ b/drivers/sensor/tdk/icp201xx/icp201xx_drv.h
@@ -0,0 +1,88 @@
+/*
+ * Copyright (c) 2025 TDK Invensense
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#ifndef ZEPHYR_DRIVERS_SENSOR_ICP201XXX_ICP101XXX_H_
+#define ZEPHYR_DRIVERS_SENSOR_ICP201XXX_ICP101XXX_H_
+
+#include <zephyr/types.h>
+#include <zephyr/device.h>
+#include <zephyr/devicetree.h>
+#include <zephyr/drivers/i2c.h>
+#include <zephyr/drivers/spi.h>
+#include <zephyr/drivers/sensor.h>
+#include "Icp201xx.h"
+#include "Icp201xxSerif.h"
+
+union icp201xx_bus {
+#if CONFIG_SPI
+	struct spi_dt_spec spi;
+#endif
+#if CONFIG_I2C
+	struct i2c_dt_spec i2c;
+#endif
+};
+
+typedef int (*icp201xx_reg_read_fn)(const union icp201xx_bus *bus, uint8_t reg, uint8_t *buf,
+				    uint32_t size);
+typedef int (*icp201xx_reg_write_fn)(const union icp201xx_bus *bus, uint8_t reg, uint8_t *buf,
+				     uint32_t size);
+
+struct icp201xx_bus_io {
+	icp201xx_reg_read_fn read;
+	icp201xx_reg_write_fn write;
+};
+
+extern const struct icp201xx_bus_io icp201xx_bus_io_spi;
+extern const struct icp201xx_bus_io icp201xx_bus_io_i2c;
+
+struct icp201xx_data {
+	int32_t raw_pressure;
+	int32_t raw_temperature;
+	icp201xx_op_mode_t op_mode;
+	inv_icp201xx_t icp_device;
+
+#ifdef CONFIG_ICP201XX_TRIGGER
+	struct sensor_value pressure_change;
+	struct sensor_value pressure_threshold;
+	const struct device *dev;
+	struct gpio_callback gpio_cb;
+	sensor_trigger_handler_t drdy_handler;
+	sensor_trigger_handler_t delta_handler;
+	sensor_trigger_handler_t threshold_handler;
+	const struct sensor_trigger *drdy_trigger;
+	const struct sensor_trigger *delta_trigger;
+	const struct sensor_trigger *threshold_trigger;
+	struct k_mutex mutex;
+#ifdef CONFIG_ICP201XX_TRIGGER_OWN_THREAD
+	K_KERNEL_STACK_MEMBER(thread_stack, CONFIG_ICP201XX_THREAD_STACK_SIZE);
+	struct k_thread thread;
+	struct k_sem gpio_sem;
+#endif
+#ifdef CONFIG_ICP201XX_TRIGGER_GLOBAL_THREAD
+	struct k_work work;
+#endif
+#endif
+};
+
+struct icp201xx_config {
+	union icp201xx_bus bus;
+	const struct icp201xx_bus_io *bus_io;
+	icp201xx_if_t if_mode;
+	struct gpio_dt_spec gpio_int;
+	icp201xx_op_mode_t op_mode;
+	uint8_t drive_strength;
+};
+
+int icp201xx_trigger_set(const struct device *dev, const struct sensor_trigger *trig,
+			 sensor_trigger_handler_t handler);
+
+int icp201xx_trigger_init(const struct device *dev);
+
+void icp201xx_mutex_lock(const struct device *dev);
+void icp201xx_mutex_unlock(const struct device *dev);
+void inv_icp201xx_app_warmup(inv_icp201xx_t *icp_device, icp201xx_op_mode_t op_mode,
+			     icp201xx_meas_mode_t meas_mode);
+#endif
diff --git a/drivers/sensor/tdk/icp201xx/icp201xx_i2c.c b/drivers/sensor/tdk/icp201xx/icp201xx_i2c.c
new file mode 100644
index 0000000..b84a9af
--- /dev/null
+++ b/drivers/sensor/tdk/icp201xx/icp201xx_i2c.c
@@ -0,0 +1,29 @@
+/*
+ * Copyright (c) 2025 TDK Invensense
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+/*
+ * Bus-specific functionality for ICP201XX accessed via I2C.
+ */
+
+#include "icp201xx_drv.h"
+
+static int icp201xx_read_reg_i2c(const union icp201xx_bus *bus, uint8_t reg, uint8_t *rbuffer,
+				 uint32_t rlen)
+{
+
+	return i2c_burst_read_dt(&bus->i2c, reg, (uint8_t *)rbuffer, rlen);
+}
+
+static int icp201xx_write_reg_i2c(const union icp201xx_bus *bus, uint8_t reg, uint8_t *wbuffer,
+				  uint32_t wlen)
+{
+	return i2c_burst_write_dt(&bus->i2c, reg, wbuffer, wlen);
+}
+
+const struct icp201xx_bus_io icp201xx_bus_io_i2c = {
+	.read = icp201xx_read_reg_i2c,
+	.write = icp201xx_write_reg_i2c,
+};
diff --git a/drivers/sensor/tdk/icp201xx/icp201xx_spi.c b/drivers/sensor/tdk/icp201xx/icp201xx_spi.c
new file mode 100644
index 0000000..983a01c
--- /dev/null
+++ b/drivers/sensor/tdk/icp201xx/icp201xx_spi.c
@@ -0,0 +1,53 @@
+/*
+ * Copyright (c) 2025 TDK Invensense
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+/*
+ * Bus-specific functionality for ICP201XX accessed via SPI.
+ */
+
+#include "icp201xx_drv.h"
+
+#define ICP201XX_SERIF_SPI_REG_WRITE_CMD 0X33
+#define ICP201XX_SERIF_SPI_REG_READ_CMD  0X3C
+static int icp201xx_read_reg_spi(const union icp201xx_bus *bus, uint8_t reg, uint8_t *rbuffer,
+				 uint32_t rlen)
+{
+	if (reg != 0) {
+		int rc = 0;
+
+		uint8_t cmd[] = {ICP201XX_SERIF_SPI_REG_READ_CMD, reg};
+		const struct spi_buf tx_buf = {.buf = cmd, .len = 2};
+		const struct spi_buf_set tx = {.buffers = &tx_buf, .count = 1};
+		struct spi_buf rx_buf[] = {{.buf = NULL, .len = 2}, {.buf = rbuffer, .len = rlen}};
+		const struct spi_buf_set rx = {.buffers = rx_buf, .count = 2};
+
+		rc = spi_transceive_dt(&bus->spi, &tx, &rx);
+
+		return rc;
+	}
+	return 0;
+}
+
+static int icp201xx_write_reg_spi(const union icp201xx_bus *bus, uint8_t reg, uint8_t *wbuffer,
+				  uint32_t wlen)
+{
+	if (reg != 0) {
+		int rc = 0;
+		uint8_t cmd[] = {ICP201XX_SERIF_SPI_REG_WRITE_CMD, reg};
+		const struct spi_buf tx_buf[] = {{.buf = cmd, .len = 2},
+						 {.buf = (uint8_t *)wbuffer, .len = wlen}};
+		const struct spi_buf_set tx = {.buffers = tx_buf, .count = 2};
+
+		rc = spi_write_dt(&bus->spi, &tx);
+		return rc;
+	}
+	return 0;
+}
+
+const struct icp201xx_bus_io icp201xx_bus_io_spi = {
+	.read = icp201xx_read_reg_spi,
+	.write = icp201xx_write_reg_spi,
+};
diff --git a/drivers/sensor/tdk/icp201xx/icp201xx_trigger.c b/drivers/sensor/tdk/icp201xx/icp201xx_trigger.c
new file mode 100644
index 0000000..46a2dc0
--- /dev/null
+++ b/drivers/sensor/tdk/icp201xx/icp201xx_trigger.c
@@ -0,0 +1,217 @@
+/*
+ * Copyright (c) 2025 TDK Invensense
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#include <zephyr/device.h>
+#include <zephyr/drivers/i2c.h>
+#include <zephyr/sys/util.h>
+#include <zephyr/kernel.h>
+#include <zephyr/drivers/sensor.h>
+#include <zephyr/logging/log.h>
+#include <zephyr/drivers/gpio.h>
+#include "icp201xx_drv.h"
+#include "Icp201xxDriver.h"
+
+LOG_MODULE_DECLARE(ICP201XX, CONFIG_SENSOR_LOG_LEVEL);
+
+static void icp201xx_gpio_callback(const struct device *dev, struct gpio_callback *cb,
+				   uint32_t pins)
+{
+	struct icp201xx_data *drv_data = CONTAINER_OF(cb, struct icp201xx_data, gpio_cb);
+	const struct icp201xx_config *cfg = (const struct icp201xx_config *)drv_data->dev->config;
+
+	ARG_UNUSED(pins);
+	gpio_pin_interrupt_configure_dt(&cfg->gpio_int, GPIO_INT_DISABLE);
+
+#if defined(CONFIG_ICP201XX_TRIGGER_OWN_THREAD)
+	k_sem_give(&drv_data->gpio_sem);
+#elif defined(CONFIG_ICP201XX_TRIGGER_GLOBAL_THREAD)
+	k_work_submit(&drv_data->work);
+#endif
+}
+
+static void icp201xx_thread_cb(const struct device *dev)
+{
+	struct icp201xx_data *drv_data = dev->data;
+	const struct icp201xx_config *cfg = dev->config;
+	uint8_t i_status;
+
+	icp201xx_mutex_lock(dev);
+	gpio_pin_interrupt_configure_dt(&cfg->gpio_int, GPIO_INT_DISABLE);
+
+	inv_icp201xx_get_int_status(&drv_data->icp_device, &i_status);
+	if (i_status) {
+		if ((i_status & ICP201XX_INT_STATUS_FIFO_WMK_HIGH) &&
+		    (drv_data->drdy_handler != NULL)) {
+			drv_data->drdy_handler(dev, drv_data->drdy_trigger);
+		}
+		if ((i_status & ICP201XX_INT_STATUS_PRESS_DELTA) &&
+		    (drv_data->delta_handler != NULL)) {
+			drv_data->delta_handler(dev, drv_data->delta_trigger);
+		}
+		if ((i_status & ICP201XX_INT_STATUS_PRESS_ABS) &&
+		    (drv_data->threshold_handler != NULL)) {
+			drv_data->threshold_handler(dev, drv_data->threshold_trigger);
+		}
+		inv_icp201xx_clear_int_status(&drv_data->icp_device, i_status);
+	}
+	gpio_pin_interrupt_configure_dt(&cfg->gpio_int, GPIO_INT_LEVEL_LOW);
+	icp201xx_mutex_unlock(dev);
+}
+
+#if defined(CONFIG_ICP201XX_TRIGGER_OWN_THREAD)
+static void icp201xx_thread(void *p1, void *p2, void *p3)
+{
+	ARG_UNUSED(p2);
+	ARG_UNUSED(p3);
+	struct device *dev = (struct device *)p1;
+	struct icp201xx_data *drv_data = (struct icp201xx_data *)dev->data;
+
+	while (1) {
+		k_sem_take(&drv_data->gpio_sem, K_FOREVER);
+		icp201xx_thread_cb(dev);
+	}
+}
+#elif defined(CONFIG_ICP201XX_TRIGGER_GLOBAL_THREAD)
+static void icp201xx_work_handler(struct k_work *work)
+{
+	struct icp201xx_data *data = CONTAINER_OF(work, struct icp201xx_data, work);
+
+	icp201xx_thread_cb(data->dev);
+}
+#endif
+
+static int icp201xx_fifo_interrupt(const struct device *dev, uint8_t fifo_watermark)
+{
+	int rc = 0;
+	struct icp201xx_data *data = (struct icp201xx_data *)dev->data;
+
+	inv_icp201xx_flush_fifo(&(data->icp_device));
+
+	rc |= inv_icp201xx_set_fifo_notification_config(
+		&(data->icp_device), ICP201XX_INT_MASK_FIFO_WMK_HIGH, fifo_watermark, 0);
+
+	inv_icp201xx_app_warmup(&(data->icp_device), data->op_mode, ICP201XX_MEAS_MODE_CONTINUOUS);
+	return rc;
+}
+
+static int icp201xx_pressure_interrupt(const struct device *dev, struct sensor_value pressure)
+{
+	int16_t pressure_value, pressure_delta_value;
+	uint8_t int_mask = 0;
+	int rc = 0;
+	struct icp201xx_data *data = (struct icp201xx_data *)dev->data;
+
+	inv_icp201xx_get_press_notification_config(&(data->icp_device), &int_mask, &pressure_value,
+						   &pressure_delta_value);
+	/* PABS = (P(kPa)-70kPa)/40kPa*2^13 */
+	pressure_value =
+		(8192 * (pressure.val1 - 70) + ((8192 * (uint64_t)pressure.val2) / 1000000)) / 40;
+	rc |= inv_icp201xx_set_press_notification_config(&(data->icp_device),
+							 ~int_mask | ICP201XX_INT_MASK_PRESS_ABS,
+							 pressure_value, pressure_delta_value);
+	return rc;
+}
+
+static int icp201xx_pressure_change_interrupt(const struct device *dev,
+					      struct sensor_value pressure_delta)
+{
+	int16_t pressure_value, pressure_delta_value;
+	uint8_t int_mask = 0;
+	int rc = 0;
+	struct icp201xx_data *data = (struct icp201xx_data *)dev->data;
+
+	inv_icp201xx_get_press_notification_config(&(data->icp_device), &int_mask, &pressure_value,
+						   &pressure_delta_value);
+	/* PDELTA = (P(kPa)/80)* 2^14 */
+	pressure_delta_value =
+		(16384 * pressure_delta.val1 + (16384 * (uint64_t)pressure_delta.val2 / 1000000)) /
+		80;
+	rc |= inv_icp201xx_set_press_notification_config(&(data->icp_device),
+							 ~int_mask | ICP201XX_INT_MASK_PRESS_DELTA,
+							 pressure_value, pressure_delta_value);
+	return rc;
+}
+
+int icp201xx_trigger_init(const struct device *dev)
+{
+	struct icp201xx_data *drv_data = dev->data;
+	const struct icp201xx_config *cfg = dev->config;
+	int result = 0;
+
+	if (!cfg->gpio_int.port) {
+		LOG_ERR("trigger enabled but no interrupt gpio supplied");
+		return -ENODEV;
+	}
+
+	if (!gpio_is_ready_dt(&cfg->gpio_int)) {
+		LOG_ERR("gpio_int gpio not ready");
+		return -ENODEV;
+	}
+
+	drv_data->dev = dev;
+	gpio_pin_configure_dt(&cfg->gpio_int, GPIO_INPUT);
+	gpio_init_callback(&drv_data->gpio_cb, icp201xx_gpio_callback, BIT(cfg->gpio_int.pin));
+	result = gpio_add_callback(cfg->gpio_int.port, &drv_data->gpio_cb);
+
+	if (result < 0) {
+		LOG_ERR("Failed to set gpio callback");
+		return result;
+	}
+
+	k_mutex_init(&drv_data->mutex);
+
+#if defined(CONFIG_ICP201XX_TRIGGER_OWN_THREAD)
+	k_sem_init(&drv_data->gpio_sem, 0, K_SEM_MAX_LIMIT);
+
+	k_thread_create(&drv_data->thread, drv_data->thread_stack,
+			CONFIG_ICP201XX_THREAD_STACK_SIZE, icp201xx_thread, (struct device *)dev,
+			NULL, NULL, K_PRIO_COOP(CONFIG_ICP201XX_THREAD_PRIORITY), 0, K_NO_WAIT);
+	k_thread_name_set(&drv_data->thread, "icp201xx");
+#elif defined(CONFIG_ICP201XX_TRIGGER_GLOBAL_THREAD)
+	drv_data->work.handler = icp201xx_work_handler;
+#endif
+
+	return 0;
+}
+
+int icp201xx_trigger_set(const struct device *dev, const struct sensor_trigger *trig,
+			 sensor_trigger_handler_t handler)
+{
+	int rc = 0;
+	struct icp201xx_data *drv_data = dev->data;
+	const struct icp201xx_config *cfg = dev->config;
+
+	icp201xx_mutex_lock(dev);
+	gpio_pin_interrupt_configure_dt(&cfg->gpio_int, GPIO_INT_DISABLE);
+	if (handler == NULL) {
+		return -1;
+	}
+
+	if ((trig->type != SENSOR_TRIG_DATA_READY) && (trig->type != SENSOR_TRIG_DELTA) &&
+	    (trig->type != SENSOR_TRIG_THRESHOLD)) {
+		icp201xx_mutex_unlock(dev);
+		return -ENOTSUP;
+	}
+
+	if (trig->type == SENSOR_TRIG_DATA_READY) {
+		rc = icp201xx_fifo_interrupt(dev, 1);
+		drv_data->drdy_handler = handler;
+		drv_data->drdy_trigger = trig;
+	} else if (trig->type == SENSOR_TRIG_DELTA) {
+		rc = icp201xx_pressure_change_interrupt(dev, drv_data->pressure_change);
+		drv_data->delta_handler = handler;
+		drv_data->delta_trigger = trig;
+	} else if (trig->type == SENSOR_TRIG_THRESHOLD) {
+		rc = icp201xx_pressure_interrupt(dev, drv_data->pressure_threshold);
+		drv_data->threshold_handler = handler;
+		drv_data->threshold_trigger = trig;
+	}
+
+	gpio_pin_interrupt_configure_dt(&cfg->gpio_int, GPIO_INT_LEVEL_LOW);
+	icp201xx_mutex_unlock(dev);
+
+	return rc;
+}