drivers/ph_oem: Initial implementation of the pH OEM sensor

The Atlas Scientific pH OEM sensor is a small circuit to be embedded in
end products to measure the pH value with any commercially available pH
electrode
This commit is contained in:
Igor Knippenberg 2019-02-10 22:59:04 +01:00
parent 0d4f7b2715
commit ead03d4a08
8 changed files with 1087 additions and 0 deletions

View File

@ -375,6 +375,12 @@ ifneq (,$(filter pcd8544,$(USEMODULE)))
USEMODULE += xtimer
endif
ifneq (,$(filter ph_oem,$(USEMODULE)))
FEATURES_REQUIRED += periph_gpio_irq
FEATURES_REQUIRED += periph_i2c
USEMODULE += xtimer
endif
ifneq (,$(filter pir,$(USEMODULE)))
FEATURES_REQUIRED += periph_gpio
FEATURES_REQUIRED += periph_gpio_irq

View File

@ -210,6 +210,10 @@ ifneq (,$(filter pcd8544,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/pcd8544/include
endif
ifneq (,$(filter ph_oem,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/ph_oem/include
endif
ifneq (,$(filter pir,$(USEMODULE)))
USEMODULE_INCLUDES += $(RIOTBASE)/drivers/pir/include
endif

362
drivers/include/ph_oem.h Normal file
View File

@ -0,0 +1,362 @@
/*
* Copyright (C) 2019 University of Applied Sciences Emden / Leer
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @defgroup drivers_ph_oem pH OEM sensor device driver
* @ingroup drivers_sensors
* @ingroup drivers_saul
* @brief Device driver for Atlas Scientific pH OEM sensor with SMBus/I2C interface
*
* The Atlas Scientific pH OEM sensor can be used with or without the interrupt
* pin. Per default this pin is mapped to @ref GPIO_UNDEF if not otherwise defined
* in your makefile.
*
* If you use an electrical isolation for most accurate readings
* e.g. with the ADM3260, keep in mind that its not recommended to use the
* interrupt pin without also isolating it somehow. The preferred method,
* if not using an isolation on the interrupt line, would be polling. In this case
* leave the interrupt pin undefined.
*
* The Sensor has no integrated temperature sensor and for the highest possible
* precision it requires another device to provide the temperature for error
* compensation.
*
* Once the pH OEM is powered on it will be ready to receive commands and take
* readings after 1ms.
*
* @note This driver provides @ref drivers_saul capabilities.
* Reading (@ref saul_driver_t.read) from the device returns the current pH value.
* Writing (@ref saul_driver_t.write) a temperature value in celsius to the
* device sets the temperature compensation. A valid temperature range is
* 1 - 20000 (0.01 °C to 200.0 °C)
*
* @note Communication is done using SMBus/I2C protocol at speeds
* of 10-100 kHz. Set your board I2C speed to @ref I2C_SPEED_LOW or
* @ref I2C_SPEED_NORMAL
*
* @{
*
* @file
* @brief Device driver for Atlas Scientific pH OEM Sensor with SMBus/I2C interface
* @author Igor Knippenberg <igor.knippenberg@gmail.com>
*/
#ifndef PH_OEM_H
#define PH_OEM_H
#ifdef __cplusplus
extern "C"
{
#endif
#include "periph/i2c.h"
#include "periph/gpio.h"
/**
* @brief Named return values
*/
typedef enum {
PH_OEM_OK = 0, /**< Everything was fine */
PH_OEM_NODEV = -1, /**< No device found on the bus */
PH_OEM_READ_ERR = -2, /**< Reading to device failed*/
PH_OEM_WRITE_ERR = -3, /**< Writing to device failed */
PH_OEM_NOT_PH = -4, /**< Not an Atlas Scientific pH OEM device */
PH_OEM_INTERRUPT_GPIO_UNDEF = -5, /**< Interrupt pin is @ref GPIO_UNDEF */
PH_OEM_GPIO_INIT_ERR = -6, /**< Error while initializing GPIO PIN */
PH_OEM_TEMP_OUT_OF_RANGE = -7 /**< Temperature is out of range */
} ph_oem_named_returns_t;
/**
* @brief LED state values
*/
typedef enum {
PH_OEM_LED_ON = 0x01, /**< LED on state */
PH_OEM_LED_OFF = 0x00, /**< LED off state */
} ph_oem_led_state_t;
/**
* @brief Device state values
*/
typedef enum {
PH_OEM_TAKE_READINGS = 0x01, /**< Device active state */
PH_OEM_STOP_READINGS = 0x00, /**< Device hibernate state */
} ph_oem_device_state_t;
/**
* @brief Interrupt pin option values
*/
typedef enum {
PH_OEM_IRQ_RISING = 0x02, /**< Pin high on new reading (manually reset) */
PH_OEM_IRQ_FALLING = 0x04, /**< Pin low on new reading (manually reset) */
PH_OEM_IRQ_BOTH = 0x08, /**< Invert state on new reading (automatically reset) */
} ph_oem_irq_option_t;
/**
* @brief Calibration option values
*/
typedef enum {
PH_OEM_CALIBRATE_LOW_POINT = 0x02, /**< Low point calibration option */
PH_OEM_CALIBRATE_MID_POINT = 0x03, /**< Mid point calibration option */
PH_OEM_CALIBRATE_HIGH_POINT = 0x04, /**< High point calibration option */
} ph_oem_calibration_option_t;
/**
* @brief pH OEM sensor params
*/
typedef struct ph_oem_params {
i2c_t i2c; /**< I2C device the sensor is connected to */
uint8_t addr; /**< the slave address of the sensor on the I2C bus */
gpio_t interrupt_pin; /**< interrupt pin (@ref GPIO_UNDEF if not defined) */
gpio_mode_t gpio_mode; /**< gpio mode of the interrupt pin */
ph_oem_irq_option_t irq_option; /**< behavior of the interrupt pin, disabled by default */
} ph_oem_params_t;
/**
* @brief pH OEM interrupt pin callback
*/
typedef void (*ph_oem_interrupt_pin_cb_t)(void *);
/**
* @brief pH OEM device descriptor
*/
typedef struct ph_oem {
ph_oem_params_t params; /**< device driver configuration */
ph_oem_interrupt_pin_cb_t cb; /**< interrupt pin callback */
void *arg; /**< interrupt pin callback param */
} ph_oem_t;
/**
* @brief Initialize a pH OEM sensor
*
* @param[in,out] dev device descriptor
* @param[in] params device configuration
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_NODEV if no device is found on the bus
* @return @ref PH_OEM_NOT_PH if the device found at the address is not a pH OEM device
* @return
*/
int ph_oem_init(ph_oem_t *dev, const ph_oem_params_t *params);
/**
* @brief Sets a new address to the pH OEM device by unlocking the
* @ref PH_OEM_REG_UNLOCK register and writing a new address to
* the @ref PH_OEM_REG_ADDRESS register.
* The device address will also be updated in the device descriptor so
* it is still usable.
*
* Settings are retained in the sensor if the power is cut.
*
* The address in the device descriptor will reverse to the default
* address you provided through PH_OEM_PARAM_ADDR after the
* microcontroller restarts
*
* @param[in] dev device descriptor
* @param[in] addr new address for the device. Range: 0x01 - 0x7f
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_WRITE_ERR if writing to the device failed
*/
int ph_oem_set_i2c_address(ph_oem_t *dev, uint8_t addr);
/**
* @brief Enable the pH OEM interrupt pin if @ref ph_oem_params_t.interrupt_pin
* is defined.
* @note @ref ph_oem_reset_interrupt_pin needs to be called in the
* callback if you use @ref PH_OEM_IRQ_FALLING or @ref PH_OEM_IRQ_RISING
*
* @note Provide the PH_OEM_PARAM_INTERRUPT_OPTION flag in your
* makefile. Valid options see: @ref ph_oem_irq_option_t.
* The default is @ref PH_OEM_IRQ_BOTH.
*
* @note Also provide the @ref gpio_mode_t as a CFLAG in your makefile.
* Most likely @ref GPIO_IN. If the pin is to sensitive use
* @ref GPIO_IN_PU for @ref PH_OEM_IRQ_FALLING or
* @ref GPIO_IN_PD for @ref PH_OEM_IRQ_RISING and
* @ref PH_OEM_IRQ_BOTH. The default is @ref GPIO_IN_PD
*
*
* @param[in] dev device descriptor
* @param[in] cb callback called when the pH OEM interrupt pin fires
* @param[in] arg callback argument
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_WRITE_ERR if writing to the device failed
* @return @ref PH_OEM_INTERRUPT_GPIO_UNDEF if the interrupt pin is undefined
* @return @ref PH_OEM_GPIO_INIT_ERR if initializing the interrupt gpio pin failed
*/
int ph_oem_enable_interrupt(ph_oem_t *dev, ph_oem_interrupt_pin_cb_t cb,
void *arg);
/**
* @brief The interrupt pin will not auto reset on option @ref PH_OEM_IRQ_RISING
* and @ref PH_OEM_IRQ_FALLING after interrupt fires,
* so call this function again to reset the pin state.
*
* @note The interrupt settings are not retained if the power is cut,
* so you have to call this function again after powering on the device.
*
* @param[in] dev device descriptor
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_WRITE_ERR if writing to the device failed
*/
int ph_oem_reset_interrupt_pin(const ph_oem_t *dev);
/**
* @brief Set the LED state of the pH OEM sensor by writing to the
* @ref PH_OEM_REG_LED register
*
* @param[in] dev device descriptor
* @param[in] state @ref ph_oem_led_state_t
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_WRITE_ERR if writing to the device failed
*/
int ph_oem_set_led_state(const ph_oem_t *dev, ph_oem_led_state_t state);
/**
* @brief Sets the device state (active/hibernate) of the pH OEM sensor by
* writing to the @ref PH_OEM_REG_HIBERNATE register.
*
* @note Once the device has been woken up it will continuously take
* readings every 420ms. Waking the device is the only way to take a
* reading. Hibernating the device is the only way to stop taking readings.
*
* @param[in] dev device descriptor
* @param[in] state @ref ph_oem_device_state_t
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_WRITE_ERR if writing to the device failed
*/
int ph_oem_set_device_state(const ph_oem_t *dev, ph_oem_device_state_t state);
/**
* @brief Starts a new reading by setting the device state to
* @ref PH_OEM_TAKE_READINGS.
*
* @note If the @ref ph_oem_params_t.interrupt_pin is @ref GPIO_UNDEF
* this function will poll every 20ms till a reading is done (~420ms)
* and stop the device from taking further readings
*
* @param[in] dev device descriptor
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_WRITE_ERR if writing to the device failed
* @return @ref PH_OEM_READ_ERR if reading from the device failed
*/
int ph_oem_start_new_reading(const ph_oem_t *dev);
/**
* @brief Clears all calibrations previously done
*
* @param[in] dev device descriptor
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_WRITE_ERR if writing to the device failed
* @return @ref PH_OEM_READ_ERR if reading from the device failed
*/
int ph_oem_clear_calibration(const ph_oem_t *dev);
/**
* @brief Sets the @ref PH_OEM_REG_CALIBRATION_BASE register to the
* calibration_value which the pH OEM sensor will be
* calibrated to. Multiply the floating point calibration value of your
* solution by 1000 e.g. pH calibration solution => 7.002 * 1000 = 7002 = 0x00001B5A
*
* The calibration value will be saved based on the given
* @ref ph_oem_calibration_option_t and retained after the power is cut.
*
* @note Calibrating with @ref PH_OEM_CALIBRATE_MID_POINT will reset the
* previous calibrations.
* Always start with @ref PH_OEM_CALIBRATE_MID_POINT if you doing
* 2 or 3 point calibration
*
* @param[in] dev device descriptor
* @param[in] calibration_value pH value multiplied by 1000 e.g 7,002 * 1000 = 7002
* @param[in] option @ref ph_oem_calibration_option_t
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_WRITE_ERR if writing to the device failed
* @return @ref PH_OEM_READ_ERR if reading from the device failed
*/
int ph_oem_set_calibration(const ph_oem_t *dev, uint16_t calibration_value,
ph_oem_calibration_option_t option);
/**
* @brief Read the @ref PH_OEM_REG_CALIBRATION_CONFIRM register.
* After a calibration event has been successfully carried out, the
* calibration confirmation register will reflect what calibration has
* been done, by setting bits 0 - 2.
*
* @param[in] dev device descriptor
* @param[out] calibration_state calibration state reflected by bits 0 - 2 <br>
* (0 = low, 1 = mid, 2 = high)
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_READ_ERR if reading from the device failed
*/
int ph_oem_read_calibration_state(const ph_oem_t *dev, uint16_t *calibration_state);
/**
* @brief Sets the @ref PH_OEM_REG_TEMP_COMPENSATION_BASE register to the
* temperature_compensation value which the pH OEM sensor will use
* to compensate the reading error.
* Multiply the floating point temperature value by 100
* e.g. temperature in degree Celsius = 34.26 * 100 = 3426
*
* @note The temperature compensation will not be retained if the power is cut.
*
* @param[in] dev device descriptor
* @param[in] temperature_compensation valid temperature range is
* 1 - 20000 (0.01 °C to 200.0 °C)
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_WRITE_ERR if writing to the device failed
* @return @ref PH_OEM_TEMP_OUT_OF_RANGE if the temperature_compensation is not in
* the valid range
*/
int ph_oem_set_compensation(const ph_oem_t *dev,
uint16_t temperature_compensation);
/**
* @brief Reads the @ref PH_OEM_REG_TEMP_CONFIRMATION_BASE register to verify
* the temperature compensation value that was used to take the pH
* reading is set to the correct temperature.
*
* @param[in] dev device descriptor
* @param[out] temperature_compensation raw temperature compensation value. <br>
* Divide by 100 for floating point <br>
* e.g 3426 / 100 = 34.26
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_READ_ERR if reading from the device failed
*/
int ph_oem_read_compensation(const ph_oem_t *dev,
uint16_t *temperature_compensation);
/**
* @brief Reads the @ref PH_OEM_REG_PH_READING_BASE register to get the current
* pH reading.
*
* @param[in] dev device descriptor
* @param[out] ph_value raw pH value <br>
* divide by 1000 for floating point <br>
* e.g 8347 / 1000 = 8.347
*
* @return @ref PH_OEM_OK on success
* @return @ref PH_OEM_READ_ERR if reading from the device failed
*/
int ph_oem_read_ph(const ph_oem_t *dev, uint16_t *ph_value);
#ifdef __cplusplus
}
#endif
#endif /* PH_OEM_H */
/** @} */

1
drivers/ph_oem/Makefile Normal file
View File

@ -0,0 +1 @@
include $(RIOTBASE)/Makefile.base

View File

@ -0,0 +1,83 @@
/*
* Copyright (C) 2019 University of Applied Sciences Emden / Leer
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup drivers_ph_oem
* @{
*
* @file
* @brief Default configuration for Atlas Scientific pH OEM sensors
*
* @author Igor Knippenberg <igor.knippenberg@gmail.com>
*/
#ifndef PH_OEM_PARAMS_H
#define PH_OEM_PARAMS_H
#include "board.h" /* THIS INCLUDE IS MANDATORY */
#include "saul_reg.h"
#include "ph_oem.h"
#include "ph_oem_regs.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @name Set default configuration parameters for the Atlas Scientific pH OEM driver
* @{
*/
#ifndef PH_OEM_PARAM_I2C
#define PH_OEM_PARAM_I2C (I2C_DEV(0))
#endif
#ifndef PH_OEM_PARAM_ADDR
#define PH_OEM_PARAM_ADDR (0x65)
#endif
#ifndef PH_OEM_PARAM_INTERRUPT_PIN
#define PH_OEM_PARAM_INTERRUPT_PIN (GPIO_UNDEF)
#endif
#ifndef PH_OEM_PARAM_INTERRUPT_OPTION
#define PH_OEM_PARAM_INTERRUPT_OPTION (PH_OEM_IRQ_BOTH)
#endif
#ifndef PH_OEM_PARAM_INTERRUPT_GPIO_MODE
#define PH_OEM_PARAM_INTERRUPT_GPIO_MODE (GPIO_IN_PD)
#endif
#ifndef PH_OEM_PARAMS
#define PH_OEM_PARAMS { .i2c = PH_OEM_PARAM_I2C, \
.addr = PH_OEM_PARAM_ADDR, \
.interrupt_pin = PH_OEM_PARAM_INTERRUPT_PIN, \
.gpio_mode = PH_OEM_PARAM_INTERRUPT_GPIO_MODE, \
.irq_option = PH_OEM_PARAM_INTERRUPT_OPTION }
#endif
#ifndef PH_OEM_SAUL_INFO
#define PH_OEM_SAUL_INFO { .name = "pH OEM sensor" }
#endif
/** @} */
/**
* @brief pH OEM defaults if not defined for a board or application
*/
static const ph_oem_params_t ph_oem_params[] =
{
PH_OEM_PARAMS
};
/**
* @brief Additional meta information to keep in the SAUL registry
*/
static const saul_reg_info_t ph_oem_saul_info[] =
{
PH_OEM_SAUL_INFO
};
#ifdef __cplusplus
}
#endif
#endif /* PH_OEM_PARAMS_H */
/** @} */

View File

@ -0,0 +1,61 @@
/*
* Copyright (C) 2019 University of Applied Sciences Emden / Leer
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup drivers_ph_oem
* @{
*
* @file
* @brief Register definitions for the Atlas Scientific pH OEM sensor.
*
* @author Igor Knippenberg <igor.knippenberg@gmail.com>
*/
#ifndef PH_OEM_REGS_H
#define PH_OEM_REGS_H
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Atlas Scientific pH OEM register addresses
*
* All registers in the pH OEM are 8 bit wide and transmitted MSB first.
*
*/
typedef enum ph_oem_reg {
PH_OEM_REG_DEVICE_TYPE = 0x00, /**< Device type register (read only) */
PH_OEM_REG_FIRMWARE_VERSION = 0x01, /**< Firmware version register (read only) */
PH_OEM_REG_UNLOCK = 0x02, /**< SMBus/I²C address lock/unlock register (read/write) */
PH_OEM_REG_ADDRESS = 0x03, /**< SMBus/I²C address register (read/write) */
PH_OEM_REG_INTERRUPT = 0x04, /**< Interrupt control register (read/write) */
PH_OEM_REG_LED = 0x05, /**< LED control register (read/write) */
PH_OEM_REG_HIBERNATE = 0x06, /**< Active/hibernate register (read/write) */
PH_OEM_REG_NEW_READING = 0x07, /**< New reading available register (read/write) */
PH_OEM_REG_CALIBRATION_BASE = 0x08, /**< Calibration value register base address. Register order is: MSB, high byte, low byte, LSB (0x08-0x0B) (read/write) */
PH_OEM_REG_CALIBRATION_REQUEST = 0x0C, /**< Calibration request register (read/write) */
PH_OEM_REG_CALIBRATION_CONFIRM = 0x0D, /**< Calibration confirm register (read/write) */
PH_OEM_REG_TEMP_COMPENSATION_BASE = 0x0E, /**< Temperature compensation register base address. Register order is: MSB, high byte, low byte, LSB (0x0E-0x11) (read/write) */
PH_OEM_REG_TEMP_CONFIRMATION_BASE = 0x12, /**< Temperature confirm register base address. Register order is: MSB, high byte, low byte, LSB (0x12-0x15) (read only) */
PH_OEM_REG_PH_READING_BASE = 0x16, /**< pH reading register base address, order= MSB, high byte, low byte, LSB (0x16-0x19) (read only) */
} ph_oem_reg_t;
/**
* @brief Device ID of the @ref PH_OEM_REG_DEVICE_TYPE register of a pH OEM sensor
*/
#define PH_OEM_DEVICE_TYPE_ID 0x01
#ifdef __cplusplus
}
#endif
#endif /* PH_OEM_REGS_H */
/** @} */

497
drivers/ph_oem/ph_oem.c Normal file
View File

@ -0,0 +1,497 @@
/*
* Copyright (C) 2019 University of Applied Sciences Emden / Leer
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup drivers_ph_oem
* @{
*
* @file
* @brief pH OEM device driver
*
* @author Igor Knippenberg <igor.knippenberg@gmail.com>
* @}
*/
#include "xtimer.h"
#include "assert.h"
#include "periph/i2c.h"
#include "periph/gpio.h"
#include "ph_oem.h"
#include "ph_oem_params.h"
#include "ph_oem_regs.h"
#define ENABLE_DEBUG (0)
#include "debug.h"
#define DEV_I2C (dev->params.i2c)
#define ADDR (dev->params.addr)
#define IRQ_OPTION (dev->params.irq_option)
/**
* @brief Unlocks the PH_OEM_REG_UNLOCK register to be able to change the
* I2C device address, by writing 0x55 and 0xAA to the register
*
* @param[in] dev device descriptor
*
* @return PH_OEM_OK on success
* @return PH_OEM_WRITE_ERR if writing to the device failed
*/
static int _unlock_address_reg(ph_oem_t *dev);
/**
* @brief Setting the pH OEM interrupt mode to the defined mode provided
* in the device descriptor
*
* @param[in] dev device descriptor
*
* @return PH_OEM_OK on success
* @return PH_OEM_WRITE_ERR if writing to the device failed
*/
static int _set_interrupt_pin(const ph_oem_t *dev);
/**
* @brief Polls the PH_OEM_REG_NEW_READING register as long as it does not
* equal 0x01, which indicates that a new pH reading is available.
* Polling is done in an interval of 20ms. Estimated completion ~420ms
*
* @param[in] dev device descriptor
*
* @return PH_OEM_OK on success
* @return PH_OEM_READ_ERR if reading from the register failed
* @return PH_OEM_WRITE_ERR if reseting the register failed
*/
static int _new_reading_available(const ph_oem_t *dev);
/**
* @brief Sets the PH_OEM_REG_CALIBRATION_BASE register to the pH
* @p calibration_value which the device will be calibrated to.
*
* @param[in] dev device descriptor
* @param[in] calibration_value pH value the device will be calibrated to
*
* @return PH_OEM_OK on success
* @return PH_OEM_READ_ERR if reading from the register failed
* @return PH_OEM_WRITE_ERR if writing the calibration_value to the device failed
*/
static int _set_calibration_value(const ph_oem_t *dev,
uint16_t calibration_value);
int ph_oem_init(ph_oem_t *dev, const ph_oem_params_t *params)
{
assert(dev && params);
dev->params = *params;
uint8_t reg_data;
i2c_acquire(DEV_I2C);
/* Register read test */
if (i2c_read_regs(DEV_I2C, ADDR, PH_OEM_REG_DEVICE_TYPE,
&reg_data, 1, 0x0) < 0) {
DEBUG("\n[ph_oem debug] init - error: unable to read reg %x\n",
PH_OEM_REG_DEVICE_TYPE);
i2c_release(DEV_I2C);
return PH_OEM_NODEV;
}
/* Test if the device ID of the attached pH OEM sensor equals the
* value of the PH_OEM_REG_DEVICE_TYPE register
* */
if (reg_data != PH_OEM_DEVICE_TYPE_ID) {
DEBUG("\n[ph_oem debug] init - error: the attached device is not a pH OEM "
"Sensor. Read Device Type ID is: %i\n",
reg_data);
i2c_release(DEV_I2C);
return PH_OEM_NOT_PH;
}
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
static int _unlock_address_reg(ph_oem_t *dev)
{
uint8_t reg_value = 1;
i2c_acquire(DEV_I2C);
i2c_write_reg(DEV_I2C, ADDR, PH_OEM_REG_UNLOCK, 0x55, 0x0);
i2c_write_reg(DEV_I2C, ADDR, PH_OEM_REG_UNLOCK, 0xAA, 0x0);
/* if successfully unlocked the register will equal 0x00 */
i2c_read_reg(DEV_I2C, ADDR, PH_OEM_REG_UNLOCK, &reg_value, 0x0);
if (reg_value != 0x00) {
DEBUG("\n[ph_oem debug] Failed at unlocking I2C address register. \n");
i2c_release(DEV_I2C);
return PH_OEM_WRITE_ERR;
}
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
int ph_oem_set_i2c_address(ph_oem_t *dev, uint8_t addr)
{
assert(dev);
if (_unlock_address_reg(dev) != PH_OEM_OK) {
return PH_OEM_WRITE_ERR;
}
i2c_acquire(DEV_I2C);
if (i2c_write_reg(DEV_I2C, ADDR, PH_OEM_REG_ADDRESS, addr, 0x0) < 0) {
DEBUG("\n[ph_oem debug] Setting I2C address to %x failed\n", addr);
i2c_release(DEV_I2C);
return PH_OEM_WRITE_ERR;
}
dev->params.addr = addr;
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
static int _set_interrupt_pin(const ph_oem_t *dev)
{
assert(dev);
i2c_acquire(DEV_I2C);
if (i2c_write_reg(DEV_I2C, ADDR, PH_OEM_REG_INTERRUPT, IRQ_OPTION,
0x0) < 0) {
DEBUG("\n[ph_oem debug] Setting interrupt pin to option %d failed.\n",
IRQ_OPTION);
i2c_release(DEV_I2C);
return PH_OEM_WRITE_ERR;
}
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
int ph_oem_enable_interrupt(ph_oem_t *dev, ph_oem_interrupt_pin_cb_t cb,
void *arg)
{
if (dev->params.interrupt_pin == GPIO_UNDEF) {
return PH_OEM_INTERRUPT_GPIO_UNDEF;
}
if (_set_interrupt_pin(dev) < 0) {
return PH_OEM_WRITE_ERR;
}
int gpio_flank = 0;
switch (IRQ_OPTION) {
case PH_OEM_IRQ_FALLING:
gpio_flank = GPIO_FALLING;
break;
case PH_OEM_IRQ_RISING:
gpio_flank = GPIO_RISING;
break;
case PH_OEM_IRQ_BOTH:
gpio_flank = GPIO_BOTH;
break;
}
dev->arg = arg;
dev->cb = cb;
if (gpio_init_int(dev->params.interrupt_pin,
dev->params.gpio_mode, gpio_flank, cb, arg) < 0) {
DEBUG("\n[ph_oem debug] Initializing interrupt gpio pin failed.\n");
return PH_OEM_GPIO_INIT_ERR;
}
return PH_OEM_OK;
}
int ph_oem_reset_interrupt_pin(const ph_oem_t *dev)
{
/* no reset needed for mode PH_OEM_IRQ_BOTH */
if (dev->params.irq_option == PH_OEM_IRQ_BOTH) {
return PH_OEM_OK;
}
if (_set_interrupt_pin(dev) < 0) {
return PH_OEM_WRITE_ERR;
}
return PH_OEM_OK;
}
int ph_oem_set_led_state(const ph_oem_t *dev, ph_oem_led_state_t state)
{
assert(dev);
i2c_acquire(DEV_I2C);
if (i2c_write_reg(DEV_I2C, ADDR, PH_OEM_REG_LED, state, 0x0) < 0) {
DEBUG("\n[ph_oem debug] Setting LED state to %d failed.\n", state);
i2c_release(DEV_I2C);
return PH_OEM_WRITE_ERR;
}
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
int ph_oem_set_device_state(const ph_oem_t *dev, ph_oem_device_state_t state)
{
assert(dev);
i2c_acquire(DEV_I2C);
if (i2c_write_reg(DEV_I2C, ADDR, PH_OEM_REG_HIBERNATE, state, 0x0) < 0) {
DEBUG("\n[ph_oem debug] Setting device state to %d failed\n", state);
i2c_release(DEV_I2C);
return PH_OEM_WRITE_ERR;
}
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
static int _new_reading_available(const ph_oem_t *dev)
{
int8_t new_reading_available;
assert(dev);
i2c_acquire(DEV_I2C);
do {
if (i2c_read_reg(DEV_I2C, ADDR, PH_OEM_REG_NEW_READING,
&new_reading_available, 0x0) < 0) {
DEBUG("\n[ph_oem debug] Failed at reading PH_OEM_REG_NEW_READING\n");
i2c_release(DEV_I2C);
return PH_OEM_READ_ERR;
}
xtimer_usleep(20 * US_PER_MS);
} while (new_reading_available == 0);
/* need to manually reset register back to 0x00 */
if (i2c_write_reg(DEV_I2C, ADDR, PH_OEM_REG_NEW_READING, 0x00, 0x0) < 0) {
DEBUG("\n[ph_oem debug] Resetting PH_OEM_REG_NEW_READING failed\n");
i2c_release(DEV_I2C);
return PH_OEM_WRITE_ERR;
}
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
int ph_oem_start_new_reading(const ph_oem_t *dev)
{
if (ph_oem_set_device_state(dev, PH_OEM_TAKE_READINGS) < 0) {
return PH_OEM_WRITE_ERR;
}
/* if interrupt pin is undefined, poll till new reading was taken and stop
* device form taking further readings */
if (dev->params.interrupt_pin == GPIO_UNDEF) {
int result = _new_reading_available(dev);
if (result < 0) {
return result;
}
if (ph_oem_set_device_state(dev, PH_OEM_STOP_READINGS) < 0) {
return PH_OEM_WRITE_ERR;
}
}
return PH_OEM_OK;
}
int ph_oem_clear_calibration(const ph_oem_t *dev)
{
uint8_t reg_value;
assert(dev);
i2c_acquire(DEV_I2C);
if (i2c_write_reg(DEV_I2C, ADDR, PH_OEM_REG_CALIBRATION_REQUEST, 0x01,
0) < 0) {
DEBUG("\n[ph_oem debug] Clearing calibration failed \n");
i2c_release(DEV_I2C);
return PH_OEM_WRITE_ERR;
}
do {
if (i2c_read_reg(DEV_I2C, ADDR, PH_OEM_REG_CALIBRATION_REQUEST,
&reg_value,
0) < 0) {
i2c_release(DEV_I2C);
return PH_OEM_READ_ERR;
}
} while (reg_value != 0x00);
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
static int _set_calibration_value(const ph_oem_t *dev,
uint16_t calibration_value)
{
uint8_t reg_value[4];
reg_value[0] = 0x00;
reg_value[1] = 0x00;
reg_value[2] = (uint8_t)(calibration_value >> 8);
reg_value[3] = (uint8_t)(calibration_value & 0x00FF);
i2c_acquire(DEV_I2C);
if (i2c_write_regs(DEV_I2C, ADDR, PH_OEM_REG_CALIBRATION_BASE, &reg_value,
4, 0) < 0) {
DEBUG("\n[ph_oem debug] Writing calibration value failed \n");
i2c_release(DEV_I2C);
return PH_OEM_WRITE_ERR;
}
/* Calibration is critical, so check if written value is in fact correct */
if (i2c_read_regs(DEV_I2C, ADDR, PH_OEM_REG_CALIBRATION_BASE, &reg_value, 4,
0) < 0) {
DEBUG("\n[ph_oem debug] Reading the calibration value failed \n");
i2c_release(DEV_I2C);
return PH_OEM_READ_ERR;
}
uint16_t confirm_value = (int16_t)(reg_value[2] << 8)
| (int16_t)(reg_value[3]);
if (confirm_value != calibration_value) {
DEBUG("\n[ph_oem debug] Setting calibration register to pH raw %d "
"failed \n", calibration_value);
i2c_release(DEV_I2C);
return PH_OEM_WRITE_ERR;
}
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
int ph_oem_set_calibration(const ph_oem_t *dev, uint16_t calibration_value,
ph_oem_calibration_option_t option)
{
assert(dev);
if (_set_calibration_value(dev, calibration_value) != PH_OEM_OK) {
return PH_OEM_WRITE_ERR;
}
uint8_t reg_value;
i2c_acquire(DEV_I2C);
if (i2c_write_reg(DEV_I2C, ADDR, PH_OEM_REG_CALIBRATION_REQUEST,
option, 0) < 0) {
DEBUG("\n[ph_oem debug] Sending calibration request failed\n");
return PH_OEM_WRITE_ERR;
}
do {
if (i2c_read_reg(DEV_I2C, ADDR, PH_OEM_REG_CALIBRATION_REQUEST,
&reg_value,
0) < 0) {
DEBUG("\n[ph_oem debug] Reading calibration request status failed\n");
i2c_release(DEV_I2C);
return PH_OEM_READ_ERR;
}
} while (reg_value != 0x00);
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
int ph_oem_read_calibration_state(const ph_oem_t *dev,
uint16_t *calibration_state)
{
assert(dev);
i2c_acquire(DEV_I2C);
if (i2c_read_reg(DEV_I2C, ADDR, PH_OEM_REG_CALIBRATION_CONFIRM,
calibration_state, 0) < 0) {
DEBUG(
"\n[ph_oem debug] Failed at reading calibration confirm register\n");
i2c_release(DEV_I2C);
return PH_OEM_READ_ERR;
}
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
int ph_oem_set_compensation(const ph_oem_t *dev,
uint16_t temperature_compensation)
{
if (!(temperature_compensation >= 1 && temperature_compensation <= 20000)) {
return PH_OEM_TEMP_OUT_OF_RANGE;
}
assert(dev);
uint8_t reg_value[4];
reg_value[0] = 0x00;
reg_value[1] = 0x00;
reg_value[2] = (uint8_t)(temperature_compensation >> 8);
reg_value[3] = (uint8_t)(temperature_compensation & 0x00FF);
i2c_acquire(DEV_I2C);
if (i2c_write_regs(DEV_I2C, ADDR, PH_OEM_REG_TEMP_COMPENSATION_BASE,
&reg_value, 4, 0) < 0) {
DEBUG("\n[ph_oem debug] Setting temperature compensation of device to "
"%d failed\n", temperature_compensation);
i2c_release(DEV_I2C);
return PH_OEM_WRITE_ERR;
}
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
int ph_oem_read_compensation(const ph_oem_t *dev,
uint16_t *temperature_compensation)
{
uint8_t reg_value[4];
assert(dev);
i2c_acquire(DEV_I2C);
if (i2c_read_regs(DEV_I2C, ADDR, PH_OEM_REG_TEMP_CONFIRMATION_BASE,
&reg_value, 4, 0) < 0) {
DEBUG("[ph_oem debug] Getting temperature compensation value failed\n");
i2c_release(DEV_I2C);
return PH_OEM_READ_ERR;
}
*temperature_compensation = (int16_t)(reg_value[2] << 8) |
(int16_t)(reg_value[3]);
i2c_release(DEV_I2C);
return PH_OEM_OK;
}
int ph_oem_read_ph(const ph_oem_t *dev, uint16_t *ph_value)
{
uint8_t reg_value[4];
assert(dev);
i2c_acquire(DEV_I2C);
if (i2c_read_regs(DEV_I2C, ADDR, PH_OEM_REG_PH_READING_BASE,
&reg_value, 4, 0) < 0) {
DEBUG("[ph_oem debug] Getting pH value failed\n");
i2c_release(DEV_I2C);
return PH_OEM_READ_ERR;
}
*ph_value = (int16_t)(reg_value[2] << 8) | (int16_t)(reg_value[3]);
i2c_release(DEV_I2C);
return PH_OEM_OK;
}

View File

@ -0,0 +1,73 @@
/*
* Copyright (C) 2019 University of Applied Sciences Emden / Leer
*
* This file is subject to the terms and conditions of the GNU Lesser
* General Public License v2.1. See the file LICENSE in the top level
* directory for more details.
*/
/**
* @ingroup drivers_ph_oem
* @{
*
* @file
* @brief pH OEM adaption to the sensor/actuator abstraction layer
*
* @author Igor Knippenberg <igor.knippenberg@gmail.com>
*
* @}
*/
#include <string.h>
#include <stdio.h>
#include "saul.h"
#include "ph_oem.h"
#include "ph_oem_regs.h"
static int read_ph(const void *dev, phydat_t *res)
{
const ph_oem_t *mydev = dev;
uint16_t ph_reading;
if (mydev->params.interrupt_pin != GPIO_UNDEF) {
puts("interrupt pin not supported with SAUL yet");
return -ENOTSUP;
}
if (ph_oem_start_new_reading(mydev) < 0) {
return -ECANCELED;
}
/* Read raw pH value */
if (ph_oem_read_ph(mydev, &ph_reading) < 0) {
return -ECANCELED;
}
res->val[0] = (int16_t)ph_reading;
res->unit = UNIT_PH;
res->scale = -3;
return 1;
}
/* Sets the temperature compensation for taking accurate pH readings.
* Valid temperature range is 1 - 20000 (0.01 °C to 200.0 °C) */
static int set_temp_compensation(const void *dev, phydat_t *res)
{
const ph_oem_t *mydev = dev;
if (!(res->val[0] >= 1 && res->val[0] <= 20000)) {
return -ECANCELED;
}
if (ph_oem_set_compensation(mydev, res->val[0]) < 0) {
return -ECANCELED;
}
return 1;
}
const saul_driver_t ph_oem_saul_driver = {
.read = read_ph,
.write = set_temp_compensation,
.type = SAUL_SENSE_PH,
};