drivers/sensors: Add driver for ST LPS25H pressure sensor
This commit is contained in:
parent
916bd8a48f
commit
b5b148fef8
@ -33,11 +33,11 @@ config BMP180
|
||||
Enable driver support for the Bosch BMP180 barometer sensor.
|
||||
|
||||
config HTS221
|
||||
bool "ST HTS221 humidity sensor"
|
||||
bool "STMicro HTS221 humidity sensor"
|
||||
default n
|
||||
select I2C
|
||||
---help---
|
||||
Enable driver support for the ST HTS221 humidity sensor.
|
||||
Enable driver support for the STMicro HTS221 humidity sensor.
|
||||
|
||||
if HTS221
|
||||
|
||||
@ -56,11 +56,11 @@ config HTS221_NPOLLWAITERS
|
||||
endif # HTS221
|
||||
|
||||
config SENSORS_L3GD20
|
||||
bool "ST L3GD20 Gyroscope Sensor support"
|
||||
bool "STMicro L3GD20 Gyroscope Sensor support"
|
||||
default n
|
||||
select SPI
|
||||
---help---
|
||||
Enable driver support for the ST L3GD20 gyroscope sensor.
|
||||
Enable driver support for the STMicro L3GD20 gyroscope sensor.
|
||||
|
||||
config SENSOR_KXTJ9
|
||||
bool "Kionix KXTJ9 Accelerometer support"
|
||||
@ -83,7 +83,7 @@ config LIS3DSH
|
||||
Enable driver support for the STMicro LIS3DSH 3-Axis acclerometer.
|
||||
|
||||
config LIS331DL
|
||||
bool "ST LIS331DL device support"
|
||||
bool "STMicro LIS331DL device support"
|
||||
default n
|
||||
select I2C
|
||||
|
||||
@ -106,6 +106,23 @@ config LSM9DS1_I2C_FREQUENCY
|
||||
range 1 400000
|
||||
depends on SN_LSM9DS1
|
||||
|
||||
config LPS25H
|
||||
bool "STMicro LPS25H pressure sensor"
|
||||
default n
|
||||
select I2C
|
||||
---help---
|
||||
Enable driver support for the STMicro LPS25H barometer sensor.
|
||||
|
||||
if LPS25H
|
||||
|
||||
config DEBUG_LPS25H
|
||||
bool "Debug support for the LPS25H"
|
||||
default n
|
||||
---help---
|
||||
Enables debug features for the LPS25H
|
||||
|
||||
endif # LPS25H
|
||||
|
||||
config MB7040
|
||||
bool "MaxBotix MB7040 Sonar support"
|
||||
default n
|
||||
@ -209,7 +226,7 @@ endif # SENSORS_ADXL345
|
||||
config MAX31855
|
||||
bool "Maxim MAX31855 Driver"
|
||||
default n
|
||||
select SPI
|
||||
select SPI
|
||||
---help---
|
||||
Enables support for the MAX31855 driver
|
||||
|
||||
@ -229,7 +246,7 @@ config LIS3MDL
|
||||
default n
|
||||
select SPI
|
||||
---help---
|
||||
Enable driver support for the ST LIS3MDL 3-axis magnetometer.
|
||||
Enable driver support for the STMicro LIS3MDL 3-axis magnetometer.
|
||||
|
||||
config LM75
|
||||
bool "STMicro LM-75 Temperature Sensor support"
|
||||
|
@ -1,7 +1,7 @@
|
||||
############################################################################
|
||||
# drivers/sensors/Make.defs
|
||||
#
|
||||
# Copyright (C) 2011-2012, 2015-2016 Gregory Nutt. All rights reserved.
|
||||
# Copyright (C) 2011-2012, 2015-2017 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
@ -65,6 +65,10 @@ ifeq ($(CONFIG_SN_LSM9DS1),y)
|
||||
CSRCS += lsm9ds1.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_LPS25H),y)
|
||||
CSRCS += lps25h.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_ADXL345_I2C),y)
|
||||
CSRCS += adxl345_i2c.c
|
||||
endif
|
||||
|
@ -178,7 +178,7 @@ static const struct file_operations g_humidityops =
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
static int hts221_do_transfer(FAR struct hts221_dev_s *dev,
|
||||
static int hts221_do_transfer(FAR struct hts221_dev_s *priv,
|
||||
FAR struct i2c_msg_s *msgv,
|
||||
size_t nmsg)
|
||||
{
|
||||
@ -187,7 +187,7 @@ static int hts221_do_transfer(FAR struct hts221_dev_s *dev,
|
||||
|
||||
for (retries = 0; retries < HTS221_I2C_RETRIES; retries++)
|
||||
{
|
||||
ret = I2C_TRANSFER(dev->i2c, msgv, nmsg);
|
||||
ret = I2C_TRANSFER(priv->i2c, msgv, nmsg);
|
||||
if (ret >= 0)
|
||||
{
|
||||
return 0;
|
||||
@ -201,7 +201,7 @@ static int hts221_do_transfer(FAR struct hts221_dev_s *dev,
|
||||
break;
|
||||
}
|
||||
|
||||
ret = up_i2creset(dev->i2c);
|
||||
ret = up_i2creset(priv->i2c);
|
||||
if (ret < 0)
|
||||
{
|
||||
hts221_dbg("up_i2creset failed: %d\n", ret);
|
||||
@ -215,51 +215,51 @@ static int hts221_do_transfer(FAR struct hts221_dev_s *dev,
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int32_t hts221_write_reg8(FAR struct hts221_dev_s *dev,
|
||||
static int32_t hts221_write_reg8(FAR struct hts221_dev_s *priv,
|
||||
const uint8_t *command)
|
||||
{
|
||||
struct i2c_msg_s msgv[2] =
|
||||
{
|
||||
{
|
||||
.addr = dev->addr,
|
||||
.addr = priv->addr,
|
||||
.flags = 0,
|
||||
.buffer = (FAR void *)&command[0],
|
||||
.length = 1
|
||||
},
|
||||
{
|
||||
.addr = dev->addr,
|
||||
.addr = priv->addr,
|
||||
.flags = I2C_M_NORESTART,
|
||||
.buffer = (FAR void *)&command[1],
|
||||
.length = 1
|
||||
}
|
||||
};
|
||||
|
||||
return hts221_do_transfer(dev, msgv, 2);
|
||||
return hts221_do_transfer(priv, msgv, 2);
|
||||
}
|
||||
|
||||
static int hts221_read_reg(FAR struct hts221_dev_s *dev,
|
||||
static int hts221_read_reg(FAR struct hts221_dev_s *priv,
|
||||
FAR const uint8_t *command, FAR uint8_t *value)
|
||||
{
|
||||
struct i2c_msg_s msgv[2] =
|
||||
{
|
||||
{
|
||||
.addr = dev->addr,
|
||||
.addr = priv->addr,
|
||||
.flags = 0,
|
||||
.buffer = (FAR void *)command,
|
||||
.length = 1
|
||||
},
|
||||
{
|
||||
.addr = dev->addr,
|
||||
.addr = priv->addr,
|
||||
.flags = I2C_M_READ,
|
||||
.buffer = value,
|
||||
.length = 1
|
||||
}
|
||||
};
|
||||
|
||||
return hts221_do_transfer(dev, msgv, 2);
|
||||
return hts221_do_transfer(priv, msgv, 2);
|
||||
}
|
||||
|
||||
static int hts221_get_id(FAR struct hts221_dev_s *priv, uint8_t * value)
|
||||
static int hts221_get_id(FAR struct hts221_dev_s *priv, uint8_t *value)
|
||||
{
|
||||
int ret = OK;
|
||||
uint8_t cmd = HTS221_WHO_AM_I;
|
||||
@ -360,7 +360,7 @@ static int hts221_config_ctrl_reg2(FAR struct hts221_dev_s *priv,
|
||||
}
|
||||
|
||||
static int hts221_config_ctrl_reg1(FAR struct hts221_dev_s *priv,
|
||||
FAR hts221_settings_t * settings)
|
||||
FAR hts221_settings_t *settings)
|
||||
{
|
||||
int ret = OK;
|
||||
uint8_t regval = 0;
|
||||
@ -418,7 +418,7 @@ static int hts221_power_on_off(FAR struct hts221_dev_s *priv, bool on)
|
||||
}
|
||||
|
||||
static int hts221_config(FAR struct hts221_dev_s *priv,
|
||||
FAR hts221_settings_t * cfgr)
|
||||
FAR hts221_settings_t *cfgr)
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
@ -475,7 +475,7 @@ static int hts221_start_conversion(FAR struct hts221_dev_s *priv)
|
||||
}
|
||||
|
||||
static int hts221_check_status(FAR struct hts221_dev_s *priv,
|
||||
FAR hts221_status_t * status)
|
||||
FAR hts221_status_t *status)
|
||||
{
|
||||
int ret = OK;
|
||||
uint8_t addr = HTS221_STATUS_REG;
|
||||
@ -496,7 +496,7 @@ static int hts221_check_status(FAR struct hts221_dev_s *priv,
|
||||
}
|
||||
|
||||
static int hts221_read_raw_data(FAR struct hts221_dev_s *priv,
|
||||
FAR hts221_raw_data_t * data)
|
||||
FAR hts221_raw_data_t *data)
|
||||
{
|
||||
int ret = OK;
|
||||
uint8_t addr_humid_low = HTS221_HUM_OUT_L;
|
||||
|
793
drivers/sensors/lps25h.c
Normal file
793
drivers/sensors/lps25h.c
Normal file
@ -0,0 +1,793 @@
|
||||
/****************************************************************************
|
||||
* drivers/sensors/lps25h.c
|
||||
*
|
||||
* Copyright (C) 2014-2017 Haltian Ltd. All rights reserved.
|
||||
*
|
||||
* 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 <nuttx/arch.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
#include <sys/types.h>
|
||||
#include <debug.h>
|
||||
#include <stdio.h>
|
||||
#include <errno.h>
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/random.h>
|
||||
|
||||
#include <nuttx/sensors/lps25h.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_DEBUG_LPS25H
|
||||
# define lps25h_dbg(x, ...) _info(x, ##__VA_ARGS__)
|
||||
#else
|
||||
# define lps25h_dbg(x, ...) sninfo(x, ##__VA_ARGS__)
|
||||
#endif
|
||||
|
||||
#define LPS25H_PRESSURE_INTERNAL_DIVIDER 4096
|
||||
|
||||
/* 'AN4450 - Hardware and software guidelines for use of LPS25H pressure
|
||||
* sensors' - '6.2 One-shot mode conversion time estimation' gives estimates
|
||||
* for conversion times:
|
||||
*
|
||||
* Typical conversion time ≈ 62*(Pavg+Tavg) + 975 μs
|
||||
* ex: Tavg = 64; Pavg = 512; Typ. conversation time ≈ 36.7 ms (compatible with
|
||||
* ODT=25 Hz)
|
||||
* ex: Tavg = 32; Pavg = 128; Typ. conversation time ≈ 10.9 ms
|
||||
* The formula is accurate within +/- 3% at room temperature
|
||||
*
|
||||
* Set timeout to 2 * max.conversation time (2*36.7*1.03 = 76 ms).
|
||||
*/
|
||||
|
||||
#define LPS25H_RETRY_TIMEOUT_MSECS 76
|
||||
#define LPS25H_MAX_RETRIES 5
|
||||
|
||||
#define LPS25H_I2C_RETRIES 10
|
||||
|
||||
/* Registers */
|
||||
|
||||
#define LPS25H_REF_P_XL 0x08
|
||||
#define LPS25H_REF_P_L 0x09
|
||||
#define LPS25H_REF_P_H 0x0a
|
||||
#define LPS25H_WHO_AM_I 0x0f
|
||||
#define LPS25H_RES_CONF 0x10
|
||||
#define LPS25H_CTRL_REG1 0x20
|
||||
#define LPS25H_CTRL_REG2 0x21
|
||||
#define LPS25H_CTRL_REG3 0x22
|
||||
#define LPS25H_CTRL_REG4 0x23
|
||||
#define LPS25H_INT_CFG 0x24
|
||||
#define LPS25H_INT_SOURCE 0x25
|
||||
#define LPS25H_STATUS_REG 0x27
|
||||
#define LPS25H_PRESS_POUT_XL 0x28
|
||||
#define LPS25H_PRESS_OUT_L 0x29
|
||||
#define LPS25H_PRESS_OUT_H 0x2a
|
||||
#define LPS25H_TEMP_OUT_L 0x2b
|
||||
#define LPS25H_TEMP_OUT_H 0x2c
|
||||
#define LPS25H_FIFO_CTRL 0x2e
|
||||
#define LPS25H_FIFO_STATUS 0x2f
|
||||
#define LPS25H_THS_P_L 0x30
|
||||
#define LPS25H_THS_P_H 0x31
|
||||
#define LPS25H_RPDS_L 0x39
|
||||
#define LPS25H_RPDS_H 0x3a
|
||||
|
||||
/* Bits in registers */
|
||||
|
||||
#define LPS25H_AUTO_ZERO (1 << 2)
|
||||
#define LPS25H_BDU (1 << 2)
|
||||
#define LPS25H_DIFF_EN (1 << 3)
|
||||
#define LPS25H_FIFO_EN (1 << 6)
|
||||
#define LPS25H_WTM_EN (1 << 5)
|
||||
#define LPS25H_FIFO_MEAN_DEC (1 << 4)
|
||||
#define LPS25H_PD (1 << 7)
|
||||
#define LPS25H_ONE_SHOT (1 << 0)
|
||||
#define LPS25H_INT_H_L (1 << 7)
|
||||
#define LPS25H_PP_OD (1 << 6)
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
struct lps25h_dev_s
|
||||
{
|
||||
struct i2c_master_s *i2c;
|
||||
uint8_t addr;
|
||||
bool irqenabled;
|
||||
volatile bool int_pending;
|
||||
sem_t devsem;
|
||||
sem_t waitsem;
|
||||
lps25h_config_t *config;
|
||||
};
|
||||
|
||||
enum LPS25H_RES_CONF_AVG_PRES
|
||||
{
|
||||
PRES_AVG_8 = 0,
|
||||
PRES_AVG_32,
|
||||
PRES_AVG_128,
|
||||
PRES_AVG_512
|
||||
};
|
||||
|
||||
enum LPS25H_RES_CONF_AVG_TEMP
|
||||
{
|
||||
TEMP_AVG_8 = 0,
|
||||
TEMP_AVG_16,
|
||||
TEMP_AVG_32,
|
||||
TEMP_AVG_64
|
||||
};
|
||||
|
||||
enum LPS25H_CTRL_REG1_ODR
|
||||
{
|
||||
CTRL_REG1_ODR_ONE_SHOT = 0,
|
||||
CTRL_REG1_ODR_1Hz,
|
||||
CTRL_REG1_ODR_7Hz,
|
||||
CTRL_REG1_ODR_12_5Hz,
|
||||
CTRL_REG1_ODR_25Hz
|
||||
};
|
||||
|
||||
enum LPS25H_CTRL_REG4_P1
|
||||
{
|
||||
P1_DRDY = 0x1,
|
||||
P1_OVERRUN = 0x02,
|
||||
P1_WTM = 0x04,
|
||||
P1_EMPTY = 0x08
|
||||
};
|
||||
|
||||
enum LPS25H_FIFO_CTRL_MODE
|
||||
{
|
||||
BYPASS_MODE = 0x0,
|
||||
FIFO_STOP_WHEN_FULL,
|
||||
STREAM_NEWEST_IN_FIFO,
|
||||
STREAM_DEASSERTED,
|
||||
BYPASS_DEASSERTED_STREAM,
|
||||
FIFO_MEAN = 0x06,
|
||||
BYPASS_DEASSERTED_FIFO
|
||||
};
|
||||
|
||||
enum LPS25H_FIFO_CTRL_WTM
|
||||
{
|
||||
SAMPLE_2 = 0x01,
|
||||
SAMPLE_4 = 0x03,
|
||||
SAMPLE_8 = 0x07,
|
||||
SAMPLE_16 = 0x0f,
|
||||
SAMPLE_32 = 0x1f
|
||||
};
|
||||
|
||||
enum LPS25H_INT_CFG_OP
|
||||
{
|
||||
PH_E = 0x1,
|
||||
PL_E = 0x2,
|
||||
LIR = 0x4
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
* Private Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
static int lps25h_open(FAR struct file *filep);
|
||||
static int lps25h_close(FAR struct file *filep);
|
||||
static ssize_t lps25h_read(FAR struct file *filep, FAR char *buffer,
|
||||
size_t buflen);
|
||||
static ssize_t lps25h_write(FAR struct file *filep, FAR const char *buffer,
|
||||
size_t buflen);
|
||||
static int lps25h_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
|
||||
|
||||
static int lps25h_configure_dev(FAR struct lps25h_dev_s *dev);
|
||||
static int lps25h_read_pressure(FAR struct lps25h_dev_s *dev,
|
||||
FAR lps25h_pressure_data_t *pres);
|
||||
static int lps25h_read_temper(FAR struct lps25h_dev_s *dev,
|
||||
FAR lps25h_temper_data_t *temper);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
static const struct file_operations g_lps25hops =
|
||||
{
|
||||
lps25h_open, /* open */
|
||||
lps25h_close, /* close */
|
||||
lps25h_read, /* read */
|
||||
lps25h_write, /* write */
|
||||
0, /* seek */
|
||||
lps25h_ioctl /* ioctl */
|
||||
#ifndef CONFIG_DISABLE_POLL
|
||||
, NULL /* poll */
|
||||
#endif
|
||||
#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS
|
||||
, NULL /* unlink */
|
||||
#endif
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
static int lps25h_do_transfer(FAR struct lps25h_dev_s *dev,
|
||||
FAR struct i2c_msg_s *msgv,
|
||||
size_t nmsg)
|
||||
{
|
||||
int ret = -EIO;
|
||||
int retries;
|
||||
|
||||
for (retries = 0; retries < LPS25H_I2C_RETRIES; retries++)
|
||||
{
|
||||
ret = I2C_TRANSFER(dev->i2c, msgv, nmsg);
|
||||
if (ret >= 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Some error. Try to reset I2C bus and keep trying. */
|
||||
#ifdef CONFIG_I2C_RESET
|
||||
if (retries == LPS25H_I2C_RETRIES - 1)
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
ret = up_i2creset(dev->i2c);
|
||||
if (ret < 0)
|
||||
{
|
||||
lps25h_dbg("up_i2creset failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
lps25h_dbg("xfer failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int lps25h_write_reg8(struct lps25h_dev_s *dev, uint8_t reg_addr,
|
||||
const uint8_t value)
|
||||
{
|
||||
struct i2c_msg_s msgv[2] =
|
||||
{
|
||||
{
|
||||
.addr = dev->addr,
|
||||
.flags = 0,
|
||||
.buffer = ®_addr,
|
||||
.length = 1
|
||||
},
|
||||
{
|
||||
.addr = dev->addr,
|
||||
.flags = I2C_M_NORESTART,
|
||||
.buffer = (void *)&value,
|
||||
.length = 1
|
||||
}
|
||||
};
|
||||
|
||||
return lps25h_do_transfer(dev, msgv, 2);
|
||||
}
|
||||
|
||||
static int lps25h_read_reg8(FAR struct lps25h_dev_s *dev,
|
||||
FAR uint8_t *reg_addr,
|
||||
FAR uint8_t *value)
|
||||
{
|
||||
struct i2c_msg_s msgv[2] =
|
||||
{
|
||||
{
|
||||
.addr = dev->addr,
|
||||
.flags = 0,
|
||||
.buffer = reg_addr,
|
||||
.length = 1
|
||||
},
|
||||
{
|
||||
.addr = dev->addr,
|
||||
.flags = I2C_M_READ,
|
||||
.buffer = value,
|
||||
.length = 1
|
||||
}
|
||||
};
|
||||
|
||||
return lps25h_do_transfer(dev, msgv, 2);
|
||||
}
|
||||
|
||||
static int lps25h_power_on_off(FAR struct lps25h_dev_s *dev, bool on)
|
||||
{
|
||||
int ret;
|
||||
uint8_t value;
|
||||
|
||||
value = on ? LPS25H_PD : 0;
|
||||
ret = lps25h_write_reg8(dev, LPS25H_CTRL_REG1, value);
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int lps25h_open(FAR struct file *filep)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct lps25h_dev_s *dev = inode->i_private;
|
||||
uint8_t value = 0;
|
||||
uint8_t addr = LPS25H_WHO_AM_I;
|
||||
int32_t ret;
|
||||
|
||||
while (sem_wait(&dev->devsem) != 0)
|
||||
{
|
||||
assert(errno == EINTR);
|
||||
}
|
||||
|
||||
dev->config->set_power(dev->config, true);
|
||||
ret = lps25h_read_reg8(dev, &addr, &value);
|
||||
if (ret < 0)
|
||||
{
|
||||
lps25h_dbg("Cannot read device's ID\n");
|
||||
dev->config->set_power(dev->config, false);
|
||||
goto out;
|
||||
}
|
||||
|
||||
lps25h_dbg("WHO_AM_I: 0x%2x\n", value);
|
||||
|
||||
dev->config->irq_enable(dev->config, true);
|
||||
dev->irqenabled = true;
|
||||
|
||||
out:
|
||||
sem_post(&dev->devsem);
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int lps25h_close(FAR struct file *filep)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct lps25h_dev_s *dev = inode->i_private;
|
||||
int ret;
|
||||
|
||||
while (sem_wait(&dev->devsem) != 0)
|
||||
{
|
||||
assert(errno == EINTR);
|
||||
}
|
||||
|
||||
dev->config->irq_enable(dev->config, false);
|
||||
dev->irqenabled = false;
|
||||
ret = lps25h_power_on_off(dev, false);
|
||||
dev->config->set_power(dev->config, false);
|
||||
lps25h_dbg("CLOSED\n");
|
||||
|
||||
sem_post(&dev->devsem);
|
||||
return ret;
|
||||
}
|
||||
|
||||
static ssize_t lps25h_read(FAR struct file *filep, FAR char *buffer,
|
||||
size_t buflen)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct lps25h_dev_s *dev = inode->i_private;
|
||||
int ret;
|
||||
ssize_t length = 0;
|
||||
lps25h_pressure_data_t data;
|
||||
|
||||
while (sem_wait(&dev->devsem) != 0)
|
||||
{
|
||||
assert(errno == EINTR);
|
||||
}
|
||||
|
||||
ret = lps25h_configure_dev(dev);
|
||||
if (ret < 0)
|
||||
{
|
||||
lps25h_dbg("cannot configure sensor: %d\n", ret);
|
||||
goto out;
|
||||
}
|
||||
|
||||
ret = lps25h_read_pressure(dev, &data);
|
||||
if (ret < 0)
|
||||
{
|
||||
lps25h_dbg("cannot read data: %d\n", ret);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* This interface is mainly intended for easy debugging in nsh. */
|
||||
|
||||
length = snprintf(buffer, buflen, "%u\n", data.pressure_Pa);
|
||||
if (length > buflen)
|
||||
{
|
||||
length = buflen;
|
||||
}
|
||||
}
|
||||
|
||||
out:
|
||||
sem_post(&dev->devsem);
|
||||
return length;
|
||||
}
|
||||
|
||||
static ssize_t lps25h_write(FAR struct file *filep, FAR const char *buffer,
|
||||
size_t buflen)
|
||||
{
|
||||
ssize_t length = 0;
|
||||
|
||||
return length;
|
||||
}
|
||||
|
||||
static void lps25h_notify(FAR struct lps25h_dev_s *dev)
|
||||
{
|
||||
DEBUGASSERT(dev != NULL);
|
||||
|
||||
dev->int_pending = true;
|
||||
sem_post(&dev->waitsem);
|
||||
}
|
||||
|
||||
static int lps25h_int_handler(int irq, FAR void *context, FAR void *arg)
|
||||
{
|
||||
FAR struct lps25h_dev_s *dev = (FAR struct lps25h_dev_s *)arg;
|
||||
|
||||
DEBUGASSERT(dev != NULL);
|
||||
|
||||
lps25h_notify(dev);
|
||||
lps25h_dbg("lps25h interrupt\n");
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int lps25h_configure_dev(FAR struct lps25h_dev_s *dev)
|
||||
{
|
||||
int ret = 0;
|
||||
|
||||
ret = lps25h_power_on_off(dev, false);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Enable FIFO */
|
||||
|
||||
ret = lps25h_write_reg8(dev, LPS25H_CTRL_REG2, LPS25H_FIFO_EN);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
ret = lps25h_write_reg8(dev, LPS25H_FIFO_CTRL, (BYPASS_MODE << 5));
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
ret = lps25h_write_reg8(dev, LPS25H_CTRL_REG4, P1_DRDY);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Write CTRL_REG1 to turn device on */
|
||||
|
||||
ret = lps25h_write_reg8(dev, LPS25H_CTRL_REG1,
|
||||
LPS25H_PD | (CTRL_REG1_ODR_1Hz << 4));
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int lps25h_one_shot(FAR struct lps25h_dev_s *dev)
|
||||
{
|
||||
int ret = ERROR;
|
||||
int retries;
|
||||
struct timespec abstime;
|
||||
irqstate_t flags;
|
||||
|
||||
if (!dev->irqenabled)
|
||||
{
|
||||
lps25h_dbg("IRQ disabled!\n");
|
||||
}
|
||||
|
||||
/* Retry one-shot measurement multiple times. */
|
||||
|
||||
for (retries = 0; retries < LPS25H_MAX_RETRIES; retries++)
|
||||
{
|
||||
/* Power off so we start from a known state. */
|
||||
|
||||
ret = lps25h_power_on_off(dev, false);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Initiate a one shot mode measurement */
|
||||
|
||||
ret = lps25h_write_reg8(dev, LPS25H_CTRL_REG2, LPS25H_ONE_SHOT);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Power on to start measurement. */
|
||||
|
||||
ret = lps25h_power_on_off(dev, true);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
(void)clock_gettime(CLOCK_REALTIME, &abstime);
|
||||
abstime.tv_sec += (LPS25H_RETRY_TIMEOUT_MSECS / 1000);
|
||||
abstime.tv_nsec += (LPS25H_RETRY_TIMEOUT_MSECS % 1000) * 1000 * 1000;
|
||||
while (abstime.tv_nsec >= (1000 * 1000 * 1000))
|
||||
{
|
||||
abstime.tv_sec++;
|
||||
abstime.tv_nsec -= 1000 * 1000 * 1000;
|
||||
}
|
||||
|
||||
while ((ret = sem_timedwait(&dev->waitsem, &abstime)) != 0)
|
||||
{
|
||||
int err = errno;
|
||||
if (err == EINTR)
|
||||
{
|
||||
continue;
|
||||
}
|
||||
else if (err == ETIMEDOUT)
|
||||
{
|
||||
uint8_t reg = LPS25H_CTRL_REG2;
|
||||
uint8_t value;
|
||||
|
||||
/* In 'AN4450 - Hardware and software guidelines for use of
|
||||
* LPS25H pressure sensors' - '4.3 One-shot mode measurement
|
||||
* sequence', one-shot mode example is given where interrupt line
|
||||
* is not used, but CTRL_REG2 is polled until ONE_SHOT bit is
|
||||
* unset (as it is self-clearing). Check ONE_SHOT bit status here
|
||||
* to see if we just missed interrupt.
|
||||
*/
|
||||
|
||||
ret = lps25h_read_reg8(dev, ®, &value);
|
||||
if (ret < 0)
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
if ((value & LPS25H_ONE_SHOT) == 0)
|
||||
{
|
||||
/* One-shot completed. */
|
||||
|
||||
ret = OK;
|
||||
break;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Some unknown mystery error */
|
||||
|
||||
DEBUGASSERT(false);
|
||||
return -err;
|
||||
}
|
||||
}
|
||||
|
||||
if (ret == OK)
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
lps25h_dbg("Retrying one-shot measurement: retries=%d\n", retries);
|
||||
}
|
||||
|
||||
if (ret != OK)
|
||||
{
|
||||
return -ETIMEDOUT;
|
||||
}
|
||||
|
||||
flags = enter_critical_section();
|
||||
dev->int_pending = false;
|
||||
leave_critical_section(flags);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int lps25h_read_pressure(FAR struct lps25h_dev_s *dev,
|
||||
FAR lps25h_pressure_data_t *pres)
|
||||
{
|
||||
int ret;
|
||||
uint8_t pres_addr_h = LPS25H_PRESS_OUT_H;
|
||||
uint8_t pres_addr_l = LPS25H_PRESS_OUT_L;
|
||||
uint8_t pres_addr_xl = LPS25H_PRESS_POUT_XL;
|
||||
uint8_t pres_value_h = 0;
|
||||
uint8_t pres_value_l = 0;
|
||||
uint8_t pres_value_xl = 0;
|
||||
int32_t pres_res = 0;
|
||||
|
||||
ret = lps25h_one_shot(dev);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
ret = lps25h_read_reg8(dev, &pres_addr_h, &pres_value_h);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
ret = lps25h_read_reg8(dev, &pres_addr_l, &pres_value_l);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
ret = lps25h_read_reg8(dev, &pres_addr_xl, &pres_value_xl);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
pres_res = ((int32_t) pres_value_h << 16) |
|
||||
((int16_t) pres_value_l << 8) |
|
||||
pres_value_xl;
|
||||
|
||||
/* Add to entropy pool. */
|
||||
|
||||
add_sensor_randomness(pres_res);
|
||||
|
||||
/* Convert to more usable format. */
|
||||
|
||||
pres->pressure_int_hP = pres_res / LPS25H_PRESSURE_INTERNAL_DIVIDER;
|
||||
pres->pressure_Pa = (uint64_t)pres_res * 100000 / LPS25H_PRESSURE_INTERNAL_DIVIDER;
|
||||
pres->raw_data = pres_res;
|
||||
lps25h_dbg("Pressure: %u Pa\n", pres->pressure_Pa);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int lps25h_read_temper(FAR struct lps25h_dev_s *dev,
|
||||
FAR lps25h_temper_data_t *temper)
|
||||
{
|
||||
int ret;
|
||||
uint8_t temper_addr_h = LPS25H_TEMP_OUT_H;
|
||||
uint8_t temper_addr_l = LPS25H_TEMP_OUT_L;
|
||||
uint8_t temper_value_h = 0;
|
||||
uint8_t temper_value_l = 0;
|
||||
int32_t temper_res;
|
||||
int16_t raw_data;
|
||||
|
||||
ret = lps25h_read_reg8(dev, &temper_addr_h, &temper_value_h);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
ret = lps25h_read_reg8(dev, &temper_addr_l, &temper_value_l);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
raw_data = (temper_value_h << 8) | temper_value_l;
|
||||
|
||||
/* Add to entropy pool. */
|
||||
|
||||
add_sensor_randomness(raw_data);
|
||||
|
||||
/* T(⁰C) = 42.5 + (raw / 480)
|
||||
* =>
|
||||
* T(⁰C) * scale = (425 * 48 + raw) * scale / 480;
|
||||
*/
|
||||
|
||||
temper_res = (425 * 48 + raw_data);
|
||||
temper_res *= LPS25H_TEMPER_DIVIDER;
|
||||
temper_res /= 480;
|
||||
|
||||
temper->int_temper = temper_res;
|
||||
temper->raw_data = raw_data;
|
||||
lps25h_dbg("Temperature: %d\n", temper_res);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int lps25h_who_am_i(struct lps25h_dev_s *dev,
|
||||
lps25h_who_am_i_data * who_am_i_data)
|
||||
{
|
||||
uint8_t who_addr = LPS25H_WHO_AM_I;
|
||||
return lps25h_read_reg8(dev, &who_addr, &who_am_i_data->who_am_i);
|
||||
}
|
||||
|
||||
static int lps25h_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct lps25h_dev_s *dev = inode->i_private;
|
||||
int ret = 0;
|
||||
|
||||
while (sem_wait(&dev->devsem) != 0)
|
||||
{
|
||||
assert(errno == EINTR);
|
||||
}
|
||||
|
||||
switch (cmd)
|
||||
{
|
||||
case SNIOC_CFGR:
|
||||
ret = lps25h_configure_dev(dev);
|
||||
break;
|
||||
|
||||
case SNIOC_PRESSURE_OUT:
|
||||
ret = lps25h_read_pressure(dev, (lps25h_pressure_data_t *) arg);
|
||||
break;
|
||||
|
||||
case SNIOC_TEMPERATURE_OUT:
|
||||
/* NOTE: call SNIOC_PRESSURE_OUT before this one,
|
||||
* or results are bogus.
|
||||
*/
|
||||
|
||||
ret = lps25h_read_temper(dev, (lps25h_temper_data_t *) arg);
|
||||
break;
|
||||
|
||||
case SNIOC_SENSOR_OFF:
|
||||
ret = lps25h_power_on_off(dev, false);
|
||||
break;
|
||||
|
||||
case SNIOC_GET_DEV_ID:
|
||||
ret = lps25h_who_am_i(dev, (lps25h_who_am_i_data *) arg);
|
||||
break;
|
||||
|
||||
default:
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
}
|
||||
|
||||
sem_post(&dev->devsem);
|
||||
return ret;
|
||||
}
|
||||
|
||||
int lps25h_register(FAR const char *devpath, FAR struct i2c_master_s *i2c,
|
||||
uint8_t addr, FAR lps25h_config_t *config)
|
||||
{
|
||||
int ret = 0;
|
||||
FAR struct lps25h_dev_s *dev;
|
||||
|
||||
dev = (struct lps25h_dev_s *)kmm_zalloc(sizeof(struct lps25h_dev_s));
|
||||
if (!dev)
|
||||
{
|
||||
lps25h_dbg("Memory cannot be allocated for LPS25H sensor\n");
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
sem_init(&dev->devsem, 0, 1);
|
||||
sem_init(&dev->waitsem, 0, 0);
|
||||
|
||||
dev->addr = addr;
|
||||
dev->i2c = i2c;
|
||||
dev->config = config;
|
||||
|
||||
if (dev->config->irq_clear)
|
||||
{
|
||||
dev->config->irq_clear(dev->config);
|
||||
}
|
||||
|
||||
ret = register_driver(devpath, &g_lps25hops, 0666, dev);
|
||||
|
||||
lps25h_dbg("Registered with %d\n", ret);
|
||||
|
||||
if (ret < 0)
|
||||
{
|
||||
kmm_free(dev);
|
||||
lps25h_dbg("Error occurred during the driver registering\n");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
dev->config->irq_attach(config, lps25h_int_handler, dev);
|
||||
dev->config->irq_enable(config, false);
|
||||
dev->irqenabled = false;
|
||||
return OK;
|
||||
}
|
@ -125,4 +125,12 @@
|
||||
#define SNIOC_READ_CONVERT_DATA _SNIOC(0x002f)
|
||||
#define SNIOC_DUMP_REGS _SNIOC(0x0030)
|
||||
|
||||
/* IOCTL commands unique to the LPS25H */
|
||||
|
||||
#define SNIOC_GET_DEV_ID _SNIOC(0x0031)
|
||||
#define SNIOC_CFGR _SNIOC(0x0032)
|
||||
#define SNIOC_TEMPERATURE_OUT _SNIOC(0x0033)
|
||||
#define SNIOC_PRESSURE_OUT _SNIOC(0x0034)
|
||||
#define SNIOC_SENSOR_OFF _SNIOC(0x0035)
|
||||
|
||||
#endif /* __INCLUDE_NUTTX_SENSORS_IOCTL_H */
|
||||
|
105
include/nuttx/sensors/lps25h.h
Normal file
105
include/nuttx/sensors/lps25h.h
Normal file
@ -0,0 +1,105 @@
|
||||
/****************************************************************************
|
||||
* include/nuttx/sensors/lps25h.h
|
||||
*
|
||||
* Copyright (C) 2014, 2017 Haltian Ltd. All rights reserved.
|
||||
*
|
||||
* 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_NUTT_SENSORS_LPS25H_H
|
||||
#define __INCLUDE_NUTT_SENSORS_LPS25H_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/sensors/ioctl.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#define LPS25H_TEMPER_DIVIDER 1000
|
||||
|
||||
#define LPS25H_VALID_WHO_AM_I 0xbd
|
||||
|
||||
/****************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************/
|
||||
|
||||
typedef struct lps25h_temper_data_s
|
||||
{
|
||||
int32_t int_temper; /* int_temper value must be divided by
|
||||
* LPS25H_TEMPER_DIVIDER in your app code */
|
||||
int16_t raw_data;
|
||||
} lps25h_temper_data_t;
|
||||
|
||||
typedef struct lps25h_pressure_data_s
|
||||
{
|
||||
uint32_t pressure_int_hP;
|
||||
uint32_t pressure_Pa;
|
||||
uint32_t raw_data;
|
||||
} lps25h_pressure_data_t;
|
||||
|
||||
typedef struct lps25h_who_am_i_data
|
||||
{
|
||||
uint8_t who_am_i;
|
||||
} lps25h_who_am_i_data;
|
||||
|
||||
typedef struct lps25h_config_s
|
||||
{
|
||||
/* Device characterization */
|
||||
|
||||
int irq; /* IRQ number received by interrupt handler. */
|
||||
|
||||
/* IRQ/GPIO access callbacks. These operations all hidden behind callbacks
|
||||
* to isolate the driver from differences in GPIO interrupt handling
|
||||
* by varying boards and MCUs.
|
||||
* irq_attach - Attach the interrupt handler to the GPIO interrupt
|
||||
* irq_enable - Enable or disable the GPIO
|
||||
* irq_clear - Acknowledge/clear any pending GPIO interrupt
|
||||
* set_power - Ask board to turn on regulator
|
||||
*/
|
||||
|
||||
CODE int (*irq_attach)(FAR struct lps25h_config_s *state, xcpt_t isr,
|
||||
FAR void *arg);
|
||||
CODE void (*irq_enable)(FAR const struct lps25h_config_s *state,
|
||||
bool enable);
|
||||
CODE void (*irq_clear)(FAR const struct lps25h_config_s *state);
|
||||
CODE int (*set_power)(FAR const struct lps25h_config_s *state, bool on);
|
||||
} lps25h_config_t;
|
||||
|
||||
/****************************************************************************
|
||||
* Public Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
int lps25h_register(FAR const char *devpath, FAR struct i2c_master_s *i2c,
|
||||
uint8_t addr, FAR lps25h_config_t *config);
|
||||
|
||||
#endif /* __INCLUDE_NUTT_SENSORS_LPS25H_H */
|
Loading…
Reference in New Issue
Block a user