summaryrefslogtreecommitdiff
path: root/nuttx/include
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/include
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/include')
-rw-r--r--nuttx/include/nuttx/ioctl.h8
-rw-r--r--nuttx/include/nuttx/sensors/lm75.h129
2 files changed, 136 insertions, 1 deletions
diff --git a/nuttx/include/nuttx/ioctl.h b/nuttx/include/nuttx/ioctl.h
index 0ce363f24..194b83715 100644
--- a/nuttx/include/nuttx/ioctl.h
+++ b/nuttx/include/nuttx/ioctl.h
@@ -60,6 +60,7 @@
#define _SIOCBASE (0x8b00) /* Socket ioctl commands */
#define _ARPBASE (0x8c00) /* ARP ioctl commands */
#define _TSBASE (0x8d00) /* Touchscreen ioctl commands */
+#define _SNBASE (0x8e00) /* Sensor ioctl commands */
/* Macros used to manage ioctl commands */
@@ -161,11 +162,16 @@
#define _ARPIOCVALID(c) (_IOC_TYPE(c)==_ARPBASE)
#define _ARPIOC(nr) _IOC(_ARPBASE,nr)
-/* NuttX ARP touchscrren ioctl definitions (see nuttx/input/touchscreen.h) **/
+/* NuttX ARP touchscreen ioctl definitions (see nuttx/input/touchscreen.h) **/
#define _TSIOCVALID(c) (_IOC_TYPE(c)==_TSBASE)
#define _TSIOC(nr) _IOC(_TSBASE,nr)
+/* NuttX ARP sensor ioctl definitions (see nuttx/sensor/*.h) ****************/
+
+#define _SNIOCVALID(c) (_IOC_TYPE(c)==_SNBASE)
+#define _SNIOC(nr) _IOC(_SNBASE,nr)
+
/****************************************************************************
* Public Type Definitions
****************************************************************************/
diff --git a/nuttx/include/nuttx/sensors/lm75.h b/nuttx/include/nuttx/sensors/lm75.h
new file mode 100644
index 000000000..54100088e
--- /dev/null
+++ b/nuttx/include/nuttx/sensors/lm75.h
@@ -0,0 +1,129 @@
+/****************************************************************************
+ * include/nuttx/lm75.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __NUTTX_SENSORSD_LM75_H
+#define __NUTTX_SENSORSD_LM75_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/ioctl.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************
+ * CONFIG_I2C - Enables support for I2C drivers
+ * CONFIG_I2C_LM75 - Enables support for the LM-75 driver
+ */
+
+#define CONFIG_LM75_BASEADDR 0x48
+
+/* IOCTL Commands ***********************************************************/
+
+#define SNIOC_READCONF _SNIOC(0x0001) /* Arg: uint8_t* pointer */
+#define SNIOC_WRITECONF _SNIOC(0x0002) /* Arg: uint8_t value */
+#define SNIOC_SHUTDOWN _SNIOC(0x0003) /* Arg: None */
+#define SNIOC_POWERUP _SNIOC(0x0004) /* Arg: None */
+#define SNIOC_FAHRENHEIT _SNIOC(0x0005) /* Arg: None */
+#define SNIOC_CENTIGRADE _SNIOC(0x0006) /* Arg: None */
+
+/* LM-75 Register Definitions ***********************************************/
+/* LM-75 Registers addresses */
+
+#define LM75_TEMP_REG 0x00 /* Temperature Register */
+#define LM75_CONF_REG 0x01 /* Configuration Register */
+#define LM75_THYS_REG 0x02 /* Temperature Register */
+#define LM75_TOS_REG 0x03 /* Over-temp Shutdown threshold Register */
+
+/* Configuration Register Bit Definitions */
+
+#define LM75_CONF_SHUTDOWN (1 << 0) /* Bit 0: Put LM75 goes in low power shutdown mode */
+#define LM75_CONF_INTMODE (1 << 1) /* Bit 1: 0=Comparator 1=Interrupt mode */
+#define LM75_CONF_POLARITY (1 << 2) /* Bit 2: 0=O.S. Active low 1=active high */
+#define LM75_CONF_FAULTQ (3) /* Bits 3-4: # faults before setting O.S. */
+
+/* NOTE: When temperature values are read, they are return as b16_t, fixed
+ * precision integer values (see include/fixedmath.h).
+ */
+
+/****************************************************************************
+ * Global Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * 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.
+ *
+ ****************************************************************************/
+
+EXTERN int lm75_register(FAR const char *devpath, FAR struct i2c_dev_s *i2c,
+ uint8_t addr);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __NUTTX_SENSORSD_LM75_H */