Merge pull request #696 from sieben/doc

Correct several doxygen tags (\file,...)
This commit is contained in:
Nicolas Tsiftes 2014-07-28 11:42:41 +02:00
commit 582bfcb8c6
35 changed files with 310 additions and 312 deletions

View file

@ -185,7 +185,7 @@ typedef uip_eth_addr uip_lladdr_t;
uip_ipaddr(&addr, 192,168,1,2);
uip_sethostaddr(&addr);
\endcode
* \param addr A pointer to an IP address of type uip_ipaddr_t;
*
@ -851,7 +851,7 @@ CCIF void uip_send(const void *data, int len);
\code
uip_ipaddr_t addr;
struct uip_udp_conn *c;
uip_ipaddr(&addr, 192,168,2,1);
c = uip_udp_new(&addr, UIP_HTONS(12345));
if(c != NULL) {
@ -912,7 +912,7 @@ struct uip_udp_conn *uip_udp_new(const uip_ipaddr_t *ripaddr, uint16_t rport);
* These functions can be used for converting between different data
* formats used by uIP.
*/
/**
* Convert an IP address to four bytes separated by commas.
*
@ -938,7 +938,7 @@ struct uip_udp_conn *uip_udp_new(const uip_ipaddr_t *ripaddr, uint16_t rport);
\code
uip_ipaddr_t ipaddr;
struct uip_conn *c;
uip_ipaddr(&ipaddr, 192,168,1,2);
c = uip_connect(&ipaddr, UIP_HTONS(80));
\endcode
@ -1336,11 +1336,11 @@ extern uint16_t uip_urglen, uip_surglen;
*/
struct uip_conn {
uip_ipaddr_t ripaddr; /**< The IP address of the remote host. */
uint16_t lport; /**< The local TCP port, in network byte order. */
uint16_t rport; /**< The local remote TCP port, in network byte
order. */
uint8_t rcv_nxt[4]; /**< The sequence number that we expect to
receive next. */
uint8_t snd_nxt[4]; /**< The sequence number that was last sent by
@ -1443,7 +1443,7 @@ struct uip_stats {
layer. */
uip_stats_t sent; /**< Number of sent packets at the IP
layer. */
uip_stats_t forwarded;/**< Number of forwarded packets at the IP
uip_stats_t forwarded;/**< Number of forwarded packets at the IP
layer. */
uip_stats_t drop; /**< Number of dropped packets at the IP
layer. */
@ -1572,14 +1572,14 @@ uip_ext_hdr_options_process(); */
* The actual uIP function which does all the work.
*/
void uip_process(uint8_t flag);
/* The following flags are passed as an argument to the uip_process()
function. They are used to distinguish between the two cases where
uip_process() is called. It can be called either because we have
incoming data that should be processed, or because the periodic
timer has fired. These values are never used directly, but only in
the macros defined in this file. */
#define UIP_DATA 1 /* Tells uIP that there is incoming
data in the uip_buf buffer. The
length of the data is stored in the
@ -1606,7 +1606,7 @@ void uip_process(uint8_t flag);
#define UIP_TIME_WAIT 7
#define UIP_LAST_ACK 8
#define UIP_TS_MASK 15
#define UIP_STOPPED 16
/* The TCP and IP headers. */
@ -1631,7 +1631,7 @@ struct uip_tcpip_hdr {
uint16_t ipchksum;
uip_ipaddr_t srcipaddr, destipaddr;
#endif /* UIP_CONF_IPV6 */
/* TCP header. */
uint16_t srcport,
destport;
@ -1667,7 +1667,7 @@ struct uip_icmpip_hdr {
uint16_t ipchksum;
uip_ipaddr_t srcipaddr, destipaddr;
#endif /* UIP_CONF_IPV6 */
/* ICMP header. */
uint8_t type, icode;
uint16_t icmpchksum;
@ -1700,7 +1700,7 @@ struct uip_udpip_hdr {
uint16_t ipchksum;
uip_ipaddr_t srcipaddr, destipaddr;
#endif /* UIP_CONF_IPV6 */
/* UDP header. */
uint16_t srcport,
destport;
@ -2035,7 +2035,7 @@ CCIF extern uip_lladdr_t uip_lladdr;
(((a)->u8[12]) == 0xFF))
/**
* \briefput in b the solicited node address corresponding to address a
* \brief put in b the solicited node address corresponding to address a
* both a and b are of type uip_ipaddr_t*
* */
#define uip_create_solicited_node(a, b) \
@ -2086,7 +2086,7 @@ CCIF extern uip_lladdr_t uip_lladdr;
(((a)->u8[13]) == (m)->addr[3]) && \
(((a)->u8[14]) == (m)->addr[4]) && \
(((a)->u8[15]) == (m)->addr[5]))
#endif /*UIP_CONF_LL_802154*/
/**

View file

@ -51,7 +51,7 @@
*/
/**
* \file lc.h
* \file core/sys/lc.h
* Local continuations
* \author
* Adam Dunkels <adam@sics.se>

View file

@ -1,13 +1,13 @@
/*
* Contiki PIC32 Port project
*
*
* Copyright (c) 2012,
* Scuola Superiore Sant'Anna (http://www.sssup.it) and
* Consorzio Nazionale Interuniversitario per le Telecomunicazioni
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -41,7 +41,7 @@
*/
/**
* \file clock.c
* \file cpu/pic32/clock.c
* \brief Clock routines.
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \author Daniele Alessandrelli <d.alessandrelli@sssup.it>
@ -129,7 +129,7 @@ clock_delay_usec(uint16_t dt)
uint32_t stop;
asm volatile("mfc0 %0, $9" : "=r"(now));
/* The Count register is incremented every two system clock (SYSCLK) cycles. */
stop = now + dt * ((pic32_clock_get_system_clock() / 1000000) / 2);

View file

@ -1,13 +1,13 @@
/*
* Contiki PIC32 Port project
*
*
* Copyright (c) 2012,
* Scuola Superiore Sant'Anna (http://www.sssup.it) and
* Consorzio Nazionale Interuniversitario per le Telecomunicazioni
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -41,7 +41,7 @@
*/
/**
* \file debug-uart.h
* \file cpu/pic32/debug-uart.h
* \brief Debug output redirection to uart.
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-03-21

View file

@ -1,13 +1,13 @@
/*
* Contiki PIC32 Port project
*
*
* Copyright (c) 2012,
* Scuola Superiore Sant'Anna (http://www.sssup.it) and
* Consorzio Nazionale Interuniversitario per le Telecomunicazioni
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -41,7 +41,7 @@
*/
/**
* \file debug-uart.h
* \file cpu/pic32/debug-uart.h
* \brief Debug output redirection to uart.
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-03-21

View file

@ -1,13 +1,13 @@
/*
* Contiki PIC32 Port project
*
*
* Copyright (c) 2012,
* Scuola Superiore Sant'Anna (http://www.sssup.it) and
* Consorzio Nazionale Interuniversitario per le Telecomunicazioni
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -34,8 +34,8 @@
*
*/
/**
* @file uart1.h
/**
* @file cpu/pic32/dev/uart1.h
* @brief UART1 routines
* @author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
*

View file

@ -1,13 +1,13 @@
/*
* Contiki PIC32 Port project
*
*
* Copyright (c) 2012,
* Scuola Superiore Sant'Anna (http://www.sssup.it) and
* Consorzio Nazionale Interuniversitario per le Telecomunicazioni
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -40,8 +40,8 @@
* @{
*/
/**
* \file mtarch.h
/**
* \file cpu/pic32/mtarch.h
* \brief Implementation of multithreading in PIC32. To be done.
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-03-23

View file

@ -1,13 +1,13 @@
/*
* Contiki PIC32 Port project
*
*
* Copyright (c) 2012,
* Scuola Superiore Sant'Anna (http://www.sssup.it) and
* Consorzio Nazionale Interuniversitario per le Telecomunicazioni
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -40,8 +40,8 @@
* @{
*/
/**
* \file mtarch.h
/**
* \file cpu/pic32/mtarch.h
* \brief PIC32MX initialization routines
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \author Daniele Alessandrelli <d.alessandrelli@sssup.it>
@ -50,7 +50,7 @@
/*
* PIC32MX795F512L - Specific Functions
*
*
* All the functions in this part of the file are specific for the
* pic32mx795f512l that is characterized by registers' name that differ from
* the 3xx and 4xx families of the pic32mx.
@ -59,7 +59,7 @@
#include <pic32_irq.h>
#include <p32xxxx.h>
#include <peripheral/system.h>
#include <peripheral/system.h>
#include <stdint.h>
#include <dev/leds.h>
@ -106,10 +106,10 @@ pic32_init(void)
SYSKEY = 0;
SYSKEY = 0xaa996655;
SYSKEY = 0x556699aa;
/* Enable Sleep Mode */
OSCCONCLR = 1 << _OSCCON_SLPEN_POSITION;
SYSKEY = 0;
ASM_EN_INT;
@ -125,7 +125,7 @@ _general_exception_handler(void)
asm volatile ("mfc0 %0,$13":"=r" (cp0_exception_cause));
cp0_exception_code = (cp0_exception_cause >> 2) & 0x0000001F;
leds_on(LEDS_ALL);
while(1){

View file

@ -1,13 +1,13 @@
/*
* Contiki PIC32 Port project
*
*
* Copyright (c) 2012,
* Scuola Superiore Sant'Anna (http://www.sssup.it) and
* Consorzio Nazionale Interuniversitario per le Telecomunicazioni
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -41,7 +41,7 @@
*/
/**
* \file rtimer-arch.c
* \file cpu/pic32/rtimer-arch.c
* \brief PIC32MX RTIMER routines
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-04-11
@ -49,7 +49,7 @@
/*
* PIC32MX795F512L - Specific Functions
*
*
* All the functions in this part of the file are specific for the
* pic32mx795f512l that is characterized by registers' name that differ from
* the 3xx and 4xx families of the pic32mx.
@ -85,7 +85,7 @@ rtimer_arch_init(void)
IPC3CLR = _IPC3_T3IP_MASK | _IPC3_T3IS_MASK;
IPC3SET = (7 << _IPC3_T3IP_POSITION) | (3 << _IPC3_T3IS_POSITION);
T2CON = 0;
T3CON = 0;
T3CON = 0;
T2CONSET = _T2CON_T32_MASK | (TIMER_B_PRESCALE_256 << _T2CON_TCKPS_POSITION);
PR2 = 0xFFFFFFFF;
TMR2 = 0;

View file

@ -1,13 +1,13 @@
/*
* Contiki PIC32 Port project
*
*
* Copyright (c) 2012,
* Scuola Superiore Sant'Anna (http://www.sssup.it) and
* Consorzio Nazionale Interuniversitario per le Telecomunicazioni
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -40,8 +40,8 @@
* @{
*/
/**
* \file rtimer-arch.h
/**
* \file cpu/pic32/rtimer-arch.h
* \brief PIC32MX RTIMER routines
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-04-11

View file

@ -1,13 +1,13 @@
/*
* Contiki PIC32 Port project
*
*
* Copyright (c) 2012,
* Scuola Superiore Sant'Anna (http://www.sssup.it) and
* Consorzio Nazionale Interuniversitario per le Telecomunicazioni
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -40,8 +40,8 @@
* @{
*/
/**
* \file watchdog.c
/**
* \file cpu/pic32/watchdog.c
* \brief PIC32MX Watchdog routines
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-03-23
@ -83,7 +83,7 @@ void
watchdog_reboot(void)
{
volatile int *p = (int *)&RSWRST;
/* Unlock sequence */
ASM_DIS_INT;
if(!(DMACONbits.SUSPEND)){
@ -92,11 +92,11 @@ watchdog_reboot(void)
; // wait to be actually suspended
}
}
SYSKEY = 0;
SYSKEY = 0xaa996655;
SYSKEY = 0x556699aa;
RSWRSTSET=_RSWRST_SWRST_MASK;
*p;

View file

@ -1,9 +1,9 @@
/**
* @file error.h
* @file cpu/stm32w108/hal/error.h
* @brief Return codes for API functions and module definitions.
*
* See @ref status_codes for documentation.
*
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
@ -28,7 +28,7 @@
*
* @param symbol The name of the constant being defined. All St returns
* begin with ST_. For example, ::ST_CONNECTION_OPEN.
*
*
* @param value The value of the return code. For example, 0x61.
*/
#define DEFINE_ERROR(symbol, value) \
@ -39,8 +39,8 @@ enum {
#ifndef DOXYGEN_SHOULD_SKIP_THIS
#include "error-def.h"
#endif //DOXYGEN_SHOULD_SKIP_THIS
/** Gets defined as a count of all the possible return codes in the
* StZNet stack API.
/** Gets defined as a count of all the possible return codes in the
* StZNet stack API.
*/
ST_ERROR_CODE_COUNT
@ -52,5 +52,5 @@ enum {
/**@} // End of addtogroup
*/

View file

@ -1,4 +1,4 @@
/** @file adc.c
/** @file cpu/stm32w108/hal/micro/cortexm3/adc.c
* @brief ADC HAL functions
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
@ -22,12 +22,12 @@ static uint16_t adcConfig[NUM_ADC_USERS];
static boolean adcCalibrated;
static int16_t Nvss;
static int16_t Nvdd;
/* Modified the original ADC driver for enabling the ADC extended range mode required for
/* Modified the original ADC driver for enabling the ADC extended range mode required for
supporting the STLM20 temperature sensor.
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
(see STM32W108 errata). As consequence, it is not reccomended to use this ADC driver for getting
the temperature values
the temperature values
*/
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
static int16_t Nvref;
@ -87,7 +87,7 @@ void halAdcIsr(void)
if (BIT(i) & adcPendingRequests) {
adcPendingConversion = i; // set pending conversion
adcPendingRequests ^= BIT(i); //clear request: conversion is starting
ADC_CFG = adcConfig[i];
ADC_CFG = adcConfig[i];
break; //conversion started, so we're done here (only one at a time)
}
}
@ -106,7 +106,7 @@ void halAdcIsr(void)
ADCUser startNextConversion()
{
uint8_t i;
ATOMIC (
// start the next requested conversion if any
if (adcPendingRequests && !(ADC_CFG & ADC_ENABLE)) {
@ -160,7 +160,7 @@ StStatus halStartAdcConversion(ADCUser id,
ADCChannelType channel,
ADCRateType rate)
{
if(reference != ADC_REF_INT)
return ST_ERR_FATAL;
@ -191,7 +191,7 @@ StStatus halRequestAdcData(ADCUser id, uint16_t *value)
//Both the ADC interrupt and the global interrupt need to be enabled,
//otherwise the ADC ISR cannot be serviced.
boolean intsAreOff = ( INTERRUPTS_ARE_OFF()
|| !(INT_CFGSET & INT_ADC)
|| !(INT_CFGSET & INT_ADC)
|| !(INT_ADCCFG & INT_ADCULDFULL) );
StStatus stat;
@ -199,7 +199,7 @@ StStatus halRequestAdcData(ADCUser id, uint16_t *value)
// If interupts are disabled but the flag is set,
// manually run the isr...
//FIXME -= is this valid???
if( intsAreOff
if( intsAreOff
&& ( (INT_CFGSET & INT_ADC) && (INT_ADCCFG & INT_ADCULDFULL) )) {
halAdcIsr();
}
@ -235,21 +235,21 @@ StStatus halReadAdcBlocking(ADCUser id, uint16_t *value)
StStatus halAdcCalibrate(ADCUser id)
{
StStatus stat;
/* Modified the original ADC driver for enabling the ADC extended range mode required for
/* Modified the original ADC driver for enabling the ADC extended range mode required for
supporting the STLM20 temperature sensor.
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
(see STM32W108 errata). As consequence, it is not reccomended to use this ADC driver for getting
the temperature values
the temperature values
*/
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
if(halAdcGetRange()){
halStartAdcConversion(id,
ADC_REF_INT,
ADC_SOURCE_VREF_VREF2,
ADC_CONVERSION_TIME_US_4096);
stat = halReadAdcBlocking(id, (uint16_t *)(&Nvref));
if (stat == ST_ADC_CONVERSION_DONE) {
halStartAdcConversion(id,
@ -264,9 +264,9 @@ StStatus halAdcCalibrate(ADCUser id)
adcCalibrated = FALSE;
stat = ST_ERR_FATAL;
}
return stat;
}
return stat;
}
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
halStartAdcConversion(id,
ADC_REF_INT,
@ -294,7 +294,7 @@ StStatus halAdcCalibrate(ADCUser id)
// to convert to 100uV units.
// FIXME: support external Vref
// use #define of Vref, ignore VDD_PADSA
// FIXME: support high voltage range
// FIXME: support high voltage range
// use Vref-Vref/2 to calibrate
// FIXME: check for mfg token specifying measured VDD_PADSA
int16_t halConvertValueToVolts(uint16_t value)
@ -302,29 +302,29 @@ int16_t halConvertValueToVolts(uint16_t value)
int32_t N;
int16_t V;
int32_t nvalue;
if (!adcCalibrated) {
halAdcCalibrate(ADC_USER_LQI);
}
if (adcCalibrated) {
/* Modified the original ADC driver for enabling the ADC extended range mode required for
/* Modified the original ADC driver for enabling the ADC extended range mode required for
supporting the STLM20 temperature sensor.
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
(see STM32W108 errata). As consequence, it is not reccomended to use this ADC driver for getting
the temperature values
the temperature values
*/
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
if(halAdcGetRange()){ // High range.
N = (((int32_t)value + Nvref - 2*Nvref2) << 16)/(2*(Nvref-Nvref2));
// Calculate voltage with: V = (N * VREF) / (2^16) where VDD = 1.2 volts
// Mutiplying by 1.2*10000 makes the result of this equation 100 uVolts
V = (int16_t)((N*12000L) >> 16);
if (V > 21000) { // VDD_PADS ?
V = 21000;
}
}
}
else {
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
@ -340,9 +340,9 @@ int16_t halConvertValueToVolts(uint16_t value)
if (V > 12000) {
V = 12000;
}
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
}
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
} else {
V = -32768;
}
@ -355,27 +355,27 @@ uint8_t halGetADCChannelFromGPIO(uint32_t io)
{
case PORTB_PIN(5):
return ADC_MUX_ADC0;
case PORTB_PIN(6):
return ADC_MUX_ADC1;
case PORTB_PIN(7):
return ADC_MUX_ADC2;
case PORTC_PIN(1):
return ADC_MUX_ADC3;
case PORTA_PIN(4):
return ADC_MUX_ADC4;
case PORTA_PIN(5):
return ADC_MUX_ADC5;
case PORTB_PIN(0):
return ADC_MUX_VREF;
default :
return 0x0F; // Invalid analogue source
}
}

View file

@ -1,5 +1,5 @@
/** @file board.c
* @brief Board file x STM32W108 Kits boards
/** @file cpu/stm32w108/hal/micro/cortexm3/board.c
* @brief Board file x STM32W108 Kits boards
*
* This file implements a software layer to support all the ST kits boards
* and deal with the difference in leds, buttons and sensors connected to the board.
@ -138,22 +138,22 @@ const MemsResourceType memsSensor = {
const BoardIOType ioMB851A = {
LedsMB851A,
ButtonsMB851A,
ButtonsMB851A,
};
const BoardIOType ioMB954A = {
LedsMB954A,
ButtonsMB954A,
ButtonsMB954A,
};
const BoardIOType ioMB950A = {
LedsMB954A,
ButtonsMB950A,
ButtonsMB950A,
};
const BoardIOType ioMB951A = {
LedsMB954A,
ButtonsMB951A,
ButtonsMB951A,
};
const BoardResourcesType MB851A = {
@ -264,7 +264,7 @@ void halBoardInit(void)
i--;
}
for (i = 0; i < (sizeof(boardList)/4) ; i++)
for (i = 0; i < (sizeof(boardList)/4) ; i++)
if (strcmp(boardName, (boardList[i])->name) == 0) {
boardDescription = (BoardResourcesType *) boardList[i];
break;

View file

@ -1,4 +1,4 @@
/** @file mems.c
/** @file cpu/stm32w108/hal/micro/cortexm3/mems.c
* @brief MB851 MEMS drivers
*
*
@ -30,9 +30,9 @@ static uint8_t i2c_MEMS_Read (t_mems_data *mems_data);
/* Functions -----------------------------------------------------------------*/
uint8_t mems_Init(void)
{
{
uint8_t ret = 0;
// GPIO assignments
// PA1: SC2SDA (Serial Data)
// PA2: SC2SCL (Serial Clock)
@ -43,27 +43,27 @@ uint8_t mems_Init(void)
SC2_MODE = SC2_MODE_I2C;
GPIO_PACFGL &= 0xFFFFF00F;
GPIO_PACFGL |= 0x00000DD0;
SC2_RATELIN = 14; // generates standard 100kbps or 400kbps
SC2_RATEEXP = 1; // 3 yields 100kbps; 1 yields 400kbps
SC2_TWICTRL1 = 0; // start from a clean state
SC2_TWICTRL2 = 0; // start from a clean state
SC2_TWICTRL2 = 0; // start from a clean state
ret = i2c_MEMS_Init();
//Add later if really needed
#ifdef ST_DBG
//Add later if really needed
#ifdef ST_DBG
if (!ret)
i2c_DeInit(MEMS_I2C);
#endif
return ret;
}/* end mems_Init */
uint8_t mems_GetValue(t_mems_data *mems_data)
{
uint8_t i;
i = i2c_MEMS_Read(mems_data);
uint8_t i;
i = i2c_MEMS_Read(mems_data);
return i;
}/* end mems_GetValue() */
@ -72,7 +72,7 @@ uint8_t mems_GetValue(t_mems_data *mems_data)
/*******************************************************************************
* Function Name : i2c_Send_Frame
* Description : It sends I2C frame
* Description : It sends I2C frame
* Input : DeviceAddress is the destination device address
* pBUffer is the buffer data
* NoOfBytes is the number of bytes
@ -85,24 +85,24 @@ static uint8_t i2c_Send_Frame (uint8_t DeviceAddress, uint8_t *pBuffer, uint8_t
SC2_TWICTRL1 |= SC_TWISTART; // send start
WAIT_CMD_FIN();
SEND_BYTE(DeviceAddress); // send the address low byte
WAIT_TX_FIN();
// loop sending the data
for (i=0; i<NoOfBytes; i++) {
halInternalResetWatchDog();
data = *(pBuffer+i);
SEND_BYTE(data);
WAIT_TX_FIN();
}
SC2_TWICTRL1 |= SC_TWISTOP;
WAIT_CMD_FIN();
return SUCCESS;
}/* end i2c_Send_Frame() */
@ -118,25 +118,25 @@ static uint8_t i2c_Send_Frame (uint8_t DeviceAddress, uint8_t *pBuffer, uint8_t
static uint8_t i2c_Receive_Frame (uint8_t slave_addr, uint8_t reg_addr, uint8_t *pBuffer, uint8_t NoOfBytes)
{
uint8_t i, addr = reg_addr;
if (NoOfBytes > 1)
addr += REPETIR;
SC2_TWICTRL1 |= SC_TWISTART; // send start
WAIT_CMD_FIN();
SEND_BYTE(slave_addr | 0x00); // send the address low byte
WAIT_TX_FIN();
SEND_BYTE(addr);
WAIT_TX_FIN();
SC2_TWICTRL1 |= SC_TWISTART; // send start
WAIT_CMD_FIN();
SEND_BYTE(slave_addr | 0x01); // send the address low byte
WAIT_TX_FIN();
// loop receiving the data
for (i=0;i<NoOfBytes;i++){
halInternalResetWatchDog();
@ -152,7 +152,7 @@ static uint8_t i2c_Receive_Frame (uint8_t slave_addr, uint8_t reg_addr, uint8_t
}
SC2_TWICTRL1 |= SC_TWISTOP; // send STOP
WAIT_CMD_FIN();
WAIT_CMD_FIN();
return SUCCESS;
}/* end i2c_Receive_Frame() */
@ -171,7 +171,7 @@ static uint8_t i2c_Receive_Frame (uint8_t slave_addr, uint8_t reg_addr, uint8_t
uint8_t i2c_write_reg (uint8_t slave_addr, uint8_t reg_addr, uint8_t reg_value)
{
uint8_t i2c_buffer[2];
i2c_buffer[0] = reg_addr;
i2c_buffer[1] = reg_value;
@ -195,7 +195,7 @@ uint8_t i2c_read_reg (uint8_t slave_addr, uint8_t reg_addr, uint8_t *pBuffer, ui
/*******************************************************************************
* Function Name : i2c_MEMS_Init
* Description : It performs basic MEMS register writes for initialization
* Description : It performs basic MEMS register writes for initialization
* purposes
* Input : None
* Output : None
@ -234,7 +234,7 @@ static uint8_t i2c_MEMS_Read (t_mems_data *mems_data)
if (i2c_buffer[0] & (1 << 3))
break;
}
i = i2c_read_reg (kLIS3L02DQ_SLAVE_ADDR, OUTX_L, i2c_buffer, 8);
i = i2c_read_reg (kLIS3L02DQ_SLAVE_ADDR, OUTX_L, i2c_buffer, 8);
mems_data->outx_h = i2c_buffer[0];
mems_data->outx_l = i2c_buffer[1];

View file

@ -1,12 +1,12 @@
/** @file hal/micro/cortexm3/mfg-token.h
* @brief Cortex-M3 Manufacturing token system
/** \file cpu/stm32w108/hal/micro/cortexm3/mfg-token.h
* \brief Cortex-M3 Manufacturing token system
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef MFG_TOKEN_H_
#define MFG_TOKEN_H_
// The manufacturing tokens live in the Info Blocks, while all other tokens
// live in the Simulated EEPROM. This requires the token names to be defined
@ -16,77 +16,77 @@
#define DEFINETOKENS
/**
* @description Macro for translating token defs into address variables
* \brief Macro for translating token defs into address variables
* that point to the correct location in the Info Blocks. (This is the
* extern, the actual definition is found in hal/micro/cortexm3/token.c)
*
* @param name: The name of the token.
* \param name: The name of the token.
*
* @param TOKEN_##name##_ADDRESS: The address in EEPROM at which the token
* \param TOKEN_##name##_ADDRESS: The address in EEPROM at which the token
* will be stored. This parameter is generated with a macro above.
*/
#define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \
extern const uint16_t TOKEN_##name;
#include "hal/micro/cortexm3/token-manufacturing.h"
#include "cpu/stm32w108/hal/micro/cortexm3/token-manufacturing.h"
#undef TOKEN_MFG
/**
* @description Macro for translating token definitions into size variables.
* \brief Macro for translating token definitions into size variables.
* This provides a convenience for abstracting the 'sizeof(type)' anywhere.
*
* @param name: The name of the token.
* \param name: The name of the token.
*
* @param type: The token type. The types are found in token-stack.h.
* \param type: The token type. The types are found in token-stack.h.
*/
#define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \
TOKEN_##name##_SIZE = sizeof(type),
enum {
#include "hal/micro/cortexm3/token-manufacturing.h"
#include "cpu/stm32w108/hal/micro/cortexm3/token-manufacturing.h"
};
#undef TOKEN_MFG
#undef TOKEN_DEF
/**
* @description Macro for typedef'ing the CamelCase token type found in
* \brief Macro for typedef'ing the CamelCase token type found in
* token-stack.h to a capitalized TOKEN style name that ends in _TYPE.
* This macro allows other macros below to use 'token##_TYPE' to declare
* a local copy of that token.
*
* @param name: The name of the token.
* \param name: The name of the token.
*
* @param type: The token type. The types are found in token-stack.h.
* \param type: The token type. The types are found in token-stack.h.
*/
#define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \
typedef type TOKEN_##name##_TYPE;
#include "hal/micro/cortexm3/token-manufacturing.h"
#include "cpu/stm32w108/hal/micro/cortexm3/token-manufacturing.h"
#undef TOKEN_MFG
#undef TOKEN_NEXT_ADDRESS
#undef TOKEN_NEXT_ADDRESS
#define DEFINEADDRESSES
/**
* @description Macro for creating a 'region' element in the enum below. This
* \brief Macro for creating a 'region' element in the enum below. This
* creates an element in the enum that provides a starting point (address) for
* subsequent tokens to align against. ( See hal/micro/cortexm3/token.c for
* the instances of TOKEN_NEXT_ADDRESS() );
*
* @param region: The name to give to the element in the address enum..
* \param region: The name to give to the element in the address enum..
*
* @param address: The address in EEPROM where the region begins.
* \param address: The address in EEPROM where the region begins.
*/
#define TOKEN_NEXT_ADDRESS(region, address) \
TOKEN_##region##_NEXT_ADDRESS = ((address) - 1),
/**
* @description Macro for creating ADDRESS and END elements for each token in
* \brief Macro for creating ADDRESS and END elements for each token in
* the enum below. The ADDRESS element is linked to from the the normal
* TOKEN_##name macro and provides the value passed into the internal token
* system calls. The END element is a placeholder providing the starting
* point for the ADDRESS of the next dynamically positioned token.
*
* @param name: The name of the token.
* \param name: The name of the token.
*
* @param arraysize: The number of elements in an indexed token (arraysize=1
* \param arraysize: The number of elements in an indexed token (arraysize=1
* for scalar tokens).
*/
#define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \
@ -95,7 +95,7 @@
(TOKEN_##name##_SIZE * arraysize) - 1,
/**
* @description The enum that operates on the two macros above. Also provides
* \brief The enum that operates on the two macros above. Also provides
* an indentifier so the address of the top of the token system can be known.
*/
enum {
@ -109,26 +109,26 @@ enum {
#ifndef DOXYGEN_SHOULD_SKIP_THIS
/**
* @description Copies the token value from non-volatile storage into a RAM
* \brief Copies the token value from non-volatile storage into a RAM
* location. This is the internal function that the exposed API
* (halCommonGetMfgToken) expands out to. The
* API simplifies the access into this function by hiding the size parameter.
*
* @param data: A pointer to where the data being read should be placed.
* \param data: A pointer to where the data being read should be placed.
*
* @param token: The name of the token to get data from. On this platform
* \param token: The name of the token to get data from. On this platform
* that name is defined as an address.
*
* @param index: The index to access. If the token being accessed is not an
* \param index: The index to access. If the token being accessed is not an
* indexed token, this parameter is set by the API to be 0x7F.
*
* @param len: The length of the token being worked on. This value is
* \param len: The length of the token being worked on. This value is
* automatically set by the API to be the size of the token.
*/
void halInternalGetMfgTokenData(void *data, uint16_t token, uint8_t index, uint8_t len);
/**
* @description Sets the value of a token in non-volatile storage. This is
* \brief Sets the value of a token in non-volatile storage. This is
* the internal function that the exposed API (halCommonSetMfgToken)
* expands out to. The API simplifies the access into this function
* by hiding the size parameter.
@ -139,12 +139,12 @@ void halInternalGetMfgTokenData(void *data, uint16_t token, uint8_t index, uint8
* <b>REMEMBER:</b> The flash hardware requires writing to 16bit aligned
* addresses with a length that is multiples of 16bits.
*
* @param token: The name of the token to get data from. On this platform
* \param token: The name of the token to get data from. On this platform
* that name is defined as an address.
*
* @param data: A pointer to the data being written.
* \param data: A pointer to the data being written.
*
* @param len: The length of the token being worked on. This value is
* \param len: The length of the token being worked on. This value is
* automatically set by the API to be the size of the token.
*/
void halInternalSetMfgTokenData(uint16_t token, void *data, uint8_t len);

View file

@ -56,8 +56,8 @@
/**
* @brief Resets the watchdog timer. This function is pointed
* to by the macro ::halResetWatchdog().
* @warning Be very careful when using this as you can easily get into an
* to by the macro ::halResetWatchdog().
* @warning Be very careful when using this as you can easily get into an
* infinite loop.
*/
void halInternalResetWatchDog( void );
@ -162,13 +162,13 @@ void halInternalSearchForBiasTrim(void);
* hardware peripherals. This function works by simply adding another
* layer on top of halCommonDelayMicroseconds().
*
* @param ms The specified time, in milliseconds.
* @param ms The specified time, in milliseconds.
*/
void halCommonDelayMilliseconds(uint16_t ms);
/** @brief Puts the microcontroller to sleep in a specified mode, allows
* the GPIO wake sources to be determined at runtime. This function
* the GPIO wake sources to be determined at runtime. This function
* requires the GPIO wake sources to be defined at compile time in the board
* file.
*
@ -180,7 +180,7 @@ void halCommonDelayMilliseconds(uint16_t ms);
* the chip from deep sleep. A high bit in the mask will enable waking
* the chip if the corresponding GPIO changes state. bit0 is PA0, bit1 is
* PA1, bit8 is PB0, bit16 is PCO, bit23 is PC7, bits[31:24] are ignored.
*
*
* @sa ::SleepModes
*/
void halSleepWithOptions(SleepModes sleepMode, uint32_t gpioWakeBitMask);
@ -203,18 +203,16 @@ void halSleepWithOptions(SleepModes sleepMode, uint32_t gpioWakeBitMask);
* to 48.5 days. Any sleep duration greater than this limit will wake up
* briefly (e.g. 16 microseconds) to reenable another sleep cycle.
*
* @nostackusage
*
* @param duration The amount of time, expressed in quarter seconds, that the
* micro should be placed into ::SLEEPMODE_WAKETIMER. When the function returns,
* this parameter provides the amount of time remaining out of the original
* sleep time request (normally the return value will be 0).
*
*
* @param gpioWakeBitMask A bit mask of the GPIO that are allowed to wake
* the chip from deep sleep. A high bit in the mask will enable waking
* the chip if the corresponding GPIO changes state. bit0 is PA0, bit1 is
* PA1, bit8 is PB0, bit16 is PCO, bit23 is PC7, bits[31:24] are ignored.
*
*
* @return An StStatus value indicating the success or
* failure of the command.
*/
@ -248,7 +246,7 @@ void halInternalSleep(SleepModes sleepMode);
* - [25] = PWRUP_SLEEPTMRCOMPB
* - [24] = PWRUP_SLEEPTMRCOMPA
* - [23:0] = corresponding GPIO activity
*
*
* WakeInfoValid means that ::halSleepWithOptions (::halInternalSleep) has been called
* at least once. Since the power on state clears the wake event info,
* this bit says the sleep code has been called since power on.
@ -260,7 +258,7 @@ void halInternalSleep(SleepModes sleepMode);
* signal is set). The net affect of skipping sleep is the Low Voltage
* domain never goes through a power/reset cycle.
*
* @return The events that caused the last wake from sleep.
* @return The events that caused the last wake from sleep.
*/
uint32_t halGetWakeInfo(void);

View file

@ -1,4 +1,4 @@
/** @file board.h
/** @file cpu/stm32w108/hal/micro/cortexm3/stm32w108/board.h
* @brief Header file x STM32W108 Kits boards abstraction.
* See @ref board for documentation.
*
@ -18,7 +18,7 @@
* See hal/micro/cortexm3/stm32w108/board.h for source code.
*@{
*/
/**
* @brief Define the number of LEDs in the specific board revision
*/
@ -134,7 +134,7 @@ typedef struct BoardIOStruct {
/** Pointer to LED resources */
const LedResourceType *leds;
/** Pointer to button resources */
const ButtonResourceType *buttons;
const ButtonResourceType *buttons;
} BoardIOType;
/**
@ -227,7 +227,7 @@ extern BoardResourcesType const *boardDescription;
/** @brief Return pointer to board description structure
*
*
*
* @return Pointer to board description structure
*/
BoardResourcesType const *halBoardGetDescription(void);

View file

@ -1,5 +1,5 @@
/**@file temperature-sensor.c
* @brief MB851 temperature sensor APIS
/**@file cpu/stm32w108/hal/micro/cortexm3/temperature-sensor.c
* @brief MB851 temperature sensor APIS
*
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
@ -17,12 +17,12 @@ void temperatureSensor_Init(void)
halGpioConfig(TEMPERATURE_SENSOR_GPIO,GPIOCFG_ANALOG);
/* Init ADC driver */
halInternalInitAdc();
/*
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
(see STM32W108 errata). As consequence, it is not reccomended to use this ADC driver for getting
the temperature values.
the temperature values.
*/
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
halAdcSetRange(TRUE);
@ -35,18 +35,18 @@ uint32_t temperatureSensor_GetValue(void)
static int16_t volts;
/*
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
(see STM32W108 errata). As consequence, it is not reccomended to use this ADC driver for getting
the temperature values.
the temperature values.
*/
halStartAdcConversion(ADC_USER_APP, ADC_REF_INT, ADC_SOURCE(halGetADCChannelFromGPIO(TEMPERATURE_SENSOR_GPIO),ADC_MUX_VREF2), ADC_CONVERSION_TIME_US_4096);
halReadAdcBlocking(ADC_USER_APP, &ADCvalue); // This blocks for a while, about 4ms.
// 100 uVolts
volts = halConvertValueToVolts(ADCvalue);
return ((18641 - (int32_t)volts)*100)/1171;
return ((18641 - (int32_t)volts)*100)/1171;
}/* end temperatureSensor_GetValue() */

View file

@ -1,5 +1,5 @@
/** @file mems.h
* @brief Header for MB851 mems APIS
/** @file cpu/stm32w108/hal/micro/mems.h
* @brief Header for MB851 mems APIS
*
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
@ -11,7 +11,7 @@
#include "hal/micro/mems-regs.h"
/** @brief Mems data type: three acceleration values each related to a specific direction
Watch out: only lower data values (e.g. those terminated by the _l) are
Watch out: only lower data values (e.g. those terminated by the _l) are
currently used by the device */
typedef struct {

View file

@ -1,10 +1,10 @@
/** @file micro-common.h
/** @file cpu/stm32w108/hal/micro/micro-common.h
* @brief Minimal Hal functions common across all microcontroller-specific files.
* See @ref micro for documentation.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/** @addtogroup micro
* Many of the supplied example applications use these microcontroller functions.
* See hal/micro/micro-common.h for source code.
@ -41,10 +41,10 @@ void halPowerUp(void);
*/
void halPowerDown(void);
/** @brief The value that must be passed as the single parameter to
* ::halInternalDisableWatchDog() in order to sucessfully disable the watchdog
/** @brief The value that must be passed as the single parameter to
* ::halInternalDisableWatchDog() in order to sucessfully disable the watchdog
* timer.
*/
*/
#define MICRO_DISABLE_WATCH_DOG_KEY 0xA5
/** @brief Enables the watchdog timer.
@ -53,9 +53,9 @@ void halInternalEnableWatchDog(void);
/** @brief Disables the watchdog timer.
*
* @note To prevent the watchdog from being disabled accidentally,
* @note To prevent the watchdog from being disabled accidentally,
* a magic key must be provided.
*
*
* @param magicKey A value (::MICRO_DISABLE_WATCH_DOG_KEY) that enables the function.
*/
void halInternalDisableWatchDog(uint8_t magicKey);
@ -113,7 +113,7 @@ enum
* be within 10us. If the micro is running off of another type of oscillator
* (e.g. RC) the timing accuracy will potentially be much worse.
*
* @param us The specified time, in microseconds.
* @param us The specified time, in microseconds.
Values should be between 1 and 65535 microseconds.
*/
void halCommonDelayMicroseconds(uint16_t us);
@ -122,7 +122,7 @@ void halCommonDelayMicroseconds(uint16_t us);
*
* This function will check whwther the user flash contains the bootloader
* and if yes it will jump into it according to the user parameters.
*
*
*
* @param mode The bootloader mode, 0 UART mode, 1 RF mode. All other
* values are reserved
@ -144,4 +144,4 @@ StStatus halBootloaderStart(uint8_t mode, uint8_t channel, uint16_t panId);
#endif //MICRO_COMMON_H_
/** @} END micro group */

View file

@ -1,6 +1,6 @@
/** @file hal/micro/system-timer.h
* @brief Header file for system_timer APIs
*
*
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
@ -35,7 +35,7 @@
/**
* @brief Initializes the system tick.
*
* @return Time to update the async registers after RTC is started (units of 100
* @return Time to update the async registers after RTC is started (units of 100
* microseconds).
*/
uint16_t halInternalStartSystemTimer(void);
@ -54,9 +54,9 @@ uint16_t halCommonGetInt16uMillisecondTick(void);
* @brief Returns the current system time in system ticks, as a 32-bit
* value.
*
* @nostackusage
* nostackusage
*
* @return The least significant 32 bits of the current system time, in
* @return The least significant 32 bits of the current system time, in
* system ticks.
*/
uint32_t halCommonGetInt32uMillisecondTick(void);
@ -65,7 +65,7 @@ uint32_t halCommonGetInt32uMillisecondTick(void);
* @brief Returns the current system time in quarter second ticks, as a
* 16-bit value.
*
* @nostackusage
* nostackusage
*
* @return The least significant 16 bits of the current system time, in system
* ticks multiplied by 256.
@ -74,7 +74,7 @@ uint16_t halCommonGetInt16uQuarterSecondTick(void);
#endif //SYSTEM_TIMER_H_
/**@} //END addtogroup
/**@} //END addtogroup
*/

View file

@ -1,5 +1,5 @@
/** @file temperature-sensor.h
* @brief Header for temperature sensor driver
/** @file cpu/stm32w108/hal/micro/temperature-sensor.h
* @brief Header for temperature sensor driver
*
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
@ -15,11 +15,11 @@
/* Functions -----------------------------------------------------------------*/
/** @brief Temperature Sensor Initialization function
/** @brief Temperature Sensor Initialization function
*/
void temperatureSensor_Init(void);
/** @brief Get temperature sensor value
/** @brief Get temperature sensor value
*/
uint32_t temperatureSensor_GetValue(void);

View file

@ -1,12 +1,12 @@
/* This file has been prepared for Doxygen automatic documentation generation.*/
/*! \file cdc_task.c **********************************************************
/*! \file platform/avr-ravenusb/cdc_task.c **********************************************************
*
* \brief
* Manages the CDC-ACM Virtual Serial Port Dataclass for the USB Device
*
* \addtogroup usbstick
*
* \author
* \author
* Colin O'Flynn <coflynn@newae.com>
*
******************************************************************************/
@ -151,13 +151,13 @@ PROCESS_THREAD(cdc_process, ev, data_proc)
// turn off LED's if necessary
if (led3_timer) led3_timer--;
else Led3_off();
if(Is_device_enumerated()) {
// If the configuration is different than the last time we checked...
if((uart_usb_get_control_line_state()&1)!=previous_uart_usb_control_line_state) {
previous_uart_usb_control_line_state = uart_usb_get_control_line_state()&1;
static FILE* previous_stdout;
if(previous_uart_usb_control_line_state&1) {
previous_stdout = stdout;
uart_usb_init();
@ -202,8 +202,8 @@ PROCESS_THREAD(cdc_process, ev, data_proc)
etimer_set(&et, CLOCK_SECOND);
}
PROCESS_WAIT_EVENT_UNTIL(etimer_expired(&et));
PROCESS_WAIT_EVENT_UNTIL(etimer_expired(&et));
} // while(1)
PROCESS_END();
@ -282,18 +282,18 @@ void menu_process(char c)
channel,
txpower
} menustate = normal;
static char channel_string[3];
static uint8_t channel_string_i;// = 0;
int tempchannel;
if (menustate == channel) {
switch(c) {
case '\r':
case '\n':
case '\n':
if (channel_string_i) {
channel_string[channel_string_i] = 0;
tempchannel = atoi(channel_string);
@ -309,7 +309,7 @@ void menu_process(char c)
} else {
#endif
#if JACKDAW_CONF_USE_SETTINGS
if(settings_set_uint8(SETTINGS_KEY_CHANNEL, tempchannel)==SETTINGS_STATUS_OK) {
if(settings_set_uint8(SETTINGS_KEY_CHANNEL, tempchannel)==SETTINGS_STATUS_OK) {
PRINTF_P(PSTR("\n\rChannel changed to %d and stored in EEPROM.\n\r"),tempchannel);
} else {
PRINTF_P(PSTR("\n\rChannel changed to %d, but unable to store in EEPROM!\n\r"),tempchannel);
@ -324,15 +324,15 @@ void menu_process(char c)
menustate = normal;
break;
case '\b':
if (channel_string_i) {
channel_string_i--;
PRINTF_P(PSTR("\b \b"));
}
break;
case '0':
case '1':
case '2':
@ -352,7 +352,7 @@ void menu_process(char c)
}
putc(c, stdout);
//uart_usb_putchar(c);
channel_string[channel_string_i] = c;
channel_string_i++;
break;
@ -364,8 +364,8 @@ void menu_process(char c)
switch(c) {
case '\r':
case '\n':
case '\n':
if (channel_string_i) {
channel_string[channel_string_i] = 0;
tempchannel = atoi(channel_string);
@ -396,15 +396,15 @@ void menu_process(char c)
menustate = normal;
break;
case '\b':
if (channel_string_i) {
channel_string_i--;
PRINTF_P(PSTR("\b \b"));
}
break;
case '0':
case '1':
case '2':
@ -424,7 +424,7 @@ void menu_process(char c)
}
putc(c, stdout);
//uart_usb_putchar(c);
channel_string[channel_string_i] = c;
channel_string_i++;
break;
@ -432,7 +432,7 @@ void menu_process(char c)
default:
break;
}
} else {
uint8_t i;
@ -482,7 +482,7 @@ void menu_process(char c)
usbstick_mode.translate = 0;
#if RF230BB
rf230_listen_channel(rf230_get_channel());
#else
#else
radio_set_trx_state(RX_ON);
#endif
break;
@ -518,7 +518,7 @@ void menu_process(char c)
usbstick_mode.translate = 1;
#if RF230BB
rf230_set_channel(rf230_get_channel());
#else
#else
radio_set_trx_state(RX_AACK_ON); //TODO: Use startup state which may be RX_ON
#endif
break;
@ -530,8 +530,8 @@ void menu_process(char c)
} else {
PRINTF_P(PSTR("Jackdaw now performs 6lowpan translations\n\r"));
usbstick_mode.sicslowpan = 1;
}
}
break;
case 'r':
@ -541,7 +541,7 @@ void menu_process(char c)
} else {
PRINTF_P(PSTR("Jackdaw now captures raw frames\n\r"));
usbstick_mode.raw = 1;
}
}
break;
#if USB_CONF_RS232
case 'd':
@ -551,7 +551,7 @@ void menu_process(char c)
} else {
PRINTF_P(PSTR("Jackdaw now outputs debug strings\n\r"));
usbstick_mode.debugOn = 1;
}
}
break;
#endif
@ -585,7 +585,7 @@ extern uip_ds6_netif_t uip_ds6_if;
uip_ds6_nbr_t *nbr;
PRINTF_P(PSTR("\n\rAddresses [%u max]\n\r"),UIP_DS6_ADDR_NB);
for (i=0;i<UIP_DS6_ADDR_NB;i++) {
if (uip_ds6_if.addr_list[i].isused) {
if (uip_ds6_if.addr_list[i].isused) {
ipaddr_add(&uip_ds6_if.addr_list[i].ipaddr);
PRINTF_P(PSTR("\n\r"));
}
@ -619,21 +619,21 @@ extern uip_ds6_netif_t uip_ds6_if;
PRINTF_P(PSTR("\n\r---------\n\r"));
break;
}
case 'G':
PRINTF_P(PSTR("Global repair returns %d\n\r"),rpl_repair_root(RPL_DEFAULT_INSTANCE));
break;
case 'L':
rpl_local_repair(rpl_get_any_dag());
PRINTF_P(PSTR("Local repair initiated\n\r"));
PRINTF_P(PSTR("Local repair initiated\n\r"));
break;
case 'Z': //zap the routing table
case 'Z': //zap the routing table
PRINTF_P(PSTR("Not implemented.\n\r"));
break;
#endif
#endif
case 'm':
PRINTF_P(PSTR("Currently Jackdaw:\n\r * Will "));
if (usbstick_mode.sendToRf == 0) { PRINTF_P(PSTR("not "));}
@ -676,7 +676,7 @@ extern uip_ds6_netif_t uip_ds6_if;
PRINTF_P(PSTR(" * Operates on channel %d with TX power "),rf230_get_channel());
printtxpower();
PRINTF_P(PSTR("\n\r"));
#else //just show the raw value
#else //just show the raw value
PRINTF_P(PSTR(" * Operates on channel %d\n\r"), rf230_get_channel());
PRINTF_P(PSTR(" * TX Power(0=+3dBm, 15=-17.2dBm): %d\n\r"), rf230_get_txpower());
#endif
@ -698,7 +698,7 @@ extern uip_ds6_netif_t uip_ds6_if;
else
PRINTF_P(PSTR("Unknown\n\r"));
}
#endif /* RF230BB */
PRINTF_P(PSTR(" * Configuration: %d, USB<->ETH is "), usb_configuration_nb);
@ -735,10 +735,10 @@ uint16_t p=(uint16_t)&__bss_end;
#endif
int8_t RSSI, maxRSSI[17];
uint16_t accRSSI[17];
bzero((void*)accRSSI,sizeof(accRSSI));
bzero((void*)maxRSSI,sizeof(maxRSSI));
for(j=0;j<(1<<12);j++) {
for(i=11;i<=26;i++) {
#if RF230BB
@ -789,7 +789,7 @@ uint16_t p=(uint16_t)&__bss_end;
}
PRINTF_P(PSTR("Done.\n"));
uart_usb_flush();
break;
@ -814,7 +814,7 @@ uint16_t p=(uint16_t)&__bss_end;
watchdog_reboot();
}
break;
#if USB_CONF_STORAGE
case 'u':

View file

@ -4,7 +4,7 @@
* Department of Innovation Engineering - University of Salento
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -32,7 +32,7 @@
*/
/**
* \file eeprom.c
* \file platform/mbxxx/dev/eeprom.c
* \brief ST M24C64W EEPROM driver.
* \author Maria Laura Stefanizzi <laura28582@gmail.com>
* \date 2013-11-20
@ -49,7 +49,7 @@
#define EE_MAX_TRIALS 300
/* Write Cycle polling
*
*
* During the internal Write cycle, the device disconnects itself from the bus,
* and writes a copy of the data from its internal latches to the memory cells.
*/

View file

@ -4,7 +4,7 @@
* Department of Innovation Engineering - University of Salento
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -32,7 +32,7 @@
*/
/**
* \file i2c.c
* \file platform/mbxxx/dev/i2c.c
* \brief I2C bus master driver for mbxxx platform.
* \author Maria Laura Stefanizzi <laura28582@gmail.com>
* \date 2013-11-20
@ -54,11 +54,11 @@ i2c_enable(void)
/* Configure serial controller to I2C mode */
SC2_MODE = SC2_MODE_I2C;
/*
* The SCL is produced by dividing down 12MHz according to
/*
* The SCL is produced by dividing down 12MHz according to
* this equation:
* Rate = 12 MHz / ( (LIN + 1) * (2^EXP) )
*
*
* Configure rate registers for Fast Mode operation (400 kbps)
*/
SC2_RATELIN = 14;

View file

@ -4,7 +4,7 @@
* Department of Innovation Engineering - University of Salento
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -32,7 +32,7 @@
*/
/**
* \file i2c.h
* \file platform/mbxxx/dev/i2c.h
* \brief I2C bus master driver for mbxxx platform.
* \author Maria Laura Stefanizzi <laura28582@gmail.com>
* \date 2013-11-20

View file

@ -7,7 +7,7 @@
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -35,7 +35,7 @@
*/
/**
* \file contiki-conf.h
* \file platform/seedeye/contiki-conf.h
* \brief Contiki configuration file for the SEEDEYE port.
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-03-21

View file

@ -7,7 +7,7 @@
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -33,7 +33,7 @@
* SUCH DAMAGE.
*
*/
/**
* \addtogroup SeedEye Contiki SEEDEYE Platform
*
@ -41,7 +41,7 @@
*/
/**
* \file battery-sensor.c
* \file platform/seedeye/dev/battery-sensor.c
* \brief Battery Sensor
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-07-04
@ -73,7 +73,7 @@ value(int type)
for(i = 0; i < BATTERY_SAMPLES; ++i) {
tmp += battery_samples[i];
}
return tmp / BATTERY_SAMPLES;
}
/*---------------------------------------------------------------------------*/
@ -82,10 +82,10 @@ configure(int type, int c)
{
// all PORTB = Digital; RB10 = analog
AD1PCFG = 0b1111110111111111;
// SSRC bit = 111 implies internal counter ends sampling and starts converting
AD1CON1 = 0b0000000011100000;
AD1CHS = 0b00000000000010100000000000000000;
AD1CSSL = 0;
@ -116,12 +116,12 @@ SENSORS_SENSOR(battery_sensor, BATTERY_SENSOR, value, configure, status);
PROCESS_THREAD(battery_process, ev, data)
{
PROCESS_BEGIN();
while(1) {
static struct etimer et;
etimer_set(&et, CLOCK_SECOND);
PROCESS_WAIT_EVENT_UNTIL(etimer_expired(&et));
// start converting
@ -130,10 +130,10 @@ PROCESS_THREAD(battery_process, ev, data)
while(!(AD1CON1 & 0b0000000000000001)) {
; // wait conversion finish
}
// read the conversion result
battery_samples[counter] = ADC1BUF0;
counter = (counter + 1) % BATTERY_SAMPLES;
}

View file

@ -7,7 +7,7 @@
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -41,7 +41,7 @@
*/
/**
* \file button-sensor.c
* \file platform/seedeye/dev/button-sensor.c
* \brief Button Sensor
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-04-24
@ -66,15 +66,15 @@ static uint8_t sensor_status = 0;
ISR(_CHANGE_NOTICE_VECTOR)
{
ENERGEST_ON(ENERGEST_TYPE_IRQ);
if(timer_expired(&debouncetimer)) {
timer_set(&debouncetimer, CLOCK_SECOND / 4);
sensors_changed(&button_sensor);
}
IFS1CLR = _IFS1_CNIF_MASK;
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
@ -99,28 +99,28 @@ configure(int type, int value)
if(value) {
if(!status(SENSORS_ACTIVE)) {
timer_set(&debouncetimer, 0);
TRISDbits.TRISD5 = 1;
CNCON = 0;
CNCONSET = 1 << _CNCON_ON_POSITION | 1 << _CNCON_SIDL_POSITION;
CNEN = 1 << _CNEN_CNEN14_POSITION;
CNPUE = 1 << _CNPUE_CNPUE14_POSITION;
IEC1CLR = _IEC1_CNIE_MASK;
IFS1CLR = _IFS1_CNIF_MASK;
IPC6CLR = _IPC6_CNIP_MASK;
IPC6SET = 6 << _IPC6_CNIP_POSITION;
IEC1SET = 1 << _IEC1_CNIE_POSITION;
sensor_status = 1;
}
}
return 1;
}
sensor_status = 0;
return 0;

View file

@ -1,13 +1,13 @@
/*
* Contiki PIC32 Port project
*
*
* Copyright (c) 2012,
* Scuola Superiore Sant'Anna (http://www.sssup.it) and
* Consorzio Nazionale Interuniversitario per le Telecomunicazioni
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -41,7 +41,7 @@
*/
/**
* \file leds-arch.c
* \file platform/seedeye/dev/leds-arch.c
* \brief LEDs Specific Arch Conf
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-03-21

View file

@ -7,7 +7,7 @@
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -41,7 +41,7 @@
*/
/**
* \file radio-sensor.c
* \file platform/seedeye/dev/radio-sensor.c
* \brief RADIO Sensor
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-04-24

View file

@ -7,7 +7,7 @@
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -41,7 +41,7 @@
*/
/**
* \file init-net.c
* \file platform/seedeye/init-net.c
* \brief Network initialization for the SEEDEYE port.
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-03-25
@ -77,7 +77,7 @@ init_net(uint8_t node_id)
uip_ds6_addr_t *lladdr;
uip_ipaddr_t ipaddr;
#endif
uint8_t i;
memset(&shortaddr, 0, sizeof(shortaddr));
@ -89,7 +89,7 @@ init_net(uint8_t node_id)
for(i = 2; i < sizeof(longaddr); ++i) {
((uint8_t *)&longaddr)[i] = random_rand();
}
PRINTF("SHORT MAC ADDRESS %02x:%02x\n",
*((uint8_t *) & shortaddr), *((uint8_t *) & shortaddr + 1));
@ -110,7 +110,7 @@ init_net(uint8_t node_id)
}
linkaddr_set_node_addr(&addr);
PRINTF("Rime started with address: ");
for(i = 0; i < sizeof(addr.u8) - 1; ++i) {
PRINTF("%d.", addr.u8[i]);
@ -120,7 +120,7 @@ init_net(uint8_t node_id)
queuebuf_init();
NETSTACK_RADIO.init();
mrf24j40_set_channel(RF_CHANNEL);
mrf24j40_set_panid(IEEE802154_PANID);
mrf24j40_set_short_mac_addr(shortaddr);

View file

@ -7,7 +7,7 @@
* (http://www.cnit.it).
*
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
@ -41,7 +41,7 @@
*/
/**
* \file init-net.h
* \file platform/seedeye/init-net.h
* \brief Network initialization for the SEEDEYE port.
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-03-25

View file

@ -34,7 +34,7 @@
*
*/
/**
* \file platform-conf.h
* \file platform/seedeye/platform-conf.h
* \brief Platform configuration file for the SEEDEYE port.
* \author Giovanni Pellerano <giovanni.pellerano@evilaliv3.org>
* \date 2012-06-06