summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-09-10 16:20:09 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-09-10 16:20:09 +0000
commitfd013e05a474d29de487f0cc310b180b123f79e2 (patch)
treeb7952308730ae052c330ae2e37b12303e81bbaa9 /nuttx/drivers
parentc6027b33c48715be5a2cb20ea60dc66308079d99 (diff)
downloadpx4-nuttx-fd013e05a474d29de487f0cc310b180b123f79e2.tar.gz
px4-nuttx-fd013e05a474d29de487f0cc310b180b123f79e2.tar.bz2
px4-nuttx-fd013e05a474d29de487f0cc310b180b123f79e2.zip
Add driver for LM-75 temperature sensor
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3947 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/sensors/Make.defs4
-rw-r--r--nuttx/drivers/sensors/lm75.c473
2 files changed, 477 insertions, 0 deletions
diff --git a/nuttx/drivers/sensors/Make.defs b/nuttx/drivers/sensors/Make.defs
index 1b3c3de03..bda3e8ed3 100644
--- a/nuttx/drivers/sensors/Make.defs
+++ b/nuttx/drivers/sensors/Make.defs
@@ -38,6 +38,10 @@
ifeq ($(CONFIG_I2C),y)
CSRCS += lis331dl.c
+
+ifeq ($(CONFIG_I2C_LM75),y)
+ CSRCS += lm75.c
+endif
endif
# Include sensor driver build support
diff --git a/nuttx/drivers/sensors/lm75.c b/nuttx/drivers/sensors/lm75.c
new file mode 100644
index 000000000..600f9aab3
--- /dev/null
+++ b/nuttx/drivers/sensors/lm75.c
@@ -0,0 +1,473 @@
+/****************************************************************************
+ * drivers/sensors/lm75.c
+ * Character driver for the STMicro LM-75 Temperature Sensor
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdlib.h>
+#include <fixedmath.h>
+#include <errno.h>
+
+#include <nuttx/fs.h>
+#include <nuttx/i2c.h>
+#include <nuttx/sensors/lm75.h>
+
+#if defined(CONFIG_I2C) && defined(CONFIG_I2C_LM75)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Centigrade to Fahrenheit conversion: F = 9*C/5 + 32 */
+
+#define B16_9DIV5 (9 * 65536 / 5)
+#define B16_32 (32 * 65536);
+
+/****************************************************************************
+ * Private
+ ****************************************************************************/
+
+struct lm75_dev_s
+{
+ FAR struct i2c_dev_s *i2c; /* I2C interface */
+ uint8_t addr; /* I2C address */
+ bool fahrenheit; /* true: temperature will be reported in fahrenheit */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+/* I2C Helpers */
+
+static int lm75_readb8(FAR struct lm75_dev_s *priv, uint8_t regaddr,
+ FAR b8_t *regvalue);
+#if 0 // Not used
+static int lm75_writeb8(FAR struct lm75_dev_s *priv, uint8_t regaddr,
+ b8_t regval);
+#endif
+static int lm75_readtemp(FAR struct lm75_dev_s *priv, b16_t *temp);
+static int lm75_readconf(FAR struct lm75_dev_s *priv, uint8_t *conf);
+static int lm75_writeconf(FAR struct lm75_dev_s *priv, uint8_t conf);
+
+/* Character driver methods */
+
+static int lm75_open(FAR struct file *filep);
+static int lm75_close(FAR struct file *filep);
+static ssize_t lm75_read(FAR struct file *, FAR char *, size_t);
+static ssize_t lm75_write(FAR struct file *filep, FAR const char *buffer, size_t buflen);
+static int lm75_ioctl(FAR struct file *filep,int cmd,unsigned long arg);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const struct file_operations lm75_fops =
+{
+ lm75_open,
+ lm75_close,
+ lm75_read,
+ lm75_write,
+ 0,
+ lm75_ioctl
+#ifndef CONFIG_DISABLE_POLL
+ , 0
+#endif
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: lm75_readb8
+ *
+ * Description:
+ * Read a 16-bit register (LM75_TEMP_REG, LM75_THYS_REG, or LM75_TOS_REG)
+ *
+ ****************************************************************************/
+
+static int lm75_readb8(FAR struct lm75_dev_s *priv, uint8_t regaddr,
+ FAR b8_t *regvalue)
+{
+ uint8_t buffer[2];
+ int ret;
+
+ /* Write the register address */
+
+ I2C_SETADDRESS(priv->i2c, priv->addr, 7);
+ ret = I2C_WRITE(priv->i2c, &regaddr, 1);
+ if (ret < 0)
+ {
+ return ret;
+ }
+
+ /* Restart and read 16-bits from the register (discarding 7) */
+
+ ret = I2C_READ(priv->i2c, buffer, 2);
+ if (ret < 0)
+ {
+ return ret;
+ }
+
+ /* Data format is: TTTTTTTT Txxxxxxx where TTTTTTTTT is a nine-bit
+ * temperature value with LSB = 0.5 degrees centigrade. So the raw
+ * data is b8_t
+ */
+
+ *regvalue = (b8_t)buffer[0] << 8 | (b8_t)buffer[1];
+ return OK;
+}
+
+/****************************************************************************
+ * Name: lm75_writeb8
+ *
+ * Description:
+ * Write to a 16-bit register (LM75_TEMP_REG, LM75_THYS_REG, or LM75_TOS_REG)
+ *
+ ****************************************************************************/
+#if 0 // Not used
+static int lm75_writeb8(FAR struct lm75_dev_s *priv, uint8_t regaddr,
+ b8_t regval)
+{
+ uint8_t buffer[3];
+
+ /* Set up a 3 byte message to send */
+
+ buffer[0] = regaddr;
+ buffer[1] = regval >> 8;
+ buffer[2] = regval;
+
+ /* Write the register address followed by the data (no RESTART) */
+
+ I2C_SETADDRESS(priv->i2c, priv->addr, 7);
+ return I2C_WRITE(priv->i2c, buffer, 3);
+}
+#endif
+
+/****************************************************************************
+ * Name: lm75_readtemp
+ *
+ * Description:
+ * Read the temperature register with special scaling (LM75_TEMP_REG)
+ *
+ ****************************************************************************/
+
+static int lm75_readtemp(FAR struct lm75_dev_s *priv, b16_t *temp)
+{
+ b8_t temp8;
+ b16_t temp16;
+ int ret;
+
+ /* Read the raw temperature data. Data format is: TTTTTTTT Txxxxxxx where
+ * TTTTTTTTT is a nine-bit temperature value with LSB = 0.5 degrees centigrade.
+ * So the raw data is b8_t.
+ */
+
+ ret = lm75_readb8(priv, LM75_TEMP_REG, &temp8);
+ if (ret < 0)
+ {
+ return ret;
+ }
+
+ /* Convert to b16_t */
+
+ temp16 = b8tob16(temp8);
+
+ /* Was fahrenheit requested? */
+
+ if (priv->fahrenheit)
+ {
+ /* Centigrade to Fahrenheit conversion: F = 9*C/5 + 32 */
+
+ temp16 = b16mulb16(temp16, B16_9DIV5) + B16_32;
+ }
+
+ *temp = temp16;
+ return OK;
+}
+
+/****************************************************************************
+ * Name: lm75_readconf
+ *
+ * Description:
+ * Read the 8-bit LM75 configuration register
+ *
+ ****************************************************************************/
+
+static int lm75_readconf(FAR struct lm75_dev_s *priv, uint8_t *conf)
+{
+ uint8_t buffer;
+ int ret;
+
+ /* Write the configuration register address */
+
+ I2C_SETADDRESS(priv->i2c, priv->addr, 7);
+
+ buffer = LM75_CONF_REG;
+ ret = I2C_WRITE(priv->i2c, &buffer, 1);
+ if (ret < 0)
+ {
+ return ret;
+ }
+
+ /* Restart and read 8-bits from the register */
+
+ ret = I2C_READ(priv->i2c, conf, 1);
+ return ret;
+}
+
+/****************************************************************************
+ * Name: lm75_writeconf
+ *
+ * Description:
+ * Write to a 8-bit LM75 configuration register.
+ *
+ ****************************************************************************/
+
+static int lm75_writeconf(FAR struct lm75_dev_s *priv, uint8_t conf)
+{
+ uint8_t buffer[2];
+
+ /* Set up a 2 byte message to send */
+
+ buffer[0] = LM75_CONF_REG;
+ buffer[1] = conf;
+
+ /* Write the register address followed by the data (no RESTART) */
+
+ I2C_SETADDRESS(priv->i2c, priv->addr, 7);
+ return I2C_WRITE(priv->i2c, buffer, 2);
+}
+
+/****************************************************************************
+ * Name: lm75_open
+ *
+ * Description:
+ * This function is called whenever the LM-75 device is opened.
+ *
+ ****************************************************************************/
+
+static int lm75_open(FAR struct file *filep)
+{
+ return OK;
+}
+
+/****************************************************************************
+ * Name: lm75_close
+ *
+ * Description:
+ * This routine is called when the LM-75 device is closed.
+ *
+ ****************************************************************************/
+
+static int lm75_close(FAR struct file *filep)
+{
+ return OK;
+}
+
+/****************************************************************************
+ * Name: lm75_read
+ ****************************************************************************/
+
+static ssize_t lm75_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
+{
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct lm75_dev_s *priv = inode->i_private;
+ FAR b16_t *ptr;
+ ssize_t nsamples;
+ int ret;
+
+ /* How many samples were requested to get? */
+
+ nsamples = buflen/sizeof(b16_t);
+ ptr = (FAR b16_t *)buffer;
+
+ /* Get the requested number of samples */
+
+ for (; nsamples > 0; nsamples--)
+ {
+ b16_t temp;
+
+ /* Read the next b16_t temperature value */
+
+ ret = lm75_readtemp(priv, &temp);
+ if (ret < 0)
+ {
+ return (ssize_t)ret;
+ }
+
+ /* Save the temperature value in the user buffer */
+
+ *ptr++ = temp;
+ }
+
+ return nsamples * sizeof(b16_t);
+}
+
+/****************************************************************************
+ * Name: lm75_write
+ ****************************************************************************/
+
+static ssize_t lm75_write(FAR struct file *filep, FAR const char *buffer,
+ size_t buflen)
+{
+ return -ENOSYS;
+}
+
+/****************************************************************************
+ * Name: lm75_ioctl
+ ****************************************************************************/
+
+static int lm75_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
+{
+ FAR struct inode *inode = filep->f_inode;
+ FAR struct lm75_dev_s *priv = inode->i_private;
+ int ret = OK;
+
+ switch (arg)
+ {
+ /* Read from the configuration register. Arg: uint8_t* pointer */
+
+ case SNIOC_READCONF:
+ {
+ FAR uint8_t *ptr = (FAR uint8_t *)((uintptr_t)arg);
+ ret = lm75_readconf(priv, ptr);
+ }
+ break;
+
+ /* Wrtie to the configuration register. Arg: uint8_t value */
+
+ case SNIOC_WRITECONF:
+ ret = lm75_writeconf(priv, (uint8_t)arg);
+ break;
+
+ /* Shutdown the LM75, Arg: None */
+
+ case SNIOC_SHUTDOWN:
+ {
+ uint8_t conf;
+ ret = lm75_readconf(priv, &conf);
+ if (ret == OK)
+ {
+ ret = lm75_writeconf(priv, conf | LM75_CONF_SHUTDOWN);
+ }
+ }
+ break;
+
+ /* Powerup the LM75, Arg: None */
+
+ case SNIOC_POWERUP:
+ {
+ uint8_t conf;
+ ret = lm75_readconf(priv, &conf);
+ if (ret == OK)
+ {
+ ret = lm75_writeconf(priv, conf & ~LM75_CONF_SHUTDOWN);
+ }
+ }
+ break;
+
+ /* Report samples in Fahrenheit */
+
+ case SNIOC_FAHRENHEIT:
+ priv->fahrenheit = true;
+ break;
+
+ /* Report Samples in Centigrade */
+
+ case SNIOC_CENTIGRADE:
+ priv->fahrenheit = false;
+ break;
+
+ default:
+ ret = -ENOTTY;
+ break;
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: lm75_register
+ *
+ * Description:
+ * Register the LM-75 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 to communicate with LM75
+ * addr - The I2C address of the LM-75. The base I2C address of the LM75
+ * is 0x48. Bits 0-3 can be controlled to get 8 unique addresses from 0x48
+ * through 0x4f.
+ *
+ * Returned Value:
+ * Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int lm75_register(FAR const char *devpath, FAR struct i2c_dev_s *i2c, uint8_t addr)
+{
+ FAR struct lm75_dev_s *priv;
+ int ret;
+
+ /* Initialize the LM-75 device structure */
+
+ priv = (FAR struct lm75_dev_s *)malloc(sizeof(struct lm75_dev_s));
+ if (!priv)
+ {
+ return -ENOMEM;
+ }
+
+ priv->i2c = i2c;
+ priv->addr = addr;
+ priv->fahrenheit = false;
+
+ /* Register the character driver */
+
+ ret = register_driver(devpath, &lm75_fops, 0555, priv);
+ if (ret < 0)
+ {
+ free(priv);
+ }
+ return ret;
+}
+#endif /* CONFIG_I2C && CONFIG_I2C_LM75 */