summaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-03 14:26:05 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-03 14:26:05 +0000
commit139456d3cb1a8c7be9e48d765eda23b15d8c8bad (patch)
treebeda77a9181d9e274d066c6c466423325b8d8f8a /nuttx/include
parentf5d629b65b9588ddae1333f06aa392083c284949 (diff)
downloadpx4-nuttx-139456d3cb1a8c7be9e48d765eda23b15d8c8bad.tar.gz
px4-nuttx-139456d3cb1a8c7be9e48d765eda23b15d8c8bad.tar.bz2
px4-nuttx-139456d3cb1a8c7be9e48d765eda23b15d8c8bad.zip
New LIS331DL driver and VSN updates from Uros
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3457 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/i2c/i2c.h (renamed from nuttx/include/nuttx/i2c.h)31
-rw-r--r--nuttx/include/nuttx/i2c/st_lis331dl.h170
2 files changed, 197 insertions, 4 deletions
diff --git a/nuttx/include/nuttx/i2c.h b/nuttx/include/nuttx/i2c/i2c.h
index 379105fc6..571c3c401 100644
--- a/nuttx/include/nuttx/i2c.h
+++ b/nuttx/include/nuttx/i2c/i2c.h
@@ -1,5 +1,5 @@
/****************************************************************************
- * include/nuttx/i2c.h
+ * include/nuttx/i2c/i2c.h
*
* Copyright(C) 2009-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -33,8 +33,8 @@
*
****************************************************************************/
-#ifndef __NUTTX_I2C_H
-#define __NUTTX_I2C_H
+#ifndef __INCLUDE_NUTTX_I2C_I2C_H
+#define __INCLUDE_NUTTX_I2C_I2C_H
/****************************************************************************
* Included Files
@@ -75,6 +75,7 @@
#define I2C_M_READ 0x0001 /* read data, from slave to master */
#define I2C_M_TEN 0x0002 /* ten bit address */
+#define I2C_M_NORESTART 0x0080 /* message should not begin with (re-)start of transfer */
/* Access macros */
@@ -184,6 +185,28 @@
#define I2C_READ(d,b,l) ((d)->ops->read(d,b,l))
/****************************************************************************
+ * Name: I2C_WRITEREAD
+ *
+ * Description:
+ * Send a block of data on I2C using the previously selected I2C
+ * frequency and slave address, followed by restarted read access.
+ * It provides a convenient wrapper to the transfer function.
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * wbuffer - A pointer to the read-only buffer of data to be written to device
+ * wbuflen - The number of bytes to send from the buffer
+ * rbuffer - A pointer to a buffer of data to receive the data from the device
+ * rbuflen - The requested number of bytes to be read
+ *
+ * Returned Value:
+ * 0: success, <0: A negated errno
+ *
+ ****************************************************************************/
+
+#define I2C_WRITEREAD(d,wb,wl,rb,rl) ((d)->ops->writeread(d,wb,wl,rb,rl))
+
+/****************************************************************************
* Name: I2C_TRANSFER
*
* Description:
@@ -307,4 +330,4 @@ EXTERN int up_i2cuninitialize(FAR struct i2c_dev_s * dev);
#if defined(__cplusplus)
}
#endif
-#endif /* __NUTTX_I2C_H */
+#endif /* __INCLUDE_NUTTX_I2C_I2C_H */
diff --git a/nuttx/include/nuttx/i2c/st_lis331dl.h b/nuttx/include/nuttx/i2c/st_lis331dl.h
new file mode 100644
index 000000000..f3f137391
--- /dev/null
+++ b/nuttx/include/nuttx/i2c/st_lis331dl.h
@@ -0,0 +1,170 @@
+/****************************************************************************
+ * include/nuttx/i2c/st_lis331dl.h
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ *
+ * Authors: Uros Platise <uros.platise@isotel.eu>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/** \file
+ * \author Uros Platise
+ * \brief ST LIS331DL I2C Device Driver
+ **/
+
+#ifndef __INCLUDE_NUTTX_I2C_ST_LIS331DL_H
+#define __INCLUDE_NUTTX_I2C_ST_LIS331DL_H
+
+#include <nuttx/i2c/i2c.h>
+#include <stdbool.h>
+
+
+/************************************************************************************
+ * Pre-Processor Declarations
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * LIS331DL Internal Registers
+ ************************************************************************************/
+
+#define ST_LIS331DL_WHOAMI 0x0F /* who am I register */
+#define ST_LIS331DL_WHOAMI_VALUE 0x3B /* Valid result is 0x3B */
+
+#define ST_LIS331DL_CTRL_REG1 0x20
+#define ST_LIS331DL_CR1_DR 0x80 /* Data-rate selection 0: 100 Hz, 1: 400 Hz */
+#define ST_LIS331DL_CR1_PD 0x40 /* Active Mode (1) / Power-down (0) */
+#define ST_LIS331DL_CR1_FS 0x20 /* Full Scale (1) +-9g or Normal Scale (0) +-2g */
+#define ST_LIS331DL_CR1_ST 0x18 /* Self test enable */
+#define ST_LIS331DL_CR1_ZEN 0x04 /* Z-Axis Enable */
+#define ST_LIS331DL_CR1_YEN 0x02 /* Y-Axis Enable */
+#define ST_LIS331DL_CR1_XEN 0x01 /* X-Axis Enable */
+
+#define ST_LIS331DL_CTRL_REG2 0x21
+#define ST_LIS331DL_CTRL_REG3 0x22
+
+#define ST_LIS331DL_HP_FILTER_RESET 0x23
+
+#define ST_LIS331DL_STATUS_REG 0x27
+
+#define ST_LIS331DL_OUT_X 0x29
+#define ST_LIS331DL_OUT_Y 0x2B
+#define ST_LIS331DL_OUT_Z 0x2D
+
+
+/************************************************************************************
+ * Public Data Types
+ ************************************************************************************/
+
+struct st_lis331dl_dev_s;
+
+struct st_lis331dl_vector_s {
+ int8_t x, y, z;
+};
+
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+/** Initialize ST LIS331DL Chip
+ *
+ * \param i2c I2C Device Structure
+ * \param address I2C Address of the proposed device
+ * \return Pointer to newly allocated ST LIS331DL structure or NULL on error with errno set.
+ *
+ * Possible errno as set by this function on error:
+ * - ENODEV: When device addressed on given address is not compatible or it is not a LIS331DL
+ * - EFAULT: When there is no device at given address.
+ * - EBUSY: When device is already addressed by other device driver (not yet supported by low-level driver)
+ **/
+EXTERN struct st_lis331dl_dev_s * st_lis331dl_init(struct i2c_dev_s * i2c, uint16_t address);
+
+/** Deinitialize ST LIS331DL Chip
+ *
+ * \param dev Device to LIS331DL device structure, as returned by the st_lis331dl_init()
+ * \return OK On success
+ *
+ **/
+EXTERN int st_lis331dl_deinit(struct st_lis331dl_dev_s * dev);
+
+/** Power up device, start conversion */
+EXTERN int st_lis331dl_powerup(struct st_lis331dl_dev_s * dev);
+
+/** Power down device, stop conversion */
+EXTERN int st_lis331dl_powerdown(struct st_lis331dl_dev_s * dev);
+
+/** Configure conversion
+ *
+ * \param dev Device to LIS331DL device structure
+ * \param full When set, range of [-9g, 9g] is selected, otherwise [-2g, +2g]
+ * \param fast When set, conversion operates at 400 Hz, otherwise at 100 Hz
+ * \return OK on success or errno is set
+ **/
+EXTERN int st_lis331dl_setconversion(struct st_lis331dl_dev_s * dev, bool full, bool fast);
+
+/** Get precision
+ *
+ * \return Precision of 1 LSB in terms of unit [g]
+ **/
+EXTERN float st_lis331dl_getprecision(struct st_lis331dl_dev_s * dev);
+
+/** Get sample rate
+ *
+ * \return Sample rate in unit of [Hz]
+ **/
+EXTERN int st_lis331dl_getsamplerate(struct st_lis331dl_dev_s * dev);
+
+/** Get readings, updates internal data structure
+ *
+ * \param dev Device to LIS331DL device structure
+ * \return Ptr to vector acceleration [x,y,z] on success, or NULL on error with errno set
+ */
+EXTERN const struct st_lis331dl_vector_s * st_lis331dl_getreadings(struct st_lis331dl_dev_s * dev);
+
+
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __INCLUDE_NUTTX_I2C_ST_LIS331DL_H */
+