create iris directory

This commit is contained in:
HATATANI Shinta 2011-06-04 21:42:19 +09:00
parent 154f971b2b
commit cae1e122e8
27 changed files with 2485 additions and 0 deletions

76
platform/iris/dev/adc.c Normal file
View file

@ -0,0 +1,76 @@
/*
* Copyright (c) 2010, University of Colombo School of Computing
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
*/
#include <avr/io.h>
#include "dev/adc.h"
/*---------------------------------------------------------------------------*/
void
adc_init()
{
ADMUX = 0;
/* AVCC with external capacitor at AREF pin. */
ADMUX |= _BV(REFS0);
/* Disable ADC interrupts. */
ADCSRA &= ~( _BV(ADIE) | _BV(ADIF) );
/* Set ADC prescaler to 64 and clear interrupt flag. */
ADCSRA |= _BV(ADPS2) | _BV(ADPS1) | _BV(ADIE);
}
/*---------------------------------------------------------------------------*/
/* Poll based approach. The interrupt based adc is currently not used.
The ADC result is right adjusted. First 8 bits(from left) are in ADCL and
other two bits are in ADCH. See Atmega128 datasheet page 228. */
uint16_t
get_adc(int channel)
{
uint16_t reading;
ADMUX |= (channel & 0x1F);
/* Disable ADC interrupts. */
ADCSRA &= ~_BV(ADIE);
/* Clear previous interrupts. */
ADCSRA |= _BV(ADIF);
/* Enable ADC and start conversion. */
ADCSRA |= _BV(ADEN) | _BV(ADSC);
/* Wait until conversion is completed. */
while ( ADCSRA & _BV(ADSC) );
/* Get first 8 bits. */
reading = ADCL;
/* Get last two bits. */
reading |= (ADCH & 3) << 8;
/* Disable ADC. */
ADCSRA &= ~_BV(ADEN);
return reading;
}
/*---------------------------------------------------------------------------*/

40
platform/iris/dev/adc.h Normal file
View file

@ -0,0 +1,40 @@
/*
* Copyright (c) 2010, University of Colombo School of Computing
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
*/
#ifndef __ADC_H__
#define __ADC_H__
void adc_init();
uint16_t get_adc(int channel);
#endif /* __ADC_H__ */

View file

@ -0,0 +1,69 @@
/*
* Copyright (c) 2009, University of Colombo School of Computing
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
* @(#)$$
*/
#include <avr/io.h>
#include "contiki.h"
#include "contiki-net.h"
#include "dev/spi.h"
#include "dev/cc2420.h"
#include "dev/leds.h"
void
cc2420_arch_init(void)
{
SFIOR |= BV(PUD); /* Beware, disable all pull-ups. */
spi_init();
DDRA |= BV(CC2420_RESET_PIN);
DDRA |= BV(CC2420_VREG_PIN);
DDRB &= ~BV(CC2420_FIFO_PIN);
DDRD &= ~BV(CC2420_CCA_PIN);
DDRD &= ~BV(CC2420_SFD_PIN);
DDRE &= ~BV(CC2420_FIFOP_PIN);
PORTA |= BV(CC2420_RESET_PIN);
PORTB |= BV(CC2420_CSN_PIN);
CC2420_SPI_DISABLE(); /* Unselect radio. */
}
ISR(CC2420_IRQ_VECTOR)
{
/* TODO : wakeup from sleep mode */
cc2420_interrupt();
}

160
platform/iris/dev/clock.c Normal file
View file

