added license headers and doxygen file information

plus replaced tabs with spaces
dev/timer
Oleg Hahm 10 years ago
parent 4931ea7d95
commit 4bc6dfbf69

@ -1,3 +1,24 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup chronos
* @{
*/
/**
* @file
* @brief eZ430-chronos board initialization
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author Ludwig Ortmann <ludwig.ortmann@fu-berlin.de>
*
*/
#include <stdint.h>
#include "board.h"

@ -1,3 +1,25 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup chronos
* @{
*/
/**
* @file
* @brief eZ430-chronos battery readout (via ADC)
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author Ludwig Ortmann <ludwig.ortmann@fu-berlin.de>
*
*/
#include <stdint.h>
#include <stdint.h>
#include <cc430f6137.h>

@ -1,3 +1,26 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup chronos
* @{
*/
/**
* @file
* @brief eZ430-chronos beeper
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author Ludwig Ortmann <ludwig.ortmann@fu-berlin.de>
* @author mikoff
*
*/
#include <stdint.h>
#include <stdint.h>
#include <cc430f6137.h>

@ -1,3 +1,24 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup chronos
* @{
*/
/**
* @file
* @brief eZ430-chronos radio driver (board dependent part)
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
*/
#include <stdint.h>
#include <stdint.h>
#include <cc430f6137.h>
@ -13,17 +34,17 @@
int cc110x_get_gdo0(void)
{
return CC1100_GDO0;
return CC1100_GDO0;
}
int cc110x_get_gdo1(void)
{
return CC1100_GDO1;
return CC1100_GDO1;
}
int cc110x_get_gdo2(void)
{
return CC1100_GDO2;
return CC1100_GDO2;
}
void cc110x_before_send(void)

@ -1,40 +1,55 @@
/* *************************************************************************************************
*
* Copyright (C) 2009 Texas Instruments Incorporated - http://www.ti.com/
* Copyright (C) 2009 Texas Instruments Incorporated - http://www.ti.com/
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* 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.
* 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.
*
* Neither the name of Texas Instruments Incorporated nor the names of
* its contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
* Neither the name of Texas Instruments Incorporated 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
* OWNER 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 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
* OWNER 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.
*
* *************************************************************************************************
* Basic display functions.
* ************************************************************************************************/
/**
* @ingroup chronos
* @{
*/
/**
* @file
* @brief eZ430-chronos display driver
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author Ludwig Ortmann <ludwig.ortmann@fu-berlin.de>
* @author Kaspar Schleiser <kaspar@schleiser.de>
* @author mikoff
*
*/
/* *************************************************************************************************
* Include section
*/
@ -134,12 +149,12 @@ void write_lcd_mem(uint8_t *lcdmem, uint8_t bits, uint8_t bitmask, uint8_t state
}
else if (state == SEG_ON_BLINK_ON) {
/* Clear visible / blink segments before writing */
*lcdmem = (uint8_t)(*lcdmem & ~bitmask);
*(lcdmem + 0x20) = (uint8_t)(*(lcdmem + 0x20) & ~bitmask);
*lcdmem = (uint8_t)(*lcdmem & ~bitmask);
*(lcdmem + 0x20) = (uint8_t)(*(lcdmem + 0x20) & ~bitmask);
/* Set visible / blink segments */
*lcdmem = (uint8_t)(*lcdmem | bits);
*(lcdmem + 0x20) = (uint8_t)(*(lcdmem + 0x20) | bits);
*lcdmem = (uint8_t)(*lcdmem | bits);
*(lcdmem + 0x20) = (uint8_t)(*(lcdmem + 0x20) | bits);
}
else if (state == SEG_ON_BLINK_OFF) {
/* Clear visible segments before writing */
@ -149,14 +164,14 @@ void write_lcd_mem(uint8_t *lcdmem, uint8_t bits, uint8_t bitmask, uint8_t state
*lcdmem = (uint8_t)(*lcdmem | bits);
/* Clear blink segments */
*(lcdmem + 0x20) = (uint8_t)(*(lcdmem + 0x20) & ~bitmask);
*(lcdmem + 0x20) = (uint8_t)(*(lcdmem + 0x20) & ~bitmask);
}
else if (state == SEG_OFF_BLINK_OFF) {
/* Clear segments */
*lcdmem = (uint8_t)(*lcdmem & ~bitmask);
/* Clear blink segments */
*(lcdmem + 0x20) = (uint8_t)(*(lcdmem + 0x20) & ~bitmask);
*(lcdmem + 0x20) = (uint8_t)(*(lcdmem + 0x20) & ~bitmask);
}
}
@ -196,7 +211,7 @@ char *itoa(uint32_t n, uint8_t digits, uint8_t blanks)
/* Remove specified number of leading '0', always keep last one */
i = 0;
while ((itoa_str[i] == '0') && (i < digits1 - 1)) {
while ((itoa_str[i] == '0') && (i < digits1 - 1)) {
if (blanks > 0) {
/* Convert only specified number of leading '0' */
itoa_str[i] = ' ';
@ -227,24 +242,24 @@ void display_symbol(uint8_t symbol, uint8_t mode)
if (symbol <= LCD_SEG_L2_DP) {
/* Get LCD memory address for symbol from table */
lcdmem = (uint8_t *)segments_lcdmem[symbol];
lcdmem = (uint8_t *)segments_lcdmem[symbol];
/* Get bits for symbol from table */
bits = segments_bitmask[symbol];
bits = segments_bitmask[symbol];
/* Bitmask for symbols equals bits */
bitmask = bits;
/* Write LCD memory */
/* Write LCD memory */
write_lcd_mem(lcdmem, bits, bitmask, mode);
}
}
void display_char(uint8_t segment, char chr, uint8_t mode)
{
uint8_t *lcdmem; /* Pointer to LCD memory */
uint8_t bitmask; /* Bitmask for character */
uint8_t bits, bits1; /* Bits to write */
uint8_t *lcdmem; /* Pointer to LCD memory */
uint8_t bitmask; /* Bitmask for character */
uint8_t bits, bits1; /* Bits to write */
/* Write to single 7-segment character */
if ((segment >= LCD_SEG_L1_3) && (segment <= LCD_SEG_L2_DP)) {
@ -283,7 +298,7 @@ void display_char(uint8_t segment, char chr, uint8_t mode)
}
}
/* Physically write to LCD memory */
/* Physically write to LCD memory */
write_lcd_mem(lcdmem, bits, bitmask, mode);
}
}
@ -291,8 +306,8 @@ void display_char(uint8_t segment, char chr, uint8_t mode)
void display_chars(uint8_t segments, char *str, uint8_t mode)
{
uint8_t i;
uint8_t length = 0; /* Write length */
uint8_t char_start = 0; /* Starting point for consecutive write */
uint8_t length = 0; /* Write length */
uint8_t char_start = 0; /* Starting point for consecutive write */
switch (segments) {
/* LINE1 */

@ -1,41 +1,50 @@
/* *************************************************************************************************
*
* Copyright (C) 2009 Texas Instruments Incorporated - http://www.ti.com/
* Copyright (C) 2009 Texas Instruments Incorporated - http://www.ti.com/
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* 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.
* 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.
*
* Neither the name of Texas Instruments Incorporated nor the names of
* its contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
* Neither the name of Texas Instruments Incorporated 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
* OWNER 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 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
* OWNER 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.
*
* ************************************************************************************************/
/* Basic display functions. */
/* ************************************************************************************************* */
/**
* @file
* @brief eZ430-chronos display driver character tables
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author Kaspar Schleiser <kaspar@schleiser.de>
*
*/
/* ************************************************************************************************* */
/* Include section */
#include <stdint.h>

@ -1,3 +1,26 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup chronos
* @{
*/
/**
* @file
* @brief eZ430-chronos putchar via display implementation
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author Kaspar Schleiser <kaspar@schleiser.de>
* @author Ludwig Ortmann <ludwig.ortmann@fu-berlin.de>
* @author mikoff
*
*/
#include <stdio.h>
#include <string.h>
#include <ctype.h>

@ -1,3 +1,24 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup chronos
* @{
*/
/**
* @file
* @brief eZ430-chronos putchar dummy implementation
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author Kaspar Schleiser <kaspar@schleiser.de>
*
*/
static void _dummy(int c)
{
}

@ -1,3 +1,23 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup boards
* @{
*/
/**
* @file
* @brief msb-430 common config module functions
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
*/
#include <stdint.h>
#include <string.h>
#include "board-conf.h"

@ -1,3 +1,24 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup boards
* @{
*/
/**
* @file
* @brief msb-430 common board initialization
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author Kaspar Schleiser <kaspar@schleiser.de>
*
*/
#include "cpu.h"
#include "board.h"
#include "kernel_internal.h"

@ -1,3 +1,23 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup boards
* @{
*/
/**
* @file
* @brief msb-430 common putchar implementation
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author Kaspar Schleiser <kaspar@schleiser.de>
*/
#include <stdio.h>
#include "board.h"
#include "kernel.h"
@ -24,7 +44,7 @@ void usart0irq(void);
/**
* \brief the interrupt function
*/
interrupt(USART1RX_VECTOR) usart0irq(void)
interrupt(USART1RX_VECTOR) usart0irq(void)
{
U1TCTL &= ~URXSE; /* Clear the URXS signal */
U1TCTL |= URXSE; /* Re-enable URXS - needed here?*/

@ -1,3 +1,24 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup boards
* @{
*/
/**
* @file
* @brief msba2 common config module functions
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author Zakaria Kasmi <zkasmi@inf.fu-berlin.de>
*
*/
#include <stdint.h>
#include <string.h>
#include "config.h"

@ -1,8 +1,23 @@
/*
* lpc2387_timer0.c
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup msba2
* @{
*/
/**
* @file
* @brief msba2 benchmark functions
*
* @author Heiko Will <heiko.will@fu-berlin.de>
* @author Zakaria Kasmi <zkasmi@inf.fu-berlin.de>
* @author Kaspar Schleiser <kaspar@schleiser.de>
*
* Created on: 13.01.2009
* Author: heiko
*/
#include <stdint.h>

@ -1,3 +1,23 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup cc430
* @{
*/
/**
* @file
* @brief eZ430 radio driver (cpu dependent part)
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
*/
#include <stdint.h>
#include "irq.h"
#include "cc110x-defaultSettings.h"
@ -34,18 +54,18 @@ uint8_t cc110x_strobe(uint8_t c)
RF1AINSTRB = c;
if ((RF1AIN & 0x04) == 0x04) { /* chip at sleep mode */
if ((RF1AIN & 0x04) == 0x04) { /* chip at sleep mode */
if ((c == RF_SXOFF) || (c == RF_SPWD) || (c == RF_SWOR)) { }
else {
while ((RF1AIN & 0x04) == 0x04); /* c-ready ? */
while ((RF1AIN & 0x04) == 0x04); /* c-ready ? */
hwtimer_wait(RTIMER_TICKS(9800)); /* Delay for ~810usec at 12MHz CPU clock */
hwtimer_wait(RTIMER_TICKS(9800)); /* Delay for ~810usec at 12MHz CPU clock */
}
}
cc110x_write_reg(IOCFG2, gdo_state); /* restore IOCFG2 setting */
}
else { /* chip active mode */
else { /* chip active mode */
RF1AINSTRB = c;
}

@ -1,40 +1,51 @@
/* *************************************************************************************************
*
* Copyright (C) 2009 Texas Instruments Incorporated - http://www.ti.com/
* Copyright (C) 2009 Texas Instruments Incorporated - http://www.ti.com/
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* 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.
* 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.
*
* Neither the name of Texas Instruments Incorporated nor the names of
* its contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
* Neither the name of Texas Instruments Incorporated 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
* OWNER 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 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
* OWNER 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.
*
* *************************************************************************************************
* ADC12 functions.
* ************************************************************************************************/
/**
* @ingroup cc430
* @{
*/
/**
* @file
* @brief eZ430 ADC driver
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
*/
#include <legacymsp430.h>
#include "cpu.h"
@ -53,13 +64,13 @@ uint8_t adc12_data_ready;
uint16_t adc12_single_conversion(uint16_t ref, uint16_t sht, uint16_t channel)
{
/* Initialize the shared reference module */
REFCTL0 |= REFMSTR + ref + REFON; /* Enable internal reference (1.5V or 2.5V) */
REFCTL0 |= REFMSTR + ref + REFON; /* Enable internal reference (1.5V or 2.5V) */
/* Initialize ADC12_A */
ADC12CTL0 = sht + ADC12ON; /* Set sample time */
ADC12CTL1 = ADC12SHP; /* Enable sample timer */
ADC12MCTL0 = ADC12SREF_1 + channel; /* ADC input channel */
ADC12IE = 0x001; /* ADC_IFG upon conv result-ADCMEMO */
ADC12CTL0 = sht + ADC12ON; /* Set sample time */
ADC12CTL1 = ADC12SHP; /* Enable sample timer */
ADC12MCTL0 = ADC12SREF_1 + channel; /* ADC input channel */
ADC12IE = 0x001; /* ADC_IFG upon conv result-ADCMEMO */
eINT();
/* Wait 2 ticks (66us) to allow internal reference to settle */
@ -83,7 +94,7 @@ uint16_t adc12_single_conversion(uint16_t ref, uint16_t sht, uint16_t channel)
ADC12CTL0 &= ~(ADC12ENC | ADC12SC | sht);
ADC12CTL0 &= ~ADC12ON;
/* Shut down reference voltage */
/* Shut down reference voltage */
REFCTL0 &= ~(REFMSTR + ref + REFON);
ADC12IE = 0;

@ -1,3 +1,23 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup cc430
* @{
*/
/**
* @file
* @brief cc430 flashrom driver
*
* @author Kévin Roussel <Kevin.Roussel@inria.fr>
*
*/
#include <stddef.h>
#include <stdint.h>
#include "cpu.h"
@ -10,7 +30,7 @@ static inline void busy_wait(void);
/*---------------------------------------------------------------------------*/
uint8_t flashrom_erase(uint8_t *addr)
{
// TODO implement this function
// TODO implement this function
return 0;
}
/*---------------------------------------------------------------------------*/

@ -1,3 +1,25 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup cc430
* @{
*/
/**
* @file
* @brief cc430 hardware timer driver
*
* @author Kévin Roussel <Kevin.Roussel@inria.fr>
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author mikoff
*
*/
#include <legacymsp430.h>
#include "board.h"
#include "hwtimer.h"
@ -14,9 +36,9 @@ extern void timer_unset(short timer);
void timerA_init(void)
{
ticks = 0; // Set tick counter value to 0
TA0CTL = TASSEL_1 + TACLR; // Clear the timer counter, set ACLK
TA0CTL &= ~TAIE; // Clear the IFG
ticks = 0; // Set tick counter value to 0
TA0CTL = TASSEL_1 + TACLR; // Clear the timer counter, set ACLK
TA0CTL &= ~TAIE; // Clear the IFG
volatile unsigned int *ccr = &TA0CCR0;
volatile unsigned int *ctl = &TA0CCTL0;

@ -22,6 +22,19 @@
*
******************************************************************************/
/**
* @ingroup lpc1768
* @{
*/
/**
* @file
* @brief lpc1768 startup code
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
*/
#include "LPC17xx.h"
#include "kernel_internal.h"
@ -33,63 +46,63 @@
*
*****************************************************************************/
/* System exception vector handler */
void WEAK Reset_Handler(void); /* Reset Handler */
void WEAK NMI_Handler(void); /* NMI Handler */
void WEAK HardFault_Handler(void); /* Hard Fault Handler */
void WEAK MemManage_Handler(void); /* MPU Fault Handler */
void WEAK BusFault_Handler(void); /* Bus Fault Handler */
void WEAK UsageFault_Handler(void); /* Usage Fault Handler */
void WEAK SVC_Handler(void); /* SVCall Handler */
void WEAK DebugMon_Handler(void); /* Debug Monitor Handler */
void WEAK PendSV_Handler(void); /* PendSV Handler */
void WEAK SysTick_Handler(void); /* SysTick Handler */
void WEAK Reset_Handler(void); /* Reset Handler */
void WEAK NMI_Handler(void); /* NMI Handler */
void WEAK HardFault_Handler(void); /* Hard Fault Handler */
void WEAK MemManage_Handler(void); /* MPU Fault Handler */
void WEAK BusFault_Handler(void); /* Bus Fault Handler */
void WEAK UsageFault_Handler(void); /* Usage Fault Handler */
void WEAK SVC_Handler(void); /* SVCall Handler */
void WEAK DebugMon_Handler(void); /* Debug Monitor Handler */
void WEAK PendSV_Handler(void); /* PendSV Handler */
void WEAK SysTick_Handler(void); /* SysTick Handler */
/* External interrupt vector handler */
void WEAK WDT_IRQHandler(void); /* Watchdog Timer */
void WEAK TIMER0_IRQHandler(void); /* Timer0 */
void WEAK TIMER1_IRQHandler(void); /* Timer1 */
void WEAK TIMER2_IRQHandler(void); /* Timer2 */
void WEAK TIMER3_IRQHandler(void); /* Timer3 */
void WEAK UART0_IRQHandler(void); /* UART0 */
void WEAK UART1_IRQHandler(void); /* UART1 */
void WEAK UART2_IRQHandler(void); /* UART2 */
void WEAK UART3_IRQHandler(void); /* UART3 */
void WEAK PWM1_IRQHandler(void); /* PWM1 */
void WEAK I2C0_IRQHandler(void); /* I2C0 */
void WEAK I2C1_IRQHandler(void); /* I2C1 */
void WEAK I2C2_IRQHandler(void); /* I2C2 */
void WEAK SPI_IRQHandler(void); /* SPI */
void WEAK SSP0_IRQHandler(void); /* SSP0 */
void WEAK SSP1_IRQHandler(void); /* SSP1 */
void WEAK PLL0_IRQHandler(void); /* PLL0 (Main PLL) */
void WEAK RTC_IRQHandler(void); /* Real Time Clock */
void WEAK EINT0_IRQHandler(void); /* External Interrupt 0 */
void WEAK EINT1_IRQHandler(void); /* External Interrupt 1 */
void WEAK EINT2_IRQHandler(void); /* External Interrupt 2 */
void WEAK EINT3_IRQHandler(void); /* External Interrupt 3 */
void WEAK ADC_IRQHandler(void); /* A/D Converter */
void WEAK BOD_IRQHandler(void); /* Brown Out Detect */
void WEAK USB_IRQHandler(void); /* USB */
void WEAK CAN_IRQHandler(void); /* CAN */
void WEAK DMA_IRQHandler(void); /* GP DMA */
void WEAK I2S_IRQHandler(void); /* I2S */
void WEAK ENET_IRQHandler(void); /* Ethernet */
void WEAK RIT_IRQHandler(void); /* Repetitive Interrupt Timer */
void WEAK MCPWM_IRQHandler(void); /* Motor Control PWM */
void WEAK QEI_IRQHandler(void); /* Quadrature Encoder Interface */
void WEAK PLL1_IRQHandler(void); /* PLL1 (USB PLL) */
void WEAK WDT_IRQHandler(void); /* Watchdog Timer */
void WEAK TIMER0_IRQHandler(void); /* Timer0 */
void WEAK TIMER1_IRQHandler(void); /* Timer1 */
void WEAK TIMER2_IRQHandler(void); /* Timer2 */
void WEAK TIMER3_IRQHandler(void); /* Timer3 */
void WEAK UART0_IRQHandler(void); /* UART0 */
void WEAK UART1_IRQHandler(void); /* UART1 */
void WEAK UART2_IRQHandler(void); /* UART2 */
void WEAK UART3_IRQHandler(void); /* UART3 */
void WEAK PWM1_IRQHandler(void); /* PWM1 */
void WEAK I2C0_IRQHandler(void); /* I2C0 */
void WEAK I2C1_IRQHandler(void); /* I2C1 */
void WEAK I2C2_IRQHandler(void); /* I2C2 */
void WEAK SPI_IRQHandler(void); /* SPI */
void WEAK SSP0_IRQHandler(void); /* SSP0 */
void WEAK SSP1_IRQHandler(void); /* SSP1 */
void WEAK PLL0_IRQHandler(void); /* PLL0 (Main PLL) */
void WEAK RTC_IRQHandler(void); /* Real Time Clock */
void WEAK EINT0_IRQHandler(void); /* External Interrupt 0 */
void WEAK EINT1_IRQHandler(void); /* External Interrupt 1 */
void WEAK EINT2_IRQHandler(void); /* External Interrupt 2 */
void WEAK EINT3_IRQHandler(void); /* External Interrupt 3 */
void WEAK ADC_IRQHandler(void); /* A/D Converter */
void WEAK BOD_IRQHandler(void); /* Brown Out Detect */
void WEAK USB_IRQHandler(void); /* USB */
void WEAK CAN_IRQHandler(void); /* CAN */
void WEAK DMA_IRQHandler(void); /* GP DMA */
void WEAK I2S_IRQHandler(void); /* I2S */
void WEAK ENET_IRQHandler(void); /* Ethernet */
void WEAK RIT_IRQHandler(void); /* Repetitive Interrupt Timer */
void WEAK MCPWM_IRQHandler(void); /* Motor Control PWM */
void WEAK QEI_IRQHandler(void); /* Quadrature Encoder Interface */
void WEAK PLL1_IRQHandler(void); /* PLL1 (USB PLL) */
/* Exported constants --------------------------------------------------------*/
extern unsigned long __etext;
extern unsigned long __sidata; /* start address for the initialization values of the .data section. defined in linker script */
extern unsigned long __data_start__; /* start address for the .data section. defined in linker script */
extern unsigned long __data_end__; /* end address for the .data section. defined in linker script */
extern unsigned long __sidata; /* start address for the initialization values of the .data section. defined in linker script */
extern unsigned long __data_start__; /* start address for the .data section. defined in linker script */
extern unsigned long __data_end__; /* end address for the .data section. defined in linker script */
extern unsigned long __bss_start__; /* start address for the .bss section. defined in linker script */
extern unsigned long __bss_end__; /* end address for the .bss section. defined in linker script */
extern unsigned long __bss_start__; /* start address for the .bss section. defined in linker script */
extern unsigned long __bss_end__; /* end address for the .bss section. defined in linker script */
extern void _estack; /* init value for the stack pointer. defined in linker script */
extern void _estack; /* init value for the stack pointer. defined in linker script */
/* function prototypes ------------------------------------------------------*/
@ -113,7 +126,7 @@ __attribute__ ((section(".isr_vector")))
void (* const g_pfnVectors[])(void) =
{
/* &_estack, // The initial stack pointer */
(void (*)(void))((unsigned long)pulStack + sizeof(pulStack)), // The initial stack pointer
(void (*)(void))((unsigned long)pulStack + sizeof(pulStack)), // The initial stack pointer
Reset_Handler, /* Reset Handler */
NMI_Handler, /* NMI Handler */
HardFault_Handler, /* Hard Fault Handler */
@ -130,7 +143,7 @@ void (* const g_pfnVectors[])(void) =
PendSV_Handler, /* PendSV Handler */
SysTick_Handler, /* SysTick Handler */
// External Interrupts
// External Interrupts
WDT_IRQHandler, /* Watchdog Timer */
TIMER0_IRQHandler, /* Timer0 */
TIMER1_IRQHandler, /* Timer1 */
@ -169,8 +182,8 @@ void (* const g_pfnVectors[])(void) =
/*******************************************************************************
* Function Name : Reset_Handler
* Description : This is the code that gets called when the processor first starts execution
* following a reset event. Only the absolutely necessary set is performed,
* after which the application supplied main() routine is called.
* following a reset event. Only the absolutely necessary set is performed,
* after which the application supplied main() routine is called.
* Input :
* Output :
* Return :
@ -184,9 +197,9 @@ void Reset_Handler(void)
*/
#if 0
for (pulDest = ((unsigned long *)AHBRAM0_BASE); \
pulDest < ((unsigned long *)(AHBRAM0_BASE + AHBRAM0_SIZE)); \
pulDest++){
*(pulDest++) = 0;
pulDest < ((unsigned long *)(AHBRAM0_BASE + AHBRAM0_SIZE)); \
pulDest++){
*(pulDest++) = 0;
}
#endif
@ -195,9 +208,9 @@ void Reset_Handler(void)
*/
#if 0
for (pulDest = ((unsigned long *)AHBRAM1_BASE); \
pulDest < ((unsigned long *)(AHBRAM1_BASE + AHBRAM1_SIZE)); \
pulDest++){
*(pulDest++) = 0;
pulDest < ((unsigned long *)(AHBRAM1_BASE + AHBRAM1_SIZE)); \
pulDest++){
*(pulDest++) = 0;
}
#endif
@ -291,7 +304,7 @@ void Reset_Handler(void)
*
****************************************************************************/
void default_handler(void) {
/* Go into an infinite loop. */
while (1) {
}
/* Go into an infinite loop. */
while (1) {
}
}

@ -1,3 +1,23 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup lpc2387
* @{
*/
/**
* @file
* @brief lpc2387 in-application programming driver (for flashrom)
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
*/
#include <stdint.h>
#include "flashrom.h"
#include "iap.h"

@ -1,11 +1,17 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup arm_common
* @ingroup cpu
* @file
* @internal
* @brief ARM kernel timer CPU dependent functions implementation
*
* @author Freie Universität Berlin, Computer Systems & Telematics
* @author INRIA
* @author Thomas Hillebrandt <hillebra@inf.fu-berlin.de>
* @author Heiko Will <hwill@inf.fu-berlin.de>
* @author Oliver Hahm <oliver.hahm@inria.fr>

@ -1,6 +1,27 @@
/*
* Copyright (C) 2014 INRIA
*
* The source code is licensed under the LGPLv2 license,
* See the file LICENSE for more details.
*/
/**
* @ingroup cpu
* @{
*/
/**
* @file
* @brief lpc iap driver
* @note based on iap driver for LPC2148 Controller made by Andreas Weschenfelder, 2008
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
*/
#include <stddef.h>
/* iap driver
*
* based on iap driver for LPC2148 Controller made by Andreas Weschenfelder, 2008
*
*/

@ -1,3 +1,24 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser General
* Public License. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup cpu
* @{
*
* @file atomic.c
* @brief atomic set and return function
*
* @author Kaspar Schleiser <kaspar@schleiser.de>
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
* @}
*/
#include "atomic.h"
#include "cpu.h"

@ -1,3 +1,24 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser General
* Public License. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup cpu
* @{
*
* @file irq.c
* @brief ISR related functions
*
* @author Kaspar Schleiser <kaspar@schleiser.de>
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
* @}
*/
#include "irq.h"
#include "cpu.h"

@ -1,3 +1,25 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser General
* Public License. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup cpu
* @{
*
* @file lpm_cpu.c
* @brief low-power mode implementation for MSP430 MCUs
*
* @author Kévin Roussel <Kevin.Roussel@inria.fr>
* @author Ludwig Ortmann <ludwig.ortmann@fu-berlin.de>
* @author Thomas Eichinger <thomas.eichinger@fu-berlin.de>
*
* @}
*/
#include <stdio.h>
#if (__GNUC__ >= 4) && (__GNUC_MINOR__ > 5)
#include <intrinsics.h> // MSP430-gcc compiler instrinsics

@ -26,11 +26,20 @@
* 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.
* Modified by Kaspar Schleiser
*/
/**
* @ingroup cpu
* @{
*
* @(#)$Id$
* @file msp430-main.c
* @brief MSP430 CPU initialization
*
* Modified by Kaspar Schleiser
* @author Kaspar Schleiser <kaspar@schleiser.de>
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
* @}
*/
#include "cpu.h"
@ -95,7 +104,7 @@ init_ports(void)
/*---------------------------------------------------------------------------*/
/* msp430-ld may align _end incorrectly. Workaround in cpu_init. */
extern int _end; /* Not in sys/unistd.h */
extern int _end; /* Not in sys/unistd.h */
static char *cur_break = (char *) &_end;
void msp430_cpu_init(void)
@ -151,7 +160,7 @@ splhigh_(void)
int sr;
asmv("mov r2, %0" : "=r"(sr));
asmv("bic %0, r2" : : "i"(GIE));
return sr & GIE; /* Ignore other sr bits. */
return sr & GIE; /* Ignore other sr bits. */
}
/*---------------------------------------------------------------------------*/
/*

@ -1,3 +1,25 @@
/*
* Copyright (C) 2014 Freie Universität Berlin
*
* This file is subject to the terms and conditions of the GNU Lesser General
* Public License. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup cpu
* @{
*
* @file startup.c
* @brief Calls startup functions on MSP430-based platforms
*
* @author Kaspar Schleiser <kaspar@schleiser.de>
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
* @}
*/
#include "irq.h"
#include <stdio.h>
#include "kernel_internal.h"

@ -1,3 +1,24 @@
/*
* Copyright (C) 2014 INRIA
*
* This file is subject to the terms and conditions of the GNU Lesser General
* Public License. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup cpu
* @{
*
* @file flashrom.c
* @brief MSP430x16xx flashrom functions
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
*
* @}
*/
#include "irq.h"
#include <stddef.h>
#include <stdint.h>
#include "cpu.h"

@ -1,3 +1,25 @@
/*
* Copyright (C) 2014 INRIA
*
* This file is subject to the terms and conditions of the GNU Lesser General
* Public License. See the file LICENSE in the top level directory for more
* details.
*/
/**
* @ingroup cpu
* @{
*
* @file flashrom.c
* @brief MSP430x16xx flashrom functions
*
* @author Oliver Hahm <oliver.hahm@inria.fr>
* @author Milan Babel <babel@inf.fu-berlin.de>
* @author Kévin Roussel <Kevin.Roussel@inria.fr>
*
* @}
*/
#include "cpu.h"
#include "hwtimer.h"
#include "hwtimer_arch.h"

Loading…
Cancel
Save