Add ADXL345 accelerometer driver. From Alan Carvalho de Assis
This commit is contained in:
parent
ece6963c21
commit
10863af628
@ -86,7 +86,7 @@ ifeq ($(CONFIG_NSH_LIBRARY),y)
|
||||
CSRCS += kl_nsh.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_INPUT_ADXL345),y)
|
||||
ifeq ($(CONFIG_SENSORS_ADXL345),y)
|
||||
CSRCS += kl_adxl345.c
|
||||
endif
|
||||
|
||||
|
@ -57,11 +57,7 @@
|
||||
****************************************************************************/
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
#ifdef CONFIG_INPUT_ADXL345
|
||||
#ifndef CONFIG_INPUT
|
||||
# error "ADXL345 support requires CONFIG_INPUT"
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_SENSORS_ADXL345
|
||||
#ifndef CONFIG_KL_SPI0
|
||||
# error "ADXL345 support requires CONFIG_KL_SPI0"
|
||||
#endif
|
||||
@ -286,4 +282,4 @@ int adxl345_archinitialize(int minor)
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_INPUT_ADXL345 */
|
||||
#endif /* CONFIG_SENSORS_ADXL345 */
|
||||
|
@ -70,7 +70,7 @@
|
||||
|
||||
int nsh_archinitialize(void)
|
||||
{
|
||||
#if defined(CONFIG_INPUT_ADXL345)
|
||||
#if defined(CONFIG_SENSORS_ADXL345)
|
||||
int ret;
|
||||
|
||||
ret = adxl345_archinitialize(0);
|
||||
|
@ -8,6 +8,49 @@ config LIS331DL
|
||||
default n
|
||||
select I2C
|
||||
|
||||
config SENSORS_ADXL345
|
||||
bool "AnalogDevices ADXL345 Driver"
|
||||
default n
|
||||
---help---
|
||||
Enables support for the ADXL345 driver
|
||||
|
||||
if SENSORS_ADXL345
|
||||
|
||||
choice
|
||||
prompt "ADXL345 Interface"
|
||||
default ADXL345_SPI
|
||||
|
||||
config ADXL345_SPI
|
||||
bool "ADXL345 SPI Interface"
|
||||
select SPI
|
||||
---help---
|
||||
Enables support for the SPI interface.
|
||||
|
||||
config ADXL345_I2C
|
||||
bool "ADXL345 I2C Interface"
|
||||
select I2C
|
||||
---help---
|
||||
Enables support for the I2C interface
|
||||
|
||||
endchoice
|
||||
|
||||
config ADXL345_ACTIVELOW
|
||||
bool "Active Low Interrupt"
|
||||
default n
|
||||
---help---
|
||||
The ADXL345 interrupt will be inverted. Instead starting low and going
|
||||
high, it will start high and will go low when an interrupt is fired.
|
||||
Default: Active high/rising edge.
|
||||
|
||||
config ADXL345_REGDEBUG
|
||||
bool "Enable Register-Level ADXL345 Debug"
|
||||
default n
|
||||
depends on DEBUG
|
||||
---help---
|
||||
Enable very low register-level debug output.
|
||||
|
||||
endif # SENSORS_ADXL345
|
||||
|
||||
config I2C_LM75
|
||||
bool
|
||||
default y if LM75
|
||||
@ -31,3 +74,4 @@ config DEBUG_QENCODER
|
||||
bool "Enable Qencoder Debug"
|
||||
default n
|
||||
depends on QENCODER
|
||||
|
||||
|
@ -34,6 +34,11 @@
|
||||
############################################################################
|
||||
|
||||
# Include sensor drivers
|
||||
|
||||
ifeq ($(CONFIG_SENSORS_ADXL345),y)
|
||||
CSRCS += adxl345_base.c
|
||||
endif
|
||||
|
||||
# These drivers depend on I2C support
|
||||
|
||||
ifeq ($(CONFIG_I2C),y)
|
||||
@ -42,10 +47,22 @@ ifeq ($(CONFIG_LIS331DL),y)
|
||||
CSRCS += lis331dl.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_ADXL345_I2C),y)
|
||||
CSRCS += adxl345_i2c.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_I2C_LM75),y)
|
||||
CSRCS += lm75.c
|
||||
endif
|
||||
endif # CONFIG_I2C
|
||||
|
||||
# These drivers depend on SPI support
|
||||
|
||||
ifeq ($(CONFIG_SPI),y)
|
||||
ifeq ($(CONFIG_ADXL345_SPI),y)
|
||||
CSRCS += adxl345_spi.c
|
||||
endif
|
||||
endif # CONFIG_SPI
|
||||
|
||||
# Quadrature encoder upper half
|
||||
|
||||
|
10
drivers/sensors/README.txt
Normal file
10
drivers/sensors/README.txt
Normal file
@ -0,0 +1,10 @@
|
||||
ADXL345
|
||||
=======
|
||||
|
||||
The ADXL345 accelerometer can operate in I2C or SPI mode. To operate in I2C
|
||||
mode just connect the CS pin to Vddi/o.
|
||||
|
||||
In order to operate in SPI mode CS need to use connected to microcontroller,
|
||||
it cannot leave unconnected.
|
||||
|
||||
In SPI mode it works with clock polarity (CPOL) = 1 and clock phase (CPHA) = 1.
|
198
drivers/sensors/adxl345.h
Normal file
198
drivers/sensors/adxl345.h
Normal file
@ -0,0 +1,198 @@
|
||||
/********************************************************************************************
|
||||
* drivers/sensors/adxl345.h
|
||||
*
|
||||
* Copyright (C) 2014 Alan Carvalho de Assis
|
||||
* Author: Alan Carvalho de Assis <acassis@gmail.com>
|
||||
* using ADXL345 driver as template reference
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 __DRIVERS_SENSORS_ADXL345_H
|
||||
#define __DRIVERS_SENSORS_ADXL345_H
|
||||
|
||||
/********************************************************************************************
|
||||
* Included Files
|
||||
********************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <semaphore.h>
|
||||
|
||||
#include <nuttx/wdog.h>
|
||||
#include <nuttx/clock.h>
|
||||
#include <nuttx/wqueue.h>
|
||||
#include <nuttx/sensors/adxl345.h>
|
||||
|
||||
#if defined(CONFIG_SENSORS_ADXL345)
|
||||
|
||||
/********************************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
********************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ADXL345_I2C
|
||||
# error "Only the ADXL345 SPI interface is supported by this driver"
|
||||
#endif
|
||||
|
||||
/* Driver support ***************************************************************************/
|
||||
/* This format is used to construct the /dev/accel[n] device driver path. It defined here
|
||||
* so that it will be used consistently in all places.
|
||||
*/
|
||||
|
||||
#define DEV_FORMAT "/dev/accel%d"
|
||||
#define DEV_NAMELEN 16
|
||||
|
||||
/* Driver flags */
|
||||
|
||||
#define ADXL345_STAT_INITIALIZED 1 /* Device has been initialized */
|
||||
|
||||
/********************************************************************************************
|
||||
* Public Types
|
||||
********************************************************************************************/
|
||||
/* This defines type of events */
|
||||
|
||||
enum adxl345_event
|
||||
{
|
||||
DATA_READY = 0, /* New data available */
|
||||
SINGLE_TAP, /* A tap event detected */
|
||||
DOUBLE_TAP, /* A double tap event detected */
|
||||
ACTIVITY, /* Activity detected */
|
||||
INACTIVITY, /* Inactivity detected */
|
||||
FREE_FAL, /* Free fall event */
|
||||
WATERMARK, /* Number samples in FIFO is equal to sample bits */
|
||||
OVERRUN, /* New data replaced unread data */
|
||||
};
|
||||
|
||||
/* This defines operating mode */
|
||||
|
||||
enum adxl345_mode
|
||||
{
|
||||
BYPASS_MODE = 0, /* Bypass FIFO, then it remain empty */
|
||||
FIFO_MODE, /* Sampled data are put in FIFO, up to 32 samples */
|
||||
STREAM_MODE, /* Sampled data are put in FIFO, when full remove old samples */
|
||||
TRIGGER_MODE /* Similar to Stream Mode, but when Trigger event happen FIFO freeze */
|
||||
};
|
||||
|
||||
/* This structure describes the results of one ADXL345 sample */
|
||||
|
||||
struct adxl345_sample_s
|
||||
{
|
||||
uint16_t data_x; /* Measured X-axis acceleration */
|
||||
uint16_t data_y; /* Measured Y-axis acceleration */
|
||||
uint8_t data_z; /* Measured Z-axis acceleration */
|
||||
};
|
||||
|
||||
/* This structure represents the state of the ADXL345 driver */
|
||||
|
||||
struct adxl345_dev_s
|
||||
{
|
||||
/* Common fields */
|
||||
|
||||
FAR struct adxl345_config_s *config; /* Board configuration data */
|
||||
sem_t exclsem; /* Manages exclusive access to this structure */
|
||||
#ifdef CONFIG_ADXL345_SPI
|
||||
FAR struct spi_dev_s *spi; /* Saved SPI driver instance */
|
||||
#else
|
||||
FAR struct i2c_dev_s *i2c; /* Saved I2C driver instance */
|
||||
#endif
|
||||
|
||||
uint8_t status; /* See ADXL345_STAT_* definitions */
|
||||
struct work_s work; /* Supports the interrupt handling "bottom half" */
|
||||
|
||||
#ifdef CONFIG_ADXL345_REFCNT
|
||||
uint8_t crefs; /* Number of times the device has been opened */
|
||||
#endif
|
||||
uint8_t nwaiters; /* Number of threads waiting for ADXL345 data */
|
||||
|
||||
uint16_t ofsx; /* Offset X value */
|
||||
uint16_t ofsy; /* Offset Y value */
|
||||
uint16_t ofsz; /* Offset Z value */
|
||||
sem_t waitsem; /* Used to wait for the availability of data */
|
||||
|
||||
struct work_s timeout; /* Supports timeout work */
|
||||
struct adxl345_sample_s sample; /* Last sampled accelerometer data */
|
||||
|
||||
/* The following is a list if poll structures of threads waiting for
|
||||
* driver events. The 'struct pollfd' reference for each open is also
|
||||
* retained in the f_priv field of the 'struct file'.
|
||||
*/
|
||||
|
||||
#ifndef CONFIG_DISABLE_POLL
|
||||
struct pollfd *fds[CONFIG_ADXL345_NPOLLWAITERS];
|
||||
#endif
|
||||
};
|
||||
|
||||
/********************************************************************************************
|
||||
* Public Function Prototypes
|
||||
********************************************************************************************/
|
||||
|
||||
/********************************************************************************************
|
||||
* Name: adxl345_getreg8
|
||||
*
|
||||
* Description:
|
||||
* Read from an 8-bit ADXL345 register
|
||||
*
|
||||
********************************************************************************************/
|
||||
|
||||
uint8_t adxl345_getreg8(FAR struct adxl345_dev_s *priv, uint8_t regaddr);
|
||||
|
||||
/********************************************************************************************
|
||||
* Name: adxl345_putreg8
|
||||
*
|
||||
* Description:
|
||||
* Write a value to an 8-bit ADXL345 register
|
||||
*
|
||||
********************************************************************************************/
|
||||
|
||||
void adxl345_putreg8(FAR struct adxl345_dev_s *priv, uint8_t regaddr, uint8_t regval);
|
||||
|
||||
/********************************************************************************************
|
||||
* Name: adxl345_getreg16
|
||||
*
|
||||
* Description:
|
||||
* Read 16-bits of data from an ADXL345 register
|
||||
*
|
||||
********************************************************************************************/
|
||||
|
||||
uint16_t adxl345_getreg16(FAR struct adxl345_dev_s *priv, uint8_t regaddr);
|
||||
|
||||
/********************************************************************************************
|
||||
* Name: adxl345_accworker
|
||||
*
|
||||
* Description:
|
||||
* Handle accelerometer interrupt events (this function actually executes in the context of
|
||||
* the worker thread).
|
||||
*
|
||||
********************************************************************************************/
|
||||
|
||||
void adxl345_accworker(FAR struct adxl345_dev_s *priv, uint8_t intsta) weak_function;
|
||||
|
||||
#endif /* CONFIG_SENSORS_ADXL345 */
|
||||
#endif /* __DRIVERS_SENSORS_ADXL345_H */
|
484
drivers/sensors/adxl345_base.c
Normal file
484
drivers/sensors/adxl345_base.c
Normal file
@ -0,0 +1,484 @@
|
||||
/****************************************************************************
|
||||
* drivers/sensors/adxl345.c
|
||||
*
|
||||
* Copyright (C) 2014 Alan Carvalho de Assis. All rights reserved.
|
||||
* Author: Alan Carvalho de Assis <acassis@gmail.com>
|
||||
* Based on STME811 driver
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 <unistd.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/sensors/adxl345.h>
|
||||
|
||||
#include "adxl345.h"
|
||||
|
||||
#if defined(CONFIG_SENSORS_ADXL345)
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/* Character driver methods */
|
||||
|
||||
static int adxl345_open(FAR struct file *filep);
|
||||
static int adxl345_close(FAR struct file *filep);
|
||||
static ssize_t adxl345_read(FAR struct file *filep, FAR char *buffer,
|
||||
size_t len);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
static struct adxl345_dev_s g_adxl345;
|
||||
|
||||
/* This the vtable that supports the character driver interface */
|
||||
|
||||
static const struct file_operations g_adxl345fops =
|
||||
{
|
||||
adxl345_open, /* open */
|
||||
adxl345_close, /* close */
|
||||
adxl345_read, /* read */
|
||||
0, /* write */
|
||||
0, /* seek */
|
||||
0, /* ioctl */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_open
|
||||
*
|
||||
* Description:
|
||||
* Standard character driver open method.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int adxl345_open(FAR struct file *filep)
|
||||
{
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_close
|
||||
*
|
||||
* Description:
|
||||
* Standard character driver close method.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int adxl345_close(FAR struct file *filep)
|
||||
{
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_read
|
||||
*
|
||||
* Description:
|
||||
* Standard character driver read method.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static ssize_t adxl345_read(FAR struct file *filep, FAR char *buffer, size_t len)
|
||||
{
|
||||
FAR struct inode *inode;
|
||||
FAR struct adxl345_dev_s *priv;
|
||||
struct adxl345_sample_s sample;
|
||||
int ret;
|
||||
|
||||
ivdbg("len=%d\n", len);
|
||||
DEBUGASSERT(filep);
|
||||
inode = filep->f_inode;
|
||||
|
||||
DEBUGASSERT(inode && inode->i_private);
|
||||
priv = (FAR struct adxl345_dev_s *)inode->i_private;
|
||||
|
||||
/* Verify that the caller has provided a buffer large enough to receive
|
||||
* the accelerometer data.
|
||||
*/
|
||||
|
||||
if (len < sizeof(struct adxl345_sample_s))
|
||||
{
|
||||
/* We could provide logic to break up a touch report into segments and
|
||||
* handle smaller reads... but why?
|
||||
*/
|
||||
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
/* Get exclusive access to the driver data structure */
|
||||
|
||||
ret = sem_wait(&priv->exclsem);
|
||||
if (ret < 0)
|
||||
{
|
||||
/* This should only happen if the wait was canceled by an signal */
|
||||
|
||||
DEBUGASSERT(errno == EINTR);
|
||||
return -EINTR;
|
||||
}
|
||||
|
||||
/* Read accelerometer X Y Z axes */
|
||||
|
||||
sample.data_x = adxl345_getreg8(priv, ADXL345_DATAX1);
|
||||
sample.data_x = (sample.data_x << 8) | adxl345_getreg8(priv, ADXL345_DATAX0);
|
||||
sample.data_y = adxl345_getreg8(priv, ADXL345_DATAY1);
|
||||
sample.data_y = (sample.data_y << 8) | adxl345_getreg8(priv, ADXL345_DATAY0);
|
||||
sample.data_z = adxl345_getreg8(priv, ADXL345_DATAZ1);
|
||||
sample.data_z = (sample.data_z << 8) | adxl345_getreg8(priv, ADXL345_DATAZ0);
|
||||
|
||||
/* Return read sample */
|
||||
|
||||
buffer = (FAR char *) &sample;
|
||||
|
||||
sem_post(&priv->exclsem);
|
||||
return sizeof(struct adxl345_sample_s);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_register
|
||||
*
|
||||
* Description:
|
||||
* This function will register the touchscreen driver as /dev/accelN where N
|
||||
* is the minor device number
|
||||
*
|
||||
* Input Parameters:
|
||||
* handle - The handle previously returned by adxl345_register
|
||||
* minor - The input device minor number
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero is returned on success. Otherwise, a negated errno value is
|
||||
* returned to indicate the nature of the failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int adxl345_register(ADXL345_HANDLE handle, int minor)
|
||||
{
|
||||
FAR struct adxl345_dev_s *priv = (FAR struct adxl345_dev_s *)handle;
|
||||
char devname[DEV_NAMELEN];
|
||||
int ret;
|
||||
|
||||
ivdbg("handle=%p minor=%d\n", handle, minor);
|
||||
DEBUGASSERT(priv);
|
||||
|
||||
/* Get exclusive access to the device structure */
|
||||
|
||||
ret = sem_wait(&priv->exclsem);
|
||||
if (ret < 0)
|
||||
{
|
||||
int errval = errno;
|
||||
idbg("ERROR: sem_wait failed: %d\n", errval);
|
||||
return -errval;
|
||||
}
|
||||
|
||||
/* Initialize the structure fields to their default values */
|
||||
|
||||
priv->ofsx = 0;
|
||||
priv->ofsy = 0;
|
||||
priv->ofsz = 0;
|
||||
|
||||
/* Register the character driver */
|
||||
|
||||
snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor);
|
||||
ret = register_driver(devname, &g_adxl345fops, 0666, priv);
|
||||
if (ret < 0)
|
||||
{
|
||||
idbg("ERROR: Failed to register driver %s: %d\n", devname, ret);
|
||||
sem_post(&priv->exclsem);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Indicate that the accelerometer was successfully initialized */
|
||||
|
||||
priv->status |= ADXL345_STAT_INITIALIZED; /* Accelerometer is initialized */
|
||||
sem_post(&priv->exclsem);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_worker
|
||||
*
|
||||
* Description:
|
||||
* This is the "bottom half" of the ADXL345 interrupt handler
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void adxl345_worker(FAR void *arg)
|
||||
{
|
||||
FAR struct adxl345_dev_s *priv = (FAR struct adxl345_dev_s *)arg;
|
||||
uint8_t regval;
|
||||
|
||||
DEBUGASSERT(priv && priv->config);
|
||||
|
||||
/* Get the global interrupt status */
|
||||
|
||||
regval = adxl345_getreg8(priv, ADXL345_INT_SOURCE);
|
||||
|
||||
/* Check for a data ready interrupt */
|
||||
|
||||
if ((regval & INT_DATA_READY) != 0)
|
||||
{
|
||||
/* Read accelerometer data to sample */
|
||||
|
||||
priv->sample.data_x = adxl345_getreg8(priv, ADXL345_DATAX1);
|
||||
priv->sample.data_x = (priv->sample.data_x << 8) | adxl345_getreg8(priv, ADXL345_DATAX0);
|
||||
priv->sample.data_y = adxl345_getreg8(priv, ADXL345_DATAY1);
|
||||
priv->sample.data_y = (priv->sample.data_y << 8) | adxl345_getreg8(priv, ADXL345_DATAY0);
|
||||
priv->sample.data_z = adxl345_getreg8(priv, ADXL345_DATAZ1);
|
||||
priv->sample.data_z = (priv->sample.data_z << 8) | adxl345_getreg8(priv, ADXL345_DATAZ0);
|
||||
}
|
||||
|
||||
/* Re-enable the ADXL345 GPIO interrupt */
|
||||
|
||||
priv->config->enable(priv->config, true);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_interrupt
|
||||
*
|
||||
* Description:
|
||||
* The ADXL345 interrupt handler
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int adxl345_interrupt(int irq, FAR void *context)
|
||||
{
|
||||
FAR struct adxl345_dev_s *priv;
|
||||
FAR struct adxl345_config_s *config;
|
||||
int ret;
|
||||
|
||||
/* Get a pointer the callbacks for convenience (and so the code is not so
|
||||
* ugly).
|
||||
*/
|
||||
|
||||
config = priv->config;
|
||||
DEBUGASSERT(config != NULL);
|
||||
|
||||
/* Disable further interrupts */
|
||||
|
||||
config->enable(config, false);
|
||||
|
||||
/* Check if interrupt work is already queue. If it is already busy, then
|
||||
* we already have interrupt processing in the pipeline and we need to do
|
||||
* nothing more.
|
||||
*/
|
||||
|
||||
if (work_available(&priv->work))
|
||||
{
|
||||
/* Yes.. Transfer processing to the worker thread. Since ADXL345
|
||||
* interrupts are disabled while the work is pending, no special
|
||||
* action should be required to protect the work queue.
|
||||
*/
|
||||
|
||||
ret = work_queue(HPWORK, &priv->work, adxl345_worker, priv, 0);
|
||||
if (ret != 0)
|
||||
{
|
||||
illdbg("Failed to queue work: %d\n", ret);
|
||||
}
|
||||
}
|
||||
|
||||
/* Clear any pending interrupts and return success */
|
||||
|
||||
config->clear(config);
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_checkid
|
||||
*
|
||||
* Description:
|
||||
* Read and verify the ADXL345 chip ID
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int adxl345_checkid(FAR struct adxl345_dev_s *priv)
|
||||
{
|
||||
uint8_t devid = 0;
|
||||
|
||||
/* Read device ID */
|
||||
|
||||
devid = adxl345_getreg8(priv, ADXL345_DEVID);
|
||||
ivdbg("devid: %04x\n", devid);
|
||||
|
||||
if (devid != (uint16_t) DEVID)
|
||||
{
|
||||
/* ID is not Correct */
|
||||
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_reset
|
||||
*
|
||||
* Description:
|
||||
* Reset the ADXL345
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void adxl345_reset(FAR struct adxl345_dev_s *priv)
|
||||
{
|
||||
/* ADXL345 doesn't have software reset */
|
||||
|
||||
/* Wait a bit to make the GOD of TIME happy */
|
||||
|
||||
usleep(20*1000);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_instantiate
|
||||
*
|
||||
* Description:
|
||||
* Instantiate and configure the ADXL345 device driver to use the provided
|
||||
* I2C or SPIdevice instance.
|
||||
*
|
||||
* Input Parameters:
|
||||
* dev - An I2C or SPI driver instance
|
||||
* config - Persistent board configuration data
|
||||
*
|
||||
* Returned Value:
|
||||
* A non-zero handle is returned on success. This handle may then be used
|
||||
* to configure the ADXL345 driver as necessary. A NULL handle value is
|
||||
* returned on failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ADXL345_SPI
|
||||
ADXL345_HANDLE adxl345_instantiate(FAR struct spi_dev_s *dev,
|
||||
FAR struct adxl345_config_s *config)
|
||||
#else
|
||||
ADXL345_HANDLE adxl345_instantiate(FAR struct i2c_dev_s *dev,
|
||||
FAR struct adxl345_config_s *config)
|
||||
#endif
|
||||
{
|
||||
FAR struct adxl345_dev_s *priv;
|
||||
uint8_t regval;
|
||||
int ret;
|
||||
|
||||
/* Use the one-and-only ADXL345 driver instance */
|
||||
|
||||
priv = &g_adxl345;
|
||||
|
||||
/* Initialize the device state structure */
|
||||
|
||||
sem_init(&priv->exclsem, 0, 1);
|
||||
priv->config = config;
|
||||
|
||||
#ifdef CONFIG_ADXL345_SPI
|
||||
priv->spi = dev;
|
||||
|
||||
/* If this SPI bus is not shared, then we can config it now.
|
||||
* If it is shared, then other device could change our config,
|
||||
* then just configure before sending data.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SPI_OWNBUS
|
||||
/* Configure SPI for the ADXL345 */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_GSENSOR, true);
|
||||
SPI_SETMODE(priv->spi, SPIDEV_MODE3);
|
||||
SPI_SETBITS(priv->spi, 8);
|
||||
SPI_SETFREQUENCY(priv->spi, ADXL345_SPI_MAXFREQUENCY);
|
||||
SPI_SELECT(priv->spi, SPIDEV_GSENSOR, false);
|
||||
#endif
|
||||
#else
|
||||
priv->i2c = dev;
|
||||
|
||||
/* Set the I2C address and frequency. REVISIT: This logic would be
|
||||
* insufficient if we share the I2C bus with any other devices that also
|
||||
* modify the address and frequency.
|
||||
*/
|
||||
|
||||
I2C_SETADDRESS(dev, config->address, 7);
|
||||
I2C_SETFREQUENCY(dev, config->frequency);
|
||||
#endif
|
||||
|
||||
/* Read and verify the ADXL345 device ID */
|
||||
|
||||
ret = adxl345_checkid(priv);
|
||||
if (ret < 0)
|
||||
{
|
||||
illdbg("Wrong Device ID!\n");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/* Generate ADXL345 Software reset */
|
||||
|
||||
adxl345_reset(priv);
|
||||
|
||||
/* Configure the interrupt output pin to generate interrupts on high or low level. */
|
||||
|
||||
regval = adxl345_getreg8(priv, ADXL345_DATA_FORMAT);
|
||||
#ifdef CONFIG_ADXL345_ACTIVELOW
|
||||
regval |= DATA_FMT_INT_INVERT; /* Pin polarity: Active low / falling edge */
|
||||
#else
|
||||
regval &= ~DATA_FMT_INT_INVERT; /* Pin polarity: Active high / rising edge */
|
||||
#endif
|
||||
adxl345_putreg8(priv, ADXL345_DATA_FORMAT, regval);
|
||||
|
||||
/* Attach the ADXL345 interrupt handler. */
|
||||
|
||||
config->attach(config, adxl345_interrupt);
|
||||
|
||||
/* Leave standby mode */
|
||||
|
||||
adxl345_putreg8(priv, ADXL345_POWER_CTL, POWER_CTL_MEASURE);
|
||||
|
||||
config->clear(config);
|
||||
config->enable(config, true);
|
||||
|
||||
/* Enable interrupts */
|
||||
|
||||
adxl345_putreg8(priv, ADXL345_INT_ENABLE, INT_DATA_READY);
|
||||
|
||||
/* Return our private data structure as an opaque handle */
|
||||
return (ADXL345_HANDLE)priv;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_SENSORS_ADXL345 */
|
212
drivers/sensors/adxl345_i2c.c
Normal file
212
drivers/sensors/adxl345_i2c.c
Normal file
@ -0,0 +1,212 @@
|
||||
/****************************************************************************
|
||||
* drivers/sensors/adxl345_i2c.c
|
||||
*
|
||||
* Copyright (C) 2014 Alan Carvalho de Assis. All rights reserved.
|
||||
* Author: Alan Carvalho de Assis <acassis@gmail.com>
|
||||
* Based on STME811 driver
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 <unistd.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/sensors/adxl345.h>
|
||||
|
||||
#include "adxl345.h"
|
||||
|
||||
#if defined(CONFIG_SENSORS_ADXL345)
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_getreg8
|
||||
*
|
||||
* Description:
|
||||
* Read from an 8-bit ADXL345 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ADXL345_I2C
|
||||
uint8_t adxl345_getreg8(FAR struct adxl345_dev_s *priv, uint8_t regaddr)
|
||||
{
|
||||
/* 8-bit data read sequence:
|
||||
*
|
||||
* Start - I2C_Write_Address - ADXL345_Reg_Address -
|
||||
* Repeated_Start - I2C_Read_Address - ADXL345_Read_Data - STOP
|
||||
*/
|
||||
|
||||
struct i2c_msg_s msg[2];
|
||||
uint8_t regval;
|
||||
int ret;
|
||||
|
||||
/* Setup 8-bit ADXL345 address write message */
|
||||
|
||||
msg[0].addr = priv->config->address; /* 7-bit address */
|
||||
msg[0].flags = 0; /* Write transaction, beginning with START */
|
||||
msg[0].buffer = ®addr; /* Transfer from this address */
|
||||
msg[0].length = 1; /* Send one byte following the address
|
||||
* (no STOP) */
|
||||
|
||||
/* Set up the 8-bit ADXL345 data read message */
|
||||
|
||||
msg[1].addr = priv->config->address; /* 7-bit address */
|
||||
msg[1].flags = I2C_M_READ; /* Read transaction, beginning with Re-START */
|
||||
msg[1].buffer = ®val; /* Transfer to this address */
|
||||
msg[1].length = 1; /* Receive one byte following the address
|
||||
* (then STOP) */
|
||||
|
||||
/* Perform the transfer */
|
||||
|
||||
ret = I2C_TRANSFER(priv->i2c, msg, 2);
|
||||
if (ret < 0)
|
||||
{
|
||||
idbg("I2C_TRANSFER failed: %d\n", ret);
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_ADXL345_REGDEBUG
|
||||
dbg("%02x->%02x\n", regaddr, regval);
|
||||
#endif
|
||||
return regval;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_putreg8
|
||||
*
|
||||
* Description:
|
||||
* Write a value to an 8-bit ADXL345 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ADXL345_I2C
|
||||
void adxl345_putreg8(FAR struct adxl345_dev_s *priv,
|
||||
uint8_t regaddr, uint8_t regval)
|
||||
{
|
||||
/* 8-bit data read sequence:
|
||||
*
|
||||
* Start - I2C_Write_Address - ADXL345_Reg_Address - ADXL345_Write_Data - STOP
|
||||
*/
|
||||
|
||||
struct i2c_msg_s msg;
|
||||
uint8_t txbuffer[2];
|
||||
int ret;
|
||||
|
||||
#ifdef CONFIG_ADXL345_REGDEBUG
|
||||
dbg("%02x<-%02x\n", regaddr, regval);
|
||||
#endif
|
||||
|
||||
/* Setup to the data to be transferred. Two bytes: The ADXL345 register
|
||||
* address followed by one byte of data.
|
||||
*/
|
||||
|
||||
txbuffer[0] = regaddr;
|
||||
txbuffer[1] = regval;
|
||||
|
||||
/* Setup 8-bit ADXL345 address write message */
|
||||
|
||||
msg.addr = priv->config->address; /* 7-bit address */
|
||||
msg.flags = 0; /* Write transaction, beginning with START */
|
||||
msg.buffer = txbuffer; /* Transfer from this address */
|
||||
msg.length = 2; /* Send two byte following the address
|
||||
* (then STOP) */
|
||||
|
||||
/* Perform the transfer */
|
||||
|
||||
ret = I2C_TRANSFER(priv->i2c, &msg, 1);
|
||||
if (ret < 0)
|
||||
{
|
||||
idbg("I2C_TRANSFER failed: %d\n", ret);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_getreg16
|
||||
*
|
||||
* Description:
|
||||
* Read 16-bits of data from an STMPE-11 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ADXL345_I2C
|
||||
uint16_t adxl345_getreg16(FAR struct adxl345_dev_s *priv, uint8_t regaddr)
|
||||
{
|
||||
/* 16-bit data read sequence:
|
||||
*
|
||||
* Start - I2C_Write_Address - ADXL345_Reg_Address -
|
||||
* Repeated_Start - I2C_Read_Address - ADXL345_Read_Data_1 -
|
||||
* ADXL345_Read_Data_2 - STOP
|
||||
*/
|
||||
|
||||
struct i2c_msg_s msg[2];
|
||||
uint8_t rxbuffer[2];
|
||||
int ret;
|
||||
|
||||
/* Setup 8-bit ADXL345 address write message */
|
||||
|
||||
msg[0].addr = priv->config->address; /* 7-bit address */
|
||||
msg[0].flags = 0; /* Write transaction, beginning with START */
|
||||
msg[0].buffer = ®addr; /* Transfer from this address */
|
||||
msg[0].length = 1; /* Send one byte following the address
|
||||
* (no STOP) */
|
||||
|
||||
/* Set up the 8-bit ADXL345 data read message */
|
||||
|
||||
msg[1].addr = priv->config->address; /* 7-bit address */
|
||||
msg[1].flags = I2C_M_READ; /* Read transaction, beginning with Re-START */
|
||||
msg[1].buffer = rxbuffer; /* Transfer to this address */
|
||||
msg[1].length = 2; /* Receive two bytes following the address
|
||||
* (then STOP) */
|
||||
|
||||
/* Perform the transfer */
|
||||
|
||||
ret = I2C_TRANSFER(priv->i2c, msg, 2);
|
||||
if (ret < 0)
|
||||
{
|
||||
idbg("I2C_TRANSFER failed: %d\n", ret);
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_ADXL345_REGDEBUG
|
||||
dbg("%02x->%02x%02x\n", regaddr, rxbuffer[0], rxbuffer[1]);
|
||||
#endif
|
||||
return (uint16_t)rxbuffer[0] << 8 | (uint16_t)rxbuffer[1];
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_SENSORS_ADXL345 */
|
213
drivers/sensors/adxl345_spi.c
Normal file
213
drivers/sensors/adxl345_spi.c
Normal file
@ -0,0 +1,213 @@
|
||||
/****************************************************************************
|
||||
* drivers/sensors/adxl345_spi.c
|
||||
*
|
||||
* Copyright (C) 2014 Alan Carvalho de Assis. All rights reserved.
|
||||
* Author: Alan Carvalho de Assis <acassis@gmail.com>
|
||||
* Based on STME811 driver
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 <unistd.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/sensors/adxl345.h>
|
||||
|
||||
#include "adxl345.h"
|
||||
|
||||
#if defined(CONFIG_SENSORS_ADXL345) && defined(CONFIG_ADXL345_SPI)
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_configspi
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef CONFIG_SPI_OWNBUS
|
||||
static inline void adxl345_configspi(FAR struct spi_dev_s *spi)
|
||||
{
|
||||
/* Configure SPI for the ADXL345 */
|
||||
|
||||
SPI_SELECT(spi, SPIDEV_GSENSOR, true);
|
||||
SPI_SETMODE(spi, SPIDEV_MODE3);
|
||||
SPI_SETBITS(spi, 8);
|
||||
SPI_SETFREQUENCY(spi, ADXL345_SPI_MAXFREQUENCY);
|
||||
SPI_SELECT(spi, SPIDEV_GSENSOR, false);
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_getreg8
|
||||
*
|
||||
* Description:
|
||||
* Read from an 8-bit ADXL345 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
uint8_t adxl345_getreg8(FAR struct adxl345_dev_s *priv, uint8_t regaddr)
|
||||
{
|
||||
uint8_t regval;
|
||||
|
||||
/* If SPI bus is shared then lock and configure it */
|
||||
|
||||
#ifndef CONFIG_SPI_OWNBUS
|
||||
(void)SPI_LOCK(priv->spi, true);
|
||||
adxl345_configspi(priv->spi);
|
||||
#endif
|
||||
|
||||
/* Select the ADXL345 */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_GSENSOR, true);
|
||||
|
||||
/* Send register to read and get the next byte */
|
||||
|
||||
(void)SPI_SEND(priv->spi, regaddr);
|
||||
SPI_RECVBLOCK(priv->spi, ®val, 1);
|
||||
|
||||
/* Deselect the ADXL345 */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_GSENSOR, false);
|
||||
|
||||
/* Unlock bus */
|
||||
|
||||
#ifndef CONFIG_SPI_OWNBUS
|
||||
(void)SPI_LOCK(priv->spi, false);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ADXL345_REGDEBUG
|
||||
dbg("%02x->%02x\n", regaddr, regval);
|
||||
#endif
|
||||
return regval;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_putreg8
|
||||
*
|
||||
* Description:
|
||||
* Write a value to an 8-bit ADXL345 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void adxl345_putreg8(FAR struct adxl345_dev_s *priv, uint8_t regaddr,
|
||||
uint8_t regval)
|
||||
{
|
||||
#ifdef CONFIG_ADXL345_REGDEBUG
|
||||
dbg("%02x<-%02x\n", regaddr, regval);
|
||||
#endif
|
||||
|
||||
/* If SPI bus is shared then lock and configure it */
|
||||
|
||||
#ifndef CONFIG_SPI_OWNBUS
|
||||
(void)SPI_LOCK(priv->spi, true);
|
||||
adxl345_configspi(priv->spi);
|
||||
#endif
|
||||
|
||||
/* Select the ADXL345 */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_GSENSOR, true);
|
||||
|
||||
/* Send register address and set the value */
|
||||
|
||||
(void)SPI_SEND(priv->spi, regaddr);
|
||||
(void)SPI_SEND(priv->spi, regval);
|
||||
|
||||
/* Deselect the ADXL345 */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_GSENSOR, false);
|
||||
|
||||
/* Unlock bus */
|
||||
#ifndef CONFIG_SPI_OWNBUS
|
||||
(void)SPI_LOCK(priv->spi, false);
|
||||
#endif
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: adxl345_getreg16
|
||||
*
|
||||
* Description:
|
||||
* Read 16-bits of data from an ADXL345 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
uint16_t adxl345_getreg16(FAR struct adxl345_dev_s *priv, uint8_t regaddr)
|
||||
{
|
||||
uint16_t regval;
|
||||
|
||||
/* If SPI bus is shared then lock and configure it */
|
||||
|
||||
#ifndef CONFIG_SPI_OWNBUS
|
||||
(void)SPI_LOCK(priv->spi, true);
|
||||
adxl345_configspi(priv->spi);
|
||||
#endif
|
||||
|
||||
/* Select the ADXL345 */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_GSENSOR, true);
|
||||
|
||||
/* Send register to read and get the next 2 bytes */
|
||||
|
||||
(void)SPI_SEND(priv->spi, regaddr);
|
||||
SPI_RECVBLOCK(priv->spi, ®val, 2);
|
||||
|
||||
/* Deselect the ADXL345 */
|
||||
|
||||
SPI_SELECT(priv->spi, SPIDEV_GSENSOR, false);
|
||||
|
||||
/* Unlock bus */
|
||||
|
||||
#ifndef CONFIG_SPI_OWNBUS
|
||||
(void)SPI_LOCK(priv->spi, false);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ADXL345_REGDEBUG
|
||||
dbg("%02x->%04x\n", regaddr, regval);
|
||||
#endif
|
||||
|
||||
return regval;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_SENSORS_ADXL345 && CONFIG_ADXL345_SPI*/
|
439
include/nuttx/sensors/adxl345.h
Normal file
439
include/nuttx/sensors/adxl345.h
Normal file
@ -0,0 +1,439 @@
|
||||
/********************************************************************************************
|
||||
* include/nuttx/input/adxl345.h
|
||||
*
|
||||
* Copyright (C) 2014 Gregory Nutt. All rights reserved.
|
||||
* Author: Alan Carvalho de Assis <acassis@gmail.com>
|
||||
*
|
||||
* 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 __INCLUDE_NUTTX_INPUT_ADXL345_H
|
||||
#define __INCLUDE_NUTTX_INPUT_ADXL345_H
|
||||
|
||||
/********************************************************************************************
|
||||
* Included Files
|
||||
********************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
|
||||
#if defined(CONFIG_SENSORS_ADXL345)
|
||||
|
||||
/********************************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
********************************************************************************************/
|
||||
/* Configuration ****************************************************************************/
|
||||
/* Settings that effect the driver: CONFIG_DISABLE_POLL
|
||||
*
|
||||
* CONFIG_SENSORS_ADXL345
|
||||
* Enables support for the ADXL345 driver
|
||||
* CONFIG_ADXL345_SPI
|
||||
* Enables support for the SPI interface (not currenly supported)
|
||||
* CONFIG_ADXL345_I2C
|
||||
* Enables support for the I2C interface
|
||||
* CONFIG_ADXL345_MULTIPLE
|
||||
* Can be defined to support multiple ADXL345 devices on board.
|
||||
* CONFIG_ADXL345_NPOLLWAITERS
|
||||
* Maximum number of threads that can be waiting on poll() (ignored if
|
||||
* CONFIG_DISABLE_POLL is set).
|
||||
* CONFIG_ADXL345_TSC_DISABLE
|
||||
* Disable driver touchscreen functionality.
|
||||
* CONFIG_ADXL345_ADC_DISABLE
|
||||
* Disable driver ADC functionality.
|
||||
* CONFIG_ADXL345_GPIO_DISABLE
|
||||
* Disable driver GPIO functionality.
|
||||
* CONFIG_ADXL345_GPIOINT_DISABLE
|
||||
* Disable driver GPIO interrupt functionlality (ignored if GPIO functionality is
|
||||
* disabled).
|
||||
* CONFIG_ADXL345_SWAPXY
|
||||
* Reverse the meaning of X and Y to handle different LCD orientations.
|
||||
* CONFIG_ADXL345_TEMP_DISABLE
|
||||
* Disable driver temperature sensor functionality.
|
||||
* CONFIG_ADXL345_REGDEBUG
|
||||
* Enable very low register-level debug output. Requires CONFIG_DEBUG.
|
||||
* CONFIG_ADXL345_THRESHX and CONFIG_ADXL345_THRESHY
|
||||
* ADXL345 touchscreen data comes in a a very high rate. New touch positions
|
||||
* will only be reported when the X or Y data changes by these thresholds.
|
||||
* This trades reduces data rate for some loss in dragging accuracy. The
|
||||
* ADXL345 is configure for 12-bit values so the raw ranges are 0-4095. So
|
||||
* for example, if your display is 320x240, then THRESHX=13 and THRESHY=17
|
||||
* would correspond to one pixel. Default: 12
|
||||
*/
|
||||
|
||||
/* The ADXL345 interfaces with the target CPU via a I2C or SPI interface. The pin IN_1
|
||||
* allows the selection of interface protocol at reset state.
|
||||
*/
|
||||
|
||||
#if !defined(CONFIG_ADXL345_SPI) && !defined(CONFIG_ADXL345_I2C)
|
||||
# error "One of CONFIG_ADXL345_SPI or CONFIG_ADXL345_I2C must be defined"
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_ADXL345_SPI) && defined(CONFIG_ADXL345_I2C)
|
||||
# error "Only one of CONFIG_ADXL345_SPI or CONFIG_ADXL345_I2C can be defined"
|
||||
#endif
|
||||
|
||||
/* Maximum number of threads than can be waiting for POLL events */
|
||||
|
||||
#ifndef CONFIG_ADXL345_NPOLLWAITERS
|
||||
# define CONFIG_ADXL345_NPOLLWAITERS 2
|
||||
#endif
|
||||
|
||||
/* Check for some required settings. This can save the user a lot of time
|
||||
* in getting the right configuration.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_ADXL345_I2C
|
||||
# ifndef CONFIG_I2C
|
||||
# error "CONFIG_I2C is required in the I2C support"
|
||||
# endif
|
||||
# ifndef CONFIG_I2C_TRANSFER
|
||||
# error "CONFIG_I2C_TRANSFER is required in the I2C configuration"
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_DISABLE_SIGNALS
|
||||
# error "Signals are required. CONFIG_DISABLE_SIGNALS must not be selected."
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_SCHED_WORKQUEUE
|
||||
# error "Work queue support required. CONFIG_SCHED_WORKQUEUE must be selected."
|
||||
#endif
|
||||
|
||||
/* Thresholds */
|
||||
|
||||
#ifndef CONFIG_ADXL345_THRESHX
|
||||
# define CONFIG_ADXL345_THRESHX 12
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_ADXL345_THRESHY
|
||||
# define CONFIG_ADXL345_THRESHY 12
|
||||
#endif
|
||||
|
||||
/* Debug output */
|
||||
|
||||
#ifndef CONFIG_DEBUG
|
||||
# undef CONFIG_ADXL345_REGDEBUG
|
||||
#endif
|
||||
|
||||
/* I2C **************************************************************************************/
|
||||
/* ADXL345 Address: The ADXL345 may have 7-bit address 0x41 or 0x44, depending upon the
|
||||
* state of the ADDR0 pin.
|
||||
*/
|
||||
|
||||
#define ADXL345_I2C_ADDRESS_MASK (0x78) /* Bits 3-7: Invariant part of ADXL345 address */
|
||||
#define ADXL345_I2C_ADDRESS (0x40) /* Bits 3-7: Always set at '0100 0xxR' */
|
||||
#define ADXL345_I2C_A1 (1 << 2) /* Bit 2: A1 */
|
||||
#define ADXL345_I2C_A0 (1 << 1) /* Bit 1: A0 */
|
||||
#define ADXL345_I2C_READ (1 << 0) /* Bit 0=1: Selects read operation */
|
||||
#define ADXL345_I2C_WRITE (0) /* Bit 0=0: Selects write operation */
|
||||
|
||||
/* I2C frequency */
|
||||
|
||||
#define ADXL345_I2C_MAXFREQUENCY 400000 /* 400KHz */
|
||||
|
||||
/* SPI **************************************************************************************/
|
||||
/* The device always operates in mode 0 */
|
||||
|
||||
#define ADXL345_SPI_MODE SPIDEV_MODE0 /* Mode 0 */
|
||||
|
||||
/* SPI frequency */
|
||||
|
||||
#define ADXL345_SPI_MAXFREQUENCY 500000 /* 5MHz */
|
||||
|
||||
/* ADXL345 Registers ************************************************************************/
|
||||
/* Register Addresses */
|
||||
|
||||
#define ADXL345_DEVID 0x00 /* Device identification (8-bit) */
|
||||
/* 0x01 to 0x1C Reserved*/
|
||||
#define ADXL345_THRESH_TAP 0x1D /* Tap threshold */
|
||||
#define ADXL345_OFSX 0x1E /* X-axis offset */
|
||||
#define ADXL345_OFSY 0x1F /* Y-axis offset */
|
||||
#define ADXL345_OFSZ 0x20 /* Z-axis offset */
|
||||
#define ADXL345_DUR 0x21 /* Tap duration */
|
||||
#define ADXL345_LATENT 0x22 /* Tap latency */
|
||||
#define ADXL345_WINDOW 0x23 /* Tap window */
|
||||
#define ADXL345_THRESH_ACT 0x24 /* Activity threshold */
|
||||
#define ADXL345_THRESH_INACT 0x25 /* Inactivity threshold */
|
||||
#define ADXL345_TIME_INACT 0x26 /* Inactivity time */
|
||||
#define ADXL345_ATC_INACT_CTL 0x27 /* Axis enable control for activity and inactivity detection */
|
||||
#define ADXL345_THRESH_FF 0x28 /* Free-fall threshold */
|
||||
#define ADXL345_TIME_FF 0x29 /* Free-fall fime */
|
||||
#define ADXL345_TAP_AXES 0x2A /* Axis control for tap/double tap */
|
||||
#define ADXL345_ACT_TAP_STATUS 0x2B /* Source of tap/double tap */
|
||||
#define ADXL345_BW_RATE 0x2C /* Data rate and power mode control */
|
||||
#define ADXL345_POWER_CTL 0x2D /* Power-saving features control */
|
||||
#define ADXL345_INT_ENABLE 0x2E /* Interrupt enable control */
|
||||
#define ADXL345_INT_MAP 0x2F /* Interrupt mapping control */
|
||||
#define ADXL345_INT_SOURCE 0x30 /* Source of interrupts */
|
||||
#define ADXL345_DATA_FORMAT 0x31 /* Data format control */
|
||||
#define ADXL345_DATAX0 0x32 /* X-axis Data 0 */
|
||||
#define ADXL345_DATAX1 0x33 /* X-axis Data 1 */
|
||||
#define ADXL345_DATAY0 0x34 /* Y-axis Data 0 */
|
||||
#define ADXL345_DATAY1 0x35 /* Y-axis Data 1 */
|
||||
#define ADXL345_DATAZ0 0x36 /* Z-axis Data 0 */
|
||||
#define ADXL345_DATAZ1 0x37 /* Z-axis Data 1 */
|
||||
#define ADXL345_FIFO_CTL 0x38 /* FIFO Control */
|
||||
#define ADXL345_FIFO_STATUS 0x39 /* FIFO Status */
|
||||
|
||||
/* Register bit definitions */
|
||||
|
||||
/* Device identification (8-bit) */
|
||||
|
||||
#define DEVID 0xE5
|
||||
|
||||
/* Register 0x27 - ACT_INACT_CTL */
|
||||
|
||||
#define INACT_Z_ENABLE (1 << 0) /* Bit 0: Include/Exclude Z-axis in detecting inactivity */
|
||||
#define INACT_Y_ENABLE (1 << 1) /* Bit 1: Include/Exclude Y-axis in detecting inactivity */
|
||||
#define INACT_X_ENABLE (1 << 2) /* Bit 2: Include/Exclude X-axis in detecting inactivity */
|
||||
#define INACT_AC_DC (1 << 3) /* Bit 3: 0 = DC-coupled operation / 1 = AC-coupled operation */
|
||||
#define ACT_Z_ENABLE (1 << 4) /* Bit 4: Include/Exclude Z-axis in detecting activity */
|
||||
#define ACT_Y_ENABLE (1 << 5) /* Bit 5: Include/Exclude Z-axis in detecting activity */
|
||||
#define ACT_X_ENABLE (1 << 6) /* Bit 6: Include/Exclude Z-axis in detecting activity */
|
||||
#define ACT_AC_DC (1 << 7) /* Bit 7: 0 = DC-coupled operation / 1 = AC-coupled operation */
|
||||
|
||||
/* Register 0x2A - TAP AXES */
|
||||
|
||||
#define TAP_Z_ENABLE (1 << 0) /* Bit 0: Enable/disable Z-axis in tap detection */
|
||||
#define TAP_Y_ENABLE (1 << 1) /* Bit 1: Enable/disable Y-axis in tap detection */
|
||||
#define TAP_X_ENABLE (1 << 2) /* Bit 2: Enable/disable X-axis in tap detection */
|
||||
#define TAP_SUPRESS (1 << 3) /* Bit 3: Supress double tap detection */
|
||||
|
||||
/* Register 0x2B - ACT_TAP_STATUS */
|
||||
|
||||
#define TAP_Z_SOURCE (1 << 0) /* Bit 0: Indicates Z-axis is involved in a tap event */
|
||||
#define TAP_Y_SOURCE (1 << 1) /* Bit 1: Indicates Y-axis is involved in a tap event */
|
||||
#define TAP_X_SOURCE (1 << 2) /* Bit 2: Indicates X-axis is involved in a tap event */
|
||||
#define ASLEEP_STATUS (1 << 3) /* Bit 3: Indicates if device is asleep */
|
||||
#define ACT_Z_SOURCE (1 << 4) /* Bit 4: Indicates Z-axis is involved in an activity event */
|
||||
#define ACT_Y_SOURCE (1 << 5) /* Bit 5: Indicates Y-axis is involved in an activity event */
|
||||
#define ACT_X_SOURCE (1 << 6) /* Bit 6: Indicates X-axis is involved in an activity event */
|
||||
|
||||
/* Register 0x2C - BW_RATE */
|
||||
|
||||
#define BWR_RATE_SHIFT 0 /* Bit 0-3: Rate bits: up to 3200Hz output data rate */
|
||||
#define BWR_RATE_MASK (15 << RATE_SHIFT) /* Bit 0: Master interrupt enable */
|
||||
#define BWR_LOW_POWER (1 << 4) /* Bit 4: Set low power operation */
|
||||
|
||||
/* Register 0x2D - POWER_CTL */
|
||||
|
||||
#define POWER_CTL_WAKEUP_SHIFT 0 /* Bit 0-1: Controls frequency of reading in sleep mode*/
|
||||
#define POWER_CTL_WAKEUP_MASK (3 << POWER_CTL_WAKEUP_SHIFT)
|
||||
#define POWER_CTL_WAKEUP_8HZ (0 << POWER_CTL_WAKEUP_SHIFT)
|
||||
#define POWER_CTL_WAKEUP_4HZ (1 << POWER_CTL_WAKEUP_SHIFT)
|
||||
#define POWER_CTL_WAKEUP_2HZ (2 << POWER_CTL_WAKEUP_SHIFT)
|
||||
#define POWER_CTL_WAKEUP_1HZ (3 << POWER_CTL_WAKEUP_SHIFT)
|
||||
#define POWER_CTL_SLEEP (1 << 2) /* Bit 2: Sleep mode, only activity function can be used */
|
||||
#define POWER_CTL_MEASURE (1 << 3) /* Bit 3: Writing 0 put part in standy mode, 1 measurement mode */
|
||||
#define POWER_CTL_AUTO_SLEEP (1 << 4) /* Bit 4: If set and link bit is set then device sleep if no activity */
|
||||
#define POWER_CTL_LINK (1 << 5) /* Bit 5: Wait an inactivity before detecting an activity */
|
||||
|
||||
/* Register 0x2E - INT_ENABLE */
|
||||
|
||||
#define INT_OVERRUN (1 << 0) /* Bit 0: Enable Overrun detection */
|
||||
#define INT_WATERMARK (1 << 1) /* Bit 1: Enable Watermark detection */
|
||||
#define INT_FREE_FALL (1 << 2) /* Bit 2: Enable Free-fall detection */
|
||||
#define INT_INACTIVITY (1 << 3) /* Bit 3: Enable Inactivity detection*/
|
||||
#define INT_ACTIVITY (1 << 4) /* Bit 4: Enable Activity detection */
|
||||
#define INT_DOUBLE_TAP (1 << 5) /* Bit 5: Enable Double tap detection */
|
||||
#define INT_SINGLE_TAP (1 << 6) /* Bit 6: Enable Single tap detection */
|
||||
#define INT_DATA_READY (1 << 7) /* Bit 7: Enable Data Ready detection */
|
||||
|
||||
/* Register 0x2F - INT_MAP */
|
||||
|
||||
#define INT_MAP_OVERRUN (1 << 0) /* Bit 0: Map Overrun interrupt 0 = INT1 / 1 = INT2 */
|
||||
#define INT_MAP_WATERMARK (1 << 1) /* Bit 1: Map Watermark interrupt 0 = INT1 / 1 = INT2 */
|
||||
#define INT_MAP_FREE_FALL (1 << 2) /* Bit 2: Map Free-fall interrupt 0 = INT1 / 1 = INT2 */
|
||||
#define INT_MAP_INACTIVITY (1 << 3) /* Bit 3: Map Inactivity interrupt 0 = INT1 / 1 = INT2 */
|
||||
#define INT_MAP_ACTIVITY (1 << 4) /* Bit 4: Map Activity interrupt 0 = INT1 / 1 = INT2 */
|
||||
#define INT_MAP_DOUBLE_TAP (1 << 5) /* Bit 5: Map Double tap interrupt 0 = INT1 / 1 = INT2 */
|
||||
#define INT_MAP_SINGLE_TAP (1 << 6) /* Bit 6: Map Single tap interrupt 0 = INT1 / 1 = INT2 */
|
||||
#define INT_MAP_DATA_READY (1 << 7) /* Bit 7: Map Data Ready interrupt 0 = INT1 / 1 = INT2 */
|
||||
|
||||
/* Register 0x30 - INT_SOURCE */
|
||||
|
||||
#define INT_SRC_OVERRUN (1 << 0) /* Bit 0: Overrun happened, even if INT_ENABLE is disabled */
|
||||
#define INT_SRC_WATERMARK (1 << 1) /* Bit 1: Watermark happened, even if INT_ENABLE is disabled*/
|
||||
#define INT_SRC_FREE_FALL (1 << 2) /* Bit 2: Free-fall detected */
|
||||
#define INT_SRC_INACTIVITY (1 << 3) /* Bit 3: Inactivity detected */
|
||||
#define INT_SRC_ACTIVITY (1 << 4) /* Bit 4: Activity detected */
|
||||
#define INT_SRC_DOUBLE_TAP (1 << 5) /* Bit 5: Double tap detected */
|
||||
#define INT_SRC_SINGLE_TAP (1 << 6) /* Bit 6: Single tap detected */
|
||||
#define INT_SRC_DATA_READY (1 << 7) /* Bit 7: Data Ready happened, even if INT_ENABLE is disabled */
|
||||
|
||||
/* Register 0x31 - DATA_FORMAT */
|
||||
|
||||
#define DATA_FMT_RANGE_SHIFT 0 /* Bits 0-1: G-force Range */
|
||||
#define DATA_FMT_RANGE_MASK (3 << DATA_FMT_RANGE_SHIFT)
|
||||
#define DATA_FMT_RANGE_2G (0 << DATA_FMT_RANGE_SHIFT)
|
||||
#define DATA_FMT_RANGE_4G (1 << DATA_FMT_RANGE_SHIFT)
|
||||
#define DATA_FMT_RANGE_8G (2 << DATA_FMT_RANGE_SHIFT)
|
||||
#define DATA_FMT_RANGE_16G (3 << DATA_FMT_RANGE_SHIFT)
|
||||
#define DATA_FMT_JUSTIFY (1 << 2) /* Bit 2: Value 1 selects left justified mode, 0 selects right just. */
|
||||
#define DATA_FMT_FULL_RES (1 << 3) /* Bit 3: Value 0 sets 10-bit mode, value 1 sets 13-bit mode */
|
||||
#define DATA_FMT_INT_INVERT (1 << 5) /* Bit 5: Value 0 interrupt active high, 1 sets interrupt active low */
|
||||
#define DATA_FMT_SPI (1 << 6) /* Bit 6: Value 1 set 3-Wire SPI mode, 0 set 4-wire SPI mode */
|
||||
#define DATA_FMT_SELF_TEST (1 << 7) /* Bit 7: Apply a SELF_TEST force to the sensor */
|
||||
|
||||
/* Register 0x38 - FIFO_CTL */
|
||||
|
||||
#define FIFO_CTL_SAMPLES_SHIFT 0 /* Bit 0-4: Numbers of samples needed to trigger a watermask event */
|
||||
#define FIFO_CTL_SAMPLES_MASK (31 << FIFO_CTL_SAMPLES_SHIFT)
|
||||
#define FIFO_CTL_TRIGGER (1 << 5) /* Bit 5: Value 0 links trigger event to INT1, value 1 to INT2 */
|
||||
#define FIFO_CTL_MODE_SHIFT 6 /* Bit 6-7: FIFO Mode */
|
||||
#define FIFO_CTL_MODE_MASK (3 << FIFO_CTL_MODE_SHIFT)
|
||||
#define FIFO_CTL_MODE_BYPASS (0 << FIFO_CTL_MODE_SHIFT)
|
||||
#define FIFO_CTL_MODE_FIFO (1 << FIFO_CTL_MODE_SHIFT)
|
||||
#define FIFO_CTL_MODE_STREAM (2 << FIFO_CTL_MODE_SHIFT)
|
||||
#define FIFO_CTL_MODE_TRIGGER (3 << FIFO_CTL_MODE_SHIFT)
|
||||
|
||||
/* Register 0x39 - FIFO_STATUS */
|
||||
|
||||
#define FIFO_STATUS_ENTRIES_SHIFT 0 /* Bit 0-5: Reports how many samples are stored in the FIFO */
|
||||
#define FIFO_STATUS_ENTRIES_MASK (63 << FIFO_STATUS_ENTRIES_SHIFT)
|
||||
#define FIFO_STATUS_TRIG (1 << 7) /* Bit 7: A 1 reports a trigger event occurred, 0 means no event */
|
||||
|
||||
/********************************************************************************************
|
||||
* Public Types
|
||||
********************************************************************************************/
|
||||
|
||||
/* Form of the GPIO "interrupt handler" callback. Callbacks do not occur from an interrupt
|
||||
* handler but rather from the context of the worker thread with interrupts enabled.
|
||||
*/
|
||||
|
||||
typedef void (*adxl345_handler_t)(int pin);
|
||||
|
||||
/* A reference to a structure of this type must be passed to the ADXL345 driver when the
|
||||
* driver is instantiated. This structure provides information about the configuration of the
|
||||
* ADXL345 and provides some board-specific hooks.
|
||||
*
|
||||
* Memory for this structure is provided by the caller. It is not copied by the driver
|
||||
* and is presumed to persist while the driver is active. The memory must be writable
|
||||
* because, under certain circumstances, the driver may modify the frequency.
|
||||
*/
|
||||
|
||||
struct adxl345_config_s
|
||||
{
|
||||
/* Device characterization */
|
||||
|
||||
#ifdef CONFIG_ADXL345_I2C
|
||||
uint8_t address; /* 7-bit I2C address (only bits 0-6 used) */
|
||||
#endif
|
||||
uint32_t frequency; /* I2C or SPI frequency */
|
||||
|
||||
/* If multiple ADXL345 devices are supported, then an IRQ number must
|
||||
* be provided for each so that their interrupts can be distinguished.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_ADXL345_MULTIPLE
|
||||
int irq; /* IRQ number received by interrupt handler. */
|
||||
#endif
|
||||
|
||||
/* IRQ/GPIO access callbacks. These operations all hidden behind
|
||||
* callbacks to isolate the ADXL345 driver from differences in GPIO
|
||||
* interrupt handling by varying boards and MCUs.
|
||||
*
|
||||
* attach - Attach the ADXL345 interrupt handler to the GPIO interrupt
|
||||
* enable - Enable or disable the GPIO interrupt
|
||||
* clear - Acknowledge/clear any pending GPIO interrupt
|
||||
*/
|
||||
|
||||
int (*attach)(FAR struct adxl345_config_s *state, xcpt_t isr);
|
||||
void (*enable)(FAR struct adxl345_config_s *state, bool enable);
|
||||
void (*clear)(FAR struct adxl345_config_s *state);
|
||||
};
|
||||
|
||||
typedef FAR void *ADXL345_HANDLE;
|
||||
|
||||
/********************************************************************************************
|
||||
* Public Function Prototypes
|
||||
********************************************************************************************/
|
||||
|
||||
#ifdef __cplusplus
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/********************************************************************************************
|
||||
* Name: adxl345_instantiate
|
||||
*
|
||||
* Description:
|
||||
* Instantiate and configure the ADXL345 device driver to use the provided I2C or SPI
|
||||
* device instance.
|
||||
*
|
||||
* Input Parameters:
|
||||
* dev - An I2C or SPI driver instance
|
||||
* config - Persistant board configuration data
|
||||
*
|
||||
* Returned Value:
|
||||
* A non-zero handle is returned on success. This handle may then be used to configure
|
||||
* the ADXL345 driver as necessary. A NULL handle value is returned on failure.
|
||||
*
|
||||
********************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ADXL345_SPI
|
||||
EXTERN ADXL345_HANDLE adxl345_instantiate(FAR struct spi_dev_s *dev,
|
||||
FAR struct adxl345_config_s *config);
|
||||
#else
|
||||
EXTERN ADXL345_HANDLE adxl345_instantiate(FAR struct i2c_dev_s *dev,
|
||||
FAR struct adxl345_config_s *config);
|
||||
#endif
|
||||
|
||||
/********************************************************************************************
|
||||
* Name: adxl345_register
|
||||
*
|
||||
* Description:
|
||||
* This function will register the accelerometer driver as /dev/accelN
|
||||
* where N is the minor device number
|
||||
*
|
||||
* Input Parameters:
|
||||
* handle - The handle previously returned by adxl345_instantiate
|
||||
* minor - The input device minor number
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero is returned on success. Otherwise, a negated errno value is returned to indicate
|
||||
* the nature of the failure.
|
||||
*
|
||||
********************************************************************************************/
|
||||
|
||||
EXTERN int adxl345_register(ADXL345_HANDLE handle, int minor);
|
||||
|
||||
#undef EXTERN
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_SENSORS_ADXL345 */
|
||||
#endif /* __INCLUDE_NUTTX_INPUT_ADXL345_H */
|
@ -361,7 +361,8 @@ enum spi_dev_e
|
||||
SPIDEV_MUX, /* Select SPI multiplexer device */
|
||||
SPIDEV_AUDIO_DATA, /* Select SPI audio codec device data port */
|
||||
SPIDEV_AUDIO_CTRL, /* Select SPI audio codec device control port */
|
||||
SPIDEV_EEPROM /* Select SPI EEPROM device */
|
||||
SPIDEV_EEPROM, /* Select SPI EEPROM device */
|
||||
SPIDEV_GSENSOR /* Select SPI Accelerometer device */
|
||||
};
|
||||
|
||||
/* Certain SPI devices may required differnt clocking modes */
|
||||
|
Loading…
Reference in New Issue
Block a user