@ -0,0 +1,160 @@
/*
* Copyright (c) 2009, University of Colombo School of Computing
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
* @(#)$$
*/
#include "sys/clock.h"
#include "sys/etimer.h"
#include <avr/io.h>
#include <avr/interrupt.h>
static volatile clock_time_t count, scount;
static volatile unsigned long seconds;
/*---------------------------------------------------------------------------*/
ISR(TIMER0_COMP_vect)
{
count++;
if(++scount == CLOCK_SECOND) {
scount = 0;
seconds++;
}
if(etimer_pending()) {
etimer_request_poll();
}
}
/*---------------------------------------------------------------------------*/
void
clock_init(void)
{
/* Disable interrupts*/
cli();
/* Disable compare match interrupts and overflow interrupts. */
TIMSK &= ~( _BV(TOIE0) | _BV(OCIE0) );
/**
* set Timer/Counter0 to be asynchronous
* from the CPU clock with a second external
* clock(32,768kHz) driving it.
*/
ASSR |= _BV(AS0);
/*
* Set timer control register:
* - prescale: 32 (CS00 and CS01)
* - counter reset via comparison register (WGM01)
*/
TCCR0 = _BV(CS00) | _BV(CS01) | _BV(WGM01);
/* Set counter to zero */
TCNT0 = 0;
/*
* 128 clock ticks per second.
* 32,768 = 32 * 8 * 128
*/
OCR0 = 8;
/* Clear interrupt flag register */
TIFR = 0x00;
/**
* Wait for TCN0UB, OCR0UB, and TCR0UB.
*
*/
while(ASSR & 0x07);
/* Raise interrupt when value in OCR0 is reached. */
TIMSK |= _BV(OCIE0);
count = 0;
/* enable all interrupts*/
sei();
}
/*---------------------------------------------------------------------------*/
clock_time_t
clock_time(void)
{
clock_time_t tmp;
do {
tmp = count;
} while(tmp != count);
return tmp;
}
/*---------------------------------------------------------------------------*/
/**
* Delay the CPU for a multiple of TODO
*/
void
clock_delay(unsigned int i)
{
for (; i > 0; i--) { /* Needs fixing XXX */
unsigned j;
for (j = 50; j > 0; j--)
asm volatile("nop");
}
}
/*---------------------------------------------------------------------------*/
/**
* Wait for a multiple of 1 / 128 sec = 7.8125 ms.
*
*/
void
clock_wait(int i)
{
clock_time_t start;
start = clock_time();
while(clock_time() - start < (clock_time_t)i);
}
/*---------------------------------------------------------------------------*/
void
clock_set_seconds(unsigned long sec)
{
// TODO
}
/*---------------------------------------------------------------------------*/
unsigned long
clock_seconds(void)
{
unsigned long tmp;
do {
tmp = seconds;
} while(tmp != seconds);
return tmp;
}
/*---------------------------------------------------------------------------*/

244
platform/iris/dev/ds2401.c Normal file
View file

