Merged in alinjerpelea/nuttx (pull request #944)
drivers: sensors: add I2C Bosch BMP280 and I2C Asahi AK09911/AK09912 Compass Sensor
* drivers: sensors: add Bosch BMP280 Barometic Pressure Sensor
add driver for the Bosch BMP280 barometic pressure sensor
This sensor is connected over I2C bus
Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>
* drivers: sensors: add Asahi AK09911/AK09912 Compass Sensor
add driver for AK09911/AK09912 Compass sensor over I2C bus
Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>
Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
parent
fb720cb817
commit
ffb4f00da9
6 changed files with 1760 additions and 0 deletions
|
|
@ -15,6 +15,13 @@ config APDS9960_I2C_FREQUENCY
|
|||
default 400000
|
||||
depends on SENSORS_APDS9960
|
||||
|
||||
config SENSORS_AK09912
|
||||
bool "Asahi AK09911/AK09912 Compass Sensor"
|
||||
default n
|
||||
select I2C
|
||||
---help---
|
||||
Enable driver for AK09911/AK09912 Compass sensor.
|
||||
|
||||
config SENSORS_AS5048B
|
||||
bool "AMS AS5048B Magnetic Rotary Encoder support"
|
||||
default n
|
||||
|
|
@ -86,6 +93,13 @@ config SENSORS_BMP180
|
|||
---help---
|
||||
Enable driver support for the Bosch BMP180 barometer sensor.
|
||||
|
||||
config SENSORS_BMP280
|
||||
bool "Bosch BMP280 Barometic Pressure Sensor"
|
||||
default n
|
||||
select I2C
|
||||
---help---
|
||||
Enable driver for the Bosch BMP280 barometic pressure sensor.
|
||||
|
||||
config SENSORS_DHTXX
|
||||
bool "DHTxx humidity/temperature Sensor support"
|
||||
default n
|
||||
|
|
|
|||
|
|
@ -57,6 +57,10 @@ ifeq ($(CONFIG_SENSORS_APDS9960),y)
|
|||
CSRCS += apds9960.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_SENSORS_AK09912),y)
|
||||
CSRCS += ak09912.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_SENSORS_AS5048B),y)
|
||||
CSRCS += as5048b.c
|
||||
endif
|
||||
|
|
@ -113,6 +117,11 @@ ifeq ($(CONFIG_SENSORS_BMP180),y)
|
|||
CSRCS += bmp180.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_SENSORS_BMP280),y)
|
||||
CSRCS += bmp280.c
|
||||
endif
|
||||
|
||||
|
||||
ifeq ($(CONFIG_SENSORS_HTS221),y)
|
||||
CSRCS += hts221.c
|
||||
endif
|
||||
|
|
|
|||
727
drivers/sensors/ak09912.c
Normal file
727
drivers/sensors/ak09912.c
Normal file
|
|
@ -0,0 +1,727 @@
|
|||
/****************************************************************************
|
||||
* drivers/sensors/ak09912.c
|
||||
*
|
||||
* Copyright 2018 Sony Semiconductor Solutions Corporation
|
||||
*
|
||||
* 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 of Sony Semiconductor Solutions Corporation 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 <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <fixedmath.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
#include <semaphore.h>
|
||||
#include <arch/types.h>
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
#include <nuttx/sensors/ak09912.h>
|
||||
#include <nuttx/wdog.h>
|
||||
#include <nuttx/irq.h>
|
||||
|
||||
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_AK09912)
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#define AK09911_DEVID 0x05
|
||||
#define AK09912_DEVID 0x04
|
||||
#define AK09912_ADDR 0x0C
|
||||
#define AK09912_FREQ 400000
|
||||
|
||||
/* REGISTER: WIA
|
||||
* Who I am.
|
||||
*/
|
||||
|
||||
#define AK09912_WIA1 0x00
|
||||
#define AK09912_WIA2 0x01
|
||||
|
||||
/* REGISTER: CNTL2
|
||||
* Power mode
|
||||
*/
|
||||
|
||||
#define POWER_MODE_ADDR 0x31
|
||||
|
||||
/* REGISTER: ASAX
|
||||
* Sensitivity values
|
||||
*/
|
||||
|
||||
#define AK09912_ASAX 0x60
|
||||
|
||||
/* REGISTER: CNTL1
|
||||
* Enable or disable temparator measure or enable or disable Noice suppression
|
||||
* filter.
|
||||
*/
|
||||
|
||||
#define AK09912_CTRL1 0x30
|
||||
|
||||
/* REGISTER: HXL
|
||||
* The start address of data registers.
|
||||
*/
|
||||
|
||||
#define AK09912_HXL 0x11
|
||||
|
||||
/* Polling timeout
|
||||
* The unit is 10 millisecond.
|
||||
*/
|
||||
|
||||
#define AK09912_POLLING_TIMEOUT (1) // 10 ms
|
||||
|
||||
/* The parameter for compensating. */
|
||||
|
||||
#define AK09912_SENSITIVITY (128)
|
||||
#define AK09912_SENSITIVITY_DIV (256)
|
||||
|
||||
/* Noice Suppression Filter */
|
||||
|
||||
#define AK09912_NSF_NONE 0b00
|
||||
#define AK09912_NSF_LOW 0b01
|
||||
#define AK09912_NSF_MIDDLE 0b10
|
||||
#define AK09912_NSF_HIGH 0b11
|
||||
|
||||
/* Power mode */
|
||||
|
||||
#define AKM_POWER_DOWN_MODE 0b0000
|
||||
#define AKM_SINGL_MEAS_MODE 0b00001
|
||||
#define AKM_CONT_MEAS_1 0b00010
|
||||
#define AKM_CONT_MEAS_2 0b00100
|
||||
#define AKM_CONT_MEAS_3 0b00110
|
||||
#define AKM_CONT_MEAS_4 0b01000
|
||||
#define AKM_EXT_TRIG_MODE 0b01010
|
||||
#define AKM_SELF_TEST_MODE 0b10000
|
||||
#define AKM_FUSE_ROM_MODE 0b11111
|
||||
|
||||
/* REGISTER: ST1
|
||||
* DRDY: Data ready bit. 0: not ready, 1: ready
|
||||
* DOR: Data overrun. 0: Not overrun, 1: overrun
|
||||
*/
|
||||
|
||||
#define AK09912_ST1 0x10
|
||||
|
||||
#define SET_BITSLICE(s, v, offset, mask) \
|
||||
do { \
|
||||
s &= mask; \
|
||||
s |= (v << offset) & mask;} while(0)
|
||||
|
||||
#define MERGE_BYTE(low, high) \
|
||||
((low & 0xff) | ((high << 8) & ~0xff))
|
||||
|
||||
/****************************************************************************
|
||||
* Private Type Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Structure for compensating data. */
|
||||
|
||||
struct sensi_data_s
|
||||
{
|
||||
uint8_t x;
|
||||
uint8_t y;
|
||||
uint8_t z;
|
||||
};
|
||||
|
||||
/* Structure for ak09912 device */
|
||||
|
||||
struct ak09912_dev_s
|
||||
{
|
||||
FAR struct i2c_master_s *i2c; /* I2C interface */
|
||||
uint8_t addr; /* I2C address */
|
||||
int freq; /* Frequency <= 3.4MHz */
|
||||
int compensated; /* 0: uncompensated, 1:compensated */
|
||||
struct sensi_data_s asa_data; /* sensitivity data */
|
||||
uint8_t mode; /* power mode */
|
||||
uint8_t nsf; /* noice suppression filter setting */
|
||||
WDOG_ID wd;
|
||||
sem_t wait;
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/* Character driver methods */
|
||||
|
||||
static int ak09912_open(FAR struct file *filep);
|
||||
static int ak09912_close(FAR struct file *filep);
|
||||
static ssize_t ak09912_read(FAR struct file *filep, FAR char *buffer,
|
||||
size_t buflen);
|
||||
static ssize_t ak09912_write(FAR struct file *filep, FAR const char *buffer,
|
||||
size_t buflen);
|
||||
static int ak09912_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
static const struct file_operations g_ak09912fops =
|
||||
{
|
||||
ak09912_open, /* open */
|
||||
ak09912_close, /* close */
|
||||
ak09912_read, /* read */
|
||||
ak09912_write, /* write */
|
||||
0, /* seek */
|
||||
ak09912_ioctl, /* ioctl */
|
||||
#ifndef CONFIG_DISABLE_POLL
|
||||
0, /* poll */
|
||||
#endif
|
||||
0 /* unlink */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_getreg8
|
||||
*
|
||||
* Description:
|
||||
* Read from an 8-bit BMP280 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static uint8_t ak09912_getreg8(FAR struct ak09912_dev_s *priv,
|
||||
uint8_t regaddr)
|
||||
{
|
||||
struct i2c_msg_s msg[2];
|
||||
uint8_t regval = 0;
|
||||
int ret;
|
||||
|
||||
msg[0].frequency = priv->freq;
|
||||
msg[0].addr = priv->addr;
|
||||
msg[0].flags = 0;
|
||||
msg[0].buffer = ®addr;
|
||||
msg[0].length = 1;
|
||||
|
||||
msg[1].frequency = priv->freq;
|
||||
msg[1].addr = priv->addr;
|
||||
msg[1].flags = I2C_M_READ;
|
||||
msg[1].buffer = ®val;
|
||||
msg[1].length = 1;
|
||||
|
||||
ret = I2C_TRANSFER(priv->i2c, msg, 2);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("I2C_TRANSFER failed: %d\n", ret);
|
||||
return 0;
|
||||
}
|
||||
|
||||
return regval;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_putreg8
|
||||
*
|
||||
* Description:
|
||||
* Write to an 8-bit BMP280 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int ak09912_putreg8(FAR struct ak09912_dev_s *priv,
|
||||
uint8_t regaddr, uint8_t regval)
|
||||
{
|
||||
struct i2c_msg_s msg[2];
|
||||
int ret;
|
||||
uint8_t txbuffer[2];
|
||||
|
||||
txbuffer[0] = regaddr;
|
||||
txbuffer[1] = regval;
|
||||
|
||||
msg[0].frequency = priv->freq;
|
||||
msg[0].addr = priv->addr;
|
||||
msg[0].flags = 0;
|
||||
msg[0].buffer = txbuffer;
|
||||
msg[0].length = 2;
|
||||
|
||||
ret = I2C_TRANSFER(priv->i2c, msg, 1);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("I2C_TRANSFER failed: %d\n", ret);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_getreg
|
||||
*
|
||||
* Description:
|
||||
* Read cnt bytes from a ak09912 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int32_t ak09912_getreg(FAR struct ak09912_dev_s *priv,
|
||||
uint8_t regaddr, uint8_t* buffer, uint32_t cnt)
|
||||
{
|
||||
struct i2c_msg_s msg[2];
|
||||
int ret;
|
||||
|
||||
msg[0].frequency = priv->freq;
|
||||
msg[0].addr = priv->addr;
|
||||
msg[0].flags = 0;
|
||||
msg[0].buffer = ®addr;
|
||||
msg[0].length = 1;
|
||||
|
||||
msg[1].frequency = priv->freq;
|
||||
msg[1].addr = priv->addr;
|
||||
msg[1].flags = I2C_M_READ;
|
||||
msg[1].buffer = buffer;
|
||||
msg[1].length = cnt;
|
||||
|
||||
ret = I2C_TRANSFER(priv->i2c, msg, 2);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("I2C_TRANSFER failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_delay_msec
|
||||
*
|
||||
* Description:
|
||||
* System level delay
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void ak09912_delay_msek(uint16_t msek)
|
||||
{
|
||||
/* This is used to short delay without schedule. */
|
||||
|
||||
up_udelay(msek * 1000);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_set_power_mode
|
||||
*
|
||||
* Description:
|
||||
* set POWER MODE for ak09912
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int ak09912_set_power_mode(FAR struct ak09912_dev_s* priv,
|
||||
uint32_t mode)
|
||||
{
|
||||
int ret = 0;
|
||||
ret = ak09912_putreg8(priv, POWER_MODE_ADDR, (uint8_t)mode);
|
||||
ak09912_delay_msek(1);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_read_sensitivity_data
|
||||
*
|
||||
* Description:
|
||||
* read sensitivity date in fuse mode.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int ak09912_read_sensitivity_data(FAR struct ak09912_dev_s* priv,
|
||||
FAR struct sensi_data_s* asa_data)
|
||||
{
|
||||
int ret = 0;
|
||||
uint8_t buffer[3];
|
||||
|
||||
ret = ak09912_getreg(priv, AK09912_ASAX, buffer, sizeof(buffer));
|
||||
if (ret == 0)
|
||||
{
|
||||
asa_data->x = buffer[0];
|
||||
asa_data->y = buffer[1];
|
||||
asa_data->z = buffer[2];
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_set_noice_suppr_flt
|
||||
*
|
||||
* Description:
|
||||
* set noice suppression filter for ak09912
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int ak09912_set_noice_suppr_flt(FAR struct ak09912_dev_s* priv,
|
||||
uint32_t nsf)
|
||||
{
|
||||
int ret = 0;
|
||||
uint8_t ctrl1 = 0;
|
||||
|
||||
ctrl1 = ak09912_getreg8(priv, AK09912_CTRL1);
|
||||
SET_BITSLICE(ctrl1, nsf, 5, 0x60);
|
||||
ret = ak09912_putreg8(priv, AK09912_CTRL1, ctrl1);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_wd_timeout
|
||||
*
|
||||
* Description:
|
||||
* a timer to check if data is ready.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void ak09912_wd_timeout(int argc, uint32_t arg, ...)
|
||||
{
|
||||
struct ak09912_dev_s *priv = (struct ak09912_dev_s *) arg;
|
||||
irqstate_t flags = enter_critical_section();
|
||||
sem_post(&priv->wait);
|
||||
leave_critical_section(flags);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_read_mag_uncomp_data
|
||||
*
|
||||
* Description:
|
||||
* read mag uncompensating data.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int ak09912_read_mag_uncomp_data(FAR struct ak09912_dev_s* priv,
|
||||
FAR struct mag_data_s* mag_data)
|
||||
{
|
||||
int ret = 0;
|
||||
uint8_t state = 0;
|
||||
uint8_t buffer[8]; /* TMPS and ST2 is read, but the value is omitted. */
|
||||
|
||||
wd_start(priv->wd, AK09912_POLLING_TIMEOUT, ak09912_wd_timeout,
|
||||
1, (uint32_t)priv);
|
||||
state = ak09912_getreg8(priv, AK09912_ST1);
|
||||
while (! (state & 0x1))
|
||||
{
|
||||
sem_wait(&priv->wait);
|
||||
}
|
||||
wd_cancel(priv->wd);
|
||||
ret = ak09912_getreg(priv, AK09912_HXL, buffer, sizeof(buffer));
|
||||
|
||||
mag_data->x = MERGE_BYTE(buffer[0], buffer[1]);
|
||||
mag_data->y = MERGE_BYTE(buffer[2], buffer[3]);
|
||||
mag_data->z = MERGE_BYTE(buffer[4], buffer[5]);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_read_mag_data
|
||||
*
|
||||
* Description:
|
||||
* read mag data with compensation
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int ak09912_read_mag_data(FAR struct ak09912_dev_s* priv,
|
||||
FAR struct mag_data_s* mag_data)
|
||||
{
|
||||
int ret = 0;
|
||||
|
||||
ret = ak09912_read_mag_uncomp_data(priv, mag_data);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("Failed to read mag data from device.\n");
|
||||
return ret;
|
||||
}
|
||||
|
||||
mag_data->x = (int16_t)(mag_data->x *
|
||||
((int32_t)priv->asa_data.x + AK09912_SENSITIVITY) /
|
||||
AK09912_SENSITIVITY_DIV);
|
||||
mag_data->y = (int16_t)(mag_data->y *
|
||||
((int32_t)priv->asa_data.y + AK09912_SENSITIVITY) /
|
||||
AK09912_SENSITIVITY_DIV);
|
||||
mag_data->z = (int16_t)(mag_data->z *
|
||||
((int32_t)priv->asa_data.z + AK09912_SENSITIVITY) /
|
||||
AK09912_SENSITIVITY_DIV);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_checkid
|
||||
*
|
||||
* Description:
|
||||
* Read and verify the AK09912 chip ID
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int ak09912_checkid(FAR struct ak09912_dev_s *priv)
|
||||
{
|
||||
uint16_t devid = 0;
|
||||
|
||||
/* Read device ID */
|
||||
|
||||
devid = ak09912_getreg8(priv, AK09912_WIA1);
|
||||
devid += ak09912_getreg8(priv, AK09912_WIA2) << 8;
|
||||
sninfo("devid: 0x%02x\n", devid);
|
||||
|
||||
if (devid != AK09911_DEVID && devid != AK09912_DEVID)
|
||||
{
|
||||
/* ID is not Correct */
|
||||
|
||||
snerr("Wrong Device ID! %02x\n", devid);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_updatecaldata
|
||||
*
|
||||
* Description:
|
||||
* Update Calibration Coefficient Data
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int ak09912_initialize(FAR struct ak09912_dev_s *priv)
|
||||
{
|
||||
int ret = 0;
|
||||
|
||||
ret += ak09912_set_power_mode(priv, AKM_FUSE_ROM_MODE);
|
||||
ret += ak09912_read_sensitivity_data(priv, &priv->asa_data);
|
||||
ret += ak09912_set_power_mode(priv, AKM_POWER_DOWN_MODE);
|
||||
ret += ak09912_set_noice_suppr_flt(priv, priv->nsf);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_open
|
||||
*
|
||||
* Description:
|
||||
* This function is called whenever the AK09912 device is opened.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int ak09912_open(FAR struct file *filep)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct ak09912_dev_s *priv = inode->i_private;
|
||||
int ret = 0;
|
||||
|
||||
ret = ak09912_set_power_mode(priv, priv->mode);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("Failed to set power mode to %d.\n", priv->mode);
|
||||
return ret;
|
||||
}
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_close
|
||||
*
|
||||
* Description:
|
||||
* This routine is called when the AK09912 device is closed.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int ak09912_close(FAR struct file *filep)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct ak09912_dev_s *priv = inode->i_private;
|
||||
int ret = 0;
|
||||
|
||||
ret = ak09912_set_power_mode(priv, AKM_POWER_DOWN_MODE);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("Failed to set power mode to %d.\n", AKM_POWER_DOWN_MODE);
|
||||
return ret;
|
||||
}
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_read
|
||||
****************************************************************************/
|
||||
|
||||
static ssize_t ak09912_read(FAR struct file *filep, FAR char *buffer,
|
||||
size_t buflen)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct ak09912_dev_s *priv = inode->i_private;
|
||||
int32_t ret = 0;
|
||||
struct mag_data_s* mag_data = (struct mag_data_s*)buffer;
|
||||
|
||||
if (! buffer)
|
||||
{
|
||||
snerr("Buffer is null\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (buflen != sizeof(struct mag_data_s))
|
||||
{
|
||||
snerr("You can't read something other than 32 bits (4 bytes)\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (priv->compensated)
|
||||
{
|
||||
irqstate_t flags = enter_critical_section();
|
||||
ret = ak09912_read_mag_data(priv, mag_data);
|
||||
leave_critical_section(flags);
|
||||
}
|
||||
else
|
||||
{
|
||||
irqstate_t flags = enter_critical_section();
|
||||
ret = ak09912_read_mag_uncomp_data(priv, mag_data);
|
||||
leave_critical_section(flags);
|
||||
}
|
||||
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("Failed to read data from ak09912.\n");
|
||||
return ret;
|
||||
}
|
||||
|
||||
return sizeof(struct mag_data_s);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_write
|
||||
****************************************************************************/
|
||||
|
||||
static ssize_t ak09912_write(FAR struct file *filep, FAR const char *buffer,
|
||||
size_t buflen)
|
||||
{
|
||||
return -ENOSYS;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_write
|
||||
****************************************************************************/
|
||||
|
||||
static int ak09912_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct ak09912_dev_s *priv = inode->i_private;
|
||||
int ret = OK;
|
||||
|
||||
switch (cmd)
|
||||
{
|
||||
case SNIOC_ENABLE_COMPENSATED:
|
||||
priv->compensated = (int)arg;
|
||||
break;
|
||||
default:
|
||||
snerr("Unrecognized cmd: %d\n", cmd);
|
||||
ret = - ENOTTY;
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_register
|
||||
*
|
||||
* Description:
|
||||
* Register the AK09912 character device as 'devpath'
|
||||
*
|
||||
* Input Parameters:
|
||||
* devpath - The full path to the driver to register. E.g., "/dev/compass0"
|
||||
* i2c - An instance of the I2C interface to use to communicate with
|
||||
* AK09912
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno value on failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int ak09912_register(FAR const char *devpath, FAR struct i2c_master_s *i2c)
|
||||
{
|
||||
FAR struct ak09912_dev_s *priv;
|
||||
char path[16];
|
||||
int ret;
|
||||
|
||||
/* Initialize the AK09912 device structure */
|
||||
|
||||
priv = (FAR struct ak09912_dev_s *)kmm_malloc(sizeof(struct ak09912_dev_s));
|
||||
if (!priv)
|
||||
{
|
||||
snerr("Failed to allocate instance\n");
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
priv->i2c = i2c;
|
||||
priv->addr = AK09912_ADDR;
|
||||
priv->freq = AK09912_FREQ;
|
||||
priv->compensated = ENABLE_COMPENSATED;
|
||||
priv->wd = wd_create();
|
||||
sem_init(&priv->wait, 0, 0);
|
||||
|
||||
/* set default noice suppression filter. */
|
||||
|
||||
priv->nsf = AK09912_NSF_LOW;
|
||||
|
||||
/* set default power mode */
|
||||
|
||||
priv->mode = AKM_CONT_MEAS_4;
|
||||
|
||||
/* Check Device ID */
|
||||
|
||||
ret = ak09912_checkid(priv);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("Failed to register driver: %d\n", ret);
|
||||
kmm_free(priv);
|
||||
return ret;
|
||||
}
|
||||
|
||||
ret = ak09912_initialize(priv);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("Failed to initialize physical device ak09912:%d\n", ret);
|
||||
kmm_free(priv);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Register the character driver */
|
||||
|
||||
(void) snprintf(path, sizeof(path), "%s%d", devpath, 0);
|
||||
ret = register_driver(path, &g_ak09912fops, 0666, priv);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("Failed to register driver: %d\n", ret);
|
||||
kmm_free(priv);
|
||||
}
|
||||
|
||||
sninfo("AK09912 driver loaded successfully!\n");
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_I2C && CONFIG_SENSORS_AK09912 */
|
||||
723
drivers/sensors/bmp280.c
Normal file
723
drivers/sensors/bmp280.c
Normal file
|
|
@ -0,0 +1,723 @@
|
|||
/****************************************************************************
|
||||
* drivers/sensors/bmp280.c
|
||||
*
|
||||
* Copyright 2018 Sony Semiconductor Solutions Corporation
|
||||
*
|
||||
* 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 of Sony Semiconductor Solutions Corporation nor
|
||||
* the names of its contributors may be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <fixedmath.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
#include <nuttx/sensors/bmp280.h>
|
||||
|
||||
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BMP280)
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#define BMP280_ADDR 0x76
|
||||
#define BMP280_FREQ 400000
|
||||
#define DEVID 0x58
|
||||
|
||||
#define BMP280_DIG_T1_LSB 0x88
|
||||
#define BMP280_DIG_T1_MSB 0x89
|
||||
#define BMP280_DIG_T2_LSB 0x8a
|
||||
#define BMP280_DIG_T2_MSB 0x8b
|
||||
#define BMP280_DIG_T3_LSB 0x8c
|
||||
#define BMP280_DIG_T3_MSB 0x8d
|
||||
#define BMP280_DIG_P1_LSB 0x8e
|
||||
#define BMP280_DIG_P1_MSB 0x8f
|
||||
#define BMP280_DIG_P2_LSB 0x90
|
||||
#define BMP280_DIG_P2_MSB 0x91
|
||||
#define BMP280_DIG_P3_LSB 0x92
|
||||
#define BMP280_DIG_P3_MSB 0x93
|
||||
#define BMP280_DIG_P4_LSB 0x94
|
||||
#define BMP280_DIG_P4_MSB 0x95
|
||||
#define BMP280_DIG_P5_LSB 0x96
|
||||
#define BMP280_DIG_P5_MSB 0x97
|
||||
#define BMP280_DIG_P6_LSB 0x98
|
||||
#define BMP280_DIG_P6_MSB 0x99
|
||||
#define BMP280_DIG_P7_LSB 0x9a
|
||||
#define BMP280_DIG_P7_MSB 0x9b
|
||||
#define BMP280_DIG_P8_LSB 0x9c
|
||||
#define BMP280_DIG_P8_MSB 0x9d
|
||||
#define BMP280_DIG_P9_LSB 0x9e
|
||||
#define BMP280_DIG_P9_MSB 0x9f
|
||||
|
||||
#define BMP280_DEVID 0xd0
|
||||
#define BMP280_SOFT_RESET 0xe0
|
||||
#define BMP280_STAT 0xf3
|
||||
#define BMP280_CTRL_MEAS 0xf4
|
||||
#define BMP280_CONFIG 0xf5
|
||||
#define BMP280_PRESS_MSB 0xf7
|
||||
#define BMP280_PRESS_LSB 0xf8
|
||||
#define BMP280_PRESS_XLSB 0xf9
|
||||
#define BMP280_TEMP_MSB 0xfa
|
||||
#define BMP280_TEMP_LSB 0xfb
|
||||
#define BMP280_TEMP_XLSB 0xfc
|
||||
|
||||
/* Power modes */
|
||||
|
||||
#define BMP280_SLEEP_MODE (0x00)
|
||||
#define BMP280_FORCED_MODE (0x01)
|
||||
#define BMP280_NORMAL_MODE (0x03)
|
||||
|
||||
/* Oversampling for temperature. */
|
||||
|
||||
#define BMP280_OST_SKIPPED (0x00 << 5)
|
||||
#define BMP280_OST_X1 (0x01 << 5)
|
||||
#define BMP280_OST_X2 (0x02 << 5)
|
||||
#define BMP280_OST_X4 (0x03 << 5)
|
||||
#define BMP280_OST_X8 (0x04 << 5)
|
||||
#define BMP280_OST_X16 (0x05 << 5)
|
||||
|
||||
/* Oversampling for pressure. */
|
||||
|
||||
#define BMP280_OSP_SKIPPED (0x00 << 2)
|
||||
#define BMP280_OSP_X1 (0x01 << 2)
|
||||
#define BMP280_OSP_X2 (0x02 << 2)
|
||||
#define BMP280_OSP_X4 (0x03 << 2)
|
||||
#define BMP280_OSP_X8 (0x04 << 2)
|
||||
#define BMP280_OSP_X16 (0x05 << 2)
|
||||
|
||||
/* Predefined oversampling combinations. */
|
||||
|
||||
#define BMP280_OS_ULTRA_HIGH_RES (BMP280_OSP_X16 | BMP280_OST_X2)
|
||||
#define BMP280_OS_STANDARD_RES (BMP280_OSP_X4 | BMP280_OST_X1)
|
||||
#define BMP280_OS_ULTRA_LOW_POWER (BMP280_OSP_X1 | BMP280_OST_X1)
|
||||
|
||||
/* Data combined from bytes to int */
|
||||
|
||||
#define COMBINE(d) (((int)(d)[0] << 12) | ((int)(d)[1] << 4) | ((int)(d)[2] >> 4))
|
||||
|
||||
/****************************************************************************
|
||||
* Private Type Definitions
|
||||
****************************************************************************/
|
||||
|
||||
struct bmp280_dev_s
|
||||
{
|
||||
FAR struct i2c_master_s *i2c; /* I2C interface */
|
||||
uint8_t addr; /* BMP280 I2C address */
|
||||
int freq; /* BMP280 Frequency <= 3.4MHz */
|
||||
int compensated; /* 0: uncompensated, 1:compensated */
|
||||
struct bmp280_calib_s
|
||||
{
|
||||
uint16_t t1;
|
||||
int16_t t2;
|
||||
int16_t t3;
|
||||
uint16_t p1;
|
||||
int16_t p2;
|
||||
int16_t p3;
|
||||
int16_t p4;
|
||||
int16_t p5;
|
||||
int16_t p6;
|
||||
int16_t p7;
|
||||
int16_t p8;
|
||||
int16_t p9;
|
||||
} calib;
|
||||
|
||||
int32_t tempfine;
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
static uint8_t bmp280_getreg8(FAR struct bmp280_dev_s *priv, uint8_t regaddr);
|
||||
static void bmp280_putreg8(FAR struct bmp280_dev_s *priv, uint8_t regaddr,
|
||||
uint8_t regval);
|
||||
static uint32_t bmp280_getpressure(FAR struct bmp280_dev_s *priv);
|
||||
|
||||
/* Character driver methods */
|
||||
|
||||
static int bmp280_open(FAR struct file *filep);
|
||||
static int bmp280_close(FAR struct file *filep);
|
||||
static ssize_t bmp280_read(FAR struct file *filep, FAR char *buffer,
|
||||
size_t buflen);
|
||||
static int bmp280_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
static const struct file_operations g_bmp280fops =
|
||||
{
|
||||
bmp280_open, /* open */
|
||||
bmp280_close, /* close */
|
||||
bmp280_read, /* read */
|
||||
0, /* write */
|
||||
0, /* seek */
|
||||
bmp280_ioctl, /* ioctl */
|
||||
#ifndef CONFIG_DISABLE_POLL
|
||||
0, /* poll */
|
||||
#endif
|
||||
0 /* unlink */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_getreg8
|
||||
*
|
||||
* Description:
|
||||
* Read from an 8-bit BMP280 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static uint8_t bmp280_getreg8(FAR struct bmp280_dev_s *priv, uint8_t regaddr)
|
||||
{
|
||||
struct i2c_msg_s msg[2];
|
||||
uint8_t regval = 0;
|
||||
int ret;
|
||||
|
||||
msg[0].frequency = priv->freq;
|
||||
msg[0].addr = priv->addr;
|
||||
msg[0].flags = 0;
|
||||
msg[0].buffer = ®addr;
|
||||
msg[0].length = 1;
|
||||
|
||||
msg[1].frequency = priv->freq;
|
||||
msg[1].addr = priv->addr;
|
||||
msg[1].flags = I2C_M_READ;
|
||||
msg[1].buffer = ®val;
|
||||
msg[1].length = 1;
|
||||
|
||||
ret = I2C_TRANSFER(priv->i2c, msg, 2);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("I2C_TRANSFER failed: %d\n", ret);
|
||||
return 0;
|
||||
}
|
||||
|
||||
return regval;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_getregs
|
||||
*
|
||||
* Description:
|
||||
* Read two 8-bit from a BMP280 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int bmp280_getregs(FAR struct bmp280_dev_s *priv, uint8_t regaddr,
|
||||
uint8_t *rxbuffer, uint8_t length)
|
||||
{
|
||||
struct i2c_msg_s msg[2];
|
||||
int ret;
|
||||
|
||||
msg[0].frequency = priv->freq;
|
||||
msg[0].addr = priv->addr;
|
||||
msg[0].flags = 0;
|
||||
msg[0].buffer = ®addr;
|
||||
msg[0].length = 1;
|
||||
|
||||
msg[1].frequency = priv->freq;
|
||||
msg[1].addr = priv->addr;
|
||||
msg[1].flags = I2C_M_READ;
|
||||
msg[1].buffer = rxbuffer;
|
||||
msg[1].length = length;
|
||||
|
||||
ret = I2C_TRANSFER(priv->i2c, msg, 2);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("I2C_TRANSFER failed: %d\n", ret);
|
||||
return -1;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_putreg8
|
||||
*
|
||||
* Description:
|
||||
* Write to an 8-bit BMP280 register
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void bmp280_putreg8(FAR struct bmp280_dev_s *priv, uint8_t regaddr,
|
||||
uint8_t regval)
|
||||
{
|
||||
struct i2c_msg_s msg[2];
|
||||
uint8_t txbuffer[2];
|
||||
int ret;
|
||||
|
||||
txbuffer[0] = regaddr;
|
||||
txbuffer[1] = regval;
|
||||
|
||||
msg[0].frequency = priv->freq;
|
||||
msg[0].addr = priv->addr;
|
||||
msg[0].flags = 0;
|
||||
msg[0].buffer = txbuffer;
|
||||
msg[0].length = 2;
|
||||
|
||||
ret = I2C_TRANSFER(priv->i2c, msg, 1);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("I2C_TRANSFER failed: %d\n", ret);
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_checkid
|
||||
*
|
||||
* Description:
|
||||
* Read and verify the BMP280 chip ID
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int bmp280_checkid(FAR struct bmp280_dev_s *priv)
|
||||
{
|
||||
uint8_t devid = 0;
|
||||
|
||||
/* Read device ID */
|
||||
|
||||
devid = bmp280_getreg8(priv, BMP280_DEVID);
|
||||
up_mdelay(1);
|
||||
sninfo("devid: 0x%02x\n", devid);
|
||||
|
||||
if (devid != (uint16_t) DEVID)
|
||||
{
|
||||
/* ID is not Correct */
|
||||
|
||||
snerr("Wrong Device ID! %02x\n", devid);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_set_standby
|
||||
*
|
||||
* Description:
|
||||
* set standby duration
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int bmp280_set_standby(FAR struct bmp280_dev_s *priv, uint8_t value)
|
||||
{
|
||||
uint8_t v_data_u8;
|
||||
uint8_t v_sb_u8;
|
||||
|
||||
/* Set the standby duration value */
|
||||
|
||||
v_data_u8 = bmp280_getreg8(priv, BMP280_CONFIG);
|
||||
v_data_u8 = (v_data_u8 & ~(0x07 << 5)) | (value << 5);
|
||||
bmp280_putreg8(priv, BMP280_CONFIG, v_data_u8);
|
||||
|
||||
/* Check the standby duration value */
|
||||
|
||||
v_data_u8 = bmp280_getreg8(priv, BMP280_CONFIG);
|
||||
v_sb_u8 = (v_data_u8 >> 5) & 0x07;
|
||||
|
||||
if (v_sb_u8 != value)
|
||||
{
|
||||
snerr("Failed to set value for standby time.");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_initialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize BMP280 device
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int bmp280_initialize(FAR struct bmp280_dev_s *priv)
|
||||
{
|
||||
uint8_t buf[24];
|
||||
int ret;
|
||||
|
||||
/* Get calibration data. */
|
||||
|
||||
ret = bmp280_getregs(priv, BMP280_DIG_T1_LSB, buf, 24);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
priv->calib.t1 = (uint16_t)buf[1] << 8 | buf[0];
|
||||
priv->calib.t2 = (int16_t) buf[3] << 8 | buf[2];
|
||||
priv->calib.t3 = (int16_t) buf[5] << 8 | buf[4];
|
||||
|
||||
priv->calib.p1 = (uint16_t)buf[ 7] << 8 | buf[ 6];
|
||||
priv->calib.p2 = (int16_t) buf[ 9] << 8 | buf[ 8];
|
||||
priv->calib.p3 = (int16_t) buf[11] << 8 | buf[10];
|
||||
priv->calib.p4 = (int16_t) buf[13] << 8 | buf[12];
|
||||
priv->calib.p5 = (int16_t) buf[15] << 8 | buf[14];
|
||||
priv->calib.p6 = (int16_t) buf[17] << 8 | buf[16];
|
||||
priv->calib.p7 = (int16_t) buf[19] << 8 | buf[18];
|
||||
priv->calib.p8 = (int16_t) buf[21] << 8 | buf[20];
|
||||
priv->calib.p9 = (int16_t) buf[23] << 8 | buf[22];
|
||||
|
||||
sninfo("T1 = %u\n", priv->calib.t1);
|
||||
sninfo("T2 = %d\n", priv->calib.t2);
|
||||
sninfo("T3 = %d\n", priv->calib.t3);
|
||||
|
||||
sninfo("P1 = %u\n", priv->calib.p1);
|
||||
sninfo("P2 = %d\n", priv->calib.p2);
|
||||
sninfo("P3 = %d\n", priv->calib.p3);
|
||||
sninfo("P4 = %d\n", priv->calib.p4);
|
||||
sninfo("P5 = %d\n", priv->calib.p5);
|
||||
sninfo("P6 = %d\n", priv->calib.p6);
|
||||
sninfo("P7 = %d\n", priv->calib.p7);
|
||||
sninfo("P8 = %d\n", priv->calib.p8);
|
||||
sninfo("P9 = %d\n", priv->calib.p9);
|
||||
|
||||
/* Set power mode to sleep */
|
||||
|
||||
bmp280_putreg8(priv, BMP280_CTRL_MEAS, BMP280_SLEEP_MODE);
|
||||
|
||||
/* Set stand-by time to 1 ms, no IIR filter */
|
||||
|
||||
ret = bmp280_set_standby(priv, BMP280_STANDBY_1_MS);
|
||||
if (ret != OK)
|
||||
{
|
||||
snerr("Failed to set value for standby time.\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_compensate
|
||||
*
|
||||
* Description:
|
||||
* calculate compensate tempreture
|
||||
*
|
||||
* Input Parameters:
|
||||
* temp - uncompensate value of tempreture.
|
||||
*
|
||||
* Returned Value:
|
||||
* calculate result of compensate tempreture.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int32_t bmp280_compensate_temp(FAR struct bmp280_dev_s *priv,
|
||||
int32_t temp)
|
||||
{
|
||||
struct bmp280_calib_s *c = &priv->calib;
|
||||
int32_t var1;
|
||||
int32_t var2;
|
||||
|
||||
var1 = ((((temp >> 3) - ((int32_t)c->t1 << 1))) * ((int32_t)c->t2)) >> 11;
|
||||
var2 = (((((temp >> 4) - ((int32_t)c->t1)) *
|
||||
((temp >> 4) - ((int32_t)c->t1))) >> 12) *
|
||||
((int32_t)c->t3)) >> 14;
|
||||
|
||||
priv->tempfine = var1 + var2;
|
||||
|
||||
return (priv->tempfine * 5 + 128) >> 8;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_compensate_press
|
||||
*
|
||||
* Description:
|
||||
* calculate compensate pressure
|
||||
*
|
||||
* Input Parameters:
|
||||
* press - uncompensate value of pressure.
|
||||
*
|
||||
* Returned Value:
|
||||
* calculate result of compensate pressure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static uint32_t bmp280_compensate_press(FAR struct bmp280_dev_s *priv,
|
||||
uint32_t press, int32_t temp)
|
||||
{
|
||||
struct bmp280_calib_s *c = &priv->calib;
|
||||
int32_t var1;
|
||||
int32_t var2;
|
||||
uint32_t p;
|
||||
|
||||
/* Update temperature fine value first. */
|
||||
|
||||
(void) bmp280_compensate_temp(priv, temp);
|
||||
|
||||
var1 = (priv->tempfine >> 1) - 64000;
|
||||
var2 = (((var1 >> 2) * (var1 >> 2)) >> 11 ) * ((int32_t)c->p6);
|
||||
var2 = var2 + ((var1 * ((int32_t)c->p5)) << 1);
|
||||
var2 = (var2 >> 2) + (((int32_t)c->p4) << 16);
|
||||
var1 = (((c->p3 * (((var1 >> 2) * (var1 >> 2)) >> 13 )) >> 3) +
|
||||
((((int32_t)c->p2) * var1) >> 1)) >> 18;
|
||||
var1 = (((32768 + var1) * ((int32_t)c->p1)) >> 15);
|
||||
|
||||
/* avoid exception caused by division by zero */
|
||||
|
||||
if (var1 == 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
p = (((uint32_t)((0x100000) - press) - (var2 >> 12))) * 3125;
|
||||
|
||||
if (p < 0x80000000)
|
||||
{
|
||||
p = (p << 1) / ((uint32_t)var1);
|
||||
}
|
||||
else
|
||||
{
|
||||
p = (p / (uint32_t)var1) * 2;
|
||||
}
|
||||
|
||||
var1 = ((int32_t)c->p9 * ((int32_t)(((p >> 3) * (p >> 3)) >> 13))) >> 12;
|
||||
var2 = ((int32_t)(p >> 2) * c->p8) >> 13;
|
||||
p = (uint32_t)((int32_t)p + ((var1 + var2 + c->p7) >> 4));
|
||||
|
||||
return p;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_getpressure
|
||||
*
|
||||
* Description:
|
||||
* Calculate the Barometric Pressure using the temperature compensated
|
||||
* See BMP280 data sheet for details
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static uint32_t bmp280_getpressure(FAR struct bmp280_dev_s *priv)
|
||||
{
|
||||
uint8_t buf[6];
|
||||
uint32_t press;
|
||||
int32_t temp;
|
||||
|
||||
bmp280_getregs(priv, BMP280_PRESS_MSB, buf, 6);
|
||||
|
||||
press = (uint32_t)COMBINE(buf);
|
||||
temp = COMBINE(&buf[3]);
|
||||
|
||||
sninfo("press = %d, temp = %d\n", press, temp);
|
||||
|
||||
if (priv->compensated == ENABLE_COMPENSATED)
|
||||
{
|
||||
press = bmp280_compensate_press(priv, press, temp);
|
||||
}
|
||||
|
||||
return press;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_open
|
||||
*
|
||||
* Description:
|
||||
* This function is called whenever the BMP280 device is opened.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int bmp280_open(FAR struct file *filep)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct bmp280_dev_s *priv = inode->i_private;
|
||||
|
||||
/* Set power mode to normal and standard sampling resolusion. */
|
||||
|
||||
bmp280_putreg8(priv, BMP280_CTRL_MEAS, BMP280_NORMAL_MODE |
|
||||
BMP280_OS_STANDARD_RES);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_close
|
||||
*
|
||||
* Description:
|
||||
* This routine is called when the BMP280 device is closed.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int bmp280_close(FAR struct file *filep)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct bmp280_dev_s *priv = inode->i_private;
|
||||
|
||||
/* Set power mode to sleep */
|
||||
|
||||
bmp280_putreg8(priv, BMP280_CTRL_MEAS, BMP280_SLEEP_MODE);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_read
|
||||
****************************************************************************/
|
||||
|
||||
static ssize_t bmp280_read(FAR struct file *filep, FAR char *buffer,
|
||||
size_t buflen)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct bmp280_dev_s *priv = inode->i_private;
|
||||
FAR uint32_t *press = (FAR uint32_t *) buffer;
|
||||
|
||||
if (!buffer)
|
||||
{
|
||||
snerr("Buffer is null\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (buflen < 4)
|
||||
{
|
||||
snerr("You can't read something other than 32 bits (4 bytes)\n");
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Get the pressure compensated */
|
||||
|
||||
*press = bmp280_getpressure(priv);
|
||||
|
||||
/* Return size of uint32_t (4 bytes) */
|
||||
|
||||
return 4;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_ioctl
|
||||
****************************************************************************/
|
||||
|
||||
static int bmp280_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
||||
{
|
||||
FAR struct inode *inode = filep->f_inode;
|
||||
FAR struct bmp280_dev_s *priv = inode->i_private;
|
||||
int ret = OK;
|
||||
|
||||
switch (cmd)
|
||||
{
|
||||
case SNIOC_ENABLE_COMPENSATED:
|
||||
priv->compensated = (int)arg;
|
||||
break;
|
||||
|
||||
case SNIOC_SETSTB:
|
||||
ret = bmp280_set_standby(priv, arg);
|
||||
break;
|
||||
|
||||
default:
|
||||
snerr("Unrecognized cmd: %d\n", cmd);
|
||||
ret = - ENOTTY;
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_register
|
||||
*
|
||||
* Description:
|
||||
* Register the BMP280 character device as 'devpath'
|
||||
*
|
||||
* Input Parameters:
|
||||
* devpath - The full path to the driver to register. E.g., "/dev/press0"
|
||||
* i2c - An instance of the I2C interface to use to communicate with
|
||||
* BMP280
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno value on failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int bmp280_register(FAR const char *devpath, FAR struct i2c_master_s *i2c)
|
||||
{
|
||||
FAR struct bmp280_dev_s *priv;
|
||||
int ret;
|
||||
|
||||
/* Initialize the BMP280 device structure */
|
||||
|
||||
priv = (FAR struct bmp280_dev_s *)kmm_malloc(sizeof(struct bmp280_dev_s));
|
||||
if (!priv)
|
||||
{
|
||||
snerr("Failed to allocate instance\n");
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
priv->i2c = i2c;
|
||||
priv->addr = BMP280_ADDR;
|
||||
priv->freq = BMP280_FREQ;
|
||||
priv->compensated = ENABLE_COMPENSATED;
|
||||
|
||||
/* Check Device ID */
|
||||
|
||||
ret = bmp280_checkid(priv);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("Failed to register driver: %d\n", ret);
|
||||
kmm_free(priv);
|
||||
return ret;
|
||||
}
|
||||
|
||||
ret = bmp280_initialize(priv);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("Failed to initialize physical device bmp280:%d\n", ret);
|
||||
kmm_free(priv);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Register the character driver */
|
||||
|
||||
ret = register_driver(devpath, &g_bmp280fops, 0666, priv);
|
||||
if (ret < 0)
|
||||
{
|
||||
snerr("Failed to register driver: %d\n", ret);
|
||||
kmm_free(priv);
|
||||
}
|
||||
|
||||
sninfo("BMP280 driver loaded successfully!\n");
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
122
include/nuttx/sensors/ak09912.h
Normal file
122
include/nuttx/sensors/ak09912.h
Normal file
|
|
@ -0,0 +1,122 @@
|
|||
/****************************************************************************
|
||||
* include/nuttx/sensors/ak09912.h
|
||||
*
|
||||
* Copyright 2018 Sony Semiconductor Solutions Corporation
|
||||
*
|
||||
* 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 of Sony Semiconductor Solutions Corporation 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_SENSORS_AK09912_H
|
||||
#define __INCLUDE_NUTTX_SENSORS_AK09912_H
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_AK09912)
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/* Prerequisites:
|
||||
*
|
||||
* CONFIG_AK09912
|
||||
* Enables support for the AK09912 driver
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************/
|
||||
|
||||
struct i2c_master_s;
|
||||
|
||||
/****************************************************************************
|
||||
* Public Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef __cplusplus
|
||||
#define EXTERN extern "C"
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/* IOCTL Commands ***********************************************************/
|
||||
|
||||
/* Arg: 0: Disable compensated
|
||||
* 1: Enable compensated
|
||||
*/
|
||||
|
||||
#define ENABLE_COMPENSATED (1)
|
||||
#define DISABLE_COMPENSATED (0)
|
||||
#define SNIOC_ENABLE_COMPENSATED _SNIOC(0x0001)
|
||||
|
||||
#define SNIOC_GETADJ _SNIOC(0x0002)
|
||||
|
||||
struct mag_data_s
|
||||
{
|
||||
int16_t x; /* X raw data */
|
||||
int16_t y; /* Y raw data */
|
||||
int16_t z; /* Z raw data */
|
||||
};
|
||||
|
||||
struct ak09912_sensadj_s
|
||||
{
|
||||
uint8_t x;
|
||||
uint8_t y;
|
||||
uint8_t z;
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ak09912_register
|
||||
*
|
||||
* Description:
|
||||
* Register the AK09912 character device as 'devpath'
|
||||
*
|
||||
* Input Parameters:
|
||||
* devpath - The full path to the driver to register. E.g., "/dev/mag0"
|
||||
* i2c - An instance of the I2C interface to use to communicate with
|
||||
* AK09912
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno value on failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
int ak09912_register(FAR const char *devpath, FAR struct i2c_master_s *i2c);
|
||||
|
||||
#undef EXTERN
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_I2C && CONFIG_AK09912 */
|
||||
#endif /* __DRIVERS_AK09912_H */
|
||||
165
include/nuttx/sensors/bmp280.h
Normal file
165
include/nuttx/sensors/bmp280.h
Normal file
|
|
@ -0,0 +1,165 @@
|
|||
/****************************************************************************
|
||||
* include/nuttx/sensors/bmp280.h
|
||||
*
|
||||
* Copyright 2018 Sony Semiconductor Solutions Corporation
|
||||
*
|
||||
* 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 of Sony Semiconductor Solutions Corporation 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_SENSORS_BMP280_H
|
||||
#define __INCLUDE_NUTTX_SENSORS_BMP280_H
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#if defined(CONFIG_I2C) && defined(CONFIG_SENSORS_BMP280)
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/* Prerequisites:
|
||||
*
|
||||
* CONFIG_BMP280
|
||||
* Enables support for the BMP280 driver
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************/
|
||||
|
||||
struct i2c_master_s;
|
||||
|
||||
/****************************************************************************
|
||||
* Public Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef __cplusplus
|
||||
#define EXTERN extern "C"
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/* IOCTL Commands ***********************************************************/
|
||||
|
||||
/* Arg: 0: Disable compensated
|
||||
* 1: Enable compensated
|
||||
*/
|
||||
|
||||
#define ENABLE_COMPENSATED (1)
|
||||
#define DISABLE_COMPENSATED (0)
|
||||
|
||||
/* Standby duration */
|
||||
|
||||
#define BMP280_STANDBY_1_MS (0x00) /* 0.5 ms */
|
||||
#define BMP280_STANDBY_63_MS (0x01) /* 62.5 ms */
|
||||
#define BMP280_STANDBY_125_MS (0x02) /* 125 ms */
|
||||
#define BMP280_STANDBY_250_MS (0x03) /* 250 ms */
|
||||
#define BMP280_STANDBY_500_MS (0x04) /* 500 ms */
|
||||
#define BMP280_STANDBY_1000_MS (0x05) /* 1000 ms */
|
||||
#define BMP280_STANDBY_2000_MS (0x06) /* 2000 ms */
|
||||
#define BMP280_STANDBY_4000_MS (0x07) /* 4000 ms */
|
||||
|
||||
/* Enable compensate of sensing values (no SCU bus only)
|
||||
*
|
||||
* Arg: ENABLE_COMPENSATED or DISABLE_COMPENSATED
|
||||
*/
|
||||
|
||||
#define SNIOC_ENABLE_COMPENSATED _SNIOC(0x0001)
|
||||
|
||||
/* Get sensor predefined adjustment values (SCU bus only)
|
||||
*
|
||||
* Arg: Pointer of struct bmp280_press_adj_s (pressure)
|
||||
* Pointer of struct bmp280_temp_adj_s (temperature)
|
||||
*/
|
||||
|
||||
#define SNIOC_GETADJ _SNIOC(0x0002)
|
||||
|
||||
/* Set sensor standby duration
|
||||
*
|
||||
* Arg: BMP280_STANDBY_*_MS
|
||||
*/
|
||||
|
||||
#define SNIOC_SETSTB _SNIOC(0x0003)
|
||||
|
||||
struct bmp280_press_adj_s
|
||||
{
|
||||
uint16_t dig_p1; /** calibration P1 data */
|
||||
int16_t dig_p2; /** calibration P2 data */
|
||||
int16_t dig_p3; /** calibration P3 data */
|
||||
int16_t dig_p4; /** calibration P4 data */
|
||||
int16_t dig_p5; /** calibration P5 data */
|
||||
int16_t dig_p6; /** calibration P6 data */
|
||||
int16_t dig_p7; /** calibration P7 data */
|
||||
int16_t dig_p8; /** calibration P8 data */
|
||||
int16_t dig_p9; /** calibration P9 data */
|
||||
};
|
||||
|
||||
struct bmp280_temp_adj_s
|
||||
{
|
||||
uint16_t dig_t1; /** calibration T1 data */
|
||||
int16_t dig_t2; /** calibration T2 data */
|
||||
int16_t dig_t3; /** calibration T3 data */
|
||||
};
|
||||
|
||||
struct bmp280_meas_s
|
||||
{
|
||||
uint8_t msb; /** meas value MSB */
|
||||
uint8_t lsb; /** meas value LSB */
|
||||
uint8_t xlsb; /** meas value XLSB */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Name: bmp280_register
|
||||
*
|
||||
* Description:
|
||||
* Register the BMP280 character device as 'devpath'
|
||||
*
|
||||
* Input Parameters:
|
||||
* devpath - The full path to the driver to register. E.g., "/dev/press"
|
||||
* i2c - An instance of the I2C interface to use to communicate with
|
||||
* BMP280
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno value on failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
int bmp280_register(FAR const char *devpath, FAR struct i2c_master_s *i2c);
|
||||
|
||||
#undef EXTERN
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* CONFIG_I2C && CONFIG_SENSORS_BMP280 */
|
||||
#endif /* __INCLUDE_NUTTX_BMP280_H */
|
||||
Loading…
Add table
Reference in a new issue