cc2538: Add adc driver and example

Signed-off-by: Benoît Thébaudeau <benoit.thebaudeau@advansee.com>
This commit is contained in:
Benoît Thébaudeau 2013-11-04 20:39:56 +01:00
parent 79e6514c80
commit dbba311270
13 changed files with 511 additions and 4 deletions

View File

@ -43,7 +43,7 @@ CONTIKI_CPU_DIRS += ../cc253x/usb/common ../cc253x/usb/common/cdc-acm
### CPU-dependent source files
CONTIKI_CPU_SOURCEFILES += clock.c rtimer-arch.c uart.c watchdog.c
CONTIKI_CPU_SOURCEFILES += nvic.c cpu.c sys-ctrl.c gpio.c ioc.c spi.c
CONTIKI_CPU_SOURCEFILES += nvic.c cpu.c sys-ctrl.c gpio.c ioc.c spi.c adc.c
CONTIKI_CPU_SOURCEFILES += cc2538-rf.c udma.c lpm.c
CONTIKI_CPU_SOURCEFILES += dbg.c ieee-addr.c
CONTIKI_CPU_SOURCEFILES += slip-arch.c slip.c

99
cpu/cc2538/dev/adc.c Normal file
View File

@ -0,0 +1,99 @@
/*
* Copyright (c) 2013, ADVANSEE - http://www.advansee.com/
* Benoît Thébaudeau <benoit.thebaudeau@advansee.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 cc2538-adc
* @{
*
* \file
* Implementation of the cc2538 ADC driver
*/
#include "contiki.h"
#include "dev/soc-adc.h"
#include "dev/cctest.h"
#include "dev/rfcore-xreg.h"
#include "dev/adc.h"
#include "reg.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
void
adc_init(void)
{
/* Start conversions only manually */
REG(SOC_ADC_ADCCON1) |= SOC_ADC_ADCCON1_STSEL;
}
/*---------------------------------------------------------------------------*/
int16_t
adc_get(uint8_t channel, uint8_t ref, uint8_t div)
{
uint32_t cctest_tr0, rfcore_xreg_atest;
int16_t res;
/* On-chip temperature sensor */
if(channel == SOC_ADC_ADCCON_CH_TEMP) {
/* Connect the temperature sensor to the ADC */
cctest_tr0 = REG(CCTEST_TR0);
REG(CCTEST_TR0) = cctest_tr0 | CCTEST_TR0_ADCTM;
/* Enable the temperature sensor */
rfcore_xreg_atest = REG(RFCORE_XREG_ATEST);
REG(RFCORE_XREG_ATEST) = (rfcore_xreg_atest & ~RFCORE_XREG_ATEST_ATEST_CTRL) |
RFCORE_XREG_ATEST_ATEST_CTRL_TEMP;
}
/* Start a single extra conversion with the given parameters */
REG(SOC_ADC_ADCCON3) = (REG(SOC_ADC_ADCCON3) &
~(SOC_ADC_ADCCON3_EREF | SOC_ADC_ADCCON3_EDIV | SOC_ADC_ADCCON3_ECH)) |
ref | div | channel;
/* Poll until end of conversion */
while(!(REG(SOC_ADC_ADCCON1) & SOC_ADC_ADCCON1_EOC));
/* Read conversion result, reading SOC_ADC_ADCH last to clear
* SOC_ADC_ADCCON1.EOC */
res = REG(SOC_ADC_ADCL) & 0xfc;
res |= REG(SOC_ADC_ADCH) << 8;
/* On-chip temperature sensor */
if(channel == SOC_ADC_ADCCON_CH_TEMP) {
/* Restore the initial temperature sensor state and connection (better for
* power consumption) */
REG(RFCORE_XREG_ATEST) = rfcore_xreg_atest;
REG(CCTEST_TR0) = cctest_tr0;
}
/* Return conversion result */
return res;
}
/** @} */

75
cpu/cc2538/dev/adc.h Normal file
View File

