From b385933fa811443310b978370d1c2947cbd8688b Mon Sep 17 00:00:00 2001 From: Jonas Olsson Date: Wed, 25 Feb 2015 13:11:09 +0100 Subject: [PATCH] Add SensorTag CC2650 files --- .../srf06-cc26xx/sensortag/Makefile.sensortag | 8 + .../srf06-cc26xx/sensortag/bmp-280-sensor.c | 391 ++++++++++ .../srf06-cc26xx/sensortag/bmp-280-sensor.h | 70 ++ platform/srf06-cc26xx/sensortag/board-i2c.c | 269 +++++++ platform/srf06-cc26xx/sensortag/board-i2c.h | 108 +++ .../sensortag/board-peripherals.h | 56 ++ platform/srf06-cc26xx/sensortag/board-spi.c | 118 +++ platform/srf06-cc26xx/sensortag/board-spi.h | 90 +++ platform/srf06-cc26xx/sensortag/board.c | 152 ++++ platform/srf06-cc26xx/sensortag/board.h | 206 ++++++ .../srf06-cc26xx/sensortag/button-sensor.c | 282 +++++++ .../srf06-cc26xx/sensortag/button-sensor.h | 66 ++ platform/srf06-cc26xx/sensortag/buzzer.c | 124 ++++ platform/srf06-cc26xx/sensortag/buzzer.h | 74 ++ platform/srf06-cc26xx/sensortag/ext-flash.c | 409 +++++++++++ platform/srf06-cc26xx/sensortag/ext-flash.h | 103 +++ platform/srf06-cc26xx/sensortag/leds-arch.c | 81 +++ .../srf06-cc26xx/sensortag/mpu-9250-sensor.c | 685 ++++++++++++++++++ .../srf06-cc26xx/sensortag/mpu-9250-sensor.h | 112 +++ .../srf06-cc26xx/sensortag/opt-3001-sensor.c | 273 +++++++ .../srf06-cc26xx/sensortag/opt-3001-sensor.h | 67 ++ platform/srf06-cc26xx/sensortag/reed-relay.c | 140 ++++ platform/srf06-cc26xx/sensortag/reed-relay.h | 59 ++ .../srf06-cc26xx/sensortag/sensor-common.c | 79 ++ .../srf06-cc26xx/sensortag/sensor-common.h | 85 +++ .../sensortag/sensortag-sensors.c | 55 ++ .../srf06-cc26xx/sensortag/sht-21-sensor.c | 386 ++++++++++ .../srf06-cc26xx/sensortag/sht-21-sensor.h | 85 +++ .../srf06-cc26xx/sensortag/tmp-007-sensor.c | 315 ++++++++ .../srf06-cc26xx/sensortag/tmp-007-sensor.h | 76 ++ 30 files changed, 5024 insertions(+) create mode 100644 platform/srf06-cc26xx/sensortag/Makefile.sensortag create mode 100644 platform/srf06-cc26xx/sensortag/bmp-280-sensor.c create mode 100644 platform/srf06-cc26xx/sensortag/bmp-280-sensor.h create mode 100644 platform/srf06-cc26xx/sensortag/board-i2c.c create mode 100644 platform/srf06-cc26xx/sensortag/board-i2c.h create mode 100644 platform/srf06-cc26xx/sensortag/board-peripherals.h create mode 100644 platform/srf06-cc26xx/sensortag/board-spi.c create mode 100644 platform/srf06-cc26xx/sensortag/board-spi.h create mode 100644 platform/srf06-cc26xx/sensortag/board.c create mode 100644 platform/srf06-cc26xx/sensortag/board.h create mode 100644 platform/srf06-cc26xx/sensortag/button-sensor.c create mode 100644 platform/srf06-cc26xx/sensortag/button-sensor.h create mode 100644 platform/srf06-cc26xx/sensortag/buzzer.c create mode 100644 platform/srf06-cc26xx/sensortag/buzzer.h create mode 100644 platform/srf06-cc26xx/sensortag/ext-flash.c create mode 100644 platform/srf06-cc26xx/sensortag/ext-flash.h create mode 100644 platform/srf06-cc26xx/sensortag/leds-arch.c create mode 100644 platform/srf06-cc26xx/sensortag/mpu-9250-sensor.c create mode 100644 platform/srf06-cc26xx/sensortag/mpu-9250-sensor.h create mode 100644 platform/srf06-cc26xx/sensortag/opt-3001-sensor.c create mode 100644 platform/srf06-cc26xx/sensortag/opt-3001-sensor.h create mode 100644 platform/srf06-cc26xx/sensortag/reed-relay.c create mode 100644 platform/srf06-cc26xx/sensortag/reed-relay.h create mode 100644 platform/srf06-cc26xx/sensortag/sensor-common.c create mode 100644 platform/srf06-cc26xx/sensortag/sensor-common.h create mode 100644 platform/srf06-cc26xx/sensortag/sensortag-sensors.c create mode 100644 platform/srf06-cc26xx/sensortag/sht-21-sensor.c create mode 100644 platform/srf06-cc26xx/sensortag/sht-21-sensor.h create mode 100644 platform/srf06-cc26xx/sensortag/tmp-007-sensor.c create mode 100644 platform/srf06-cc26xx/sensortag/tmp-007-sensor.h diff --git a/platform/srf06-cc26xx/sensortag/Makefile.sensortag b/platform/srf06-cc26xx/sensortag/Makefile.sensortag new file mode 100644 index 000000000..98fad7a68 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/Makefile.sensortag @@ -0,0 +1,8 @@ +CFLAGS += -DBOARD_SENSORTAG=1 -DTI_BSP_BOARD_HDR=\"ti-bsp-st.h\" +CFLAGS += -DBACKDOOR_IOID=0x00000000 + +BOARD_SOURCEFILES += leds-arch.c sensortag-sensors.c sensor-common.c +BOARD_SOURCEFILES += bmp-280-sensor.c tmp-007-sensor.c opt-3001-sensor.c +BOARD_SOURCEFILES += sht-21-sensor.c mpu-9250-sensor.c button-sensor.c +BOARD_SOURCEFILES += reed-relay.c ext-flash.c buzzer.c +BOARD_SOURCEFILES += board.c board-spi.c board-i2c.c diff --git a/platform/srf06-cc26xx/sensortag/bmp-280-sensor.c b/platform/srf06-cc26xx/sensortag/bmp-280-sensor.c new file mode 100644 index 000000000..a3b85ccc2 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/bmp-280-sensor.c @@ -0,0 +1,391 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-bmp-sensor + * @{ + * + * \file + * Driver for the Sensortag-CC26XX BMP280 Altimeter / Pressure Sensor + */ +/*---------------------------------------------------------------------------*/ +#include "contiki-conf.h" +#include "lib/sensors.h" +#include "bmp-280-sensor.h" +#include "sys/ctimer.h" +#include "sensor-common.h" +#include "board-i2c.h" +#include "ti-lib.h" + +#include +#include +#include +/*---------------------------------------------------------------------------*/ +#define DEBUG 0 +#if DEBUG +#define PRINTF(...) printf(__VA_ARGS__) +#else +#define PRINTF(...) +#endif +/*---------------------------------------------------------------------------*/ +#define BMP280_I2C_ADDRESS 0x77 +/*---------------------------------------------------------------------------*/ +/* Registers */ +#define ADDR_CALIB 0x88 +#define ADDR_PROD_ID 0xD0 +#define ADDR_RESET 0xE0 +#define ADDR_STATUS 0xF3 +#define ADDR_CTRL_MEAS 0xF4 +#define ADDR_CONFIG 0xF5 +#define ADDR_PRESS_MSB 0xF7 +#define ADDR_PRESS_LSB 0xF8 +#define ADDR_PRESS_XLSB 0xF9 +#define ADDR_TEMP_MSB 0xFA +#define ADDR_TEMP_LSB 0xFB +#define ADDR_TEMP_XLSB 0xFC +/*---------------------------------------------------------------------------*/ +/* Reset values */ +#define VAL_PROD_ID 0x58 +#define VAL_RESET 0x00 +#define VAL_STATUS 0x00 +#define VAL_CTRL_MEAS 0x00 +#define VAL_CONFIG 0x00 +#define VAL_PRESS_MSB 0x80 +#define VAL_PRESS_LSB 0x00 +#define VAL_TEMP_MSB 0x80 +#define VAL_TEMP_LSB 0x00 +/*---------------------------------------------------------------------------*/ +/* Test values */ +#define VAL_RESET_EXECUTE 0xB6 +#define VAL_CTRL_MEAS_TEST 0x55 +/*---------------------------------------------------------------------------*/ +/* Misc. */ +#define MEAS_DATA_SIZE 6 +#define CALIB_DATA_SIZE 24 +/*---------------------------------------------------------------------------*/ +#define RES_OFF 0 +#define RES_ULTRA_LOW_POWER 1 +#define RES_LOW_POWER 2 +#define RES_STANDARD 3 +#define RES_HIGH 5 +#define RES_ULTRA_HIGH 6 +/*---------------------------------------------------------------------------*/ +/* Bit fields in CTRL_MEAS register */ +#define PM_OFF 0 +#define PM_FORCED 1 +#define PM_NORMAL 3 +/*---------------------------------------------------------------------------*/ +#define OSRST(v) ((v) << 5) +#define OSRSP(v) ((v) << 2) +/*---------------------------------------------------------------------------*/ +typedef struct bmp_280_calibration { + uint16_t dig_t1; + int16_t dig_t2; + int16_t dig_t3; + uint16_t dig_p1; + int16_t dig_p2; + int16_t dig_p3; + int16_t dig_p4; + int16_t dig_p5; + int16_t dig_p6; + int16_t dig_p7; + int16_t dig_p8; + int16_t dig_p9; + int32_t t_fine; +} bmp_280_calibration_t; +/*---------------------------------------------------------------------------*/ +static uint8_t calibration_data[CALIB_DATA_SIZE]; +/*---------------------------------------------------------------------------*/ +#define SENSOR_STATUS_DISABLED 0 +#define SENSOR_STATUS_INITIALISED 1 +#define SENSOR_STATUS_NOT_READY 2 +#define SENSOR_STATUS_READY 3 + +static int enabled = SENSOR_STATUS_DISABLED; +/*---------------------------------------------------------------------------*/ +/* A buffer for the raw reading from the sensor */ +#define SENSOR_DATA_BUF_SIZE 6 + +static uint8_t sensor_value[SENSOR_DATA_BUF_SIZE]; +/*---------------------------------------------------------------------------*/ +/* Wait SENSOR_STARTUP_DELAY clock ticks for the sensor to be ready - ~80ms */ +#define SENSOR_STARTUP_DELAY 11 + +static struct ctimer startup_timer; +/*---------------------------------------------------------------------------*/ +static void +notify_ready(void *not_used) +{ + enabled = SENSOR_STATUS_READY; + sensors_changed(&bmp_280_sensor); +} +/*---------------------------------------------------------------------------*/ +static void +select(void) +{ + /* Set up I2C */ + board_i2c_select(BOARD_I2C_INTERFACE_0, BMP280_I2C_ADDRESS); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Initalise the sensor + */ +static void +init(void) +{ + uint8_t val; + + select(); + + /* Read and store calibration data */ + sensor_common_read_reg(ADDR_CALIB, calibration_data, CALIB_DATA_SIZE); + + /* Reset the sensor */ + val = VAL_RESET_EXECUTE; + sensor_common_write_reg(ADDR_RESET, &val, sizeof(val)); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Enable/disable measurements + * \param enable 0: disable, enable otherwise + * + * @return none + */ +static void +enable_sensor(bool enable) +{ + uint8_t val; + + select(); + + if(enable) { + /* Enable forced mode */ + val = PM_NORMAL | OSRSP(1) | OSRST(1); + } else { + val = PM_OFF; + } + sensor_common_write_reg(ADDR_CTRL_MEAS, &val, sizeof(val)); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Read temperature and pressure data + * \param data Pointer to a buffer where temperature and pressure will be + * written (6 bytes) + * \return True if valid data could be retrieved + */ +static bool +read_data(uint8_t *data) +{ + bool success; + + select(); + + success = sensor_common_read_reg(ADDR_PRESS_MSB, data, MEAS_DATA_SIZE); + if(!success) { + sensor_common_set_error_data(data, MEAS_DATA_SIZE); + } + + return success; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Convert raw data to values in degrees C (temp) and Pascal (pressure) + * \param data Pointer to a buffer that holds raw sensor data + * \param temp Pointer to a variable where the converted temperature will be + * written + * \param press Pointer to a variable where the converted pressure will be + * written + */ +static void +convert(uint8_t *data, int32_t *temp, uint32_t *press) +{ + int32_t utemp, upress; + bmp_280_calibration_t *p = (bmp_280_calibration_t *)calibration_data; + int32_t v_x1_u32r; + int32_t v_x2_u32r; + int32_t temperature; + uint32_t pressure; + + /* Pressure */ + upress = (int32_t)((((uint32_t)(data[0])) << 12) + | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4)); + + /* Temperature */ + utemp = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) + | ((uint32_t)data[5] >> 4)); + + /* Compensate temperature */ + v_x1_u32r = ((((utemp >> 3) - ((int32_t)p->dig_t1 << 1))) + * ((int32_t)p->dig_t2)) >> 11; + v_x2_u32r = (((((utemp >> 4) - ((int32_t)p->dig_t1)) + * ((utemp >> 4) - ((int32_t)p->dig_t1))) >> 12) + * ((int32_t)p->dig_t3)) + >> 14; + p->t_fine = v_x1_u32r + v_x2_u32r; + temperature = (p->t_fine * 5 + 128) >> 8; + *temp = temperature; + + /* Compensate pressure */ + v_x1_u32r = (((int32_t)p->t_fine) >> 1) - (int32_t)64000; + v_x2_u32r = (((v_x1_u32r >> 2) * (v_x1_u32r >> 2)) >> 11) + * ((int32_t)p->dig_p6); + v_x2_u32r = v_x2_u32r + ((v_x1_u32r * ((int32_t)p->dig_p5)) << 1); + v_x2_u32r = (v_x2_u32r >> 2) + (((int32_t)p->dig_p4) << 16); + v_x1_u32r = + (((p->dig_p3 * (((v_x1_u32r >> 2) * (v_x1_u32r >> 2)) >> 13)) >> 3) + + ((((int32_t)p->dig_p2) * v_x1_u32r) >> 1)) >> 18; + v_x1_u32r = ((((32768 + v_x1_u32r)) * ((int32_t)p->dig_p1)) >> 15); + + if(v_x1_u32r == 0) { + return; /* Avoid exception caused by division by zero */ + } + + pressure = (((uint32_t)(((int32_t)1048576) - upress) - (v_x2_u32r >> 12))) + * 3125; + if(pressure < 0x80000000) { + pressure = (pressure << 1) / ((uint32_t)v_x1_u32r); + } else { + pressure = (pressure / (uint32_t)v_x1_u32r) * 2; + } + + v_x1_u32r = (((int32_t)p->dig_p9) + * ((int32_t)(((pressure >> 3) * (pressure >> 3)) >> 13))) >> 12; + v_x2_u32r = (((int32_t)(pressure >> 2)) * ((int32_t)p->dig_p8)) >> 13; + pressure = (uint32_t)((int32_t)pressure + + ((v_x1_u32r + v_x2_u32r + p->dig_p7) >> 4)); + + *press = pressure; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Returns a reading from the sensor + * \param BMP_280_SENSOR_TYPE_TEMP or BMP_280_SENSOR_TYPE_PRESS + * \return Temperature (centi degrees C) or Pressure (Pascal). + */ +static int +value(int type) +{ + int rv; + int32_t temp = 0; + uint32_t pres = 0; + + if(enabled != SENSOR_STATUS_READY) { + PRINTF("Sensor disabled or starting up (%d)\n", enabled); + return CC26XX_SENSOR_READING_ERROR; + } + + if((type != BMP_280_SENSOR_TYPE_TEMP) && type != BMP_280_SENSOR_TYPE_PRESS) { + PRINTF("Invalid type\n"); + return CC26XX_SENSOR_READING_ERROR; + } else { + memset(sensor_value, 0, SENSOR_DATA_BUF_SIZE); + + rv = read_data(sensor_value); + + if(rv == 0) { + return CC26XX_SENSOR_READING_ERROR; + } + + PRINTF("val: %02x%02x%02x %02x%02x%02x\n", + sensor_value[0], sensor_value[1], sensor_value[2], + sensor_value[3], sensor_value[4], sensor_value[5]); + + convert(sensor_value, &temp, &pres); + + if(type == BMP_280_SENSOR_TYPE_TEMP) { + rv = (int)temp; + } else if(type == BMP_280_SENSOR_TYPE_PRESS) { + rv = (int)pres; + } + } + return rv; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Configuration function for the BMP280 sensor. + * + * \param type Activate, enable or disable the sensor. See below + * \param enable + * + * When type == SENSORS_HW_INIT we turn on the hardware + * When type == SENSORS_ACTIVE and enable==1 we enable the sensor + * When type == SENSORS_ACTIVE and enable==0 we disable the sensor + */ +static int +configure(int type, int enable) +{ + switch(type) { + case SENSORS_HW_INIT: + enabled = SENSOR_STATUS_INITIALISED; + init(); + break; + case SENSORS_ACTIVE: + /* Must be initialised first */ + if(enabled == SENSOR_STATUS_DISABLED) { + return SENSOR_STATUS_DISABLED; + } + if(enable) { + enable_sensor(1); + ctimer_set(&startup_timer, SENSOR_STARTUP_DELAY, notify_ready, NULL); + enabled = SENSOR_STATUS_NOT_READY; + } else { + ctimer_stop(&startup_timer); + enable_sensor(0); + enabled = SENSOR_STATUS_INITIALISED; + } + break; + default: + break; + } + return enabled; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Returns the status of the sensor + * \param type SENSORS_ACTIVE or SENSORS_READY + * \return 1 if the sensor is enabled + */ +static int +status(int type) +{ + switch(type) { + case SENSORS_ACTIVE: + case SENSORS_READY: + return enabled; + break; + default: + break; + } + return SENSOR_STATUS_DISABLED; +} +/*---------------------------------------------------------------------------*/ +SENSORS_SENSOR(bmp_280_sensor, "BMP280", value, configure, status); +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/bmp-280-sensor.h b/platform/srf06-cc26xx/sensortag/bmp-280-sensor.h new file mode 100644 index 000000000..e27013c40 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/bmp-280-sensor.h @@ -0,0 +1,70 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-bmp-sensor SensorTag 2.0 Pressure Sensor + * + * Due to the time required for the sensor to startup, this driver is meant to + * be used in an asynchronous fashion. The caller must first activate the + * sensor by calling SENSORS_ACTIVATE(). This will trigger the sensor's startup + * sequence, but the call will not wait for it to complete so that the CPU can + * perform other tasks or drop to a low power mode. + * + * Once the sensor is stable, the driver will generate a sensors_changed event. + * + * Once a reading has been taken, the caller has two options: + * - Turn the sensor off by calling SENSORS_DEACTIVATE, but in order to take + * subsequent readings SENSORS_ACTIVATE must be called again + * - Leave the sensor on. In this scenario, the caller can simply keep calling + * value() for subsequent readings, but having the sensor on will consume + * energy + * @{ + * + * \file + * Header file for the Sensortag-CC26xx BMP280 Altimeter / Pressure Sensor + */ +/*---------------------------------------------------------------------------*/ +#ifndef BMP_280_SENSOR_H_ +#define BMP_280_SENSOR_H_ +/*---------------------------------------------------------------------------*/ +#define BMP_280_SENSOR_TYPE_TEMP 1 +#define BMP_280_SENSOR_TYPE_PRESS 2 +/*---------------------------------------------------------------------------*/ +extern const struct sensors_sensor bmp_280_sensor; +/*---------------------------------------------------------------------------*/ +#endif /* BMP_280_SENSOR_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/board-i2c.c b/platform/srf06-cc26xx/sensortag/board-i2c.c new file mode 100644 index 000000000..0e1f544a6 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/board-i2c.c @@ -0,0 +1,269 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-i2c + * @{ + * + * \file + * Board-specific I2C driver for the Sensortag-CC26xx + */ +/*---------------------------------------------------------------------------*/ +#include "contiki-conf.h" +#include "ti-lib.h" +#include "board-i2c.h" +/*---------------------------------------------------------------------------*/ +static uint8_t slave_addr = 0x00; +static uint8_t interface = 0xFF; +/*---------------------------------------------------------------------------*/ +static bool +i2c_status() +{ + uint32_t status; + + status = ti_lib_i2c_master_err(I2C0_BASE); + if(status & (I2C_MSTAT_DATACK_N_M | I2C_MSTAT_ADRACK_N_M)) { + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_SEND_ERROR_STOP); + } + + return status == I2C_MASTER_ERR_NONE; +} +/*---------------------------------------------------------------------------*/ +void +board_i2c_init() +{ + /* The I2C peripheral must be enabled */ + ti_lib_prcm_peripheral_run_enable(PRCM_PERIPH_I2C0); + ti_lib_prcm_load_set(); + while(!ti_lib_prcm_load_get()); + + /* Reset the I2C controller */ + HWREG(PRCM_BASE + PRCM_O_RESETI2C) = PRCM_RESETI2C_I2C; + + /* Enable and initialize the I2C master module */ + ti_lib_i2c_master_init_exp_clk(I2C0_BASE, + ti_lib_sys_ctrl_peripheral_clock_get( + PRCM_PERIPH_I2C0, SYSCTRL_SYSBUS_ON), + true); +} +/*---------------------------------------------------------------------------*/ +bool +board_i2c_write(uint8_t *data, uint8_t len) +{ + uint32_t i; + bool success; + + /* Write slave address */ + ti_lib_i2c_master_slave_addr_set(I2C0_BASE, slave_addr, false); + + /* Write first byte */ + ti_lib_i2c_master_data_put(I2C0_BASE, data[0]); + + /* Check if another master has access */ + while(ti_lib_i2c_master_bus_busy(I2C0_BASE)); + + /* Assert RUN + START */ + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_SEND_START); + while(ti_lib_i2c_master_busy(I2C0_BASE)); + success = i2c_status(); + + for(i = 1; i < len && success; i++) { + /* Write next byte */ + ti_lib_i2c_master_data_put(I2C0_BASE, data[i]); + if(i < len - 1) { + /* Clear START */ + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_SEND_CONT); + while(ti_lib_i2c_master_busy(I2C0_BASE)); + success = i2c_status(); + } + } + + /* Assert stop */ + if(success) { + /* Assert STOP */ + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_SEND_FINISH); + while(ti_lib_i2c_master_busy(I2C0_BASE)); + success = i2c_status(); + while(ti_lib_i2c_master_bus_busy(I2C0_BASE)); + } + + return success; +} +/*---------------------------------------------------------------------------*/ +bool +board_i2c_write_single(uint8_t data) +{ + bool success; + + /* Write slave address */ + ti_lib_i2c_master_slave_addr_set(I2C0_BASE, slave_addr, false); + + /* Write first byte */ + ti_lib_i2c_master_data_put(I2C0_BASE, data); + + /* Check if another master has access */ + while(ti_lib_i2c_master_bus_busy(I2C0_BASE)); + + /* Assert RUN + START + STOP */ + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_SINGLE_SEND); + while(ti_lib_i2c_master_busy(I2C0_BASE)); + success = i2c_status(); + + return success; +} +/*---------------------------------------------------------------------------*/ +bool +board_i2c_read(uint8_t *data, uint8_t len) +{ + uint8_t i; + bool success; + + /* Set slave address */ + ti_lib_i2c_master_slave_addr_set(I2C0_BASE, slave_addr, true); + + /* Check if another master has access */ + while(ti_lib_i2c_master_bus_busy(I2C0_BASE)); + + /* Assert RUN + START + ACK */ + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_RECEIVE_START); + + i = 0; + success = true; + while(i < (len - 1) && success) { + while(ti_lib_i2c_master_busy(I2C0_BASE)); + success = i2c_status(); + if(success) { + data[i] = ti_lib_i2c_master_data_get(I2C0_BASE); + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_RECEIVE_CONT); + i++; + } + } + + if(success) { + while(ti_lib_i2c_master_busy(I2C0_BASE)); + success = i2c_status(); + if(success) { + data[len - 1] = ti_lib_i2c_master_data_get(I2C0_BASE); + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_RECEIVE_FINISH); + while(ti_lib_i2c_master_bus_busy(I2C0_BASE)); + } + } + + return success; +} +/*---------------------------------------------------------------------------*/ +bool +board_i2c_write_read(uint8_t *wdata, uint8_t wlen, uint8_t *rdata, uint8_t rlen) +{ + uint32_t i; + bool success; + + /* Set slave address for write */ + ti_lib_i2c_master_slave_addr_set(I2C0_BASE, slave_addr, false); + + /* Write first byte */ + ti_lib_i2c_master_data_put(I2C0_BASE, wdata[0]); + + /* Check if another master has access */ + while(ti_lib_i2c_master_bus_busy(I2C0_BASE)); + + /* Assert RUN + START */ + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_SEND_START); + while(ti_lib_i2c_master_busy(I2C0_BASE)); + success = i2c_status(); + + for(i = 1; i < wlen && success; i++) { + /* Write next byte */ + ti_lib_i2c_master_data_put(I2C0_BASE, wdata[i]); + if(i < wlen - 1) { + /* Clear START */ + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_SEND_CONT); + while(ti_lib_i2c_master_busy(I2C0_BASE)); + success = i2c_status(); + } + } + if(!success) { + return false; + } + + /* Set slave address for read */ + ti_lib_i2c_master_slave_addr_set(I2C0_BASE, slave_addr, true); + + /* Assert ACK */ + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_RECEIVE_START); + + i = 0; + while(i < (rlen - 1) && success) { + while(ti_lib_i2c_master_busy(I2C0_BASE)); + success = i2c_status(); + if(success) { + rdata[i] = ti_lib_i2c_master_data_get(I2C0_BASE); + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_RECEIVE_CONT); + i++; + } + } + + if(success) { + while(ti_lib_i2c_master_busy(I2C0_BASE)); + success = i2c_status(); + if(success) { + rdata[rlen - 1] = ti_lib_i2c_master_data_get(I2C0_BASE); + ti_lib_i2c_master_control(I2C0_BASE, I2C_MASTER_CMD_BURST_RECEIVE_FINISH); + while(ti_lib_i2c_master_bus_busy(I2C0_BASE)); + } + } + + return success; +} +/*---------------------------------------------------------------------------*/ +void +board_i2c_select(uint8_t new_interface, uint8_t address) +{ + slave_addr = address; + + if(new_interface != interface) { + interface = new_interface; + if(interface == BOARD_I2C_INTERFACE_0) { + ti_lib_ioc_io_port_pull_set(BOARD_IOID_SDA, IOC_NO_IOPULL); + ti_lib_ioc_io_port_pull_set(BOARD_IOID_SCL, IOC_NO_IOPULL); + ti_lib_ioc_pin_type_i2c(I2C0_BASE, BOARD_IOID_SDA, BOARD_IOID_SCL); + ti_lib_ioc_pin_type_gpio_input(BOARD_IOID_SDA_HP); + ti_lib_ioc_pin_type_gpio_input(BOARD_IOID_SCL_HP); + } else if(interface == BOARD_I2C_INTERFACE_1) { + ti_lib_ioc_io_port_pull_set(BOARD_IOID_SDA_HP, IOC_NO_IOPULL); + ti_lib_ioc_io_port_pull_set(BOARD_IOID_SCL_HP, IOC_NO_IOPULL); + ti_lib_ioc_pin_type_i2c(I2C0_BASE, BOARD_IOID_SDA_HP, BOARD_IOID_SCL_HP); + ti_lib_ioc_pin_type_gpio_input(BOARD_IOID_SDA); + ti_lib_ioc_pin_type_gpio_input(BOARD_IOID_SCL); + } + } +} +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/board-i2c.h b/platform/srf06-cc26xx/sensortag/board-i2c.h new file mode 100644 index 000000000..bed78cf46 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/board-i2c.h @@ -0,0 +1,108 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-i2c SensorTag 2.0 I2C functions + * @{ + * + * \file + * Header file for the Sensortag-CC26xx I2C Driver + */ +/*---------------------------------------------------------------------------*/ +#ifndef BOARD_I2C_H_ +#define BOARD_I2C_H_ +/*---------------------------------------------------------------------------*/ +#include +#include +/*---------------------------------------------------------------------------*/ +#define BOARD_I2C_INTERFACE_0 0 +#define BOARD_I2C_INTERFACE_1 1 +/*---------------------------------------------------------------------------*/ +#define board_i2c_deselect(...) +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialise the I2C controller with defaults for the sensortag + */ +void board_i2c_init(void); + +/** + * \brief Select an I2C slave + * \param interface The I2C interface to be used (BOARD_I2C_INTERFACE_0 or _1) + * \param slave_addr The slave's address + * + * The various sensors on the sensortag are connected either on interface 0 or + * 1. All sensors are connected to interface 0, with the exception of the MPU + * that is connected to 1. + */ +void board_i2c_select(uint8_t interface, uint8_t slave_addr); + +/** + * \brief Burst read from an I2C device + * \param buf Pointer to a buffer where the read data will be stored + * \param len Number of bytes to read + * \return True on success + */ +bool board_i2c_read(uint8_t *buf, uint8_t len); + +/** + * \brief Burst write to an I2C device + * \param buf Pointer to the buffer to be written + * \param len Number of bytes to write + * \return True on success + */ +bool board_i2c_write(uint8_t *buf, uint8_t len); + +/** + * \brief Single write to an I2C device + * \param data The byte to write + * \return True on success + */ +bool board_i2c_write_single(uint8_t data); + +/** + * \brief Write and read in one operation + * \param wdata Pointer to the buffer to be written + * \param wlen Number of bytes to write + * \param rdata Pointer to a buffer where the read data will be stored + * \param rlen Number of bytes to read + * \return True on success + */ +bool board_i2c_write_read(uint8_t *wdata, uint8_t wlen, uint8_t *rdata, + uint8_t rlen); +/*---------------------------------------------------------------------------*/ +#endif /* BOARD_I2C_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/board-peripherals.h b/platform/srf06-cc26xx/sensortag/board-peripherals.h new file mode 100644 index 000000000..aa61ab333 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/board-peripherals.h @@ -0,0 +1,56 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** \addtogroup cc26xx-srf-tag + * @{ + * + * \file + * Header file with definitions related to the sensors on the Sensortag-CC26xx + * + * \note Do not include this file directly. + */ +/*---------------------------------------------------------------------------*/ +#ifndef BOARD_PERIPHERALS_H_ +#define BOARD_PERIPHERALS_H_ +/*---------------------------------------------------------------------------*/ +#include "bmp-280-sensor.h" +#include "tmp-007-sensor.h" +#include "opt-3001-sensor.h" +#include "sht-21-sensor.h" +#include "mpu-9250-sensor.h" +#include "reed-relay.h" +#include "buzzer.h" +#include "ext-flash.h" +/*---------------------------------------------------------------------------*/ +#endif /* BOARD_PERIPHERALS_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/board-spi.c b/platform/srf06-cc26xx/sensortag/board-spi.c new file mode 100644 index 000000000..01dd65857 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/board-spi.c @@ -0,0 +1,118 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-spi + * @{ + * + * \file + * Board-specific SPI driver for the Sensortag-CC26xx + */ +/*---------------------------------------------------------------------------*/ +#include "contiki.h" +#include "ti-lib.h" +#include "board-spi.h" +#include "board.h" +/*---------------------------------------------------------------------------*/ +#define CPU_FREQ 48000000ul +/*---------------------------------------------------------------------------*/ +int +board_spi_write(const uint8_t *buf, size_t len) +{ + while(len > 0) { + uint32_t ul; + + ti_lib_ssi_data_put(SSI0_BASE, *buf); + ti_lib_rom_ssi_data_get(SSI0_BASE, &ul); + len--; + buf++; + } + + return 0; +} +/*---------------------------------------------------------------------------*/ +int +board_spi_read(uint8_t *buf, size_t len) +{ + while(len > 0) { + uint32_t ul; + + if(!ti_lib_rom_ssi_data_put_non_blocking(SSI0_BASE, 0)) { + /* Error */ + return -1; + } + ti_lib_rom_ssi_data_get(SSI0_BASE, &ul); + *buf = (uint8_t)ul; + len--; + buf++; + } + return 0; +} +/*---------------------------------------------------------------------------*/ +void +board_spi_flush() +{ + uint32_t ul; + while(ti_lib_rom_ssi_data_get_non_blocking(SSI0_BASE, &ul)); +} +/*---------------------------------------------------------------------------*/ +void +board_spi_open(uint32_t bit_rate, uint32_t clk_pin) +{ + uint32_t buf; + + /* SPI power */ + ti_lib_rom_prcm_peripheral_run_enable(PRCM_PERIPH_SSI0); + ti_lib_prcm_load_set(); + while(!ti_lib_prcm_load_get()); + + /* SPI configuration */ + ti_lib_ssi_int_disable(SSI0_BASE, SSI_RXOR | SSI_RXFF | SSI_RXTO | SSI_TXFF); + ti_lib_ssi_int_clear(SSI0_BASE, SSI_RXOR | SSI_RXTO); + ti_lib_rom_ssi_config_set_exp_clk(SSI0_BASE, CPU_FREQ, SSI_FRF_MOTO_MODE_0, + SSI_MODE_MASTER, bit_rate, 8); + ti_lib_rom_ioc_pin_type_ssi_master(SSI0_BASE, BOARD_IOID_SPI_MISO, + BOARD_IOID_SPI_MOSI, IOID_UNUSED, clk_pin); + ti_lib_ssi_enable(SSI0_BASE); + + /* Get rid of residual data from SSI port */ + while(ti_lib_ssi_data_get_non_blocking(SSI0_BASE, &buf)); +} +/*---------------------------------------------------------------------------*/ +void +board_spi_close() +{ + /* Power down SSI0 */ + ti_lib_rom_prcm_peripheral_run_disable(PRCM_PERIPH_SSI0); + ti_lib_prcm_load_set(); + while(!ti_lib_prcm_load_get()); +} +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/board-spi.h b/platform/srf06-cc26xx/sensortag/board-spi.h new file mode 100644 index 000000000..0c1e49d1f --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/board-spi.h @@ -0,0 +1,90 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-spi SensorTag 2.0 SPI functions + * @{ + * + * \file + * Header file for the Sensortag-CC26xx SPI Driver + */ +/*---------------------------------------------------------------------------*/ +#ifndef BOARD_SPI_H_ +#define BOARD_SPI_H_ +/*---------------------------------------------------------------------------*/ +#include +#include +#include +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialize the SPI interface + * \param bit_rate The bit rate to use + * \param clk_pin The IOID for the clock pin. This can be IOID_0 etc + * \return none + */ +void board_spi_open(uint32_t bit_rate, uint32_t clk_pin); + +/** + * \brief Close the SPI interface + * \return True when successful. + */ +void board_spi_close(void); + +/** + * \brief Clear data from the SPI interface + * \return none + */ +void board_spi_flush(void); + +/** + * \brief Read from an SPI device + * \param buf The buffer to store data + * \param length The number of bytes to read + * \return True when successful. + */ +int board_spi_read(uint8_t *buf, size_t length); + +/** + * \brief Write to an SPI device + * \param buf The buffer with the data to write + * \param length The number of bytes to write + * \return True when successful. + */ +int board_spi_write(const uint8_t *buf, size_t length); +/*---------------------------------------------------------------------------*/ +#endif /* BOARD_SPI_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/board.c b/platform/srf06-cc26xx/sensortag/board.c new file mode 100644 index 000000000..5246a85ef --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/board.c @@ -0,0 +1,152 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \file + * Sensortag-specific board initialisation driver + */ +/*---------------------------------------------------------------------------*/ +#include "contiki-conf.h" +#include "lib/sensors.h" +#include "buzzer.h" +#include "lpm.h" +#include "ti-lib.h" +#include "board-peripherals.h" +#include "board-i2c.h" + +#include +#include +/*---------------------------------------------------------------------------*/ +#define PRCM_DOMAINS (PRCM_DOMAIN_SERIAL | PRCM_DOMAIN_PERIPH) +/*---------------------------------------------------------------------------*/ +static void +power_domains_on(void) +{ + /* Turn on relevant power domains */ + ti_lib_prcm_power_domain_on(PRCM_DOMAINS); + + /* Wait for domains to power on */ + while((ti_lib_prcm_power_domain_status(PRCM_DOMAINS) + != PRCM_DOMAIN_POWER_ON)); +} +/*---------------------------------------------------------------------------*/ +static void +lpm_wakeup_handler(void) +{ + power_domains_on(); + + board_i2c_init(); +} +/*---------------------------------------------------------------------------*/ +static void +shutdown_handler(uint8_t mode) +{ + if(mode == LPM_MODE_SHUTDOWN) { + buzzer_stop(); + SENSORS_DEACTIVATE(bmp_280_sensor); + SENSORS_DEACTIVATE(opt_3001_sensor); + SENSORS_DEACTIVATE(tmp_007_sensor); + SENSORS_DEACTIVATE(sht_21_sensor); + mpu_9250_sensor.configure(MPU_9250_SENSOR_SHUTDOWN, 0); + } +} +/*---------------------------------------------------------------------------*/ +/* + * Declare a data structure to register with LPM. + * We don't care about what power mode we'll drop to, we don't care about + * getting notified before deep sleep. All we need is to be notified when we + * wake up so we can turn power domains back on for I2C and SSI, and to make + * sure everything on the board is off before CM3 shutdown. + */ +LPM_MODULE(sensortag_module, NULL, shutdown_handler, lpm_wakeup_handler); +/*---------------------------------------------------------------------------*/ +void +board_init() +{ + /* Disable global interrupts */ + uint8_t int_disabled = ti_lib_int_master_disable(); + + power_domains_on(); + + /* Configure all clock domains to run at full speed */ + ti_lib_prcm_clock_configure_set(PRCM_DOMAIN_SYSBUS, PRCM_CLOCK_DIV_1); + ti_lib_prcm_clock_configure_set(PRCM_DOMAIN_CPU, PRCM_CLOCK_DIV_1); + ti_lib_prcm_clock_configure_set(PRCM_DOMAIN_TIMER, PRCM_CLOCK_DIV_1); + ti_lib_prcm_clock_configure_set(PRCM_DOMAIN_SERIAL, PRCM_CLOCK_DIV_1); + ti_lib_prcm_clock_configure_set(PRCM_DOMAIN_PERIPH, PRCM_CLOCK_DIV_1); + + /* Enable GPIO peripheral */ + ti_lib_prcm_peripheral_run_enable(PRCM_PERIPH_GPIO); + + /* Apply settings and wait for them to take effect */ + ti_lib_prcm_load_set(); + while(!ti_lib_prcm_load_get()); + + /* Enable GPT0 module - Wait for the clock to be enabled */ + ti_lib_prcm_peripheral_run_enable(PRCM_PERIPH_TIMER0); + ti_lib_prcm_load_set(); + while(!ti_lib_prcm_load_get()); + + /* Keys (input pullup) */ + ti_lib_rom_ioc_pin_type_gpio_input(BOARD_IOID_KEY_LEFT); + ti_lib_rom_ioc_pin_type_gpio_input(BOARD_IOID_KEY_RIGHT); + ti_lib_ioc_io_port_pull_set(BOARD_IOID_KEY_LEFT, IOC_IOPULL_UP); + ti_lib_ioc_io_port_pull_set(BOARD_IOID_KEY_RIGHT, IOC_IOPULL_UP); + + /* I2C controller */ + board_i2c_init(); + + /* Sensor interface */ + ti_lib_rom_ioc_pin_type_gpio_input(BOARD_IOID_MPU_INT); + ti_lib_ioc_io_port_pull_set(BOARD_IOID_MPU_INT, IOC_IOPULL_DOWN); + + ti_lib_rom_ioc_pin_type_gpio_input(BOARD_IOID_REED_RELAY); + ti_lib_ioc_io_port_pull_set(BOARD_IOID_REED_RELAY, IOC_IOPULL_DOWN); + + ti_lib_rom_ioc_pin_type_gpio_output(BOARD_IOID_MPU_POWER); + + /* Flash interface */ + ti_lib_rom_ioc_pin_type_gpio_output(BOARD_IOID_FLASH_CS); + ti_lib_gpio_pin_write(BOARD_FLASH_CS, 1); + + buzzer_init(); + + lpm_register_module(&sensortag_module); + + /* Re-enable interrupt if initially enabled. */ + if(!int_disabled) { + ti_lib_int_master_enable(); + } +} +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/board.h b/platform/srf06-cc26xx/sensortag/board.h new file mode 100644 index 000000000..00afb98f2 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/board.h @@ -0,0 +1,206 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** \addtogroup cc26xx-srf-tag + * @{ + * + * \defgroup sensortag-cc26xx-peripherals Sensortag Peripherals + * + * Defines related to the Sensortag-CC26XX + * + * This file provides connectivity information on LEDs, Buttons, UART and + * other peripherals + * + * This file can be used as the basis to configure other boards using the + * CC26XX code as their basis. + * + * This file is not meant to be modified by the user. + * @{ + * + * \file + * Header file with definitions related to the I/O connections on the TI + * Sensortag + * + * \note Do not include this file directly. It gets included by contiki-conf + * after all relevant directives have been set. + */ +/*---------------------------------------------------------------------------*/ +#ifndef BOARD_H_ +#define BOARD_H_ +/*---------------------------------------------------------------------------*/ +#include "ioc.h" +/*---------------------------------------------------------------------------*/ +/** + * \name LED configurations + * + * Those values are not meant to be modified by the user + * @{ + */ +/* Some files include leds.h before us, so we need to get rid of defaults in + * leds.h before we provide correct definitions */ +#undef LEDS_GREEN +#undef LEDS_YELLOW +#undef LEDS_RED +#undef LEDS_CONF_ALL + +#define LEDS_RED 1 +#define LEDS_GREEN 2 +#define LEDS_YELLOW LEDS_GREEN +#define LEDS_ORANGE LEDS_RED + +#define LEDS_CONF_ALL 3 + +/* Notify various examples that we have LEDs */ +#define PLATFORM_HAS_LEDS 1 +/** @} */ +/*---------------------------------------------------------------------------*/ +/** + * \name LED IOID mappings + * + * Those values are not meant to be modified by the user + * @{ + */ +#define BOARD_IOID_LED_1 IOID_10 +#define BOARD_IOID_LED_2 IOID_15 +#define BOARD_LED_1 (1 << BOARD_IOID_LED_1) +#define BOARD_LED_2 (1 << BOARD_IOID_LED_2) +#define BOARD_LED_ALL (BOARD_LED_1 | BOARD_LED_2) +/** @} */ +/*---------------------------------------------------------------------------*/ +/** + * \name UART IOID mapping + * + * Those values are not meant to be modified by the user + * @{ + */ +#define BOARD_IOID_UART_RX IOID_17 +#define BOARD_IOID_UART_TX IOID_16 +#define BOARD_IOID_UART_CTS IOID_UNUSED +#define BOARD_IOID_UART_RTS IOID_UNUSED +#define BOARD_UART_RXD (1 << BOARD_IOID_UART_RXD) +#define BOARD_UART_TXD (1 << BOARD_IOID_UART_TXD) +#define BOARD_UART_CTS (1 << BOARD_IOID_UART_CTS) +#define BOARD_UART_RTS (1 << BOARD_IOID_UART_RTS) +/** @} */ +/*---------------------------------------------------------------------------*/ +/** + * \name Button IOID mapping + * + * Those values are not meant to be modified by the user + * @{ + */ +#define BOARD_IOID_KEY_LEFT IOID_0 +#define BOARD_IOID_KEY_RIGHT IOID_4 +#define BOARD_KEY_LEFT (1 << BOARD_IOID_KEY_LEFT) +#define BOARD_KEY_RIGHT (1 << BOARD_IOID_KEY_RIGHT) +/** @} */ +/*---------------------------------------------------------------------------*/ +/** + * \brief SPI IOID mappings + * + * Those values are not meant to be modified by the user + * @{ + */ +#define BOARD_IOID_SPI_MOSI IOID_19 +#define BOARD_IOID_SPI_MISO IOID_18 +/** @} */ +/*---------------------------------------------------------------------------*/ +/** + * \name Buzzer configuration + * @{ + */ +#define BOARD_IOID_BUZZER IOID_21 /**< Buzzer Pin */ +/** @} */ +/*---------------------------------------------------------------------------*/ +/** + * \name Reed Relay IOID mapping + * + * Those values are not meant to be modified by the user + * @{ + */ +#define BOARD_IOID_REED_RELAY IOID_3 +/** @} */ +/*---------------------------------------------------------------------------*/ +/** + * \name External flash IOID mapping + * + * Those values are not meant to be modified by the user + * @{ + */ +#define BOARD_IOID_FLASH_CS IOID_14 +#define BOARD_FLASH_CS (1 << BOARD_IOID_FLASH_CS) +#define BOARD_SPI_CLK_FLASH IOID_11 +/** @} */ +/*---------------------------------------------------------------------------*/ +/** + * \brief I2C IOID mappings + * + * Those values are not meant to be modified by the user + * @{ + */ +#define BOARD_IOID_SDA IOID_5 /**< Interface 0 SDA: All sensors bar MPU */ +#define BOARD_IOID_SCL IOID_6 /**< Interface 0 SCL: All sensors bar MPU */ +#define BOARD_IOID_SDA_HP IOID_8 /**< Interface 1 SDA: MPU */ +#define BOARD_IOID_SCL_HP IOID_9 /**< Interface 1 SCL: MPU */ +/** @} */ +/*---------------------------------------------------------------------------*/ +/** + * \brief MPU IOID mappings + * + * Those values are not meant to be modified by the user + * @{ + */ +#define BOARD_IOID_MPU_INT IOID_7 +#define BOARD_IOID_MPU_POWER IOID_12 +#define BOARD_MPU_INT (1 << BOARD_IOID_MPU_INT) +#define BOARD_MPU_POWER (1 << BOARD_IOID_MPU_POWER) +/** @} */ +/*---------------------------------------------------------------------------*/ +/** + * \name Device string used on startup + * @{ + */ +#define BOARD_STRING "TI CC2650 SensorTag" + +/** @} */ +/*---------------------------------------------------------------------------*/ +/** + * \brief Board specific iniatialisation + * @{ + */ +void board_init(void); +/** @} */ +/*---------------------------------------------------------------------------*/ +#endif /* BOARD_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/button-sensor.c b/platform/srf06-cc26xx/sensortag/button-sensor.c new file mode 100644 index 000000000..089ea7332 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/button-sensor.c @@ -0,0 +1,282 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-button-sensor + * @{ + * + * \file + * Driver for the Sensortag-CC26xx buttons + */ +/*---------------------------------------------------------------------------*/ +#include "contiki.h" +#include "lib/sensors.h" +#include "sensortag/button-sensor.h" +#include "gpio-interrupt.h" +#include "sys/timer.h" +#include "lpm.h" + +#include "ti-lib.h" + +#include +/*---------------------------------------------------------------------------*/ +#ifdef BUTTON_SENSOR_CONF_ENABLE_SHUTDOWN +#define BUTTON_SENSOR_ENABLE_SHUTDOWN BUTTON_SENSOR_CONF_ENABLE_SHUTDOWN +#else +#define BUTTON_SENSOR_ENABLE_SHUTDOWN 1 +#endif +/*---------------------------------------------------------------------------*/ +#define BUTTON_GPIO_CFG (IOC_CURRENT_2MA | IOC_STRENGTH_AUTO | \ + IOC_IOPULL_UP | IOC_SLEW_DISABLE | \ + IOC_HYST_DISABLE | IOC_BOTH_EDGES | \ + IOC_INT_ENABLE | IOC_IOMODE_NORMAL | \ + IOC_NO_WAKE_UP | IOC_INPUT_ENABLE | \ + IOC_JTAG_DISABLE) +/*---------------------------------------------------------------------------*/ +#define DEBOUNCE_DURATION (CLOCK_SECOND >> 5) + +struct btn_timer { + struct timer debounce; + clock_time_t start; + clock_time_t duration; +}; + +static struct btn_timer left_timer, right_timer; +/*---------------------------------------------------------------------------*/ +/** + * \brief Handler for Sensortag-CC26XX button presses + */ +static void +button_press_handler(uint8_t ioid) +{ + if(ioid == BOARD_IOID_KEY_LEFT) { + if(!timer_expired(&left_timer.debounce)) { + return; + } + + timer_set(&left_timer.debounce, DEBOUNCE_DURATION); + + /* + * Start press duration counter on press (falling), notify on release + * (rising) + */ + if(ti_lib_gpio_pin_read(BOARD_KEY_LEFT) == 0) { + left_timer.start = clock_time(); + left_timer.duration = 0; + } else { + left_timer.duration = clock_time() - left_timer.start; + sensors_changed(&button_left_sensor); + } + } + + if(ioid == BOARD_IOID_KEY_RIGHT) { + if(BUTTON_SENSOR_ENABLE_SHUTDOWN == 0) { + if(!timer_expired(&right_timer.debounce)) { + return; + } + + timer_set(&right_timer.debounce, DEBOUNCE_DURATION); + + /* + * Start press duration counter on press (falling), notify on release + * (rising) + */ + if(ti_lib_gpio_pin_read(BOARD_KEY_RIGHT) == 0) { + right_timer.start = clock_time(); + right_timer.duration = 0; + } else { + right_timer.duration = clock_time() - right_timer.start; + sensors_changed(&button_right_sensor); + } + } else { + lpm_shutdown(BOARD_IOID_KEY_RIGHT); + } + } +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Configuration function for the button sensor for all buttons. + * + * \param type This function does nothing unless type == SENSORS_ACTIVE + * \param c 0: disable the button, non-zero: enable + * \param key: One of BOARD_KEY_LEFT, BOARD_KEY_RIGHT etc + */ +static void +config_buttons(int type, int c, uint32_t key) +{ + switch(type) { + case SENSORS_HW_INIT: + ti_lib_gpio_event_clear(1 << key); + ti_lib_ioc_port_configure_set(key, IOC_PORT_GPIO, BUTTON_GPIO_CFG); + ti_lib_gpio_dir_mode_set((1 << key), GPIO_DIR_MODE_IN); + gpio_interrupt_register_handler(key, button_press_handler); + break; + case SENSORS_ACTIVE: + if(c) { + ti_lib_gpio_event_clear(1 << key); + ti_lib_ioc_port_configure_set(key, IOC_PORT_GPIO, BUTTON_GPIO_CFG); + ti_lib_gpio_dir_mode_set((1 << key), GPIO_DIR_MODE_IN); + ti_lib_ioc_int_enable(key); + } else { + ti_lib_ioc_int_disable(key); + } + break; + default: + break; + } +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Configuration function for the left button. + * + * Parameters are passed onto config_buttons, which does the actual + * configuration + * Parameters are ignored. They have been included because the prototype is + * dictated by the core sensor API. The return value is also required by + * the API but otherwise ignored. + * + * \param type passed to config_buttons as-is + * \param value passed to config_buttons as-is + * + * \return ignored + */ +static int +config_left(int type, int value) +{ + config_buttons(type, value, BOARD_IOID_KEY_LEFT); + + return 1; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Configuration function for the right button. + * + * Parameters are passed onto config_buttons, which does the actual + * configuration + * Parameters are ignored. They have been included because the prototype is + * dictated by the core sensor api. The return value is also required by + * the API but otherwise ignored. + * + * \param type passed to config_buttons as-is + * \param value passed to config_buttons as-is + * + * \return ignored + */ +static int +config_right(int type, int value) +{ + config_buttons(type, value, BOARD_IOID_KEY_RIGHT); + + return 1; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Status function for all buttons + * \param type SENSORS_ACTIVE or SENSORS_READY + * \param key_io_id BOARD_IOID_KEY_LEFT, BOARD_IOID_KEY_RIGHT etc + * \return 1 if the button's port interrupt is enabled (edge detect) + * + * This function will only be called by status_left, status_right and the + * called will pass the correct key_io_id + */ +static int +status(int type, uint32_t key_io_id) +{ + switch(type) { + case SENSORS_ACTIVE: + case SENSORS_READY: + if(ti_lib_ioc_port_configure_get(key_io_id) & IOC_INT_ENABLE) { + return 1; + } + break; + default: + break; + } + return 0; +} +/*---------------------------------------------------------------------------*/ +static int +value_left(int type) +{ + if(type == BUTTON_SENSOR_VALUE_STATE) { + return ti_lib_gpio_pin_read(BOARD_KEY_LEFT) == 0 ? + BUTTON_SENSOR_VALUE_PRESSED : BUTTON_SENSOR_VALUE_RELEASED; + } else if(type == BUTTON_SENSOR_VALUE_DURATION) { + return (int)left_timer.duration; + } + return 0; +} +/*---------------------------------------------------------------------------*/ +static int +value_right(int type) +{ + if(type == BUTTON_SENSOR_VALUE_STATE) { + return ti_lib_gpio_pin_read(BOARD_KEY_RIGHT) == 0 ? + BUTTON_SENSOR_VALUE_PRESSED : BUTTON_SENSOR_VALUE_RELEASED; + } else if(type == BUTTON_SENSOR_VALUE_DURATION) { + return (int)right_timer.duration; + } + return 0; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Status function for the left button. + * \param type SENSORS_ACTIVE or SENSORS_READY + * \return 1 if the button's port interrupt is enabled (edge detect) + * + * This function will call status. It will pass type verbatim and it will also + * pass the correct key_io_id + */ +static int +status_left(int type) +{ + return status(type, BOARD_IOID_KEY_LEFT); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Status function for the right button. + * \param type SENSORS_ACTIVE or SENSORS_READY + * \return 1 if the button's port interrupt is enabled (edge detect) + * + * This function will call status. It will pass type verbatim and it will also + * pass the correct key_io_id + */ +static int +status_right(int type) +{ + return status(type, BOARD_IOID_KEY_RIGHT); +} +/*---------------------------------------------------------------------------*/ +SENSORS_SENSOR(button_left_sensor, BUTTON_SENSOR, value_left, config_left, + status_left); +SENSORS_SENSOR(button_right_sensor, BUTTON_SENSOR, value_right, config_right, + status_right); +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/button-sensor.h b/platform/srf06-cc26xx/sensortag/button-sensor.h new file mode 100644 index 000000000..6e15b4d4c --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/button-sensor.h @@ -0,0 +1,66 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-button-sensor SensorTag 2.0 Button Sensor + * + * One of the buttons can be configured as general purpose or as an on/off key + * @{ + * + * \file + * Header file for the Sensortag-CC26xx Button Driver + */ +/*---------------------------------------------------------------------------*/ +#ifndef BUTTON_SENSOR_H_ +#define BUTTON_SENSOR_H_ +/*---------------------------------------------------------------------------*/ +#include "lib/sensors.h" +/*---------------------------------------------------------------------------*/ +#define BUTTON_SENSOR "Button" +/*---------------------------------------------------------------------------*/ +#define BUTTON_SENSOR_VALUE_STATE 0 +#define BUTTON_SENSOR_VALUE_DURATION 1 + +#define BUTTON_SENSOR_VALUE_RELEASED 0 +#define BUTTON_SENSOR_VALUE_PRESSED 1 +/*---------------------------------------------------------------------------*/ +#define button_sensor button_left_sensor +extern const struct sensors_sensor button_left_sensor; +extern const struct sensors_sensor button_right_sensor; +/*---------------------------------------------------------------------------*/ +#endif /* BUTTON_SENSOR_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/buzzer.c b/platform/srf06-cc26xx/sensortag/buzzer.c new file mode 100644 index 000000000..57d063897 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/buzzer.c @@ -0,0 +1,124 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-buzzer + * @{ + * + * \file + * Driver for the Sensortag-CC26XX Buzzer + */ +/*---------------------------------------------------------------------------*/ +#include "contiki-conf.h" +#include "buzzer.h" +#include "ti-lib.h" +#include "lpm.h" + +#include +#include +#include +/*---------------------------------------------------------------------------*/ +static uint8_t buzzer_on; +static lpm_power_domain_lock_t lock; +/*---------------------------------------------------------------------------*/ +void +buzzer_init() +{ + buzzer_on = 0; + + /* Drive the I/O ID with GPT0 / Timer A */ + ti_lib_ioc_port_configure_set(BOARD_IOID_BUZZER, IOC_PORT_MCU_PORT_EVENT0, + IOC_STD_OUTPUT); + + /* GPT0 / Timer A: PWM, Interrupt Enable */ + HWREG(GPT0_BASE + GPT_O_TAMR) = (TIMER_CFG_A_PWM & 0xFF) | GPT_TAMR_TAPWMIE; +} +/*---------------------------------------------------------------------------*/ +uint8_t +buzzer_state() +{ + return buzzer_on; +} +/*---------------------------------------------------------------------------*/ +void +buzzer_start(int freq) +{ + uint32_t load; + + buzzer_on = 1; + + lpm_pd_lock_obtain(&lock, PRCM_DOMAIN_PERIPH); + + /* Stop the timer */ + ti_lib_timer_disable(GPT0_BASE, TIMER_A); + + if(freq > 0) { + load = (GET_MCU_CLOCK / freq); + + ti_lib_timer_load_set(GPT0_BASE, TIMER_A, load); + ti_lib_timer_match_set(GPT0_BASE, TIMER_A, load / 2); + + /* Start */ + ti_lib_timer_enable(GPT0_BASE, TIMER_A); + } + + /* Run in sleep mode */ + ti_lib_prcm_peripheral_sleep_enable(PRCM_PERIPH_TIMER0); + ti_lib_prcm_peripheral_deep_sleep_enable(PRCM_PERIPH_TIMER0); + ti_lib_prcm_load_set(); + while(!ti_lib_prcm_load_get()); +} +/*---------------------------------------------------------------------------*/ +void +buzzer_stop() +{ + buzzer_on = 0; + + lpm_pd_lock_release(&lock); + + /* Stop the timer */ + ti_lib_timer_disable(GPT0_BASE, TIMER_A); + + /* + * Stop running in sleep mode. + * ToDo: Currently GPT0 is in use by clock_delay_usec (GPT0/TB) and by this + * module here (GPT0/TA). clock_delay_usec will never need GPT0/TB in sleep + * mode and we control TA here. Thus, with the current setup, it's OK to + * control whether GPT0 runs in sleep mode in this module here. However, if + * some other module at some point starts using GPT0, we should change this + * to happen through an umbrella module + */ + ti_lib_prcm_peripheral_sleep_disable(PRCM_PERIPH_TIMER0); + ti_lib_prcm_peripheral_deep_sleep_disable(PRCM_PERIPH_TIMER0); + ti_lib_prcm_load_set(); + while(!ti_lib_prcm_load_get()); +} +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/buzzer.h b/platform/srf06-cc26xx/sensortag/buzzer.h new file mode 100644 index 000000000..653b46f88 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/buzzer.h @@ -0,0 +1,74 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-buzzer SensorTag 2.0 Buzzer + * @{ + * + * \file + * Header file for the Sensortag-CC26xx Buzzer + */ +/*---------------------------------------------------------------------------*/ +#ifndef BUZZER_H_ +#define BUZZER_H_ +/*---------------------------------------------------------------------------*/ +#include +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialise the buzzer + */ +void buzzer_init(void); + +/** + * \brief Start the buzzer + * \param freq The buzzer frequency + */ +void buzzer_start(int freq); + +/** + * \brief Stop the buzzer + */ +void buzzer_stop(void); + +/** + * \brief Retrieve the buzzer state + * \return 1: on, 0: off + */ +uint8_t buzzer_state(void); +/*---------------------------------------------------------------------------*/ +#endif /* BUZZER_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/ext-flash.c b/platform/srf06-cc26xx/sensortag/ext-flash.c new file mode 100644 index 000000000..83d2758a4 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/ext-flash.c @@ -0,0 +1,409 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-ext-flash + * @{ + * + * \file + * Driver for the Sensortag-CC26xx WinBond W25X20CL Flash + */ +/*---------------------------------------------------------------------------*/ +#include "contiki.h" +#include "ext-flash.h" +#include "ti-lib.h" +#include "board-spi.h" +/*---------------------------------------------------------------------------*/ +/* Instruction codes */ + +#define BLS_CODE_PROGRAM 0x02 /**< Page Program */ +#define BLS_CODE_READ 0x03 /**< Read Data */ +#define BLS_CODE_READ_STATUS 0x05 /**< Read Status Register */ +#define BLS_CODE_WRITE_ENABLE 0x06 /**< Write Enable */ +#define BLS_CODE_SECTOR_ERASE 0x20 /**< Sector Erase */ +#define BLS_CODE_MDID 0x90 /**< Manufacturer Device ID */ + +#define BLS_CODE_DP 0xB9 /**< Power down */ +#define BLS_CODE_RDP 0xAB /**< Power standby */ +/*---------------------------------------------------------------------------*/ +/* Erase instructions */ + +#define BLS_CODE_ERASE_4K 0x20 /**< Sector Erase */ +#define BLS_CODE_ERASE_32K 0x52 +#define BLS_CODE_ERASE_64K 0xD8 +#define BLS_CODE_ERASE_ALL 0xC7 /**< Mass Erase */ +/*---------------------------------------------------------------------------*/ +/* Bitmasks of the status register */ + +#define BLS_STATUS_SRWD_BM 0x80 +#define BLS_STATUS_BP_BM 0x0C +#define BLS_STATUS_WEL_BM 0x02 +#define BLS_STATUS_WIP_BM 0x01 + +#define BLS_STATUS_BIT_BUSY 0x01 /**< Busy bit of the status register */ +/*---------------------------------------------------------------------------*/ +/* Part specific constants */ + +#define BLS_MANUFACTURER_ID 0xEF +#define BLS_DEVICE_ID 0x11 + +#define BLS_PROGRAM_PAGE_SIZE 256 +#define BLS_ERASE_SECTOR_SIZE 4096 +/*---------------------------------------------------------------------------*/ +/** + * Clear external flash CSN line + */ +static void +select(void) +{ + ti_lib_gpio_pin_write(BOARD_FLASH_CS, 0); +} +/*---------------------------------------------------------------------------*/ +/** + * Set external flash CSN line + */ +static void +deselect(void) +{ + ti_lib_gpio_pin_write(BOARD_FLASH_CS, 1); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Wait till previous erase/program operation completes. + * \return Zero when successful. + */ +static int +wait_ready(void) +{ + const uint8_t wbuf[1] = { BLS_CODE_READ_STATUS }; + + select(); + + /* Throw away all garbages */ + board_spi_flush(); + + int ret = board_spi_write(wbuf, sizeof(wbuf)); + + if(ret) { + deselect(); + return -2; + } + + for(;;) { + uint8_t buf; + /* Note that this temporary implementation is not + * energy efficient. + * Thread could have yielded while waiting for flash + * erase/program to complete. + */ + ret = board_spi_read(&buf, sizeof(buf)); + + if(ret) { + /* Error */ + deselect(); + return -2; + } + if(!(buf & BLS_STATUS_BIT_BUSY)) { + /* Now ready */ + break; + } + } + deselect(); + return 0; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Put the device in power save mode. No access to data; only + * the status register is accessible. + * \return True when SPI transactions succeed + */ +static bool +power_down(void) +{ + uint8_t cmd; + bool success; + + cmd = BLS_CODE_DP; + select(); + success = board_spi_write(&cmd, sizeof(cmd)); + deselect(); + + return success; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Take device out of power save mode and prepare it for normal operation + * \return True if the command was written successfully + */ +static bool +power_standby(void) +{ + uint8_t cmd; + bool success; + + cmd = BLS_CODE_RDP; + select(); + success = board_spi_write(&cmd, sizeof(cmd)); + + if(success) { + success = wait_ready() == 0; + } + + deselect(); + + return success; +} +/*---------------------------------------------------------------------------*/ +/** + * Verify the flash part. + * @return True when successful. + */ +static bool +verify_part(void) +{ + const uint8_t wbuf[] = { BLS_CODE_MDID, 0xFF, 0xFF, 0x00 }; + uint8_t rbuf[2]; + int ret; + + select(); + + ret = board_spi_write(wbuf, sizeof(wbuf)); + + if(ret) { + deselect(); + return false; + } + + ret = board_spi_read(rbuf, sizeof(rbuf)); + deselect(); + + if(ret || rbuf[0] != BLS_MANUFACTURER_ID || rbuf[1] != BLS_DEVICE_ID) { + return false; + } + return true; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Enable write. + * \return Zero when successful. + */ +static int +write_enable(void) +{ + const uint8_t wbuf[] = { BLS_CODE_WRITE_ENABLE }; + + select(); + int ret = board_spi_write(wbuf, sizeof(wbuf)); + deselect(); + + if(ret) { + return -3; + } + return 0; +} +/*---------------------------------------------------------------------------*/ +bool +ext_flash_open() +{ + board_spi_open(4000000, BOARD_SPI_CLK_FLASH); + + /* GPIO pin configuration */ + ti_lib_ioc_pin_type_gpio_output(BOARD_IOID_FLASH_CS); + + /* Default output to clear chip select */ + deselect(); + + /* Put the part is standby mode */ + power_standby(); + + return verify_part(); +} +/*---------------------------------------------------------------------------*/ +void +ext_flash_close() +{ + /* Put the part in low power mode */ + power_down(); + + board_spi_close(); +} +/*---------------------------------------------------------------------------*/ +bool +ext_flash_read(size_t offset, size_t length, uint8_t *buf) +{ + uint8_t wbuf[4]; + + /* Wait till previous erase/program operation completes */ + int ret = wait_ready(); + if(ret) { + return false; + } + + /* + * SPI is driven with very low frequency (1MHz < 33MHz fR spec) + * in this implementation, hence it is not necessary to use fast read. + */ + wbuf[0] = BLS_CODE_READ; + wbuf[1] = (offset >> 16) & 0xff; + wbuf[2] = (offset >> 8) & 0xff; + wbuf[3] = offset & 0xff; + + select(); + + if(board_spi_write(wbuf, sizeof(wbuf))) { + /* failure */ + deselect(); + return false; + } + + ret = board_spi_read(buf, length); + + deselect(); + + return ret == 0; +} +/*---------------------------------------------------------------------------*/ +bool +ext_flash_write(size_t offset, size_t length, const uint8_t *buf) +{ + uint8_t wbuf[4]; + int ret; + size_t ilen; /* interim length per instruction */ + + while(length > 0) { + /* Wait till previous erase/program operation completes */ + ret = wait_ready(); + if(ret) { + return false; + } + + ret = write_enable(); + if(ret) { + return false; + } + + ilen = BLS_PROGRAM_PAGE_SIZE - (offset % BLS_PROGRAM_PAGE_SIZE); + if(length < ilen) { + ilen = length; + } + + wbuf[0] = BLS_CODE_PROGRAM; + wbuf[1] = (offset >> 16) & 0xff; + wbuf[2] = (offset >> 8) & 0xff; + wbuf[3] = offset & 0xff; + + offset += ilen; + length -= ilen; + + /* Upto 100ns CS hold time (which is not clear + * whether it's application only inbetween reads) + * is not imposed here since above instructions + * should be enough to delay + * as much. */ + select(); + + if(board_spi_write(wbuf, sizeof(wbuf))) { + /* failure */ + deselect(); + return false; + } + + if(board_spi_write(buf, ilen)) { + /* failure */ + deselect(); + return false; + } + buf += ilen; + deselect(); + } + + return true; +} +/*---------------------------------------------------------------------------*/ +bool +ext_flash_erase(size_t offset, size_t length) +{ + /* + * Note that Block erase might be more efficient when the floor map + * is well planned for OTA, but to simplify this implementation, + * sector erase is used blindly. + */ + uint8_t wbuf[4]; + size_t i, numsectors; + size_t endoffset = offset + length - 1; + + offset = (offset / BLS_ERASE_SECTOR_SIZE) * BLS_ERASE_SECTOR_SIZE; + numsectors = (endoffset - offset + BLS_ERASE_SECTOR_SIZE - 1) / BLS_ERASE_SECTOR_SIZE; + + wbuf[0] = BLS_CODE_SECTOR_ERASE; + + for(i = 0; i < numsectors; i++) { + /* Wait till previous erase/program operation completes */ + int ret = wait_ready(); + if(ret) { + return false; + } + + ret = write_enable(); + if(ret) { + return false; + } + + wbuf[1] = (offset >> 16) & 0xff; + wbuf[2] = (offset >> 8) & 0xff; + wbuf[3] = offset & 0xff; + + select(); + + if(board_spi_write(wbuf, sizeof(wbuf))) { + /* failure */ + deselect(); + return false; + } + deselect(); + + offset += BLS_ERASE_SECTOR_SIZE; + } + + return true; +} +/*---------------------------------------------------------------------------*/ +bool +ext_flash_test(void) +{ + bool ret; + + ret = ext_flash_open(); + ext_flash_close(); + + return ret; +} +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/ext-flash.h b/platform/srf06-cc26xx/sensortag/ext-flash.h new file mode 100644 index 000000000..ca2ef80ea --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/ext-flash.h @@ -0,0 +1,103 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-ext-flash SensorTag 2.0 External Flash + * @{ + * + * \file + * Header file for the Sensortag-CC26xx External Flash Driver + */ +/*---------------------------------------------------------------------------*/ +#ifndef EXT_FLASH_H_ +#define EXT_FLASH_H_ +/*---------------------------------------------------------------------------*/ +#include +#include +#include +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialize storage driver. + * \return True when successful. + */ +bool ext_flash_open(void); + +/** + * \brief Close the storage driver + */ +void ext_flash_close(void); + +/** + * \brief Read storage content + * \param offset Address to read from + * \param length Number of bytes to read + * \param buf Buffer where to store the read bytes + * \return True when successful. + * + * buf must be allocated by the caller + */ +bool ext_flash_read(size_t offset, size_t length, uint8_t *buf); + +/** + * \brief Erase storage sectors corresponding to the range. + * \param offset Address to start erasing + * \param length Number of bytes to erase + * \return True when successful. + * + * The erase operation will be sector-wise, therefore a call to this function + * will generally start the erase procedure at an address lower than offset + */ +bool ext_flash_erase(size_t offset, size_t length); + +/** + * \brief Write to storage sectors. + * \param offset Address to write to + * \param length Number of bytes to write + * \param buf Buffer holding the bytes to be written + * + * \return True when successful. + */ +bool ext_flash_write(size_t offset, size_t length, const uint8_t *buf); + +/** + * \brief Test the flash (power on self-test) + * \return True when successful. + */ +bool ext_flash_test(void); +/*---------------------------------------------------------------------------*/ +#endif /* EXT_FLASH_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/leds-arch.c b/platform/srf06-cc26xx/sensortag/leds-arch.c new file mode 100644 index 000000000..e415dca55 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/leds-arch.c @@ -0,0 +1,81 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \file + * Driver for the Sensortag-CC26XX LEDs + */ +/*---------------------------------------------------------------------------*/ +#include "contiki.h" +#include "dev/leds.h" + +#include "ti-lib.h" +/*---------------------------------------------------------------------------*/ +static unsigned char c; +static int inited = 0; +/*---------------------------------------------------------------------------*/ +void +leds_arch_init(void) +{ + if(inited) { + return; + } + inited = 1; + + ti_lib_rom_ioc_pin_type_gpio_output(BOARD_IOID_LED_1); + ti_lib_rom_ioc_pin_type_gpio_output(BOARD_IOID_LED_2); + + ti_lib_gpio_pin_write(BOARD_LED_ALL, 0); +} +/*---------------------------------------------------------------------------*/ +unsigned char +leds_arch_get(void) +{ + return c; +} +/*---------------------------------------------------------------------------*/ +void +leds_arch_set(unsigned char leds) +{ + c = leds; + ti_lib_gpio_pin_write(BOARD_LED_ALL, 0); + + if((leds & LEDS_RED) == LEDS_RED) { + ti_lib_gpio_pin_write(BOARD_LED_1, 1); + } + if((leds & LEDS_YELLOW) == LEDS_YELLOW) { + ti_lib_gpio_pin_write(BOARD_LED_2, 1); + } +} +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/mpu-9250-sensor.c b/platform/srf06-cc26xx/sensortag/mpu-9250-sensor.c new file mode 100644 index 000000000..fd7bff688 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/mpu-9250-sensor.c @@ -0,0 +1,685 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-mpu + * @{ + * + * \file + * Driver for the Sensortag-CC26XX Invensense MPU9250 motion processing unit + */ +/*---------------------------------------------------------------------------*/ +#include "contiki-conf.h" +#include "lib/sensors.h" +#include "mpu-9250-sensor.h" +#include "sys/rtimer.h" +#include "sensor-common.h" +#include "board-i2c.h" + +#include "ti-lib.h" + +#include +#include +#include +#include +/*---------------------------------------------------------------------------*/ +#define DEBUG 0 +#if DEBUG +#define PRINTF(...) printf(__VA_ARGS__) +#else +#define PRINTF(...) +#endif +/*---------------------------------------------------------------------------*/ +/* Sensor I2C address */ +#define SENSOR_I2C_ADDRESS 0x68 +#define SENSOR_MAG_I2_ADDRESS 0x0C +/*---------------------------------------------------------------------------*/ +/* Registers */ +#define SELF_TEST_X_GYRO 0x00 /* R/W */ +#define SELF_TEST_Y_GYRO 0x01 /* R/W */ +#define SELF_TEST_Z_GYRO 0x02 /* R/W */ +#define SELF_TEST_X_ACCEL 0x0D /* R/W */ +#define SELF_TEST_Z_ACCEL 0x0E /* R/W */ +#define SELF_TEST_Y_ACCEL 0x0F /* R/W */ +/*---------------------------------------------------------------------------*/ +#define XG_OFFSET_H 0x13 /* R/W */ +#define XG_OFFSET_L 0x14 /* R/W */ +#define YG_OFFSET_H 0x15 /* R/W */ +#define YG_OFFSET_L 0x16 /* R/W */ +#define ZG_OFFSET_H 0x17 /* R/W */ +#define ZG_OFFSET_L 0x18 /* R/W */ +/*---------------------------------------------------------------------------*/ +#define SMPLRT_DIV 0x19 /* R/W */ +#define CONFIG 0x1A /* R/W */ +#define GYRO_CONFIG 0x1B /* R/W */ +#define ACCEL_CONFIG 0x1C /* R/W */ +#define ACCEL_CONFIG_2 0x1D /* R/W */ +#define LP_ACCEL_ODR 0x1E /* R/W */ +#define WOM_THR 0x1F /* R/W */ +#define FIFO_EN 0x23 /* R/W */ +/*---------------------------------------------------------------------------*/ +/* + * Registers 0x24 - 0x36 are not applicable to the SensorTag HW configuration + * (IC2 Master) + */ +#define INT_PIN_CFG 0x37 /* R/W */ +#define INT_ENABLE 0x38 /* R/W */ +#define INT_STATUS 0x3A /* R */ +#define ACCEL_XOUT_H 0x3B /* R */ +#define ACCEL_XOUT_L 0x3C /* R */ +#define ACCEL_YOUT_H 0x3D /* R */ +#define ACCEL_YOUT_L 0x3E /* R */ +#define ACCEL_ZOUT_H 0x3F /* R */ +#define ACCEL_ZOUT_L 0x40 /* R */ +#define TEMP_OUT_H 0x41 /* R */ +#define TEMP_OUT_L 0x42 /* R */ +#define GYRO_XOUT_H 0x43 /* R */ +#define GYRO_XOUT_L 0x44 /* R */ +#define GYRO_YOUT_H 0x45 /* R */ +#define GYRO_YOUT_L 0x46 /* R */ +#define GYRO_ZOUT_H 0x47 /* R */ +#define GYRO_ZOUT_L 0x48 /* R */ +/*---------------------------------------------------------------------------*/ +/* + * Registers 0x49 - 0x60 are not applicable to the SensorTag HW configuration + * (external sensor data) + * + * Registers 0x63 - 0x67 are not applicable to the SensorTag HW configuration + * (I2C master) + */ +#define SIGNAL_PATH_RESET 0x68 /* R/W */ +#define ACCEL_INTEL_CTRL 0x69 /* R/W */ +#define USER_CTRL 0x6A /* R/W */ +#define PWR_MGMT_1 0x6B /* R/W */ +#define PWR_MGMT_2 0x6C /* R/W */ +#define FIFO_COUNT_H 0x72 /* R/W */ +#define FIFO_COUNT_L 0x73 /* R/W */ +#define FIFO_R_W 0x74 /* R/W */ +#define WHO_AM_I 0x75 /* R/W */ +/*---------------------------------------------------------------------------*/ +/* Masks is mpuConfig valiable */ +#define ACC_CONFIG_MASK 0x38 +#define GYRO_CONFIG_MASK 0x07 +/*---------------------------------------------------------------------------*/ +/* Values PWR_MGMT_1 */ +#define MPU_SLEEP 0x4F /* Sleep + stop all clocks */ +#define MPU_WAKE_UP 0x09 /* Disable temp. + intern osc */ +/*---------------------------------------------------------------------------*/ +/* Values PWR_MGMT_2 */ +#define ALL_AXES 0x3F +#define GYRO_AXES 0x07 +#define ACC_AXES 0x38 +/*---------------------------------------------------------------------------*/ +/* Data sizes */ +#define DATA_SIZE 6 +/*---------------------------------------------------------------------------*/ +/* Output data rates */ +#define INV_LPA_0_3125HZ 0 +#define INV_LPA_0_625HZ 1 +#define INV_LPA_1_25HZ 2 +#define INV_LPA_2_5HZ 3 +#define INV_LPA_5HZ 4 +#define INV_LPA_10HZ 5 +#define INV_LPA_20HZ 6 +#define INV_LPA_40HZ 7 +#define INV_LPA_80HZ 8 +#define INV_LPA_160HZ 9 +#define INV_LPA_320HZ 10 +#define INV_LPA_640HZ 11 +#define INV_LPA_STOPPED 255 +/*---------------------------------------------------------------------------*/ +/* Bit values */ +#define BIT_ANY_RD_CLR 0x10 +#define BIT_RAW_RDY_EN 0x01 +#define BIT_WOM_EN 0x40 +#define BIT_LPA_CYCLE 0x20 +#define BIT_STBY_XA 0x20 +#define BIT_STBY_YA 0x10 +#define BIT_STBY_ZA 0x08 +#define BIT_STBY_XG 0x04 +#define BIT_STBY_YG 0x02 +#define BIT_STBY_ZG 0x01 +#define BIT_STBY_XYZA (BIT_STBY_XA | BIT_STBY_YA | BIT_STBY_ZA) +#define BIT_STBY_XYZG (BIT_STBY_XG | BIT_STBY_YG | BIT_STBY_ZG) +/*---------------------------------------------------------------------------*/ +/* User control register */ +#define BIT_ACTL 0x80 +#define BIT_LATCH_EN 0x20 +/*---------------------------------------------------------------------------*/ +/* INT Pin / Bypass Enable Configuration */ +#define BIT_AUX_IF_EN 0x20 /* I2C_MST_EN */ +#define BIT_BYPASS_EN 0x02 +/*---------------------------------------------------------------------------*/ +#define ACC_RANGE_INVALID -1 + +#define ACC_RANGE_2G 0 +#define ACC_RANGE_4G 1 +#define ACC_RANGE_8G 2 +#define ACC_RANGE_16G 3 + +#define MPU_AX_GYR_X 2 +#define MPU_AX_GYR_Y 1 +#define MPU_AX_GYR_Z 0 +#define MPU_AX_GYR 0x07 + +#define MPU_AX_ACC_X 5 +#define MPU_AX_ACC_Y 4 +#define MPU_AX_ACC_Z 3 +#define MPU_AX_ACC 0x38 + +#define MPU_AX_MAG 6 +/*---------------------------------------------------------------------------*/ +#define MPU_DATA_READY 0x01 +#define MPU_MOVEMENT 0x40 +/*---------------------------------------------------------------------------*/ +/* Sensor selection/deselection */ +#define SENSOR_SELECT() board_i2c_select(BOARD_I2C_INTERFACE_1, SENSOR_I2C_ADDRESS) +#define SENSOR_DESELECT() board_i2c_deselect() +/*---------------------------------------------------------------------------*/ +/* Delay */ +#define delay_ms(i) (ti_lib_cpu_delay(8000 * (i))) +/*---------------------------------------------------------------------------*/ +static uint8_t mpu_config; +static uint8_t acc_range; +static uint8_t acc_range_reg; +static uint8_t val; +static uint8_t interrupt_status; +/*---------------------------------------------------------------------------*/ +#define SENSOR_STATUS_DISABLED 0 +#define SENSOR_STATUS_BOOTING 1 +#define SENSOR_STATUS_ENABLED 2 + +static int enabled = SENSOR_STATUS_DISABLED; +static int elements; +/*---------------------------------------------------------------------------*/ +/* 3 16-byte words for all sensor readings */ +#define SENSOR_DATA_BUF_SIZE 3 + +static uint16_t sensor_value[SENSOR_DATA_BUF_SIZE]; +/*---------------------------------------------------------------------------*/ +/* + * Wait SENSOR_BOOT_DELAY ticks for the sensor to boot and + * SENSOR_STARTUP_DELAY for readings to be ready + * Gyro is a little slower than Acc + */ +#define SENSOR_BOOT_DELAY 8 +#define SENSOR_STARTUP_DELAY 5 + +static struct ctimer startup_timer; +/*---------------------------------------------------------------------------*/ +/* Wait for the MPU to have data ready */ +rtimer_clock_t t0; + +/* + * Wait timeout in rtimer ticks. This is just a random low number, since the + * first time we read the sensor status, it should be ready to return data + */ +#define READING_WAIT_TIMEOUT 10 +/*---------------------------------------------------------------------------*/ +/** + * \brief Place the MPU in low power mode + */ +static void +sensor_sleep(void) +{ + SENSOR_SELECT(); + + val = ALL_AXES; + sensor_common_write_reg(PWR_MGMT_2, &val, 1); + + val = MPU_SLEEP; + sensor_common_write_reg(PWR_MGMT_1, &val, 1); + SENSOR_DESELECT(); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Exit low power mode + */ +static void +sensor_wakeup(void) +{ + SENSOR_SELECT(); + val = MPU_WAKE_UP; + sensor_common_write_reg(PWR_MGMT_1, &val, 1); + + /* All axis initially disabled */ + val = ALL_AXES; + sensor_common_write_reg(PWR_MGMT_2, &val, 1); + mpu_config = 0; + + /* Restore the range */ + sensor_common_write_reg(ACCEL_CONFIG, &acc_range_reg, 1); + + /* Clear interrupts */ + sensor_common_read_reg(INT_STATUS, &val, 1); + SENSOR_DESELECT(); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Select gyro and accelerometer axes + */ +static void +select_axes(void) +{ + val = ~mpu_config; + sensor_common_write_reg(PWR_MGMT_2, &val, 1); +} +/*---------------------------------------------------------------------------*/ +static void +convert_to_le(uint8_t *data, uint8_t len) +{ + int i; + for(i = 0; i < len; i += 2) { + uint8_t tmp; + tmp = data[i]; + data[i] = data[i + 1]; + data[i + 1] = tmp; + } +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Set the range of the accelerometer + * \param new_range: ACC_RANGE_2G, ACC_RANGE_4G, ACC_RANGE_8G, ACC_RANGE_16G + * \return true if the write to the sensor succeeded + */ +static bool +acc_set_range(uint8_t new_range) +{ + bool success; + + if(new_range == acc_range) { + return true; + } + + success = false; + + acc_range_reg = (new_range << 3); + + /* Apply the range */ + SENSOR_SELECT(); + success = sensor_common_write_reg(ACCEL_CONFIG, &acc_range_reg, 1); + SENSOR_DESELECT(); + + if(success) { + acc_range = new_range; + } + + return success; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialise the MPU + * \return True if success + */ +static bool +init_sensor(void) +{ + bool ret; + + interrupt_status = false; + acc_range = ACC_RANGE_INVALID; + mpu_config = 0; /* All axes off */ + + /* Device reset */ + val = 0x80; + SENSOR_SELECT(); + ret = sensor_common_write_reg(PWR_MGMT_1, &val, 1); + SENSOR_DESELECT(); + + if(ret) { + delay_ms(200); + + /* Initial configuration */ + acc_set_range(ACC_RANGE_8G); + /* Power save */ + sensor_sleep(); + } + + return ret; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Check whether a data or wake on motion interrupt has occurred + * \return Return the interrupt status + * + * This driver does not use interrupts, however this function allows us to + * determine whether a new sensor reading is available + */ +static uint8_t +int_status(void) +{ + SENSOR_SELECT(); + sensor_common_read_reg(INT_STATUS, &interrupt_status, 1); + SENSOR_DESELECT(); + + return interrupt_status; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Enable the MPU + * \param axes: Gyro bitmap [0..2], X = 1, Y = 2, Z = 4. 0 = gyro off + * Acc bitmap [3..5], X = 8, Y = 16, Z = 32. 0 = accelerometer off + */ +static void +enable_sensor(uint16_t axes) +{ + if(mpu_config == 0 && axes != 0) { + /* Wake up the sensor if it was off */ + sensor_wakeup(); + } + + mpu_config = axes; + + if(mpu_config != 0) { + /* Enable gyro + accelerometer readout */ + select_axes(); + delay_ms(10); + } else if(mpu_config == 0) { + sensor_sleep(); + } +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Read data from the accelerometer - X, Y, Z - 3 words + * \return True if a valid reading could be taken, false otherwise + */ +static bool +acc_read(uint16_t *data) +{ + bool success; + + if(interrupt_status & BIT_RAW_RDY_EN) { + /* Burst read of all accelerometer values */ + SENSOR_SELECT(); + success = sensor_common_read_reg(ACCEL_XOUT_H, (uint8_t *)data, DATA_SIZE); + SENSOR_DESELECT(); + + if(success) { + convert_to_le((uint8_t *)data, DATA_SIZE); + } else { + sensor_common_set_error_data((uint8_t *)data, DATA_SIZE); + } + } else { + /* Data not ready */ + success = false; + } + + return success; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Read data from the gyroscope - X, Y, Z - 3 words + * \return True if a valid reading could be taken, false otherwise + */ +static bool +gyro_read(uint16_t *data) +{ + bool success; + + if(interrupt_status & BIT_RAW_RDY_EN) { + /* Select this sensor */ + SENSOR_SELECT(); + + /* Burst read of all gyroscope values */ + success = sensor_common_read_reg(GYRO_XOUT_H, (uint8_t *)data, DATA_SIZE); + + SENSOR_DESELECT(); + + if(success) { + convert_to_le((uint8_t *)data, DATA_SIZE); + } else { + sensor_common_set_error_data((uint8_t *)data, DATA_SIZE); + } + } else { + success = false; + } + + return success; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Convert accelerometer raw reading to a value in G + * \param raw_data The raw accelerometer reading + * \return The converted value + */ +static float +acc_convert(int16_t raw_data) +{ + float v = 0; + + switch(acc_range) { + case ACC_RANGE_2G: + /* Calculate acceleration, unit G, range -2, +2 */ + v = (raw_data * 1.0) / (32768 / 2); + break; + case ACC_RANGE_4G: + /* Calculate acceleration, unit G, range -4, +4 */ + v = (raw_data * 1.0) / (32768 / 4); + break; + case ACC_RANGE_8G: + /* Calculate acceleration, unit G, range -8, +8 */ + v = (raw_data * 1.0) / (32768 / 8); + break; + case ACC_RANGE_16G: + /* Calculate acceleration, unit G, range -16, +16 */ + v = (raw_data * 1.0) / (32768 / 16); + break; + default: + v = 0; + break; + } + + return v; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Convert gyro raw reading to a value in deg/sec + * \param raw_data The raw accelerometer reading + * \return The converted value + */ +static float +gyro_convert(int16_t raw_data) +{ + /* calculate rotation, unit deg/s, range -250, +250 */ + return (raw_data * 1.0) / (65536 / 500); +} +/*---------------------------------------------------------------------------*/ +static void +notify_ready(void *not_used) +{ + enabled = SENSOR_STATUS_ENABLED; + sensors_changed(&mpu_9250_sensor); +} +/*---------------------------------------------------------------------------*/ +static void +initialise(void *not_used) +{ + init_sensor(); + + /* Configure the accelerometer range */ + if((elements & MPU_9250_SENSOR_TYPE_ACC) != 0) { + acc_set_range(MPU_9250_SENSOR_ACC_RANGE); + } + + enable_sensor(elements & MPU_9250_SENSOR_TYPE_ALL); + + ctimer_set(&startup_timer, SENSOR_STARTUP_DELAY, notify_ready, NULL); +} +/*---------------------------------------------------------------------------*/ +static void +power_up(void) +{ + ti_lib_gpio_pin_write(BOARD_MPU_POWER, 1); + enabled = SENSOR_STATUS_BOOTING; + + ctimer_set(&startup_timer, SENSOR_BOOT_DELAY, initialise, NULL); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Returns a reading from the sensor + * \param type MPU_9250_SENSOR_TYPE_ACC_[XYZ] or MPU_9250_SENSOR_TYPE_GYRO_[XYZ] + * \return centi-G (ACC) or centi-Deg/Sec (Gyro) + */ +static int +value(int type) +{ + int rv; + float converted_val = 0; + + if(enabled == SENSOR_STATUS_DISABLED) { + PRINTF("MPU: Sensor Disabled\n"); + return CC26XX_SENSOR_READING_ERROR; + } + + memset(sensor_value, 0, sizeof(sensor_value)); + + if((type & MPU_9250_SENSOR_TYPE_ACC) != 0) { + t0 = RTIMER_NOW(); + + while(!int_status() && + (RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + READING_WAIT_TIMEOUT))); + + rv = acc_read(sensor_value); + + if(rv == 0) { + return CC26XX_SENSOR_READING_ERROR; + } + + PRINTF("MPU: ACC = 0x%04x 0x%04x 0x%04x = ", + sensor_value[0], sensor_value[1], sensor_value[2]); + + /* Convert */ + if(type == MPU_9250_SENSOR_TYPE_ACC_X) { + converted_val = acc_convert(sensor_value[0]); + } else if(type == MPU_9250_SENSOR_TYPE_ACC_Y) { + converted_val = acc_convert(sensor_value[1]); + } else if(type == MPU_9250_SENSOR_TYPE_ACC_Z) { + converted_val = acc_convert(sensor_value[2]); + } + rv = (int)(converted_val * 100); + } else if((type & MPU_9250_SENSOR_TYPE_GYRO) != 0) { + t0 = RTIMER_NOW(); + + while(!int_status() && + (RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + READING_WAIT_TIMEOUT))); + + rv = gyro_read(sensor_value); + + if(rv == 0) { + return CC26XX_SENSOR_READING_ERROR; + } + + PRINTF("MPU: Gyro = 0x%04x 0x%04x 0x%04x = ", + sensor_value[0], sensor_value[1], sensor_value[2]); + + if(type == MPU_9250_SENSOR_TYPE_GYRO_X) { + converted_val = gyro_convert(sensor_value[0]); + } else if(type == MPU_9250_SENSOR_TYPE_GYRO_Y) { + converted_val = gyro_convert(sensor_value[1]); + } else if(type == MPU_9250_SENSOR_TYPE_GYRO_Z) { + converted_val = gyro_convert(sensor_value[2]); + } + rv = (int)(converted_val * 100); + } else { + PRINTF("MPU: Invalid type\n"); + rv = CC26XX_SENSOR_READING_ERROR; + } + + PRINTF("%ld\n", (long int)(converted_val * 100)); + + return rv; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Configuration function for the MPU9250 sensor. + * + * \param type Activate, enable or disable the sensor. See below + * \param enable + * + * When type == SENSORS_HW_INIT we turn on the hardware + * When type == SENSORS_ACTIVE and enable==1 we enable the sensor + * When type == SENSORS_ACTIVE and enable==0 we disable the sensor + */ +static int +configure(int type, int enable) +{ + switch(type) { + case SENSORS_HW_INIT: + elements = MPU_9250_SENSOR_TYPE_NONE; + break; + case SENSORS_ACTIVE: + if((enable & MPU_9250_SENSOR_TYPE_ACC) != 0 || + (enable & MPU_9250_SENSOR_TYPE_GYRO) != 0) { + PRINTF("MPU: Enabling\n"); + elements = enable & MPU_9250_SENSOR_TYPE_ALL; + + power_up(); + + enabled = SENSOR_STATUS_BOOTING; + } else { + PRINTF("MPU: Disabling\n"); + ctimer_stop(&startup_timer); + elements = MPU_9250_SENSOR_TYPE_NONE; + enable_sensor(0); + while(ti_lib_i2c_master_busy(I2C0_BASE)); + enabled = SENSOR_STATUS_DISABLED; + } + break; + case MPU_9250_SENSOR_SHUTDOWN: + ti_lib_gpio_pin_write(BOARD_MPU_POWER, 0); + break; + default: + break; + } + return enabled; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Returns the status of the sensor + * \param type SENSORS_ACTIVE or SENSORS_READY + * \return 1 if the sensor is enabled + */ +static int +status(int type) +{ + switch(type) { + case SENSORS_ACTIVE: + case SENSORS_READY: + return enabled; + break; + default: + break; + } + return SENSOR_STATUS_DISABLED; +} +/*---------------------------------------------------------------------------*/ +SENSORS_SENSOR(mpu_9250_sensor, "MPU9250", value, configure, status); +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/mpu-9250-sensor.h b/platform/srf06-cc26xx/sensortag/mpu-9250-sensor.h new file mode 100644 index 000000000..46836a538 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/mpu-9250-sensor.h @@ -0,0 +1,112 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-mpu SensorTag 2.0 Motion Processing Unit + * + * Driver for the Invensense MPU9250 Motion Processing Unit. + * + * Due to the time required between triggering a reading and the reading + * becoming available, this driver is meant to be used in an asynchronous + * fashion. The caller must first activate the sensor by calling + * mpu_9250_sensor.configure(SENSORS_ACTIVE, xyz); + * The value for the xyz arguments depends on the required readings. If the + * caller intends to read both the accelerometer as well as the gyro then + * xyz should be MPU_9250_SENSOR_TYPE_ALL. If the caller only needs to take a + * reading from one of the two elements, xyz should be one of + * MPU_9250_SENSOR_TYPE_ACC or MPU_9250_SENSOR_TYPE_GYRO + * + * Calling .configure() will power up the sensor and initialise it. When the + * sensor is ready to provide readings, the driver will generate a + * sensors_changed event. + * + * Calls to .status() will return the driver's state which could indicate that + * the sensor is off, booting or on. + * + * Once a reading has been taken, the caller has two options: + * - Turn the sensor off by calling SENSORS_DEACTIVATE, but in order to take + * subsequent readings the sensor must be started up all over + * - Leave the sensor on. In this scenario, the caller can simply keep calling + * value() for subsequent readings, but having the sensor on will consume + * more energy, especially if both accelerometer and the gyro are on. + * @{ + * + * \file + * Header file for the Sensortag-CC26XX Invensense MPU9250 motion processing unit + */ +/*---------------------------------------------------------------------------*/ +#ifndef MPU_9250_SENSOR_H_ +#define MPU_9250_SENSOR_H_ +/*---------------------------------------------------------------------------*/ +/* ACC / Gyro Axes */ +#define MPU_9250_SENSOR_TYPE_GYRO_Z 0x01 +#define MPU_9250_SENSOR_TYPE_GYRO_Y 0x02 +#define MPU_9250_SENSOR_TYPE_GYRO_X 0x04 +#define MPU_9250_SENSOR_TYPE_GYRO_ALL 0x07 + +#define MPU_9250_SENSOR_TYPE_ACC_Z 0x08 +#define MPU_9250_SENSOR_TYPE_ACC_Y 0x10 +#define MPU_9250_SENSOR_TYPE_ACC_X 0x20 +#define MPU_9250_SENSOR_TYPE_ACC_ALL 0x38 + +#define MPU_9250_SENSOR_TYPE_MASK 0x3F +#define MPU_9250_SENSOR_TYPE_ACC 0x38 +#define MPU_9250_SENSOR_TYPE_GYRO 0x07 + +#define MPU_9250_SENSOR_TYPE_NONE 0 +#define MPU_9250_SENSOR_TYPE_ALL (MPU_9250_SENSOR_TYPE_ACC | \ + MPU_9250_SENSOR_TYPE_GYRO) + +#define MPU_9250_SENSOR_SHUTDOWN 0xFF +/*---------------------------------------------------------------------------*/ +/* Accelerometer range */ +#define MPU_9250_SENSOR_ACC_RANGE_2G 0 +#define MPU_9250_SENSOR_ACC_RANGE_4G 1 +#define MPU_9250_SENSOR_ACC_RANGE_8G 2 +#define MPU_9250_SENSOR_ACC_RANGE_16G 3 +/*---------------------------------------------------------------------------*/ +/* Accelerometer range configuration */ +#ifdef MPU_9250_SENSOR_CONF_ACC_RANGE +#define MPU_9250_SENSOR_ACC_RANGE MPU_9250_SENSOR_CONF_ACC_RANGE +#else +#define MPU_9250_SENSOR_ACC_RANGE MPU_9250_SENSOR_ACC_RANGE_2G +#endif +/*---------------------------------------------------------------------------*/ +extern const struct sensors_sensor mpu_9250_sensor; +/*---------------------------------------------------------------------------*/ +#endif /* MPU_9250_SENSOR_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/opt-3001-sensor.c b/platform/srf06-cc26xx/sensortag/opt-3001-sensor.c new file mode 100644 index 000000000..7cb41bf6d --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/opt-3001-sensor.c @@ -0,0 +1,273 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-opt-sensor + * @{ + * + * \file + * Driver for the Sensortag-CC26xx Opt3001 light sensor + */ +/*---------------------------------------------------------------------------*/ +#include "contiki-conf.h" +#include "lib/sensors.h" +#include "opt-3001-sensor.h" +#include "sys/ctimer.h" +#include "ti-lib.h" +#include "board-i2c.h" +#include "sensor-common.h" + +#include +#include +#include +#include +#include +/*---------------------------------------------------------------------------*/ +#define DEBUG 0 +#if DEBUG +#define PRINTF(...) printf(__VA_ARGS__) +#else +#define PRINTF(...) +#endif +/*---------------------------------------------------------------------------*/ +/* Slave address */ +#define OPT3001_I2C_ADDRESS 0x45 +/*---------------------------------------------------------------------------*/ +/* Register addresses */ +#define REG_RESULT 0x00 +#define REG_CONFIGURATION 0x01 +#define REG_LOW_LIMIT 0x02 +#define REG_HIGH_LIMIT 0x03 + +#define REG_MANUFACTURER_ID 0x7E +#define REG_DEVICE_ID 0x7F +/*---------------------------------------------------------------------------*/ +/* Register values */ +#define MANUFACTURER_ID 0x5449 /* TI */ +#define DEVICE_ID 0x3001 /* Opt 3001 */ +#define CONFIG_RESET 0xC810 +#define CONFIG_TEST 0xCC10 +#define CONFIG_ENABLE 0x10CC /* 0xCC10 */ +#define CONFIG_DISABLE 0x108C /* 0xC810 */ +/*---------------------------------------------------------------------------*/ +/* Bit values */ +#define DATA_RDY_BIT 0x0080 /* Data ready */ +/*---------------------------------------------------------------------------*/ +/* Register length */ +#define REGISTER_LENGTH 2 +/*---------------------------------------------------------------------------*/ +/* Sensor data size */ +#define DATA_LENGTH 2 +/*---------------------------------------------------------------------------*/ +#define SENSOR_STATUS_DISABLED 0 +#define SENSOR_STATUS_NOT_READY 1 +#define SENSOR_STATUS_ENABLED 2 + +static int enabled = SENSOR_STATUS_DISABLED; +/*---------------------------------------------------------------------------*/ +/* Wait SENSOR_STARTUP_DELAY for the sensor to be ready - 125ms */ +#define SENSOR_STARTUP_DELAY (CLOCK_SECOND >> 3) + +static struct ctimer startup_timer; +/*---------------------------------------------------------------------------*/ +static void +notify_ready(void *not_used) +{ + enabled = SENSOR_STATUS_ENABLED; + sensors_changed(&opt_3001_sensor); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Select the sensor on the I2C bus + */ +static void +select(void) +{ + /* Select slave and set clock rate */ + board_i2c_select(BOARD_I2C_INTERFACE_0, OPT3001_I2C_ADDRESS); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Turn the sensor on/off + * \param enable TRUE: on, FALSE: off + */ +static void +enable_sensor(bool enable) +{ + uint16_t val; + + select(); + + if(enable) { + val = CONFIG_ENABLE; + } else { + val = CONFIG_DISABLE; + } + + sensor_common_write_reg(REG_CONFIGURATION, (uint8_t *)&val, REGISTER_LENGTH); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Read the result register + * \param raw_data Pointer to a buffer to store the reading + * \return TRUE if valid data + */ +static bool +read_data(uint16_t *raw_data) +{ + bool success; + uint16_t val; + + select(); + + success = sensor_common_read_reg(REG_CONFIGURATION, (uint8_t *)&val, + REGISTER_LENGTH); + + if(success) { + success = (val & DATA_RDY_BIT) == DATA_RDY_BIT; + } + + if(success) { + success = sensor_common_read_reg(REG_RESULT, (uint8_t *)&val, DATA_LENGTH); + } + + if(success) { + /* Swap bytes */ + *raw_data = (val << 8) | (val >> 8 & 0xFF); + } else { + sensor_common_set_error_data((uint8_t *)raw_data, DATA_LENGTH); + } + + return success; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Convert raw data to a value in lux + * \param data Pointer to a buffer with a raw sensor reading + * \return Converted value (lux) + */ +static float +convert(uint16_t raw_data) +{ + uint16_t e, m; + + m = raw_data & 0x0FFF; + e = (raw_data & 0xF000) >> 12; + + return m * (0.01 * exp2(e)); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Returns a reading from the sensor + * \param type Ignored + * \return Illuminance in centilux + */ +static int +value(int type) +{ + int rv; + uint16_t raw_val; + float converted_val; + + if(enabled != SENSOR_STATUS_ENABLED) { + PRINTF("Sensor disabled or starting up (%d)\n", enabled); + return CC26XX_SENSOR_READING_ERROR; + } + + rv = read_data(&raw_val); + + if(rv == 0) { + return CC26XX_SENSOR_READING_ERROR; + } + + converted_val = convert(raw_val); + PRINTF("OPT: %04X r=%d (centilux)\n", raw_val, + (int)(converted_val * 100)); + + rv = (int)(converted_val * 100); + + return rv; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Configuration function for the OPT3001 sensor. + * + * \param type Activate, enable or disable the sensor. See below + * \param enable + * + * When type == SENSORS_HW_INIT we turn on the hardware + * When type == SENSORS_ACTIVE and enable==1 we enable the sensor + * When type == SENSORS_ACTIVE and enable==0 we disable the sensor + */ +static int +configure(int type, int enable) +{ + switch(type) { + case SENSORS_HW_INIT: + break; + case SENSORS_ACTIVE: + if(enable) { + enable_sensor(1); + ctimer_set(&startup_timer, SENSOR_STARTUP_DELAY, notify_ready, NULL); + enabled = SENSOR_STATUS_NOT_READY; + } else { + ctimer_stop(&startup_timer); + enable_sensor(0); + enabled = SENSOR_STATUS_DISABLED; + } + break; + default: + break; + } + return enabled; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Returns the status of the sensor + * \param type SENSORS_ACTIVE or SENSORS_READY + * \return 1 if the sensor is enabled + */ +static int +status(int type) +{ + switch(type) { + case SENSORS_ACTIVE: + case SENSORS_READY: + return enabled; + break; + default: + break; + } + return SENSOR_STATUS_DISABLED; +} +/*---------------------------------------------------------------------------*/ +SENSORS_SENSOR(opt_3001_sensor, "OPT3001", value, configure, status); +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/opt-3001-sensor.h b/platform/srf06-cc26xx/sensortag/opt-3001-sensor.h new file mode 100644 index 000000000..205ab00ff --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/opt-3001-sensor.h @@ -0,0 +1,67 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-opt-sensor SensorTag 2.0 Light Sensor + * + * Due to the time required for the sensor to startup, this driver is meant to + * be used in an asynchronous fashion. The caller must first activate the + * sensor by calling SENSORS_ACTIVATE(). This will trigger the sensor's startup + * sequence, but the call will not wait for it to complete so that the CPU can + * perform other tasks or drop to a low power mode. + * + * Once the sensor is stable, the driver will generate a sensors_changed event. + * + * Once a reading has been taken, the caller has two options: + * - Turn the sensor off by calling SENSORS_DEACTIVATE, but in order to take + * subsequent readings SENSORS_ACTIVATE must be called again + * - Leave the sensor on. In this scenario, the caller can simply keep calling + * value() for subsequent readings, but having the sensor on will consume + * energy + * @{ + * + * \file + * Header file for the Sensortag-CC26xx Opt3001 light sensor + */ +/*---------------------------------------------------------------------------*/ +#ifndef OPT_3001_SENSOR_H_ +#define OPT_3001_SENSOR_H_ +/*---------------------------------------------------------------------------*/ +extern const struct sensors_sensor opt_3001_sensor; +/*---------------------------------------------------------------------------*/ +#endif /* OPT_3001_SENSOR_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/reed-relay.c b/platform/srf06-cc26xx/sensortag/reed-relay.c new file mode 100644 index 000000000..b5956f6f8 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/reed-relay.c @@ -0,0 +1,140 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-reed-relay + * @{ + * + * \file + * Driver for the Sensortag-CC26XX Reed Relay + */ +/*---------------------------------------------------------------------------*/ +#include "contiki.h" +#include "sys/clock.h" +#include "sys/timer.h" +#include "lib/sensors.h" +#include "sensortag/reed-relay.h" +#include "gpio-interrupt.h" +#include "sys/timer.h" + +#include "ti-lib.h" + +#include +/*---------------------------------------------------------------------------*/ +static struct timer debouncetimer; +/*---------------------------------------------------------------------------*/ +#define REED_ISR_CFG (IOC_CURRENT_2MA | IOC_STRENGTH_AUTO | \ + IOC_IOPULL_DOWN | IOC_SLEW_DISABLE | \ + IOC_HYST_DISABLE | IOC_BOTH_EDGES | \ + IOC_INT_DISABLE | IOC_IOMODE_NORMAL | \ + IOC_NO_WAKE_UP | IOC_INPUT_ENABLE | \ + IOC_JTAG_DISABLE) +/*---------------------------------------------------------------------------*/ +/** + * \brief Handler for Sensortag-CC26XX reed interrupts + */ +static void +reed_interrupt_handler(uint8_t ioid) +{ + if(!timer_expired(&debouncetimer)) { + ENERGEST_OFF(ENERGEST_TYPE_IRQ); + return; + } + + sensors_changed(&reed_relay_sensor); + timer_set(&debouncetimer, CLOCK_SECOND / 2); +} +/*---------------------------------------------------------------------------*/ +static int +value(int type) +{ + return (int)ti_lib_gpio_pin_read(1 << BOARD_IOID_REED_RELAY); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Configuration function for the button sensor for all buttons. + * + * \param type SENSORS_HW_INIT: Initialise. SENSORS_ACTIVE: Enables/Disables + * depending on 'value' + * \param value 0: disable, non-zero: enable + * \return Always returns 1 + */ +static int +configure(int type, int value) +{ + switch(type) { + case SENSORS_HW_INIT: + ti_lib_ioc_int_disable(BOARD_IOID_REED_RELAY); + ti_lib_gpio_event_clear(1 << BOARD_IOID_REED_RELAY); + + /* Enabled the GPIO clock when the CM3 is running */ + ti_lib_prcm_peripheral_run_enable(PRCM_PERIPH_GPIO); + ti_lib_ioc_port_configure_set(BOARD_IOID_REED_RELAY, IOC_PORT_GPIO, + REED_ISR_CFG); + + gpio_interrupt_register_handler(BOARD_IOID_REED_RELAY, + reed_interrupt_handler); + break; + case SENSORS_ACTIVE: + if(value) { + ti_lib_ioc_int_enable(BOARD_IOID_REED_RELAY); + } else { + ti_lib_ioc_int_disable(BOARD_IOID_REED_RELAY); + } + break; + default: + break; + } + return 1; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Status function for the reed + * \param type SENSORS_ACTIVE or SENSORS_READY + * \return 1 Interrupt enabled, 0: Disabled + */ +static int +status(int type) +{ + switch(type) { + case SENSORS_ACTIVE: + case SENSORS_READY: + return (ti_lib_ioc_port_configure_get(BOARD_IOID_REED_RELAY) + & IOC_INT_ENABLE) == IOC_INT_ENABLE; + break; + default: + break; + } + return 0; +} +/*---------------------------------------------------------------------------*/ +SENSORS_SENSOR(reed_relay_sensor, "REED", value, configure, status); +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/reed-relay.h b/platform/srf06-cc26xx/sensortag/reed-relay.h new file mode 100644 index 000000000..3ec712719 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/reed-relay.h @@ -0,0 +1,59 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-reed-relay SensorTag 2.0 Reed Relay + * + * The reed relay acts like a button without a button. To trigger the reed, + * approach a magnet to the sensortag and a sensors_changed event will be + * generated, in a fashion similar to as if a button had been pressed + * + * @{ + * + * \file + * Header file for the Sensortag-CC26XX Reed Relay + */ +/*---------------------------------------------------------------------------*/ +#ifndef REED_RELAY_H +#define REED_RELAY_H +/*---------------------------------------------------------------------------*/ +#include "lib/sensors.h" +/*---------------------------------------------------------------------------*/ +extern const struct sensors_sensor reed_relay_sensor; +/*---------------------------------------------------------------------------*/ +#endif /* REED_RELAY_H */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/sensor-common.c b/platform/srf06-cc26xx/sensortag/sensor-common.c new file mode 100644 index 000000000..0c09bf630 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/sensor-common.c @@ -0,0 +1,79 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-sensor-common + * @{ + * + * \file + * Utilities common among SensorTag sensors + */ +/*---------------------------------------------------------------------------*/ +#include "sensor-common.h" +#include "board-i2c.h" +/*---------------------------------------------------------------------------*/ +/* Data to use when an error occurs */ +#define ERROR_DATA 0xCC +/*---------------------------------------------------------------------------*/ +static uint8_t buffer[32]; +/*---------------------------------------------------------------------------*/ +bool +sensor_common_read_reg(uint8_t addr, uint8_t *buf, uint8_t len) +{ + return board_i2c_write_read(&addr, 1, buf, len); +} +/*---------------------------------------------------------------------------*/ +bool +sensor_common_write_reg(uint8_t addr, uint8_t *buf, uint8_t len) +{ + uint8_t i; + uint8_t *p = buffer; + + /* Copy address and data to local buffer for burst write */ + *p++ = addr; + for(i = 0; i < len; i++) { + *p++ = *buf++; + } + len++; + + /* Send data */ + return board_i2c_write(buffer, len); +} +/*---------------------------------------------------------------------------*/ +void +sensor_common_set_error_data(uint8_t *buf, uint8_t len) +{ + while(len > 0) { + len--; + buf[len] = ERROR_DATA; + } +} +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/sensor-common.h b/platform/srf06-cc26xx/sensortag/sensor-common.h new file mode 100644 index 000000000..977650d5e --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/sensor-common.h @@ -0,0 +1,85 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-sensor-common SensorTag 2.0 Sensors + * @{ + * + * \file + * Header file for the Sensortag-CC26xx Common sensor utilities + */ +/*---------------------------------------------------------------------------*/ +#ifndef SENSOR_H +#define SENSOR_H +/*---------------------------------------------------------------------------*/ +#include "board-i2c.h" + +#include +#include +/*---------------------------------------------------------------------------*/ +/** + * \brief Reads a sensor's register over I2C + * \param addr The address of the register to read + * \param buf Pointer to buffer to place data + * \param len Number of bytes to read + * \return TRUE if the required number of bytes are received + * + * The sensor must be selected before this routine is called. + */ +bool sensor_common_read_reg(uint8_t addr, uint8_t *buf, uint8_t len); + +/** + * \brief Write to a sensor's register over I2C + * \param addr The address of the register to read + * \param buf Pointer to buffer containing data to be written + * \param len Number of bytes to write + * \return TRUE if successful write + * + * The sensor must be selected before this routine is called. + */ +bool sensor_common_write_reg(uint8_t addr, uint8_t *buf, uint8_t len); + +/** + * \brief Fill a result buffer with dummy error data + * \param buf Pointer to the buffer where to write the data + * \param len Number of bytes to fill + * \return bitmask of error flags + */ +void sensor_common_set_error_data(uint8_t *buf, uint8_t len); +/*---------------------------------------------------------------------------*/ +#endif /* SENSOR_H */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/sensortag-sensors.c b/platform/srf06-cc26xx/sensortag/sensortag-sensors.c new file mode 100644 index 000000000..a8f26aefe --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/sensortag-sensors.c @@ -0,0 +1,55 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \file + * Generic module controlling sensors on CC26XX Sensortag + */ +/*---------------------------------------------------------------------------*/ +#include "contiki.h" +#include "sensortag/button-sensor.h" +#include "sensortag/bmp-280-sensor.h" +#include "sensortag/tmp-007-sensor.h" +#include "sensortag/opt-3001-sensor.h" +#include "sensortag/sht-21-sensor.h" +#include "sensortag/mpu-9250-sensor.h" +#include "sensortag/reed-relay.h" + +#include +/*---------------------------------------------------------------------------*/ +/** \brief Exports a global symbol to be used by the sensor API */ +SENSORS(&button_left_sensor, &button_right_sensor, + &bmp_280_sensor, &tmp_007_sensor, &opt_3001_sensor, &sht_21_sensor, + &mpu_9250_sensor, &reed_relay_sensor); +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/sht-21-sensor.c b/platform/srf06-cc26xx/sensortag/sht-21-sensor.c new file mode 100644 index 000000000..f90e12f55 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/sht-21-sensor.c @@ -0,0 +1,386 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-sht-sensor + * @{ + * + * \file + * Driver for the Sensortag-CC26xx Sensirion SHT21 Humidity sensor + */ +/*---------------------------------------------------------------------------*/ +#include "contiki-conf.h" +#include "sys/ctimer.h" +#include "lib/sensors.h" +#include "sht-21-sensor.h" +#include "sensor-common.h" +#include "board-i2c.h" + +#include "ti-lib.h" + +#include +#include +#include +/*---------------------------------------------------------------------------*/ +#define DEBUG 0 +#if DEBUG +#define PRINTF(...) printf(__VA_ARGS__) +#else +#define PRINTF(...) +#endif +/*---------------------------------------------------------------------------*/ +/* Sensor I2C address */ +#define HAL_SHT21_I2C_ADDRESS 0x40 +/*---------------------------------------------------------------------------*/ +#define S_REG_LEN 2 +#define DATA_LEN 3 +/*---------------------------------------------------------------------------*/ +/* Internal commands */ +#define SHT21_CMD_TEMP_T_NH 0xF3 /* command trig. temp meas. no hold master */ +#define SHT21_CMD_HUMI_T_NH 0xF5 /* command trig. humidity meas. no hold master */ +#define SHT21_CMD_WRITE_U_R 0xE6 /* command write user register */ +#define SHT21_CMD_READ_U_R 0xE7 /* command read user register */ +#define SHT21_CMD_SOFT_RST 0xFE /* command soft reset */ +/*---------------------------------------------------------------------------*/ +#define HUMIDITY 0x00 +#define TEMPERATURE 0x01 +/*---------------------------------------------------------------------------*/ +#define USR_REG_MASK 0x38 /* Mask off reserved bits (3,4,5) */ +#define USR_REG_DEFAULT 0x02 /* Disable OTP reload */ +#define USR_REG_RES_MASK 0x7E /* Only change bits 0 and 7 (meas. res.) */ +#define USR_REG_11BITRES 0x81 /* 11-bit resolution */ +/*---------------------------------------------------------------------------*/ +#define USR_REG_TEST_VAL 0x83 +/*---------------------------------------------------------------------------*/ +#define DATA_SIZE 6 +/*---------------------------------------------------------------------------*/ +static uint8_t usr; /* User register value */ +static uint8_t buf[DATA_SIZE]; /* Data buffer */ +static bool success; +/*---------------------------------------------------------------------------*/ +static int enabled = SHT_21_SENSOR_STATUS_DISABLED; +/*---------------------------------------------------------------------------*/ +/* + * Maximum measurement durations in clock ticks. We use 11bit resolution, thus: + * - Tmp: 11ms + * - RH: 15ms + */ +#define MEASUREMENT_DURATION 3 + +/* + * Wait SENSOR_STARTUP_DELAY clock ticks between activation and triggering a + * reading + */ +#define SENSOR_STARTUP_DELAY 4 + +static struct ctimer startup_timer; +/*---------------------------------------------------------------------------*/ +/** + * \brief Select the SHT sensor on the I2C-bus + */ +static void +select(void) +{ + /* Select the SHT21 address */ + board_i2c_select(BOARD_I2C_INTERFACE_0, HAL_SHT21_I2C_ADDRESS); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Write a command over I2C + * \param cmd The command to send + * \return TRUE if the command was sent successfully + */ +static bool +write_cmd(uint8_t cmd) +{ + /* Send command */ + return board_i2c_write_single(cmd); +} +/*---------------------------------------------------------------------------*/ +/* + * \brief Read data from the SHT over I2C + * \param buf Pointer to buffer where data will be stored + * \param len Number of bytes to read + * \return TRUE if the required number of bytes were received + */ +static bool +read_data(uint8_t *buf, uint8_t len) +{ + /* Read data */ + return board_i2c_read(buf, len); +} +/*---------------------------------------------------------------------------*/ +/** + * @brief Initialise the SHT21 sensor + */ +static void +sensor_init(void) +{ + select(); + + /* Set 11 bit resolution */ + sensor_common_read_reg(SHT21_CMD_READ_U_R, &usr, 1); + usr &= USR_REG_RES_MASK; + usr |= USR_REG_11BITRES; + sensor_common_write_reg(SHT21_CMD_WRITE_U_R, &usr, 1); + success = true; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Start a temperature measurement + */ +static void +start_temp(void) +{ + if(success) { + select(); + success = write_cmd(SHT21_CMD_TEMP_T_NH); + } +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Latch the last temperature measurement + */ +static void +latch_temp(void) +{ + if(success) { + select(); + success = read_data(buf, DATA_LEN); + } +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Start a humidity measurement + */ +static void +start_humidity(void) +{ + if(success) { + select(); + success = write_cmd(SHT21_CMD_HUMI_T_NH); + } +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Latch the last humidity measurement + */ +static void +latch_humidity(void) +{ + if(success) { + select(); + success = read_data(buf + DATA_LEN, DATA_LEN); + } +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Retrieve latched raw readings from buffer and store in variables + * \param raw_temp Pointer to a buffer where the temperature reading will be + * stored + * \param raw_hum Pointer to a buffer where the humidity reading will be + * stored + * \return TRUE on success + */ +static bool +get_readings(uint16_t *raw_temp, uint16_t *raw_hum) +{ + bool valid; + + valid = success; + if(!success) { + sensor_common_set_error_data(buf, DATA_SIZE); + } + + /* Store temperature */ + *raw_temp = buf[0] << 8 | buf[1]; + + /* [2] We ignore the CRC */ + + /* Store humidity */ + *raw_hum = buf[3] << 8 | buf[4]; + + /* [5] We ignore the CRC */ + + success = true; + + return valid; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Convert raw data to temperature (degrees C) and rel. humidity (%RH) + * \param raw_temp Raw temperature data (little endian) + * \param raw_hum Raw humidity data (little endian) + * \param temp Converted temperature value + * \param hum Converted humidity value + */ +static void +convert(uint16_t raw_temp, uint16_t raw_hum, float *temp, float *hum) +{ + /* Convert temperature to degrees C */ + raw_temp &= ~0x0003; /* clear bits [1..0] (status bits) */ + *temp = -46.85 + 175.72 / 65536 * (double)(int16_t)raw_temp; + + /* Convert relative humidity to a %RH value */ + raw_hum &= ~0x0003; /* clear bits [1..0] (status bits) */ + + /* RH= -6 + 125 * SRH / 2^16 */ + *hum = -6.0 + 125.0 / 65536 * (double)raw_hum; +} +/*---------------------------------------------------------------------------*/ +static void +state_machine(void *not_used) +{ + switch(enabled) { + case SHT_21_SENSOR_STATUS_INITIALISED: + start_temp(); + enabled = SHT_21_SENSOR_STATUS_READING_TEMP; + break; + case SHT_21_SENSOR_STATUS_READING_TEMP: + latch_temp(); + start_humidity(); + enabled = SHT_21_SENSOR_STATUS_READING_HUMIDITY; + break; + case SHT_21_SENSOR_STATUS_READING_HUMIDITY: + latch_humidity(); + enabled = SHT_21_SENSOR_STATUS_READINGS_READY; + sensors_changed(&sht_21_sensor); + return; + case SHT_21_SENSOR_STATUS_READINGS_READY: + case SHT_21_SENSOR_STATUS_DISABLED: + default: + ctimer_stop(&startup_timer); + return; + } + + ctimer_set(&startup_timer, MEASUREMENT_DURATION, state_machine, NULL); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Returns a reading from the sensor + * \param type SHT_21_SENSOR_TYPE_TEMP or SHT_21_SENSOR_TYPE_HUMIDITY + * \return Temperature (centi degrees C) or Humidity (centi %RH) + */ +static int +value(int type) +{ + int rv; + uint16_t raw_temp; + uint16_t raw_hum; + float temp; + float hum; + + if(enabled != SHT_21_SENSOR_STATUS_READINGS_READY) { + PRINTF("Sensor disabled or starting up (%d)\n", enabled); + return CC26XX_SENSOR_READING_ERROR; + } + + if((type != SHT_21_SENSOR_TYPE_TEMP) && type != SHT_21_SENSOR_TYPE_HUMIDITY) { + PRINTF("Invalid type\n"); + return CC26XX_SENSOR_READING_ERROR; + } else { + rv = get_readings(&raw_temp, &raw_hum); + + if(rv == 0) { + return CC26XX_SENSOR_READING_ERROR; + } + + convert(raw_temp, raw_hum, &temp, &hum); + PRINTF("SHT: %04X %04X t=%d h=%d\n", raw_temp, raw_hum, + (int)(temp * 100), (int)(hum * 100)); + + if(type == SHT_21_SENSOR_TYPE_TEMP) { + rv = (int)(temp * 100); + } else if(type == SHT_21_SENSOR_TYPE_HUMIDITY) { + rv = (int)(hum * 100); + } + } + return rv; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Configuration function for the SHT21 sensor. + * + * \param type Activate, enable or disable the sensor. See below + * \param enable + * + * When type == SENSORS_HW_INIT we turn on the hardware + * When type == SENSORS_ACTIVE and enable==1 we enable the sensor + * When type == SENSORS_ACTIVE and enable==0 we disable the sensor + */ +static int +configure(int type, int enable) +{ + switch(type) { + case SENSORS_HW_INIT: + sensor_init(); + enabled = SHT_21_SENSOR_STATUS_INITIALISED; + break; + case SENSORS_ACTIVE: + /* Must be initialised first */ + if(enabled == SHT_21_SENSOR_STATUS_DISABLED) { + return SHT_21_SENSOR_STATUS_DISABLED; + } + if(enable) { + enabled = SHT_21_SENSOR_STATUS_INITIALISED; + ctimer_set(&startup_timer, SENSOR_STARTUP_DELAY, state_machine, NULL); + } else { + ctimer_stop(&startup_timer); + enabled = SHT_21_SENSOR_STATUS_INITIALISED; + } + break; + default: + break; + } + return enabled; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Returns the status of the sensor + * \param type SENSORS_ACTIVE or SENSORS_READY + * \return One of the SENSOR_STATUS_xyz defines + */ +static int +status(int type) +{ + switch(type) { + case SENSORS_ACTIVE: + case SENSORS_READY: + return enabled; + break; + default: + break; + } + return SHT_21_SENSOR_STATUS_DISABLED; +} +/*---------------------------------------------------------------------------*/ +SENSORS_SENSOR(sht_21_sensor, "SHT21", value, configure, status); +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/sht-21-sensor.h b/platform/srf06-cc26xx/sensortag/sht-21-sensor.h new file mode 100644 index 000000000..af2f5d401 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/sht-21-sensor.h @@ -0,0 +1,85 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-sht-sensor SensorTag 2.0 Humidity Sensor + * + * Due to the time required between triggering a reading and the reading + * becoming available, this driver is meant to be used in an asynchronous + * fashion. The caller must first activate the sensor by calling + * SENSORS_ACTIVATE(). This will trigger a cycle which will read both + * temperature and humidity, but the call will not wait for the cycle to + * complete so that the CPU can perform other tasks or drop to a low power + * mode. + * + * Once readings are available, the driver will generate a sensors_changed + * event. + * + * Calls to .status() will return the driver's state which could indicate that + * a measurement is in progress (different return values for each) or that + * readings are ready. + * + * Multiple calls to value() will simply return the reading that was latched + * after the last cycle. In order to obtain fresh readings, a new cycle must be + * started by a new call to SENSORS_ACTIVATE. + * @{ + * + * \file + * Header file for the Sensortag-CC26ss Sensirion SHT21 Humidity sensor + */ +/*---------------------------------------------------------------------------*/ +#ifndef SHT_21_SENSOR_H_ +#define SHT_21_SENSOR_H_ +/*---------------------------------------------------------------------------*/ +#define SHT_21_SENSOR_TYPE_TEMP 1 +#define SHT_21_SENSOR_TYPE_HUMIDITY 2 +/*---------------------------------------------------------------------------*/ +/** + * \name SHT21 driver states + * @{ + */ +#define SHT_21_SENSOR_STATUS_DISABLED 0 /**< Not initialised */ +#define SHT_21_SENSOR_STATUS_INITIALISED 1 /**< Initialised but idle */ +#define SHT_21_SENSOR_STATUS_READING_TEMP 2 /**< Temp reading in progress */ +#define SHT_21_SENSOR_STATUS_READING_HUMIDITY 3 /**< Humidity reading in progress */ +#define SHT_21_SENSOR_STATUS_READINGS_READY 4 /**< Both readings ready */ +/** @} */ +/*---------------------------------------------------------------------------*/ +extern const struct sensors_sensor sht_21_sensor; +/*---------------------------------------------------------------------------*/ +#endif /* SHT_21_SENSOR_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */ diff --git a/platform/srf06-cc26xx/sensortag/tmp-007-sensor.c b/platform/srf06-cc26xx/sensortag/tmp-007-sensor.c new file mode 100644 index 000000000..8f880cb54 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/tmp-007-sensor.c @@ -0,0 +1,315 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-tmp-sensor + * @{ + * + * \file + * Driver for the Sensortag-CC26xx TI TMP007 infrared thermophile sensor + */ +/*---------------------------------------------------------------------------*/ +#include "contiki-conf.h" +#include "lib/sensors.h" +#include "tmp-007-sensor.h" +#include "sys/ctimer.h" +#include "board-i2c.h" +#include "sensor-common.h" +#include "ti-lib.h" + +#include +#include +#include +#include +/*---------------------------------------------------------------------------*/ +#define DEBUG 0 +#if DEBUG +#define PRINTF(...) printf(__VA_ARGS__) +#else +#define PRINTF(...) +#endif +/*---------------------------------------------------------------------------*/ +/* Slave address */ +#define SENSOR_I2C_ADDRESS 0x44 +/*---------------------------------------------------------------------------*/ +/* TMP007 register addresses */ +#define TMP007_REG_ADDR_VOLTAGE 0x00 +#define TMP007_REG_ADDR_LOCAL_TEMP 0x01 +#define TMP007_REG_ADDR_CONFIG 0x02 +#define TMP007_REG_ADDR_OBJ_TEMP 0x03 +#define TMP007_REG_ADDR_STATUS 0x04 +#define TMP007_REG_PROD_ID 0x1F +/*---------------------------------------------------------------------------*/ +/* TMP007 register values */ +#define TMP007_VAL_CONFIG_ON 0x1000 /* Sensor on state */ +#define TMP007_VAL_CONFIG_OFF 0x0000 /* Sensor off state */ +#define TMP007_VAL_CONFIG_RESET 0x8000 +#define TMP007_VAL_PROD_ID 0x0078 /* Product ID */ +/*---------------------------------------------------------------------------*/ +/* Conversion ready (status register) bit values */ +#define CONV_RDY_BIT 0x4000 +/*---------------------------------------------------------------------------*/ +/* Register length */ +#define REGISTER_LENGTH 2 +/*---------------------------------------------------------------------------*/ +/* Sensor data size */ +#define DATA_SIZE 4 +/*---------------------------------------------------------------------------*/ +/* Byte swap of 16-bit register value */ +#define HI_UINT16(a) (((a) >> 8) & 0xFF) +#define LO_UINT16(a) ((a) & 0xFF) + +#define SWAP(v) ((LO_UINT16(v) << 8) | HI_UINT16(v)) +/*---------------------------------------------------------------------------*/ +#define SELECT() board_i2c_select(BOARD_I2C_INTERFACE_0, SENSOR_I2C_ADDRESS); +/*---------------------------------------------------------------------------*/ +static uint8_t buf[DATA_SIZE]; +static uint16_t val; +/*---------------------------------------------------------------------------*/ +#define SENSOR_STATUS_DISABLED 0 +#define SENSOR_STATUS_INITIALISED 1 +#define SENSOR_STATUS_NOT_READY 2 +#define SENSOR_STATUS_READY 3 + +static int enabled = SENSOR_STATUS_DISABLED; +/*---------------------------------------------------------------------------*/ +/* Wait SENSOR_STARTUP_DELAY clock ticks for the sensor to be ready - 275ms */ +#define SENSOR_STARTUP_DELAY 36 + +static struct ctimer startup_timer; +/*---------------------------------------------------------------------------*/ +/* Latched values */ +static int obj_temp_latched; +static int amb_temp_latched; +/*---------------------------------------------------------------------------*/ +static void +notify_ready(void *not_used) +{ + enabled = SENSOR_STATUS_READY; + sensors_changed(&tmp_007_sensor); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Turn the sensor on/off + */ +static bool +enable_sensor(bool enable) +{ + bool success; + + SELECT() + + if(enable) { + val = TMP007_VAL_CONFIG_ON; + } else { + val = TMP007_VAL_CONFIG_OFF; + } + val = SWAP(val); + + success = sensor_common_write_reg(TMP007_REG_ADDR_CONFIG, (uint8_t *)&val, + REGISTER_LENGTH); + + return success; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Read the sensor value registers + * \param raw_temp Temperature in 16 bit format + * \param raw_obj_temp object temperature in 16 bit format + * \return TRUE if valid data could be retrieved + */ +static bool +read_data(uint16_t *raw_temp, uint16_t *raw_obj_temp) +{ + bool success; + + SELECT(); + + success = sensor_common_read_reg(TMP007_REG_ADDR_STATUS, (uint8_t *)&val, + REGISTER_LENGTH); + + if(success) { + val = SWAP(val); + success = val & CONV_RDY_BIT; + } + + if(success) { + success = sensor_common_read_reg(TMP007_REG_ADDR_LOCAL_TEMP, &buf[0], + REGISTER_LENGTH); + if(success) { + success = sensor_common_read_reg(TMP007_REG_ADDR_OBJ_TEMP, &buf[2], + REGISTER_LENGTH); + } + } + + if(!success) { + sensor_common_set_error_data(buf, 4); + } + + /* Swap byte order */ + *raw_temp = buf[0] << 8 | buf[1]; + *raw_obj_temp = buf[2] << 8 | buf[3]; + + return success; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Convert raw data to values in degrees C + * \param raw_temp raw ambient temperature from sensor + * \param raw_obj_temp raw object temperature from sensor + * \param obj converted object temperature + * \param amb converted ambient temperature + */ +static void +convert(uint16_t raw_temp, uint16_t raw_obj_temp, float *obj, float *amb) +{ + const float SCALE_LSB = 0.03125; + float t; + int it; + + it = (int)((raw_obj_temp) >> 2); + t = ((float)(it)) * SCALE_LSB; + *obj = t; + + it = (int)((raw_temp) >> 2); + t = (float)it; + *amb = t * SCALE_LSB; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Returns a reading from the sensor + * \param type TMP_007_SENSOR_TYPE_OBJECT or TMP_007_SENSOR_TYPE_AMBIENT + * \return Object or Ambient temperature in milli degrees C + */ +static int +value(int type) +{ + int rv; + uint16_t raw_temp; + uint16_t raw_obj_temp; + float obj_temp; + float amb_temp; + + if(enabled != SENSOR_STATUS_READY) { + PRINTF("Sensor disabled or starting up (%d)\n", enabled); + return CC26XX_SENSOR_READING_ERROR; + } + + if((type & TMP_007_SENSOR_TYPE_ALL) == 0) { + PRINTF("Invalid type\n"); + return CC26XX_SENSOR_READING_ERROR; + } + + rv = CC26XX_SENSOR_READING_ERROR; + + if(type == TMP_007_SENSOR_TYPE_ALL) { + rv = read_data(&raw_temp, &raw_obj_temp); + + if(rv == 0) { + return CC26XX_SENSOR_READING_ERROR; + } + + convert(raw_temp, raw_obj_temp, &obj_temp, &amb_temp); + PRINTF("TMP: %04X %04X o=%d a=%d\n", raw_temp, raw_obj_temp, + (int)(obj_temp * 1000), (int)(amb_temp * 1000)); + + obj_temp_latched = (int)(obj_temp * 1000); + amb_temp_latched = (int)(amb_temp * 1000); + rv = 1; + } else if(type == TMP_007_SENSOR_TYPE_OBJECT) { + rv = obj_temp_latched; + } else if(type == TMP_007_SENSOR_TYPE_AMBIENT) { + rv = amb_temp_latched; + } + + return rv; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Configuration function for the TMP007 sensor. + * + * \param type Activate, enable or disable the sensor. See below + * \param enable + * + * When type == SENSORS_HW_INIT we turn on the hardware + * When type == SENSORS_ACTIVE and enable==1 we enable the sensor + * When type == SENSORS_ACTIVE and enable==0 we disable the sensor + */ +static int +configure(int type, int enable) +{ + switch(type) { + case SENSORS_HW_INIT: + enable_sensor(false); + enabled = SENSOR_STATUS_INITIALISED; + break; + case SENSORS_ACTIVE: + /* Must be initialised first */ + if(enabled == SENSOR_STATUS_DISABLED) { + return SENSOR_STATUS_DISABLED; + } + if(enable) { + enable_sensor(true); + ctimer_set(&startup_timer, SENSOR_STARTUP_DELAY, notify_ready, NULL); + enabled = SENSOR_STATUS_NOT_READY; + } else { + ctimer_stop(&startup_timer); + enable_sensor(false); + enabled = SENSOR_STATUS_INITIALISED; + } + break; + default: + break; + } + return enabled; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Returns the status of the sensor + * \param type SENSORS_ACTIVE or SENSORS_READY + * \return 1 if the sensor is enabled + */ +static int +status(int type) +{ + switch(type) { + case SENSORS_ACTIVE: + case SENSORS_READY: + return enabled; + break; + default: + break; + } + return SENSOR_STATUS_DISABLED; +} +/*---------------------------------------------------------------------------*/ +SENSORS_SENSOR(tmp_007_sensor, "TMP007", value, configure, status); +/*---------------------------------------------------------------------------*/ +/** @} */ diff --git a/platform/srf06-cc26xx/sensortag/tmp-007-sensor.h b/platform/srf06-cc26xx/sensortag/tmp-007-sensor.h new file mode 100644 index 000000000..10c96c8a0 --- /dev/null +++ b/platform/srf06-cc26xx/sensortag/tmp-007-sensor.h @@ -0,0 +1,76 @@ +/* + * Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/ + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder 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 HOLDER 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. + */ +/*---------------------------------------------------------------------------*/ +/** + * \addtogroup sensortag-cc26xx-peripherals + * @{ + * + * \defgroup sensortag-cc26xx-tmp-sensor SensorTag 2.0 IR thermophile sensor + * + * Due to the time required for the sensor to startup, this driver is meant to + * be used in an asynchronous fashion. The caller must first activate the + * sensor by calling SENSORS_ACTIVATE(). This will trigger the sensor's startup + * sequence, but the call will not wait for it to complete so that the CPU can + * perform other tasks or drop to a low power mode. + * + * Once the sensor is stable, the driver will generate a sensors_changed event. + * + * The caller should then use value(TMP_007_SENSOR_TYPE_ALL) to read sensor + * values and latch them. Once completed successfully, individual readings can + * be retrieved with calls to value(TMP_007_SENSOR_TYPE_OBJECT) or + * value(TMP_007_SENSOR_TYPE_AMBIENT). + * + * Once required readings have been taken, the caller has two options: + * - Turn the sensor off by calling SENSORS_DEACTIVATE, but in order to take + * subsequent readings SENSORS_ACTIVATE must be called again + * - Leave the sensor on. In this scenario, the caller can simply keep calling + * value(TMP_007_SENSOR_TYPE_ALL) to read and latch new values. However + * keeping the sensor on will consume more energy + * @{ + * + * \file + * Header file for the Sensortag-CC26xx TI TMP007 infrared thermophile sensor + */ +/*---------------------------------------------------------------------------*/ +#ifndef TMP_007_SENSOR_H_ +#define TMP_007_SENSOR_H_ +/*---------------------------------------------------------------------------*/ +#define TMP_007_SENSOR_TYPE_OBJECT 1 +#define TMP_007_SENSOR_TYPE_AMBIENT 2 +#define TMP_007_SENSOR_TYPE_ALL 3 +/*---------------------------------------------------------------------------*/ +extern const struct sensors_sensor tmp_007_sensor; +/*---------------------------------------------------------------------------*/ +#endif /* TMP_007_SENSOR_H_ */ +/*---------------------------------------------------------------------------*/ +/** + * @} + * @} + */