@ -0,0 +1,244 @@
/*
* Copyright (c) 2009, University of Colombo School of Computing
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
*/
/*
* Device driver for the Dallas Semiconductor DS2401 chip. Heavily
* based on the application note 126 "1-Wire Communications Through
* Software".
*
* http://www.maxim-ic.com/appnotes.cfm/appnote_number/126
*/
/*
* For now we stuff in Crossbow Technology, Inc's unique OUI.
* 00:1A:4C Crossbow Technology, Inc
*
* The EUI-64 is a concatenation of the 24-bit OUI value assigned by
* the IEEE Registration Authority and a 40-bit extension identifier
* assigned by the organization with that OUI assignment.
*/
#include <avr/io.h>
#include <string.h>
#include "contiki.h"
#include "ds2401.h"
unsigned char ds2401_id[8];
/* 1-wire is at PortA.4 */
#define SERIAL_ID_PIN_READ PINA
#define SERIAL_ID_PIN_MASK _BV(4)
#define SERIAL_ID_PxOUT PORTA
#define SERIAL_ID_PxDIR DDRA
#define SET_PIN_INPUT() (SERIAL_ID_PxDIR &= ~SERIAL_ID_PIN_MASK)
#define SET_PIN_OUTPUT() (SERIAL_ID_PxDIR |= SERIAL_ID_PIN_MASK)
#define OUTP_0() (SERIAL_ID_PxOUT &= ~SERIAL_ID_PIN_MASK)
#define OUTP_1() (SERIAL_ID_PxOUT |= SERIAL_ID_PIN_MASK)
#define PIN_INIT() do{ \
SET_PIN_INPUT(); \
OUTP_0(); \
} while(0)
/* Drive the one wire interface low */
#define OW_DRIVE() do { \
SET_PIN_OUTPUT(); \
OUTP_0(); \
} while (0)
/* Release the one wire by turning on the internal pull-up. */
#define OW_RELEASE() do { \
SET_PIN_INPUT(); \
OUTP_1(); \
} while (0)
/* Read one bit. */
#define INP() (SERIAL_ID_PIN_READ & SERIAL_ID_PIN_MASK)
/*
* Delay times in us.
*/
#define tA 6 /* min-5, recommended-6, max-15 */
#define tB 64 /* min-59, recommended-64, max-N/A */
#define tC 60 /* min-60, recommended-60, max-120 */
#define tD 10 /* min-5.3, recommended-10, max-N/A */
#define tE 9 /* min-0.3, recommended-9, max-9.3 */
#define tF 55 /* min-50, recommended-55, max-N/A */
#define tG 0 /* min-0, recommended-0, max-0 */
#define tH 480 /* min-480, recommended-480, max-640 */
#define tI 70 /* min-60.3, recommended-70, max-75.3 */
#define tJ 410 /* min-410, recommended-410, max-N/A */
/*---------------------------------------------------------------------------*/
/*
* The delay caused by calling the delay_loop is given by the following
* formula.
* delay(us) = (4n + 1)/XTAL
* where n is the number of iterations and XTAL is the clock frequency(in MHz).
* TODO: Moving the delay_loop to dev/clock.c
*/
static void
delay_loop(uint16_t __count)
{
asm volatile ("1: sbiw %0,1" "\n\t"
"brne 1b"
: "=w" (__count)
: "0" (__count)
);
}
/*---------------------------------------------------------------------------*/
/*
* This macro relies on the compiler doing the arithmetic during compile time
* for the needed iterations.!!
* In MICAz, XTAL = 7.3728 MHz
*/
#define udelay(u) delay_loop(((7.3728F * u)-1)/4)
/*---------------------------------------------------------------------------*/
static uint8_t
reset(void)
{
uint8_t result;
OW_DRIVE();
udelay(500); /* 480 < tH < 640 */
OW_RELEASE(); /* Releases the bus */
udelay(tI);
result = INP();
udelay(tJ);
return result;
}
/*---------------------------------------------------------------------------*/
static void
write_byte(uint8_t byte)
{
uint8_t i = 7;
do {
if (byte & 0x01) {
OW_DRIVE();
udelay(tA);
OW_RELEASE(); /* Releases the bus */
udelay(tB);
} else {
OW_DRIVE();
udelay(tC);
OW_RELEASE(); /* Releases the bus */
udelay(tD);
}
if (i == 0)
return;
i--;
byte >>= 1;
} while (1);
}
/*---------------------------------------------------------------------------*/
static unsigned
read_byte(void)
{
unsigned result = 0;
int i = 7;
do {
OW_DRIVE();
udelay(tA);
OW_RELEASE(); /* Releases the bus */
udelay(tE);
if (INP())
result |= 0x80; /* LSbit first */
udelay(tF);
if (i == 0)
return result;
i--;
result >>= 1;
} while (1);
}
/*---------------------------------------------------------------------------*/
/* Polynomial ^8 + ^5 + ^4 + 1 */
static unsigned
crc8_add(unsigned acc, unsigned byte)
{
int i;
acc ^= byte;
for (i = 0; i < 8; i++)
if (acc & 1)
acc = (acc >> 1) ^ 0x8c;
else
acc >>= 1;
return acc;
}
/*---------------------------------------------------------------------------*/
int
ds2401_init()
{
int i;
uint8_t volatile sreg;
unsigned family, crc, acc;
PIN_INIT();
sreg = SREG; /* Save status register before disabling interrupts. */
cli(); /* Disable interrupts. */
if (reset() == 0) {
write_byte(0x33); /* Read ROM command. */
family = read_byte();
for (i = 7; i >= 2; i--) {
ds2401_id[i] = read_byte();
}
crc = read_byte();
SREG = sreg; /* Enable interrupts. */
if(family != 0x01) {
goto fail;
}
acc = crc8_add(0x0, family);
for (i = 7; i >= 2; i--) {
acc = crc8_add(acc, ds2401_id[i]);
}
if (acc == crc) {
/* 00:1A:4C OUI for Crossbow Technology, Inc. */
ds2401_id[0] = 0x00;
ds2401_id[1] = 0x1A;
ds2401_id[2] = 0x4C;
return 1; /* Success! */
}
} else {
SREG = sreg; /* Enable interrupts. */
}
fail:
memset(ds2401_id, 0x0, sizeof(ds2401_id));
return 0; /* Fail! */
}
/*---------------------------------------------------------------------------*/

