diff options
| -rw-r--r-- | os/ex/ST/hts221.c | 560 | ||||
| -rw-r--r-- | os/ex/ST/hts221.h | 408 | ||||
| -rw-r--r-- | os/ex/ST/hts221.mk | 6 | 
3 files changed, 974 insertions, 0 deletions
diff --git a/os/ex/ST/hts221.c b/os/ex/ST/hts221.c new file mode 100644 index 000000000..762478f9b --- /dev/null +++ b/os/ex/ST/hts221.c @@ -0,0 +1,560 @@ +/*
 +    ChibiOS - Copyright (C) 2016 Rocco Marco Guglielmi
 +
 +    This file is part of ChibiOS.
 +
 +    ChibiOS is free software; you can redistribute it and/or modify
 +    it under the terms of the GNU General Public License as published by
 +    the Free Software Foundation; either version 3 of the License, or
 +    (at your option) any later version.
 +
 +    ChibiOS is distributed in the hope that it will be useful,
 +    but WITHOUT ANY WARRANTY; without even the implied warranty of
 +    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 +    GNU General Public License for more details.
 +
 +    You should have received a copy of the GNU General Public License
 +    along with this program.  If not, see <http://www.gnu.org/licenses/>.
 +	
 +*/
 +
 +/**
 + * @file    hts221.c
 + * @brief   HTS221 MEMS interface module code.
 + *
 + * @addtogroup hts221
 + * @{
 + */
 +
 +#include "hal.h"
 +#include "hts221.h"
 +
 +/*===========================================================================*/
 +/* Driver local definitions.                                                 */
 +/*===========================================================================*/
 +
 +#define HTS221_SEL(mask, offset)    (int16_t)(mask << offset)
 +
 +/*===========================================================================*/
 +/* Driver exported variables.                                                */
 +/*===========================================================================*/
 +
 +/*===========================================================================*/
 +/* Driver local variables and types.                                         */
 +/*===========================================================================*/
 +
 +static float hts221_bias[2] = {0.0f, 0.0f};
 +static float hts221_sens[2] = {0.0f, 0.0f};
 +
 +/*===========================================================================*/
 +/* Driver local functions.                                                   */
 +/*===========================================================================*/
 +
 +#if (HTS221_USE_I2C) || defined(__DOXYGEN__)
 +/**
 + * @brief   Reads registers value using I2C.
 + * @pre     The I2C interface must be initialized and the driver started.
 + *
 + * @param[in]  i2cp      pointer to the I2C interface
 + * @param[in]  reg       first sub-register address
 + * @param[out] rxbuf     pointer to an output buffer
 + * @return               the operation status.
 + * @param[in]  n         number of consecutive register to read
 + * @notapi
 + */
 +msg_t hts221I2CReadRegister(I2CDriver *i2cp, uint8_t reg, uint8_t* rxbuf,
 +                             size_t n) {
 +  uint8_t txbuf = reg;
 +  if(n > 1)
 +    txbuf |= HTS221_SUB_MS;
 +
 +  return i2cMasterTransmitTimeout(i2cp, HTS221_SAD, &txbuf, 1, rxbuf, n,
 +                                  TIME_INFINITE);
 +}
 +
 +/**
 + * @brief   Writes a value into a register using I2C.
 + * @pre     The I2C interface must be initialized and the driver started.
 + *
 + * @param[in] i2cp       pointer to the I2C interface
 + * @param[in] txbuf      buffer containing sub-address value in first position
 + *                       and values to write
 + * @param[in] n          size of txbuf less one (not considering the first
 + *                       element)
 + * @return               the operation status.
 + * @notapi
 + */
 +msg_t hts221I2CWriteRegister(I2CDriver *i2cp, uint8_t* txbuf, size_t n) {
 +  if (n > 1)
 +    (*txbuf) |= HTS221_SUB_MS;
 +
 +  return i2cMasterTransmitTimeout(i2cp, HTS221_SAD, txbuf, n + 1, NULL, 0,
 +                                  TIME_INFINITE);
 +}
 +#endif /* HTS221_USE_I2C */
 +
 +/**
 + * @brief   Compute biases and sensitivities starting from data stored in
 + *          calibration registers.
 + * @notapi
 + *
 + * @param[in] dev        pointer to the HTS221 interface
 + * @return               the operation status.
 + */
 +msg_t hts221Calibrate(HTS221Driver *devp) {
 +  msg_t msg;
 +  uint8_t calib[16], H0_rH_x2, H1_rH_x2, msb;
 +  int16_t H0_T0_OUT, H1_T0_OUT, T0_degC_x8, T1_degC_x8, T0_OUT, T1_OUT;
 +
 +
 +#if HTS221_SHARED_I2C
 +  i2cAcquireBus(devp->config->i2cp);
 +  i2cStart(devp->config->i2cp, devp->config->i2ccfg);
 +#endif /* HTS221_SHARED_I2C */
 +
 +  /* Retrieving rH values from Calibration registers */
 +	msg = hts221I2CReadRegister(devp->config->i2cp,
 +                               HTS221_AD_CALIB_0, calib, 16);
 +#if HTS221_SHARED_I2C
 +    i2cReleaseBus(devp->config->i2cp);
 +#endif /* HTS221_SHARED_I2C */
 +															
 +  H0_rH_x2 = calib[0];
 +  H1_rH_x2 = calib[1];
 +  H0_T0_OUT = calib[6];
 +  H0_T0_OUT += calib[7] << 8;
 +  H1_T0_OUT = calib[10];
 +  H1_T0_OUT += calib[11] << 8;
 +	
 +  T0_degC_x8 = calib[2];
 +  T1_degC_x8 = calib[3];
 +
 +  /* completing T0_degC_x8 value */
 +  msb = (calib[5] & HTS221_SEL(0x03, 0));
 +  if(msb & HTS221_SEL(0x01, 1)) {
 +    msb |= HTS221_SEL(0x3F, 2);
 +  }
 +  T0_degC_x8 += msb << 8;
 +
 +  /* completing T1_degC_x8 value */
 +  msb = ((calib[5] & HTS221_SEL(0x03, 2)) >> 2);
 +  if(msb & HTS221_SEL(0x01, 1)) {
 +    msb |= HTS221_SEL(0x3F, 2);
 +  }
 +  T1_degC_x8 += msb << 8;
 +
 +  T0_OUT = calib[12];
 +  T0_OUT += calib[13] << 8;
 +  T1_OUT = calib[14];
 +  T1_OUT += calib[15] << 8;
 +	
 +
 +  /* Storing data both in sensor data and in a reference variable used also
 +     when user reset bias and sensitivity */
 +  hts221_sens[0] = ((float)H1_rH_x2 - (float)H0_rH_x2) /
 +                   (2.0f * ((float)H1_T0_OUT - (float)H0_T0_OUT));
 +  devp->sensitivity[0] = hts221_sens[0];
 +
 +  hts221_bias[0] = (devp->sensitivity[0] * (float)H0_T0_OUT) -
 +                   ((float)H0_rH_x2 / 2.0f);
 +  devp->bias[0] = hts221_bias[0];
 +
 +  hts221_sens[1] = ((float)T1_degC_x8 - (float)T0_degC_x8) /
 +                   (8.0f * ((float)T1_OUT - (float)T0_OUT));
 +  devp->sensitivity[1] = hts221_sens[1];
 +
 +  hts221_bias[1] = (devp->sensitivity[1] * (float)T0_OUT) -
 +                   ((float)T0_degC_x8 / 8.0f);
 +  devp->bias[1] = hts221_bias[1];
 +  return msg;
 +}
 +
 +/*
 + * Interface implementation.
 + */
 +static size_t hygro_get_axes_number(void *ip) {
 +
 +  osalDbgCheck(ip != NULL);
 +  return HTS221_HYGRO_NUMBER_OF_AXES;
 +}
 +
 +static size_t thermo_get_axes_number(void *ip) {
 +
 +  osalDbgCheck(ip != NULL);
 +  return HTS221_THERMO_NUMBER_OF_AXES;
 +}
 +
 +static size_t sens_get_axes_number(void *ip) {
 +
 +  osalDbgCheck(ip != NULL);
 +  return (thermo_get_axes_number(ip) + hygro_get_axes_number(ip));
 +}
 +
 +static msg_t hygro_read_raw(void *ip, int32_t axis[]) {
 +  int16_t tmp;
 +  uint8_t buff[2];
 +  msg_t msg = MSG_OK;
 +	
 +  osalDbgCheck((ip != NULL) && (axis != NULL));
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY),
 +              "hygro_read_raw(), invalid state");
 +
 +	*axis = 0.0f;
 +#if HTS221_USE_I2C
 +  osalDbgAssert((((HTS221Driver *)ip)->config->i2cp->state == I2C_READY),
 +                "hygro_read_raw(), channel not ready");
 +#if HTS221_SHARED_I2C
 +  i2cAcquireBus(((HTS221Driver *)ip)->config->i2cp);
 +  i2cStart(((HTS221Driver *)ip)->config->i2cp,
 +           ((HTS221Driver *)ip)->config->i2ccfg);
 +#endif /* HTS221_SHARED_I2C */
 +
 +
 +  msg = hts221I2CReadRegister(((HTS221Driver *)ip)->config->i2cp,
 +                              HTS221_AD_HUMIDITY_OUT_L, buff, 2);	
 +#if HTS221_SHARED_I2C
 +  i2cReleaseBus(((HTS221Driver *)ip)->config->i2cp);
 +#endif /* HTS221_SHARED_I2C */
 +#endif /* HTS221_USE_I2C */
 +
 +  if(msg == MSG_OK) {
 +    tmp = buff[0] + (buff[1] << 8);
 +    *axis = (int32_t)tmp;
 +  }
 +  return msg;
 +}
 +
 +static msg_t thermo_read_raw(void *ip, int32_t axis[]) {
 +  int16_t tmp;
 +	uint8_t buff[2];
 +  msg_t msg = MSG_OK;
 +	
 +  osalDbgCheck((ip != NULL) && (axis != NULL));
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY),
 +              "thermo_read_raw(), invalid state");	
 +	*axis = 0.0f;
 +	
 +#if HTS221_USE_I2C
 +  osalDbgAssert((((HTS221Driver *)ip)->config->i2cp->state == I2C_READY),
 +                "thermo_read_raw(), channel not ready");
 +								
 +#if HTS221_SHARED_I2C
 +  i2cAcquireBus(((HTS221Driver *)ip)->config->i2cp);
 +  i2cStart(((HTS221Driver *)ip)->config->i2cp,
 +           ((HTS221Driver *)ip)->config->i2ccfg);
 +#endif /* HTS221_SHARED_I2C */
 +
 +  msg = hts221I2CReadRegister(((HTS221Driver *)ip)->config->i2cp,
 +                                  HTS221_AD_TEMP_OUT_L,
 +                                  buff, 2);	
 +																	
 +#if HTS221_SHARED_I2C
 +  i2cReleaseBus(((HTS221Driver *)ip)->config->i2cp);
 +#endif /* HTS221_SHARED_I2C */
 +#endif /* HTS221_USE_I2C */
 +
 +  if(msg == MSG_OK) {
 +    tmp = buff[0] + (buff[1] << 8);
 +    *axis = (int32_t)tmp;
 +  }
 +  return msg;
 +}
 +
 +static msg_t sens_read_raw(void *ip, int32_t axes[]) {
 +  int32_t* bp = axes;
 +  msg_t msg;
 +  msg = hygro_read_raw(ip, bp);
 +  if (msg != MSG_OK){
 +    return msg;
 +  }
 +  bp += HTS221_HYGRO_NUMBER_OF_AXES;
 +  return thermo_read_raw(ip, bp);
 +}
 +
 +static msg_t hygro_read_cooked(void *ip, float* axis) {
 +  int32_t raw;
 +  msg_t msg;
 +
 +  osalDbgCheck((ip != NULL) && (axis != NULL));
 +
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY),
 +              "hygro_read_cooked(), invalid state");
 +
 +  msg = hygro_read_raw(ip, &raw);
 +
 +  *axis = raw * ((HTS221Driver *)ip)->sensitivity[0];
 +  *axis -= ((HTS221Driver *)ip)->bias[0];
 +  return msg;
 +}
 +
 +static msg_t thermo_read_cooked(void *ip, float* axis) {
 +  int32_t raw;
 +  msg_t msg;
 +
 +  osalDbgCheck((ip != NULL) && (axis != NULL));
 +
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY),
 +              "thermo_read_cooked(), invalid state");
 +
 +  msg = thermo_read_raw(ip, &raw);
 +
 +  *axis = raw * ((HTS221Driver *)ip)->sensitivity[1];
 +  *axis -= ((HTS221Driver *)ip)->bias[1];
 +  return msg;
 +}
 +
 +static msg_t sens_read_cooked(void *ip, float axes[]) {
 +  float *dp = axes;
 +  msg_t msg;
 +
 +  osalDbgCheck((ip != NULL) && (axes != NULL));
 +
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY),
 +              "sens_read_cooked(), invalid state");
 +
 +  msg = hygro_read_cooked(ip, dp);
 +  if(msg != MSG_OK)
 +    return msg;
 +  dp += HTS221_THERMO_NUMBER_OF_AXES;
 +  return thermo_read_cooked(ip, dp);
 +}
 +
 +static msg_t hygro_set_bias(void *ip, float *bp) {
 +  osalDbgCheck((ip != NULL) && (bp != NULL));
 +
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY) ||
 +                (((HTS221Driver *)ip)->state == HTS221_STOP),
 +                "thermo_set_bias(), invalid state");
 +
 +  ((HTS221Driver *)ip)->bias[0] = *bp;
 +  return MSG_OK;
 +}
 +
 +static msg_t thermo_set_bias(void *ip, float *bp) {
 +  osalDbgCheck((ip != NULL) && (bp != NULL));
 +
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY) ||
 +                (((HTS221Driver *)ip)->state == HTS221_STOP),
 +                "thermo_set_bias(), invalid state");
 +
 +  ((HTS221Driver *)ip)->bias[1] = *bp;
 +  return MSG_OK;
 +}
 +
 +static msg_t hygro_reset_bias(void *ip) {
 +  osalDbgCheck(ip != NULL);
 +
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY) ||
 +                (((HTS221Driver *)ip)->state == HTS221_STOP),
 +                "hygro_reset_bias(), invalid state");
 +
 +  ((HTS221Driver *)ip)->bias[0] = 0;
 +  return MSG_OK;
 +}
 +
 +static msg_t thermo_reset_bias(void *ip) {
 +  osalDbgCheck(ip != NULL);
 +
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY) ||
 +                (((HTS221Driver *)ip)->state == HTS221_STOP),
 +                "thermo_reset_bias(), invalid state");
 +
 +  ((HTS221Driver *)ip)->bias[1] = 0;
 +  return MSG_OK;
 +}
 +
 +static msg_t hygro_set_sensitivity(void *ip, float *sp) {
 +  osalDbgCheck((ip != NULL) && (sp != NULL));
 +
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY) ||
 +                (((HTS221Driver *)ip)->state == HTS221_STOP),
 +                "thermo_set_sensitivity(), invalid state");
 +
 +  ((HTS221Driver *)ip)->sensitivity[0] = *sp;
 +  return MSG_OK;
 +}
 +
 +static msg_t thermo_set_sensitivity(void *ip, float *sp) {
 +  osalDbgCheck((ip != NULL) && (sp != NULL));
 +
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY) ||
 +                (((HTS221Driver *)ip)->state == HTS221_STOP),
 +                "thermo_set_sensitivity(), invalid state");
 +
 +  ((HTS221Driver *)ip)->sensitivity[1] = *sp;
 +  return MSG_OK;
 +}
 +
 +static msg_t hygro_reset_sensitivity(void *ip) {
 +  osalDbgCheck(ip != NULL);
 +
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY) ||
 +                (((HTS221Driver *)ip)->state == HTS221_STOP),
 +                "hygro_reset_sensitivity(), invalid state");
 +
 +  ((HTS221Driver *)ip)->sensitivity[0] = HTS221_HYGRO_SENS;
 +  return MSG_OK;
 +}
 +
 +static msg_t thermo_reset_sensitivity(void *ip) {
 +  osalDbgCheck(ip != NULL);
 +
 +  osalDbgAssert((((HTS221Driver *)ip)->state == HTS221_READY) ||
 +                (((HTS221Driver *)ip)->state == HTS221_STOP),
 +                "thermo_reset_sensitivity(), invalid state");
 +
 +  ((HTS221Driver *)ip)->sensitivity[1] = HTS221_THERMO_SENS;
 +  return MSG_OK;
 +}
 +
 +
 +static const struct BaseSensorVMT vmt_basesensor = {
 +  sens_get_axes_number, sens_read_raw, sens_read_cooked
 +};
 +
 +static const struct BaseHygrometerVMT vmt_basehygrometer = {
 +  hygro_get_axes_number, hygro_read_raw, hygro_read_cooked,
 +  hygro_set_bias, hygro_reset_bias,
 +  hygro_set_sensitivity, hygro_reset_sensitivity
 +};
 +
 +static const struct BaseThermometerVMT vmt_basethermometer = {
 +  thermo_get_axes_number, thermo_read_raw, thermo_read_cooked,
 +  thermo_set_bias, thermo_reset_bias,
 +  thermo_set_sensitivity, thermo_reset_sensitivity
 +};
 +
 +/*===========================================================================*/
 +/* Driver exported functions.                                                */
 +/*===========================================================================*/
 +
 +/**
 + * @brief   Initializes an instance.
 + *
 + * @param[out] devp     pointer to the @p HTS221Driver object
 + *
 + * @init
 + */
 +void hts221ObjectInit(HTS221Driver *devp) {
 +
 +  devp->vmt_basesensor = &vmt_basesensor;
 +  devp->vmt_basehygrometer = &vmt_basehygrometer;
 +  devp->vmt_basethermometer = &vmt_basethermometer;
 +  devp->config = NULL;
 +  devp->state  = HTS221_STOP;
 +  devp->bias[0] = 0.0;
 +  devp->bias[1] = 0.0;
 +  devp->sensitivity[0] = 0.0;
 +  devp->sensitivity[1] = 0.0;
 +}
 +
 +/**
 + * @brief   Configures and activates HTS221 Complex Driver peripheral.
 + *
 + * @param[in] devp      pointer to the @p HTS221Driver object
 + * @param[in] config    pointer to the @p HTS221Config object
 + *
 + * @api
 + */
 +void hts221Start(HTS221Driver *devp, const HTS221Config *config) {
 +  uint8_t cr[2];
 +  osalDbgCheck((devp != NULL) && (config != NULL));
 +
 +  osalDbgAssert((devp->state == HTS221_STOP) || (devp->state == HTS221_READY),
 +              "hts221Start(), invalid state");			  
 +
 +  devp->config = config;
 +
 +#if HTS221_USE_I2C
 +#if	HTS221_SHARED_I2C
 +  i2cAcquireBus((devp)->config->i2cp);
 +#endif /* HTS221_SHARED_I2C */
 +  i2cStart((devp)->config->i2cp,
 +           (devp)->config->i2ccfg);
 +
 +  /* Control register 1 configuration block.*/
 +  {
 +		cr[0] = HTS221_AD_CTRL_REG1;
 +    cr[1] = devp->config->outputdatarate | HTS221_CTRL_REG1_PD;
 +#if HTS221_USE_ADVANCED || defined(__DOXYGEN__)
 +    cr[1] |= devp->config->blockdataupdate;
 +
 +#endif
 +    hts221I2CWriteRegister(devp->config->i2cp, cr, 1);
 +  }
 +
 +  /* Average register configuration block.*/
 +  {
 +		cr[0] = HTS221_AD_AV_CONF;
 +    cr[1] = 0x05;
 +#if HTS221_USE_ADVANCED || defined(__DOXYGEN__)
 +    cr[1] = devp->config->reshumidity | devp->config->restemperature;
 +
 +#endif
 +		hts221I2CWriteRegister(devp->config->i2cp, cr, 1);
 +  }
 +
 +#if	HTS221_SHARED_I2C
 +  i2cReleaseBus((devp)->config->i2cp);
 +#endif /* HTS221_SHARED_I2C */  
 +#endif /* HTS221_USE_I2C */
 +
 +  hts221Calibrate(devp);
 +
 +  if(devp->config->sensitivity != NULL) {
 +    /* Taking Sensitivity from user configurations */
 +    devp->sensitivity[0] = devp->config->sensitivity[0];
 +    devp->sensitivity[1] = devp->config->sensitivity[1];
 +  }
 +
 +  if(devp->config->bias != NULL) {
 +    /* Taking Bias from user configurations */
 +    devp->bias[0] = devp->config->bias[0];
 +    devp->bias[1] = devp->config->bias[1];
 +  }
 +
 +  /* This is the MEMS transient recovery time */
 +  osalThreadSleepMilliseconds(5);
 +
 +  devp->state = HTS221_READY;
 +} 
 +
 +/**
 + * @brief   Deactivates the HTS221 Complex Driver peripheral.
 + *
 + * @param[in] devp       pointer to the @p HTS221Driver object
 + *
 + * @api
 + */
 +void hts221Stop(HTS221Driver *devp) {
 +  uint8_t cr[2];
 +
 +  osalDbgCheck(devp != NULL);
 +
 +  osalDbgAssert((devp->state == HTS221_STOP) || (devp->state == HTS221_READY),
 +                "hts221Stop(), invalid state");
 +
 +#if (HTS221_USE_I2C)
 +  if (devp->state == HTS221_STOP) {
 +#if	HTS221_SHARED_I2C
 +    i2cAcquireBus((devp)->config->i2cp);
 +    i2cStart((devp)->config->i2cp,
 +             (devp)->config->i2ccfg);
 +#endif /* HTS221_SHARED_I2C */
 +
 +  /* Control register 1 configuration block.*/
 +  {
 +    cr[0] = HTS221_AD_CTRL_REG1;
 +    cr[1] = 0;
 +    hts221I2CWriteRegister(devp->config->i2cp, cr, 1);
 +  }
 +	
 +    i2cStop((devp)->config->i2cp);
 +#if	HTS221_SHARED_I2C
 +    i2cReleaseBus((devp)->config->i2cp);
 +#endif /* HTS221_SHARED_I2C */    
 +  }			  
 +#endif /* HTS221_USE_I2C */
 +  devp->state = HTS221_STOP;
 +}
 +/** @} */
 diff --git a/os/ex/ST/hts221.h b/os/ex/ST/hts221.h new file mode 100644 index 000000000..58c4af956 --- /dev/null +++ b/os/ex/ST/hts221.h @@ -0,0 +1,408 @@ +/*
 +    ChibiOS - Copyright (C) 2016 Rocco Marco Guglielmi
 +
 +    This file is part of ChibiOS.
 +
 +    ChibiOS is free software; you can redistribute it and/or modify
 +    it under the terms of the GNU General Public License as published by
 +    the Free Software Foundation; either version 3 of the License, or
 +    (at your option) any later version.
 +
 +    ChibiOS is distributed in the hope that it will be useful,
 +    but WITHOUT ANY WARRANTY; without even the implied warranty of
 +    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 +    GNU General Public License for more details.
 +
 +    You should have received a copy of the GNU General Public License
 +    along with this program.  If not, see <http://www.gnu.org/licenses/>.
 +	
 +*/
 +
 +/**
 + * @file    hts221.h
 + * @brief   HTS221 MEMS interface module header.
 + *
 + * @{
 + */
 +#ifndef _HTS221_H_
 +#define _HTS221_H_
 +
 +#include "hal_hygrometer.h"
 +#include "hal_thermometer.h"
 +
 +/*===========================================================================*/
 +/* Driver constants.                                                         */
 +/*===========================================================================*/
 +
 +/**
 + * @name    Version identification
 + * @{
 + */
 +/**
 + * @brief   HTS221 driver version string.
 + */
 +#define EX_HTS221_VERSION           "1.0.0"
 +
 +/**
 + * @brief   HTS221 driver version major number.
 + */
 +#define EX_HTS221_MAJOR             1
 +
 +/**
 + * @brief   HTS221 driver version minor number.
 + */
 +#define EX_HTS221_MINOR             0
 +
 +/**
 + * @brief   HTS221 driver version patch number.
 + */
 +#define EX_HTS221_PATCH             0
 +/** @} */
 +
 +/**
 + * @brief   HTS221 characteristics. + *
 + * @{
 + */ +#define HTS221_HYGRO_NUMBER_OF_AXES         1U +#define HTS221_THERMO_NUMBER_OF_AXES        1U
 +
 +#define HTS221_HYGRO_SENS                   256.0f    /**< LSB/%rH          */
 +#define HTS221_THERMO_SENS                  64.0f     /**< LSB/°C           */ +/** @} */ + +/** + * @name    HTS221 communication interfaces related bit masks + * @{ + */ +#define HTS221_DI_MASK              0xFF        /**< Data In mask           */ +#define HTS221_DI(n)                (1 << n)    /**< Data In bit n          */ +#define HTS221_AD_MASK              0x3F        /**< Address Data mask      */ +#define HTS221_AD(n)                (1 << n)    /**< Address Data bit n     */ +#define HTS221_MS                   (1 << 6)    /**< Multiple read write    */ +#define HTS221_RW                   (1 << 7)    /**< Read Write selector    */
 +
 +#define HTS221_SUB_MS               (1 << 7)    /**< Multiple RW in I2C mode*/
 +
 +#define HTS221_SAD                  0x5F        /**< Slave Address          */ +/** @} */ + +/** + * @name    HTS221 register addresses + * @{ + */
 +#define HTS221_AD_WHO_AM_I          0x0F
 +#define HTS221_AD_AV_CONF           0x10 +#define HTS221_AD_CTRL_REG1         0x20 +#define HTS221_AD_CTRL_REG2         0x21 +#define HTS221_AD_CTRL_REG3         0x22
 +#define HTS221_AD_STATUS_REG        0x27 +#define HTS221_AD_HUMIDITY_OUT_L    0x28 +#define HTS221_AD_HUMIDITY_OUT_H    0x29 +#define HTS221_AD_TEMP_OUT_L        0x2A +#define HTS221_AD_TEMP_OUT_H        0x2B
 +#define HTS221_AD_CALIB_0           0x30
 +#define HTS221_AD_CALIB_1           0x31
 +#define HTS221_AD_CALIB_2           0x32
 +#define HTS221_AD_CALIB_3           0x33
 +#define HTS221_AD_CALIB_4           0x34
 +#define HTS221_AD_CALIB_5           0x35
 +#define HTS221_AD_CALIB_6           0x36
 +#define HTS221_AD_CALIB_7           0x37
 +#define HTS221_AD_CALIB_8           0x38
 +#define HTS221_AD_CALIB_9           0x39
 +#define HTS221_AD_CALIB_A           0x3A
 +#define HTS221_AD_CALIB_B           0x3B
 +#define HTS221_AD_CALIB_C           0x3C
 +#define HTS221_AD_CALIB_D           0x3D
 +#define HTS221_AD_CALIB_E           0x3E
 +#define HTS221_AD_CALIB_F           0x3F +/** @} */ + +/** + * @name    HTS221_CTRL_REG1 register bits definitions + * @{ + */ +#define HTS221_CTRL_REG1_MASK               0x87        +#define HTS221_CTRL_REG1_ODR0               (1 << 0) +#define HTS221_CTRL_REG1_ODR1               (1 << 1)  +#define HTS221_CTRL_REG1_BDU                (1 << 2) +#define HTS221_CTRL_REG1_PD                 (1 << 7) +/** @} */ + +/**
 + * @name    HTS221_CTRL_REG2 register bits definitions
 + * @{
 + */
 +#define HTS221_CTRL_REG2_MASK               0x83       
 +#define HTS221_CTRL_REG2_ONE_SHOT           (1 << 0)
 +#define HTS221_CTRL_REG2_HEATER             (1 << 1) 
 +#define HTS221_CTRL_REG2_BOOT               (1 << 7)
 +/** @} */ + +/**
 + * @name    HTS221_CTRL_REG3 register bits definitions
 + * @{
 + */
 +#define HTS221_CTRL_REG3_MASK               0xC4       
 +#define HTS221_CTRL_REG3_DRDY               (1 << 2) 
 +#define HTS221_CTRL_REG3_PP_OD              (1 << 6)
 +#define HTS221_CTRL_REG3_INT_H_L            (1 << 7)
 +/** @} */
 +
 +/*===========================================================================*/ +/* Driver pre-compile time settings.                                         */ +/*===========================================================================*/ + +/** + * @name    Configuration options + * @{ + */ +/** + * @brief   HTS221 SPI interface switch. + * @details If set to @p TRUE the support for SPI is included. + * @note    The default is @p FALSE. + */ +#if !defined(HTS221_USE_SPI) || defined(__DOXYGEN__) +#define HTS221_USE_SPI                      FALSE +#endif + +/** + * @brief   HTS221 I2C interface switch. + * @details If set to @p TRUE the support for I2C is included. + * @note    The default is @p TRUE. + */ +#if !defined(HTS221_USE_I2C) || defined(__DOXYGEN__) +#define HTS221_USE_I2C                      TRUE +#endif + +/** + * @brief   HTS221 advanced configurations switch. + * @details If set to @p TRUE more configurations are available. + * @note    The default is @p FALSE. + */ +#if !defined(HTS221_USE_ADVANCED) || defined(__DOXYGEN__) +#define HTS221_USE_ADVANCED                 FALSE +#endif + +/** + * @brief   HTS221 shared I2C switch. + * @details If set to @p TRUE the device acquires I2C bus ownership + *          on each transaction. + * @note    The default is @p FALSE. Requires I2C_USE_MUTUAL_EXCLUSION + */ +#if !defined(HTS221_SHARED_SPI) || defined(__DOXYGEN__) +#define HTS221_SHARED_I2C                   FALSE +#endif +/** @} */ + +/*===========================================================================*/ +/* Derived constants and error checks.                                       */ +/*===========================================================================*/ + +#if !(HTS221_USE_SPI ^ HTS221_USE_I2C) +#error "HTS221_USE_SPI and HTS221_USE_I2C cannot be both true or both false" +#endif + +#if HTS221_USE_SPI && !HAL_USE_SPI +#error "HTS221_USE_SPI requires HAL_USE_SPI" +#endif +
 +#if HTS221_USE_SPI
 +#error "HTS221 over SPI still not supported"
 +#endif
 + +#if HTS221_USE_I2C && !HAL_USE_I2C +#error "HTS221_USE_I2C requires HAL_USE_I2C" +#endif + +#if HTS221_SHARED_I2C && !I2C_USE_MUTUAL_EXCLUSION +#error "HTS221_SHARED_I2C requires I2C_USE_MUTUAL_EXCLUSION" +#endif
 +
 +/*
 + * TODO: Add SPI support.
 + */ + +/*===========================================================================*/ +/* Driver data structures and types.                                         */ +/*===========================================================================*/ + +/** + * @name    HTS221 data structures and types. + * @{ + */
 +/** + * @brief   HTS221 output data rate and bandwidth. + */ +typedef enum {
 +  HTS221_ODR_ONE_SHOT = 0x00,       /**< One shot.                          */ +  HTS221_ODR_1HZ = 0x01,            /**< Output data rate 1 Hz.             */ +  HTS221_ODR_7HZ = 0x02,            /**< Output data rate 7 Hz.             */ +  HTS221_ODR_12P5HZ = 0x03,         /**< Output data rate 12.5 Hz.          */ +}hts221_odr_t; +
 +/**
 + * @brief   HTS221 humidity resolution.
 + */
 +typedef enum {
 +  HTS221_AVGH_4 = 0x00,             /**< Number of internal average is 4.   */
 +  HTS221_AVGH_8 = 0x01,             /**< Number of internal average is 8.   */
 +  HTS221_AVGH_16 = 0x02,            /**< Number of internal average is 16.  */
 +  HTS221_AVGH_32 = 0x03,            /**< Number of internal average is 32.  */
 +  HTS221_AVGH_64 = 0x04,            /**< Number of internal average is 64.  */
 +  HTS221_AVGH_128 = 0x05,           /**< Number of internal average is 128. */
 +  HTS221_AVGH_256 = 0x06,           /**< Number of internal average is 256. */
 +  HTS221_AVGH_512 = 0x07            /**< Number of internal average is 512. */
 +}hts221_avgh_t;
 +
 +/**
 + * @brief   HTS221 temperature resolution.
 + */
 +typedef enum {
 +  HTS221_AVGT_2 = 0x00,             /**< Number of internal average is 2.   */
 +  HTS221_AVGT_4 = 0x08,             /**< Number of internal average is 4.   */
 +  HTS221_AVGT_8 = 0x10,             /**< Number of internal average is 8.   */
 +  HTS221_AVGT_16 = 0x18,            /**< Number of internal average is 16.  */
 +  HTS221_AVGT_32 = 0x20,            /**< Number of internal average is 32.  */
 +  HTS221_AVGT_64 = 0x28,            /**< Number of internal average is 64.  */
 +  HTS221_AVGT_128 = 0x30,           /**< Number of internal average is 128. */
 +  HTS221_AVGT_256 = 0x38,           /**< Number of internal average is 256. */
 +}hts221_avgt_t;
 + +/** + * @brief   HTS221 block data update. + */ +typedef enum { +  HTS221_BDU_CONTINUOUS = 0x00,     /**< Block data continuously updated.   */ +  HTS221_BDU_BLOCKED = 0x40         /**< Block data updated after reading.  */ +}hts221_bdu_t; + +/** + * @brief   Driver state machine possible states. + */ +typedef enum { +  HTS221_UNINIT = 0,                /**< Not initialized.                   */ +  HTS221_STOP = 1,                  /**< Stopped.                           */ +  HTS221_READY = 2,                 /**< Ready.                             */ +} hts221_state_t; +
 +/** + * @brief   HTS221 configuration structure. + */ +typedef struct { + +#if HTS221_USE_SPI || defined(__DOXYGEN__) +  /** +   * @brief SPI driver associated to this HTS221. +   */ +  SPIDriver                 *spip; +  /** +   * @brief SPI configuration associated to this HTS221. +   */ +  const SPIConfig           *spicfg; +#endif /* HTS221_USE_SPI */ +#if HTS221_USE_I2C || defined(__DOXYGEN__) +  /** +   * @brief I2C driver associated to this HTS221. +   */ +  I2CDriver                 *i2cp; +  /** +   * @brief I2C configuration associated to this HTS221. +   */ +  const I2CConfig           *i2ccfg; +#endif /* HTS221_USE_I2C */ +  /** +   * @brief HTS221 initial sensitivity.
 +   * @note  Value are respectively related to hygrometer
 +   *        and thermometer. +   */ +  float*                    sensitivity; +  /** +   * @brief HTS221 initial bias.
 +   * @note  Value are respectively related to hygrometer
 +   *        and thermometer. +   */ +  float*                    bias; +  /** +   * @brief HTS221 output data rate selection. +   */ +  hts221_odr_t              outputdatarate; +#if HTS221_USE_ADVANCED || defined(__DOXYGEN__) +  /** +   * @brief HTS221 block data update. +   */ +  hts221_bdu_t              blockdataupdate;
 +  /**
 +   * @brief   HTS221 humidity resolution.
 +   */
 +  hts221_avgh_t             reshumidity;
 +  /**
 +   * @brief   HTS221 temperature resolution.
 +   */
 +  hts221_avgt_t             restemperature; +#endif +} HTS221Config; + +/** + * @brief   Structure representing a HTS221 driver. + */ +typedef struct HTS221Driver HTS221Driver; + +/** + * @brief   @p HTS221Driver specific data. + */ +#define _hts221_data                                                        \ +  _base_hygrometer_data                                                     \
 +  _base_thermometer_data                                                    \ +  /* Driver state.*/                                                        \ +  hts221_state_t            state;                                          \ +  /* Current configuration data.*/                                          \ +  const HTS221Config        *config;                                        \ +  /* Current sensitivity data.*/                                            \ +  float                     sensitivity[HTS221_HYGRO_NUMBER_OF_AXES +       \
 +                                        HTS221_THERMO_NUMBER_OF_AXES];      \ +  /* Current Bias data.*/                                                   \ +  float                     bias[HTS221_HYGRO_NUMBER_OF_AXES +              \
 +                                 HTS221_THERMO_NUMBER_OF_AXES]; + +/** + * @extends BaseGyroscope + * + * @brief   HTS221 3-axis barometer class. + * @details This class extends @p BaseGyroscope by adding physical + *          driver implementation. + */ +struct HTS221Driver { +  /** @brief BaseSensor Virtual Methods Table. */ +  const struct BaseSensorVMT *vmt_basesensor; +  /** @brief BaseHygrometer Virtual Methods Table. */ +  const struct BaseHygrometerVMT *vmt_basehygrometer;
 +	  /** @brief BaseThermometer Virtual Methods Table. */
 +  const struct BaseThermometerVMT *vmt_basethermometer; +  _hts221_data +}; +/** @} */ + +/*===========================================================================*/ +/* Driver macros.                                                            */ +/*===========================================================================*/ +        +/*===========================================================================*/ +/* External declarations.                                                    */ +/*===========================================================================*/ + +#ifdef __cplusplus +extern "C" { +#endif +  void hts221ObjectInit(HTS221Driver *devp); +  void hts221Start(HTS221Driver *devp, const HTS221Config *config); +  void hts221Stop(HTS221Driver *devp); +#ifdef __cplusplus +} +#endif + +#endif /* _HTS221_H_ */ + +/** @} */ + diff --git a/os/ex/ST/hts221.mk b/os/ex/ST/hts221.mk new file mode 100644 index 000000000..7e8c8d7e4 --- /dev/null +++ b/os/ex/ST/hts221.mk @@ -0,0 +1,6 @@ +# List of all the HTS221 device files.
 +HTS221SRC := $(CHIBIOS)/os/ex/ST/hts221.c
 +
 +# Required include directories
 +HTS221INC := $(CHIBIOS)/os/hal/lib/peripherals/sensors \
 +             $(CHIBIOS)/os/ex/ST
\ No newline at end of file  | 