@ -0,0 +1,75 @@
/*
* Copyright (c) 2013, ADVANSEE - http://www.advansee.com/
* Benoît Thébaudeau <benoit.thebaudeau@advansee.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 cc2538
* @{
*
* \defgroup cc2538-adc cc2538 ADC
*
* Driver for the cc2538 ADC controller
* @{
*
* \file
* Header file for the cc2538 ADC driver
*/
#ifndef ADC_H_
#define ADC_H_
#include "contiki.h"
#include "dev/soc-adc.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/** \name ADC functions
* @{
*/
/** \brief Initializes the ADC controller */
void adc_init(void);
/** \brief Performs a single conversion on a given ADC channel
* \param channel The channel used for the conversion: \c SOC_ADC_ADCCON_CH_x
* \param ref The reference voltage used for the conversion: \c SOC_ADC_ADCCON_REF_x
* \param div The decimation rate used for the conversion: \c SOC_ADC_ADCCON_DIV_x
* \return Signed 16-bit conversion result: 2's complement, ENOBs in MSBs
* \note PD[5:4] are not usable when the temperature sensor is selected.
*/
int16_t adc_get(uint8_t channel, uint8_t ref, uint8_t div);
/** @} */
#endif /* ADC_H_ */
/**
* @}
* @}
*/

92
cpu/cc2538/dev/cctest.h Normal file
View File

@ -0,0 +1,92 @@
/*
* Original file:
* Copyright (C) 2013 Texas Instruments Incorporated - http://www.ti.com/
* All rights reserved.
*
* Port to Contiki:
* Copyright (c) 2013, ADVANSEE - http://www.advansee.com/
* Benoît Thébaudeau <benoit.thebaudeau@advansee.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 cc2538-rfcore
* @{
*
* \file
* Header with declarations of CCTEST module registers.
*/
#ifndef CCTEST_H
#define CCTEST_H
/*---------------------------------------------------------------------------*/
/**
* \name CCTEST register offsets
* @{
*/
#define CCTEST_IO 0x44010000 /**< Output strength control */
#define CCTEST_OBSSEL0 0x44010014 /**< Observation output 0 */
#define CCTEST_OBSSEL1 0x44010018 /**< Observation output 1 */
#define CCTEST_OBSSEL2 0x4401001C /**< Observation output 2 */
#define CCTEST_OBSSEL3 0x44010020 /**< Observation output 3 */
#define CCTEST_OBSSEL4 0x44010024 /**< Observation output 4 */
#define CCTEST_OBSSEL5 0x44010028 /**< Observation output 5 */
#define CCTEST_OBSSEL6 0x4401002C /**< Observation output 6 */
#define CCTEST_OBSSEL7 0x44010030 /**< Observation output 7 */
#define CCTEST_TR0 0x44010034 /**< Test register 0 */
#define CCTEST_USBCTRL 0x44010050 /**< USB PHY stand-by control */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name CCTEST_IO register bit fields
* @{
*/
#define CCTEST_IO_SC 0x00000001 /**< I/O strength control */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name CCTEST_OBSSELx registers bit fields
* @{
*/
#define CCTEST_OBSSEL_EN 0x00000080 /**< Observation output enable */
#define CCTEST_OBSSEL_SEL_M 0x0000007F /**< n - obs_sigs[n] output selection mask */
#define CCTEST_OBSSEL_SEL_S 0 /**< n - obs_sigs[n] output selection shift */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name CCTEST_TR0 register bit fields
* @{
*/
#define CCTEST_TR0_ADCTM 0x00000002 /**< Connect temperature sensor to ADC */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name CCTEST_USBCTRL register bit fields
* @{
*/
#define CCTEST_USBCTRL_USB_STB 0x00000001 /**< USB PHY stand-by override */
/** @} */
#endif /* CCTEST_H */
/** @} */

View File

@ -575,6 +575,8 @@
* @{
*/
#define RFCORE_XREG_ATEST_ATEST_CTRL 0x0000003F /**< Controls the analog test mode */
#define RFCORE_XREG_ATEST_ATEST_CTRL_DIS 0x00000000 /**< Analog test mode: disabled */
#define RFCORE_XREG_ATEST_ATEST_CTRL_TEMP 0x00000001 /**< Analog test mode: enable temperature sensor */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name RFCORE_XREG_PTEST0 register bit masks

View File

@ -83,6 +83,34 @@
#define SOC_ADC_ADCCON3_ECH 0x0000000F /**< Single channel select */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SOC_ADC_ADCCONx registers field values
* @{
*/
#define SOC_ADC_ADCCON_REF_INT (0 << 6) /**< Internal reference */
#define SOC_ADC_ADCCON_REF_EXT_SINGLE (1 << 6) /**< External reference on AIN7 pin */
#define SOC_ADC_ADCCON_REF_AVDD5 (2 << 6) /**< AVDD5 pin */
#define SOC_ADC_ADCCON_REF_EXT_DIFF (3 << 6) /**< External reference on AIN6-AIN7 differential input */
#define SOC_ADC_ADCCON_DIV_64 (0 << 4) /**< 64 decimation rate (7 bits ENOB) */
#define SOC_ADC_ADCCON_DIV_128 (1 << 4) /**< 128 decimation rate (9 bits ENOB) */
#define SOC_ADC_ADCCON_DIV_256 (2 << 4) /**< 256 decimation rate (10 bits ENOB) */
#define SOC_ADC_ADCCON_DIV_512 (3 << 4) /**< 512 decimation rate (12 bits ENOB) */
#define SOC_ADC_ADCCON_CH_AIN0 0x0 /**< AIN0 */
#define SOC_ADC_ADCCON_CH_AIN1 0x1 /**< AIN1 */
#define SOC_ADC_ADCCON_CH_AIN2 0x2 /**< AIN2 */
#define SOC_ADC_ADCCON_CH_AIN3 0x3 /**< AIN3 */
#define SOC_ADC_ADCCON_CH_AIN4 0x4 /**< AIN4 */
#define SOC_ADC_ADCCON_CH_AIN5 0x5 /**< AIN5 */
#define SOC_ADC_ADCCON_CH_AIN6 0x6 /**< AIN6 */
#define SOC_ADC_ADCCON_CH_AIN7 0x7 /**< AIN7 */
#define SOC_ADC_ADCCON_CH_AIN0_AIN1 0x8 /**< AIN0-AIN1 */
#define SOC_ADC_ADCCON_CH_AIN2_AIN3 0x9 /**< AIN2-AIN3 */
#define SOC_ADC_ADCCON_CH_AIN4_AIN5 0xA /**< AIN4-AIN5 */
#define SOC_ADC_ADCCON_CH_AIN6_AIN7 0xB /**< AIN6-AIN7 */
#define SOC_ADC_ADCCON_CH_GND 0xC /**< GND */
#define SOC_ADC_ADCCON_CH_TEMP 0xE /**< Temperature sensor */
#define SOC_ADC_ADCCON_CH_VDD_3 0xF /**< VDD/3 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SOC_ADC_ADC[L:H] register bit masks
* @{
*/

View File

@ -50,6 +50,8 @@
* - BTN_DOWN turns on LEDS_REBOOT and causes a watchdog reboot
* - BTN_UP to soft reset (SYS_CTRL_PWRDBG::FORCE_WARM_RESET)
* - BTN_LEFT and BTN_RIGHT flash the LED defined as LEDS_BUTTON
* - ADC sensors : On-chip VDD / 3 and temperature, and ambient light sensor
* values are printed over UART periodically.
* - UART : Every LOOP_INTERVAL the EM will print something over the
* UART. Receiving an entire line of text over UART (ending
* in \\r) will cause LEDS_SERIAL_IN to toggle
@ -68,6 +70,7 @@
#include "dev/leds.h"
#include "dev/uart.h"
#include "dev/button-sensor.h"
#include "dev/adc-sensor.h"
#include "dev/watchdog.h"
#include "dev/serial-line.h"
#include "dev/sys-ctrl.h"
@ -111,6 +114,7 @@ rt_callback(struct rtimer *t, void *ptr)
/*---------------------------------------------------------------------------*/
PROCESS_THREAD(cc2538_demo_process, ev, data)
{
int16_t value;
PROCESS_EXITHANDLER(broadcast_close(&bc))
@ -126,7 +130,18 @@ PROCESS_THREAD(cc2538_demo_process, ev, data)
if(ev == PROCESS_EVENT_TIMER) {
leds_on(LEDS_PERIODIC);
printf("Counter = 0x%08x\n", counter);
printf("-----------------------------------------\n"
"Counter = 0x%08x\n", counter);
value = adc_sensor.value(ADC_SENSOR_VDD_3);
printf("VDD = %d mV\n", value * (3 * 1190) / (2047 << 4));
value = adc_sensor.value(ADC_SENSOR_TEMP);
printf("Temperature = %d mC\n",
25000 + ((value >> 4) - 1422) * 10000 / 42);
value = adc_sensor.value(ADC_SENSOR_ALS);
printf("Ambient light sensor = %d raw\n", value);
etimer_set(&et, CLOCK_SECOND);
rtimer_set(&rt, RTIMER_NOW() + LEDS_OFF_HYSTERISIS, 1,

View File

@ -8,7 +8,8 @@ CONTIKI_TARGET_DIRS = . dev
CONTIKI_TARGET_SOURCEFILES += leds.c leds-arch.c
CONTIKI_TARGET_SOURCEFILES += contiki-main.c
CONTIKI_TARGET_SOURCEFILES += sensors.c smartrf-sensors.c button-sensor.c
CONTIKI_TARGET_SOURCEFILES += sensors.c smartrf-sensors.c
CONTIKI_TARGET_SOURCEFILES += button-sensor.c adc-sensor.c
TARGET_START_SOURCEFILES += startup-gcc.c
TARGET_STARTFILES = ${addprefix $(OBJECTDIR)/,${call oname, $(TARGET_START_SOURCEFILES)}}

View File

@ -28,9 +28,11 @@ In terms of hardware support, the following drivers have been implemented:
* Random number generator
* Low Power Modes
* General-Purpose Timers. NB: GPT0 is in use by the platform code, the remaining GPTs are available for application development.
* ADC
* SmartRF06 EB and BB peripherals
* LEDs
* Buttons
* ADC sensors (on-chip VDD / 3 and temperature, ambient light sensor)
* UART connectivity over the XDS100v3 backchannel (EB only)
Requirements

View File

@ -0,0 +1,111 @@
/*
* Copyright (c) 2013, ADVANSEE - http://www.advansee.com/
* Benoît Thébaudeau <benoit.thebaudeau@advansee.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 cc2538dk-adc-sensor
* @{
*
* \file
* Driver for the SmartRF06EB ADC
*/
#include "contiki.h"
#include "sys/clock.h"
#include "dev/ioc.h"
#include "dev/gpio.h"
#include "dev/adc.h"
#include "dev/adc-sensor.h"
#include <stdint.h>
#define ADC_ALS_PWR_PORT_BASE GPIO_PORT_TO_BASE(ADC_ALS_PWR_PORT)
#define ADC_ALS_PWR_PIN_MASK GPIO_PIN_MASK(ADC_ALS_PWR_PIN)
#define ADC_ALS_OUT_PIN_MASK GPIO_PIN_MASK(ADC_ALS_OUT_PIN)
/*---------------------------------------------------------------------------*/
static int
value(int type)
{
uint8_t channel;
int16_t res;
switch(type) {
case ADC_SENSOR_VDD_3:
channel = SOC_ADC_ADCCON_CH_VDD_3;
break;
case ADC_SENSOR_TEMP:
channel = SOC_ADC_ADCCON_CH_TEMP;
break;
case ADC_SENSOR_ALS:
channel = SOC_ADC_ADCCON_CH_AIN0 + ADC_ALS_OUT_PIN;
GPIO_SET_PIN(ADC_ALS_PWR_PORT_BASE, ADC_ALS_PWR_PIN_MASK);
clock_delay_usec(2000);
break;
default:
return 0;
}
res = adc_get(channel, SOC_ADC_ADCCON_REF_INT, SOC_ADC_ADCCON_DIV_512);
if(type == ADC_SENSOR_ALS) {
GPIO_CLR_PIN(ADC_ALS_PWR_PORT_BASE, ADC_ALS_PWR_PIN_MASK);
}
return res;
}
/*---------------------------------------------------------------------------*/
static int
configure(int type, int value)
{
switch(type) {
case SENSORS_HW_INIT:
GPIO_SOFTWARE_CONTROL(ADC_ALS_PWR_PORT_BASE, ADC_ALS_PWR_PIN_MASK);
GPIO_SET_OUTPUT(ADC_ALS_PWR_PORT_BASE, ADC_ALS_PWR_PIN_MASK);
GPIO_CLR_PIN(ADC_ALS_PWR_PORT_BASE, ADC_ALS_PWR_PIN_MASK);
ioc_set_over(ADC_ALS_PWR_PORT, ADC_ALS_PWR_PIN, IOC_OVERRIDE_DIS);
GPIO_SOFTWARE_CONTROL(GPIO_A_BASE, ADC_ALS_OUT_PIN_MASK);
GPIO_SET_INPUT(GPIO_A_BASE, ADC_ALS_OUT_PIN_MASK);
ioc_set_over(GPIO_A_NUM, ADC_ALS_OUT_PIN, IOC_OVERRIDE_ANA);
adc_init();
break;
}
return 0;
}
/*---------------------------------------------------------------------------*/
static int
status(int type)
{
return 1;
}
/*---------------------------------------------------------------------------*/
SENSORS_SENSOR(adc_sensor, ADC_SENSOR, value, configure, status);
/** @} */

View File

@ -0,0 +1,67 @@
/*
* Copyright (c) 2013, ADVANSEE - http://www.advansee.com/
* Benoît Thébaudeau <benoit.thebaudeau@advansee.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 cc2538-smartrf-sensors
* @{
*
* \defgroup cc2538dk-adc-sensor cc2538dk ADC Driver
*
* Driver for the SmartRF06EB ADC sensors
* @{
*
* \file
* Header file for the cc2538dk ADC Driver
*/
#ifndef ADC_SENSOR_H_
#define ADC_SENSOR_H_
#include "lib/sensors.h"
/*---------------------------------------------------------------------------*/
/** \name ADC sensors
* @{
*/
#define ADC_SENSOR "ADC"
#define ADC_SENSOR_VDD_3 0 /**< On-chip VDD / 3 */
#define ADC_SENSOR_TEMP 1 /**< On-chip temperature */
#define ADC_SENSOR_ALS 2 /**< Ambient light sensor */
/** @} */
extern const struct sensors_sensor adc_sensor;
#endif /* ADC_SENSOR_H_ */
/**
* @}
* @}
*/

View File

@ -167,6 +167,20 @@
#define PLATFORM_HAS_BUTTON 1
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name ADC configuration
*
* These values configure which CC2538 pins and ADC channels to use for the ADC
* inputs.
*
* ADC inputs can only be on port A.
* @{
*/
#define ADC_ALS_PWR_PORT GPIO_A_NUM /**< ALS power GPIO control port */
#define ADC_ALS_PWR_PIN 7 /**< ALS power GPIO control pin */
#define ADC_ALS_OUT_PIN 6 /**< ALS output ADC input pin on port A */
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name SPI configuration
*

View File

@ -42,12 +42,13 @@
*/
#include "contiki.h"
#include "dev/button-sensor.h"
#include "dev/adc-sensor.h"
#include <string.h>
/** \brief Exports a global symbol to be used by the sensor API */
SENSORS(&button_select_sensor, &button_left_sensor, &button_right_sensor,
&button_up_sensor, &button_down_sensor);
&button_up_sensor, &button_down_sensor, &adc_sensor);
/**
* @}