View file

@ -0,0 +1,39 @@
/*
* Copyright (c) 2009, University of Colombo School of Computing
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
*/
#ifndef DS2401_H
#define DS2401_H
extern unsigned char ds2401_id[8];
extern int ds2401_init();
#endif /* DS2401_H */

View file

@ -0,0 +1,67 @@
/*
* Copyright (c) 2009, University of Colombo School of Computing
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
* @(#)$$
*/
/**
* \file
* LED architecture of the MICAz port.
* \author
* Kasun Hewage <kasun.ch@gmail.com>
*/
#include "contiki-conf.h"
#include "dev/leds.h"
#include <avr/io.h>
/*---------------------------------------------------------------------------*/
void leds_arch_init(void)
{
LEDS_PxDIR |= (LEDS_CONF_RED | LEDS_CONF_GREEN | LEDS_CONF_YELLOW);
LEDS_PxOUT |= (LEDS_CONF_RED | LEDS_CONF_GREEN | LEDS_CONF_YELLOW);
}
/*---------------------------------------------------------------------------*/
unsigned char leds_arch_get(void)
{
return ((LEDS_PxOUT & LEDS_CONF_RED) ? 0 : LEDS_RED)
| ((LEDS_PxOUT & LEDS_CONF_GREEN) ? 0 : LEDS_GREEN)
| ((LEDS_PxOUT & LEDS_CONF_YELLOW) ? 0 : LEDS_YELLOW);
}
/*---------------------------------------------------------------------------*/
void leds_arch_set(unsigned char leds)
{
LEDS_PxOUT = (LEDS_PxOUT & ~(LEDS_CONF_RED|LEDS_CONF_GREEN|LEDS_CONF_YELLOW))
| ((leds & LEDS_RED) ? 0 : LEDS_CONF_RED)
| ((leds & LEDS_GREEN) ? 0 : LEDS_CONF_GREEN)
| ((leds & LEDS_YELLOW) ? 0 : LEDS_CONF_YELLOW);
}
/*---------------------------------------------------------------------------*/

View file

@ -0,0 +1,103 @@
/*
* Copyright (c) 2010, University of Colombo School of Computing.
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*/
/**
* \file
* Battery sensor driver.
* \author
* Kasun Hewage <kasun.ch@gmail.com>
*/
#include <avr/io.h>
#include "dev/battery-sensor.h"
#include "dev/adc.h"
#define BAT_MONITOR_PORT PORTF
#define BAT_MONITOR_PIN_MASK _BV(1)
#define BAT_MONITOR_PORT_DDR DDRF
#define BAT_MONITOR_ADC_CHANNEL 30
const struct sensors_sensor battery_sensor;
static uint8_t active;
/*---------------------------------------------------------------------------*/
static void
activate(void)
{
/* This assumes that some other sensor system already did setup the ADC */
adc_init();
/* Enable battery sensor. */
BAT_MONITOR_PORT |= BAT_MONITOR_PIN_MASK;
BAT_MONITOR_PORT_DDR |= BAT_MONITOR_PIN_MASK;
active = 1;
}
/*---------------------------------------------------------------------------*/
static void
deactivate(void)
{
active = 0;
}
/*---------------------------------------------------------------------------*/
static int
value(int type)
{
return get_adc(BAT_MONITOR_ADC_CHANNEL);
}
/*---------------------------------------------------------------------------*/
static int
configure(int type, int c)
{
switch(type) {
case SENSORS_ACTIVE:
if (c) {
activate();
} else {
deactivate();
}
}
return 0;
}
/*---------------------------------------------------------------------------*/
static int
status(int type)
{
switch (type) {
case SENSORS_ACTIVE:
case SENSORS_READY:
return active;
}
return 0;
}
/*---------------------------------------------------------------------------*/
SENSORS_SENSOR(battery_sensor, BATTERY_SENSOR,
value, configure, status);

