This is an automated email from the ASF dual-hosted git repository. acassis pushed a commit to branch master in repository https://gitbox.apache.org/repos/asf/nuttx.git
The following commit(s) were added to refs/heads/master by this push: new 3ba6047e294 drivers/sensors/tmp112: Add support for TMP112 temperature sensor 3ba6047e294 is described below commit 3ba6047e2940f84d0e24bee2fb84be20cb5c8ef3 Author: Niccolò Maggioni <nicco.maggi...@gmail.com> AuthorDate: Mon Aug 11 14:19:07 2025 +0200 drivers/sensors/tmp112: Add support for TMP112 temperature sensor Add support for the Texas Instruments TMP112 I2C/SMBus digital temperature sensor. Also add a new defconfig that includes support for a TMP112 sensor and extend the existing documentation to include its description. Signed-off-by: Niccolò Maggioni <nicco.maggioni+nu...@gmail.com> --- .../arm/rp2040/boards/raspberrypi-pico/index.rst | 66 +++-- boards/arm/rp2040/common/include/rp2040_tmp112.h | 89 ++++++ boards/arm/rp2040/common/src/Make.defs | 4 + .../arm/rp2040/common/src/rp2040_common_bringup.c | 17 ++ boards/arm/rp2040/common/src/rp2040_tmp112.c | 105 +++++++ .../raspberrypi-pico/configs/tmp112/defconfig | 58 ++++ drivers/sensors/CMakeLists.txt | 4 + drivers/sensors/Kconfig | 15 + drivers/sensors/Make.defs | 4 + drivers/sensors/tmp112.c | 304 +++++++++++++++++++++ include/nuttx/sensors/tmp112.h | 117 ++++++++ 11 files changed, 764 insertions(+), 19 deletions(-) diff --git a/Documentation/platforms/arm/rp2040/boards/raspberrypi-pico/index.rst b/Documentation/platforms/arm/rp2040/boards/raspberrypi-pico/index.rst index 955fa88b7d9..020fb24beac 100644 --- a/Documentation/platforms/arm/rp2040/boards/raspberrypi-pico/index.rst +++ b/Documentation/platforms/arm/rp2040/boards/raspberrypi-pico/index.rst @@ -48,34 +48,34 @@ Pad Signal Notes ===== ========== ========== 1 GPIO0 Default TX for UART0 serial console 2 GPIO1 Default RX for UART0 serial console -3 Ground -4 GPIO2 -5 GPIO3 +3 Ground +4 GPIO2 +5 GPIO3 6 GPIO4 Default SDA for I2C0 7 GPIO5 Default SCL for I2C0 -8 Ground +8 Ground 9 GPIO6 Default SDA for I2C1 10 GPIO7 Default SCL for I2C1 11 GPIO8 Default RX for SPI1 12 GPIO9 Default CSn for SPI1 -13 Ground +13 Ground 14 GPIO10 Default SCK for SPI1 15 GPIO11 Default TX for SPI1 -16 GPIO12 -17 GPIO13 -18 Ground -19 GPIO14 -20 GPIO15 +16 GPIO12 +17 GPIO13 +18 Ground +19 GPIO14 +20 GPIO15 21 GPIO16 Default RX for SPI0 22 GPIO17 Default CSn for SPI0 -23 Ground +23 Ground 24 GPIO18 Default SCK for SPI0 25 GPIO19 Default TX for SPI0 26 GPIO20 Default TX for UART1 serial console 27 GPIO21 Default RX for UART1 serial console -28 Ground -29 GPIO22 -30 Run +28 Ground +29 GPIO22 +30 Run 31 GPIO26 ADC0 32 GPIO27 ADC1 33 AGND Analog Ground @@ -83,7 +83,7 @@ Pad Signal Notes 35 ADC_VREF Analog reference voltage 36 3V3 Power output to peripherals 37 3V3_EN Pull to ground to turn off. -38 Ground +38 Ground 39 VSYS +5V Supply to board 40 VBUS Connected to USB +5V ===== ========== ========== @@ -217,7 +217,7 @@ LCD1602 Segment LCD Display (I2C). :widths: auto :header-rows: 1 - * - PCF8574 BackPack + * - PCF8574 BackPack - Raspberry Pi Pico * - GND - GND (Pin 3 or 38 or ...) @@ -263,7 +263,7 @@ card support enabled. * - SD card slot - Raspberry Pi Pico - * - DAT2 + * - DAT2 - Not connected * - DAT3/CS - GP17 (SPI0 CSn) (Pin 22) @@ -277,7 +277,7 @@ card support enabled. - GND (Pin 3 or 38 or ...) * - DAT0/DO - GP16 (SPI0 RX) (Pin 21) - * - DAT1 + * - DAT1 - Not connected Card hot swapping is not supported. @@ -300,7 +300,7 @@ for SSD1306 OLED display (I2C) test configuration. - 3V3 OUT (Pin 36) * - SDA - GP4 (I2C0 SDA) (Pin 6) - * - SCL + * - SCL - GP5 (I2C0 SCL) (Pin 7) st7735 @@ -332,6 +332,34 @@ ST7735 SPI LCD. * - RESET - GP10 (Pin 14) +tmp112 +------ + +NuttShell configuration (console enabled in USB Port, at 115200 bps) with support for Texas Instruments TMP112 sensor: + +.. list-table:: TMP112 connections + :widths: auto + :header-rows: 1 + + * - TMP112 + - Raspberry Pi Pico + * - GND + - GND (Pin 3 or 38 or ...) + * - VCC + - 3V3 OUT (Pin 36) + * - SDA + - GP4 (I2C0 SDA) (Pin 6) + * - SCL + - GP5 (I2C0 SCL) (Pin 7) + * - ADD0 + - GND (Pin 3 or 38 or ...) + +.. code-block:: console + + nsh> tmp112 + Sensor #1 = 27.688 degrees Celsius + nsh> + usbmsc ------ diff --git a/boards/arm/rp2040/common/include/rp2040_tmp112.h b/boards/arm/rp2040/common/include/rp2040_tmp112.h new file mode 100644 index 00000000000..657cbe04047 --- /dev/null +++ b/boards/arm/rp2040/common/include/rp2040_tmp112.h @@ -0,0 +1,89 @@ +/**************************************************************************** + * boards/arm/rp2040/common/include/rp2040_tmp112.h + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __BOARDS_ARM_RP2040_COMMON_INCLUDE_RP2040_TMP112_H +#define __BOARDS_ARM_RP2040_COMMON_INCLUDE_RP2040_TMP112_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include <nuttx/config.h> +#include <nuttx/i2c/i2c_master.h> + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Type Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Inline Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: board_tmp112_initialize + * + * Description: + * Initialize and register the TMP112 temperature sensor driver. + * + * Input Parameters: + * i2c - An instance of the I2C interface to use. + * devno - The device number, used to build the device path as /dev/tempN. + * addr - The I2C address to use. + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int board_tmp112_initialize(FAR struct i2c_master_s *i2c, int devno, + uint8_t addr); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __BOARDS_ARM_RP2040_COMMON_INCLUDE_RP2040_TMP112_H */ diff --git a/boards/arm/rp2040/common/src/Make.defs b/boards/arm/rp2040/common/src/Make.defs index e6c4e73d5ad..c7c0fef41ba 100644 --- a/boards/arm/rp2040/common/src/Make.defs +++ b/boards/arm/rp2040/common/src/Make.defs @@ -109,6 +109,10 @@ ifeq ($(CONFIG_SENSORS_MAX6675),y) CSRCS += rp2040_max6675.c endif +ifeq ($(CONFIG_SENSORS_TMP112),y) + CSRCS += rp2040_tmp112.c +endif + DEPPATH += --dep-path src VPATH += :src CFLAGS += ${INCDIR_PREFIX}$(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)src diff --git a/boards/arm/rp2040/common/src/rp2040_common_bringup.c b/boards/arm/rp2040/common/src/rp2040_common_bringup.c index e91f5e6563d..8536f24adf5 100644 --- a/boards/arm/rp2040/common/src/rp2040_common_bringup.c +++ b/boards/arm/rp2040/common/src/rp2040_common_bringup.c @@ -90,6 +90,12 @@ #include "rp2040_max6675.h" #endif +#ifdef CONFIG_SENSORS_TMP112 +#include <nuttx/sensors/tmp112.h> +#include "rp2040_tmp112.h" +#include "rp2040_i2c.h" +#endif + #ifdef CONFIG_RP2040_PWM #include "rp2040_pwm.h" #include "rp2040_pwmdev.h" @@ -569,6 +575,17 @@ int rp2040_common_bringup(void) } #endif +#ifdef CONFIG_SENSORS_TMP112 + /* Try to register TMP112 device at I2C0 with a common address */ + + ret = board_tmp112_initialize(rp2040_i2cbus_initialize(0), 0, + TMP112_ADDR_1); + if (ret < 0) + { + syslog(LOG_ERR, "Failed to initialize TMP112 driver: %d\n", ret); + } +#endif + #ifdef CONFIG_VIDEO_FB ret = fb_register(0, 0); if (ret < 0) diff --git a/boards/arm/rp2040/common/src/rp2040_tmp112.c b/boards/arm/rp2040/common/src/rp2040_tmp112.c new file mode 100644 index 00000000000..8fcbea6e33d --- /dev/null +++ b/boards/arm/rp2040/common/src/rp2040_tmp112.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * boards/arm/rp2040/common/src/rp2040_tmp112.c + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include <nuttx/config.h> + +#include <stdio.h> +#include <debug.h> + +#include <nuttx/arch.h> +#include <nuttx/sensors/tmp112.h> + +#include "rp2040_i2c.h" +#include "rp2040_tmp112.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_tmp112_initialize + * + * Description: + * Initialize and register the TMP112 temperature sensor driver. + * + * Input Parameters: + * i2c - An instance of the I2C interface to use. + * devno - The device number, used to build the device path as /dev/tempN. + * addr - The I2C address to use. + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int board_tmp112_initialize(FAR struct i2c_master_s *i2c, int devno, + uint8_t addr) +{ + char devpath[11]; + int ret; + + sninfo("Initializing TMP112 with address %#4x\n", addr); + + if (i2c) + { + snprintf(devpath, sizeof(devpath), "/dev/temp%d", devno); + ret = tmp112_register(devpath, i2c, addr); + if (ret < 0) + { + snerr("ERROR: Error registering TMP112 at /dev/temp%d\n", devno); + } + } + else + { + ret = -ENODEV; + } + + return ret; +} diff --git a/boards/arm/rp2040/raspberrypi-pico/configs/tmp112/defconfig b/boards/arm/rp2040/raspberrypi-pico/configs/tmp112/defconfig new file mode 100644 index 00000000000..06db48e6e5e --- /dev/null +++ b/boards/arm/rp2040/raspberrypi-pico/configs/tmp112/defconfig @@ -0,0 +1,58 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_LIBC_LONG_LONG is not set +# CONFIG_NSH_ARGCAT is not set +# CONFIG_NSH_CMDOPT_HEXDUMP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_LOSMART is not set +# CONFIG_RP2040_UART0 is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="raspberrypi-pico" +CONFIG_ARCH_BOARD_COMMON=y +CONFIG_ARCH_BOARD_RASPBERRYPI_PICO=y +CONFIG_ARCH_CHIP="rp2040" +CONFIG_ARCH_CHIP_RP2040=y +CONFIG_ARCH_RAMVECTORS=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_LOOPSPERMSEC=10450 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_CONSOLE=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DISABLE_POSIX_TIMERS=y +CONFIG_EXAMPLES_HELLO=y +CONFIG_EXAMPLES_TMP112=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_NFILE_DESCRIPTORS_PER_BLOCK=6 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_READLINE=y +CONFIG_NSH_USBCONSOLE=y +CONFIG_RAM_SIZE=270336 +CONFIG_RAM_START=0x20000000 +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_RP2040_I2C0=y +CONFIG_RP2040_I2C=y +CONFIG_RR_INTERVAL=200 +CONFIG_SCHED_WAITPID=y +CONFIG_SENSORS=y +CONFIG_SENSORS_TMP112=y +CONFIG_START_DAY=9 +CONFIG_START_MONTH=2 +CONFIG_START_YEAR=2021 +CONFIG_SYSTEM_NSH=y +CONFIG_TESTING_GETPRIME=y +CONFIG_TESTING_OSTEST=y +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y diff --git a/drivers/sensors/CMakeLists.txt b/drivers/sensors/CMakeLists.txt index 9f4810a40ef..b3ca24e07b0 100644 --- a/drivers/sensors/CMakeLists.txt +++ b/drivers/sensors/CMakeLists.txt @@ -340,6 +340,10 @@ if(CONFIG_SENSORS) list(APPEND SRCS amg88xx.c) endif() + if(CONFIG_SENSORS_TMP112) + list(APPEND SRCS tmp112.c) + endif() + endif() # CONFIG_I2C # These drivers depend on SPI support diff --git a/drivers/sensors/Kconfig b/drivers/sensors/Kconfig index c23cac7986f..0d630a22f92 100644 --- a/drivers/sensors/Kconfig +++ b/drivers/sensors/Kconfig @@ -2146,4 +2146,19 @@ config SENSORS_FS3000_THREAD_STACKSIZE endif # SENSORS_FS3000 +config SENSORS_TMP112 + bool "Texas Instruments TMP112x Temperature Sensor support" + default n + select I2C + ---help--- + Enable driver support for the Texas Instruments TMP112x temperature sensor. + +if SENSORS_TMP112 + +config TMP112_I2C_FREQUENCY + int "TMP112 I2C frequency" + default 400000 + +endif #SENSORS_TMP112 + endif # SENSORS diff --git a/drivers/sensors/Make.defs b/drivers/sensors/Make.defs index d3d7e0f554e..870afeb40df 100644 --- a/drivers/sensors/Make.defs +++ b/drivers/sensors/Make.defs @@ -332,6 +332,10 @@ ifeq ($(CONFIG_SENSORS_BMM150),y) CSRCS += bmm150_uorb.c endif +ifeq ($(CONFIG_SENSORS_TMP112),y) + CSRCS += tmp112.c +endif + endif # CONFIG_I2C # These drivers depend on SPI support diff --git a/drivers/sensors/tmp112.c b/drivers/sensors/tmp112.c new file mode 100644 index 00000000000..6cf70658252 --- /dev/null +++ b/drivers/sensors/tmp112.c @@ -0,0 +1,304 @@ +/**************************************************************************** + * drivers/sensors/tmp112.c + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include <nuttx/config.h> + +#include <assert.h> +#include <errno.h> +#include <debug.h> +#include <string.h> +#include <time.h> + +#include <nuttx/arch.h> +#include <nuttx/kmalloc.h> +#include <nuttx/signal.h> +#include <nuttx/fs/fs.h> +#include <nuttx/i2c/i2c_master.h> +#include <nuttx/random.h> + +#include <nuttx/sensors/tmp112.h> + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct tmp112_dev_s +{ + FAR struct i2c_master_s *i2c; /* I2C interface */ + uint8_t addr; /* TMP112 I2C address */ + int freq; /* TMP112 Frequency */ + uint16_t tmp112_temp_raw; /* Temperature as read from TMP112 */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Character driver methods */ + +static ssize_t tmp112_read(FAR struct file *filep, FAR char *buffer, + size_t buflen); + +static ssize_t tmp112_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations g_tmp112fops = +{ + NULL, /* open */ + NULL, /* close */ + tmp112_read, /* read */ + tmp112_write, /* write */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static uint16_t tmp112_getreg16(FAR struct tmp112_dev_s *priv, + uint8_t regaddr, uint8_t ms_delay) +{ + struct i2c_config_s config; + uint16_t msb; + uint16_t lsb; + uint16_t regval = 0; + int ret; + + /* Set up the I2C configuration */ + + config.frequency = priv->freq; + config.address = priv->addr; + config.addrlen = 7; + + /* Register to read */ + + ret = i2c_write(priv->i2c, &config, ®addr, 1); + if (ret < 0) + { + snerr("ERROR: i2c_write failed: %s (%d)\n", strerror(-ret), ret); + return ret; + } + + if (ms_delay > 0) + { + nxsig_usleep(ms_delay * 1000); + } + + /* Read register */ + + ret = i2c_read(priv->i2c, &config, (FAR uint8_t *)®val, 2); + if (ret < 0) + { + snerr("ERROR: i2c_read failed: %d\n", ret); + return ret; + } + + /* MSB and LSB are inverted */ + + msb = (regval & 0xff); + lsb = (regval & 0xff00) >> 8; + + regval = (msb << 4) | (lsb >> 4); + + return regval; +} + +static int tmp112_putreg16(FAR struct tmp112_dev_s *priv, uint8_t regaddr, + uint16_t regval) +{ + struct i2c_config_s config; + uint8_t data[3]; + int ret; + + /* Set up the I2C configuration */ + + config.frequency = priv->freq; + config.address = priv->addr; + config.addrlen = 7; + + data[0] = regaddr; + data[1] = (regval >> 8) & 0xff; + data[2] = regval & 0xff; + + /* Write the register address and value */ + + ret = i2c_write(priv->i2c, &config, (FAR uint8_t *)&data, 3); + if (ret < 0) + { + snerr("ERROR: i2c_write failed: %s (%d)\n", strerror(-ret), ret); + return ret; + } + + return OK; +} + +static int tmp112_writeconfig(FAR struct tmp112_dev_s *priv) +{ + /* Datasheet Table 7-10: Configuration and Power-Up/Reset Formats + * | BYTE | D7 | D6 | D5 | D4 | D3 | D2 | D1 | D0 | + * |------|-----|-----|-----|-----|-----|-----|-----|-----| + * | 1 | OS | R1 | R0 | F1 | F0 | POL | TM | SD | + * | | 0 | 1 | 1 | 0 | 0 | 0 | 0 | 0 | + * |------|-----|-----|-----|-----|-----|-----|-----|-----| + * | 2 | CR1 | CR0 | AL | EM | 0 | 0 | 0 | 0 | + * | | 1 | 0 | 1 | 0 | 0 | 0 | 0 | 0 | + * |------|-----|-----|-----|-----|-----|-----|-----|-----| + */ + + /* Byte 1: set 12 bit resolution, Comparator mode, Continuous + * Conversion mode + */ + + const uint8_t b1 = 0b01100000; + + /* Byte 2: set 4Hz conversion rate, non-Extended mode */ + + const uint8_t b2 = 0b10100000; + + return tmp112_putreg16(priv, TMP112_REG_CONFIG, (b1 << 8) | b2); +} + +static void tmp112_read_temp(FAR struct tmp112_dev_s *priv) +{ + /* Wait 1.5x typical conversion time (10ms) to ensure that the + * temperature register is primed and then read it. + */ + + uint16_t value = tmp112_getreg16(priv, TMP112_REG_TEMP, 15); + + if (value >= UINT16_MAX - __ELASTERROR) + { + snerr("ERROR: Invalid temperature read\n"); + priv->tmp112_temp_raw = 0; + } + else + { + priv->tmp112_temp_raw = value; + sninfo("Temperature (raw) = %" PRIu16 "\n", priv->tmp112_temp_raw); + } +} + +static ssize_t tmp112_read(FAR struct file *filep, FAR char *buffer, + size_t buflen) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct tmp112_dev_s *priv = inode->i_private; + FAR float *temperature = (FAR float *)buffer; + + if (!buffer) + { + snerr("ERROR: Buffer is null\n"); + return -1; + } + + if (buflen != 4) + { + snerr("ERROR: You can't read something other than 32 bits " + "(4 bytes)\n"); + return -1; + } + + /* Refresh the temperature */ + + tmp112_read_temp(priv); + + /* Get the temperature */ + + *temperature = (float)priv->tmp112_temp_raw * 0.0625f; + + /* Return size of data (float, 4 bytes) */ + + return sizeof(float); +} + +static ssize_t tmp112_write(FAR struct file *filep, FAR const char *buffer, + size_t buflen) +{ + return -ENOSYS; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: tmp112_register + * + * Description: + * Register the TMP112 character device as 'devpath' + * + * Input Parameters: + * devpath - The full path to the driver to register. E.g., "/dev/temp0" + * i2c - An instance of the I2C interface to use. + * addr - The I2C address to use. + * When multiple sensors are connected to the same bus, each one + * must be electrically configured to use a different I2C + * address as specified in the datasheet. + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int tmp112_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr) +{ + FAR struct tmp112_dev_s *priv; + int ret; + + /* Initialize the TMP112 device structure */ + + priv = (FAR struct tmp112_dev_s *)kmm_malloc(sizeof(struct tmp112_dev_s)); + if (!priv) + { + snerr("ERROR: Failed to allocate instance\n"); + return -ENOMEM; + } + + priv->i2c = i2c; + priv->addr = addr; + priv->freq = CONFIG_TMP112_I2C_FREQUENCY; + + /* Write the configuration registers */ + + sninfo("Writing configuration\n"); + tmp112_writeconfig(priv); + + /* Register the character driver */ + + ret = register_driver(devpath, &g_tmp112fops, 0666, priv); + if (ret < 0) + { + snerr("ERROR: Failed to register driver: %d\n", ret); + kmm_free(priv); + } + + sninfo("Driver loaded successfully\n"); + return ret; +} diff --git a/include/nuttx/sensors/tmp112.h b/include/nuttx/sensors/tmp112.h new file mode 100644 index 00000000000..f6821686146 --- /dev/null +++ b/include/nuttx/sensors/tmp112.h @@ -0,0 +1,117 @@ +/**************************************************************************** + * include/nuttx/sensors/tmp112.h + * + * SPDX-License-Identifier: Apache-2.0 + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __INCLUDE_NUTTX_SENSORS_TMP112_H +#define __INCLUDE_NUTTX_SENSORS_TMP112_H + +#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_TMP112) + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include <nuttx/config.h> +#include <nuttx/i2c/i2c_master.h> + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define TMP112_REG_CONFIG 0x01 +#define TMP112_REG_TEMP 0x00 + +/* Addresses for the Alert-only and Address+Alert versions of this IC. + * Typically include: + * - TMP112D0 (X2SON-5 package) + * - TMP112D1 (X2SON-5 package) + * - TMP112D2 (X2SON-5 package) + * - TMP112D3 (X2SON-5 package) + * - TMP112A (SOT563-6 package) + * - TMP112B (SOT563-6 package) + * - TMP112D (SOT563-6 package) + * - TMP112N (SOT563-6 package) + */ + +#define TMP112_ADDR_1 0x48 +#define TMP112_ADDR_2 0x49 +#define TMP112_ADDR_3 0x4A +#define TMP112_ADDR_4 0x4B + +/* Addresses for the Address-only version of this IC. + * Typically includes: + * - TMP112D (X2SON-5 package) + */ + +#define TMP112_ALT_ADDR_1 0x40 +#define TMP112_ALT_ADDR_2 0x41 +#define TMP112_ALT_ADDR_3 0x42 +#define TMP112_ALT_ADDR_4 0x43 + +/* Configuration ************************************************************/ + +/* Prerequisites: + * + * CONFIG_SENSORS_TMP112 + * Enables support for the TMP112 driver + */ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Name: tmp112_register + * + * Description: + * Register the TMP112 character device as 'devpath' + * + * Input Parameters: + * devpath - The full path to the driver to register. E.g., "/dev/temp0" + * i2c - An instance of the I2C interface to use. + * addr - The I2C address to use. + * When multiple sensors are connected to the same bus, each one + * must be electrically configured to use a different I2C + * address as specified in the datasheet. + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + ****************************************************************************/ + +int tmp112_register(FAR const char *devpath, FAR struct i2c_master_s *i2c, + uint8_t addr); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_I2C && CONFIG_SENSORS_TMP112 */ +#endif /* __INCLUDE_NUTTX_SENSORS_TMP112_H */