View file

@ -0,0 +1,221 @@
/*
* Copyright (c) 2009, University of Colombo School of Computing
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
* @(#)$$
*/
/**
* \file
* Device drivers implementation for MTS300 sensor board.
* \author
* Kasun Hewage <kasun.ch@gmail.com>
*/
#include "mts300.h"
/*---------------------------------------------------------------------------*/
void
sounder_on()
{ SOUNDER_DDR |= SOUNDER_MASK;
SOUNDER_PORT &= ~SOUNDER_MASK;
SOUNDER_PORT |= SOUNDER_MASK;
}
/*---------------------------------------------------------------------------*/
void
sounder_off()
{
SOUNDER_PORT &= ~(SOUNDER_MASK);
SOUNDER_DDR &= ~(SOUNDER_MASK);
}
/*---------------------------------------------------------------------------*/
void
adc_init()
{
ADMUX = 0;
/* AVCC with external capacitor at AREF pin. */
//ADMUX |= _BV(REFS0)
/* Disable ADC interrupts. */
ADCSRA &= ~( _BV(ADIE) | _BV(ADIF) );
/* Set ADC prescaler to 64 and clear interrupt flag. */
ADCSRA |= _BV(ADPS2) | _BV(ADPS1) | _BV(ADIE);
}
/*---------------------------------------------------------------------------*/
/* Poll based approach. The interrupt based adc is currently not used.
The ADC result is right adjusted. First 8 bits(from left) are in ADCL and
other two bits are in ADCH. See Atmega128 datasheet page 228. */
uint16_t
get_adc(int channel)
{
uint16_t reading;
ADMUX |= (channel & 0x1F);
/* Disable ADC interrupts. */
ADCSRA &= ~_BV(ADIE);
/* Clear previous interrupts. */
ADCSRA |= _BV(ADIF);
/* Enable ADC and start conversion. */
ADCSRA |= _BV(ADEN) | _BV(ADSC);
/* Wait until conversion is completed. */
while ( ADCSRA & _BV(ADSC) );
/* Get first 8 bits. */
reading = ADCL;
/* Get last two bits. */
reading |= (ADCH & 3) << 8;
/* Disable ADC. */
ADCSRA &= ~_BV(ADEN);
return reading;
}
/*---------------------------------------------------------------------------*/
uint16_t
get_light()
{
uint16_t reading;
/* Enable light sensor. */
LIGHT_PORT |= LIGHT_PIN_MASK;
LIGHT_PORT_DDR |= LIGHT_PIN_MASK;
/* Disable temperature sensor. */
TEMP_PORT_DDR &= ~TEMP_PIN_MASK;
TEMP_PORT &= ~TEMP_PIN_MASK;
/* Read ADC. */
reading = get_adc(LIGHT_ADC_CHANNEL);
/* Disable light sensor. */
LIGHT_PORT &= ~LIGHT_PIN_MASK;
LIGHT_PORT_DDR &= ~LIGHT_PIN_MASK;
return reading;
}
/*---------------------------------------------------------------------------*/
uint16_t
get_temp()
{
uint16_t reading;
/* Disable light sensor. */
LIGHT_PORT &= ~LIGHT_PIN_MASK;
LIGHT_PORT_DDR &= ~LIGHT_PIN_MASK;
/* Enable temperature sensor. */
TEMP_PORT_DDR |= TEMP_PIN_MASK;
TEMP_PORT |= TEMP_PIN_MASK;
/* Read ADC. */
reading = get_adc(TEMP_ADC_CHANNEL);
/* Disable temperature sensor. */
TEMP_PORT_DDR &= ~TEMP_PIN_MASK;
TEMP_PORT &= ~TEMP_PIN_MASK;
return reading;
}
/*---------------------------------------------------------------------------*/
uint16_t
get_accx()
{
uint16_t reading;
/* Enable accelerometer. */
ACCEL_PORT_DDR |= ACCEL_PIN_MASK;
ACCEL_PORT |= ACCEL_PIN_MASK;
/* Read ADC. */
reading = get_adc(ACCELX_ADC_CHANNEL);
/* Enable accelerometer. */
ACCEL_PORT_DDR &= ~ACCEL_PIN_MASK;
ACCEL_PORT &= ~ACCEL_PIN_MASK;
return reading;
}
/*---------------------------------------------------------------------------*/
uint16_t
get_accy()
{
uint16_t reading;
/* Enable accelerometer. */
ACCEL_PORT_DDR |= ACCEL_PIN_MASK;
ACCEL_PORT |= ACCEL_PIN_MASK;
/* Read ADC. */
reading = get_adc(ACCELY_ADC_CHANNEL);
/* Enable accelerometer. */
ACCEL_PORT_DDR &= ~ACCEL_PIN_MASK;
ACCEL_PORT &= ~ACCEL_PIN_MASK;
return reading;
}
/*---------------------------------------------------------------------------*/
uint16_t
get_magx()
{
uint16_t reading;
/* Enable magnetometer. */
MAGNET_PORT_DDR |= MAGNET_PIN_MASK;
MAGNET_PORT |= MAGNET_PIN_MASK;
/* Read ADC. */
reading = get_adc(MAGNETX_ADC_CHANNEL);
/* Enable magnetometer. */
MAGNET_PORT_DDR &= ~MAGNET_PIN_MASK;
MAGNET_PORT &= ~MAGNET_PIN_MASK;
return reading;
}
/*---------------------------------------------------------------------------*/
uint16_t
get_magy()
{
uint16_t reading;
/* Enable magnetometer. */
MAGNET_PORT_DDR |= MAGNET_PIN_MASK;
MAGNET_PORT |= MAGNET_PIN_MASK;
/* Read ADC. */
reading = get_adc(MAGNETY_ADC_CHANNEL);
/* Enable magnetometer. */
MAGNET_PORT_DDR &= ~MAGNET_PIN_MASK;
MAGNET_PORT &= ~MAGNET_PIN_MASK;
return reading;
}
/*---------------------------------------------------------------------------*/
uint16_t
get_mic()
{
uint16_t reading;
/* Enable mic. */
MIC_PORT_DDR |= MIC_PIN_MASK;
MIC_PORT |= MIC_PIN_MASK;
/* Read ADC. */
reading = get_adc(MIC_ADC_CHANNEL);
/* Enable mic. */
MIC_PORT_DDR &= ~MIC_PIN_MASK;
MIC_PORT &= ~MIC_PIN_MASK;
return reading;
}
/*---------------------------------------------------------------------------*/

View file

@ -0,0 +1,112 @@
/*
* Copyright (c) 2009, University of Colombo School of Computing
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
* @(#)$$
*/
/**
* \file
* Device drivers header file for MTS300 sensor board.
* \author
* Kasun Hewage <kasun.ch@gmail.com>
*/
#ifndef __MTS300_H__
#define __MTS300_H__
#include <avr/io.h>
#include "contiki-conf.h"
#define SOUNDER_PORT PORTC
#define SOUNDER_MASK _BV(2)
#define SOUNDER_DDR DDRC
/* MTS300CA and MTS310CA, the light sensor power is controlled
* by setting signal INT1(PORTE pin 5).
* Both light and thermistor use the same ADC channel.
*/
#define LIGHT_PORT_DDR DDRE
#define LIGHT_PORT PORTE
#define LIGHT_PIN_MASK _BV(5)
#define LIGHT_ADC_CHANNEL 1
/* MTS300CA and MTS310CA, the thermistor power is controlled
* by setting signal INT2(PORTE pin 6).
* Both light and thermistor use the same ADC channel.
*/
#define TEMP_PORT_DDR DDRE
#define TEMP_PORT PORTE
#define TEMP_PIN_MASK _BV(6)
#define TEMP_ADC_CHANNEL 1
/* Power is controlled to the accelerometer by setting signal
* PW4(PORTC pin 4), and the analog data is sampled on ADC3 and ADC4.
*/
#define ACCEL_PORT_DDR DDRC
#define ACCEL_PORT PORTC
#define ACCEL_PIN_MASK _BV(4)
#define ACCELX_ADC_CHANNEL 3
#define ACCELY_ADC_CHANNEL 4
/* Power is controlled to the magnetometer by setting signal
* PW5(PORTC pin 5), and the analog data is sampled on ADC5 and ADC6.
*/
#define MAGNET_PORT_DDR DDRC
#define MAGNET_PORT PORTC
#define MAGNET_PIN_MASK _BV(5)
#define MAGNETX_ADC_CHANNEL 5
#define MAGNETY_ADC_CHANNEL 6
#define MIC_PORT_DDR DDRC
#define MIC_PORT PORTC
#define MIC_PIN_MASK _BV(3)
#define MIC_ADC_CHANNEL 2
void sounder_on();
void sounder_off();
uint16_t get_light();
uint16_t get_temp();
uint16_t get_accx();
uint16_t get_accy();
uint16_t get_magx();
uint16_t get_magy();
uint16_t get_mic();
void mts300_init();
#endif /* __MTS300_H__ */

View file

@ -0,0 +1,93 @@
/*
* Copyright (c) 2010, University of Colombo School of Computing
* 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 Institute 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 INSTITUTE 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 INSTITUTE 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.
*
* This file is part of the Contiki operating system.
*
* @(#)$$
*/
/**
* \file
* Machine dependent AVR SLIP routines for UART0.
* \author
* Kasun Hewage <kasun.ch@gmail.com>
*/
#include <stdio.h>
#include "contiki.h"
#include "dev/rs232.h"
#include "slip.h"
/*---------------------------------------------------------------------------*/
static int
slip_putchar(char c, FILE *stream)
{
#define SLIP_END 0300
static char debug_frame = 0;
if (!debug_frame) { /* Start of debug output */
slip_arch_writeb(SLIP_END);
slip_arch_writeb('\r'); /* Type debug line == '\r' */
debug_frame = 1;
}
slip_arch_writeb((unsigned char)c);
/*
* Line buffered output, a newline marks the end of debug output and
* implicitly flushes debug output.
*/
if (c == '\n') {
slip_arch_writeb(SLIP_END);
debug_frame = 0;
}
return c;
}
/*---------------------------------------------------------------------------*/
static FILE slip_stdout = FDEV_SETUP_STREAM(slip_putchar, NULL,
_FDEV_SETUP_WRITE);
/*---------------------------------------------------------------------------*/
void
slip_arch_init(unsigned long ubr)
{
rs232_set_input(RS232_PORT_0, slip_input_byte);
stdout = &slip_stdout;
}
/*---------------------------------------------------------------------------*/
/*
XXX:
Currently, the following function is in cpu/avr/dev/rs232.c file. this
should be moved to here from there hence this is a platform specific slip
related function.
void
slip_arch_writeb(unsigned char c)
{
rs232_send(RS232_PORT_0, c);
}
*/