Merge branch 'develop' into contrib/tsch-print-schedule

This commit is contained in:
George Oikonomou 2018-02-25 18:48:00 +00:00 committed by GitHub
commit 1f44c1530e
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
91 changed files with 1879 additions and 482 deletions

View File

@ -42,16 +42,6 @@
/*---------------------------------------------------------------------------*/
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/**
* \name Compiler configuration
*
* Those values are not meant to be modified by the user
* @{
*/
#define CCIF
#define CLIF
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name Macros and typedefs
*

View File

@ -17,7 +17,7 @@ CONTIKI_CPU_DIRS = . dev usb usb/common usb/common/cdc-acm
CONTIKI_CPU_SOURCEFILES += soc.c clock.c rtimer-arch.c uart.c watchdog.c
CONTIKI_CPU_SOURCEFILES += nvic.c sys-ctrl.c gpio.c ioc.c spi.c adc.c
CONTIKI_CPU_SOURCEFILES += crypto.c aes.c ecb.c cbc.c ctr.c cbc-mac.c gcm.c
CONTIKI_CPU_SOURCEFILES += ccm.c sha256.c
CONTIKI_CPU_SOURCEFILES += ccm.c sha256.c gpio-hal-arch.c
CONTIKI_CPU_SOURCEFILES += cc2538-aes-128.c cc2538-ccm-star.c
CONTIKI_CPU_SOURCEFILES += cc2538-rf.c udma.c lpm.c int-master.c
CONTIKI_CPU_SOURCEFILES += pka.c bignum-driver.c ecc-driver.c ecc-algorithm.c

View File

@ -64,6 +64,8 @@
/* Path to headers with implementation of mutexes and memory barriers */
#define MUTEX_CONF_ARCH_HEADER_PATH "mutex-cortex.h"
#define MEMORY_BARRIER_CONF_ARCH_HEADER_PATH "memory-barrier-cortex.h"
#define GPIO_HAL_CONF_ARCH_HDR_PATH "dev/gpio-hal-arch.h"
/*---------------------------------------------------------------------------*/
#endif /* CC2538_DEF_H_ */
/*---------------------------------------------------------------------------*/

View File

@ -114,7 +114,7 @@ clock_init(void)
REG(GPT_0_BASE + GPTIMER_TAPR) = PRESCALER_VALUE;
}
/*---------------------------------------------------------------------------*/
CCIF clock_time_t
clock_time_t
clock_time(void)
{
return rt_ticks_startup / RTIMER_CLOCK_TICK_RATIO;
@ -126,7 +126,7 @@ clock_set_seconds(unsigned long sec)
rt_ticks_epoch = (uint64_t)sec * RTIMER_SECOND;
}
/*---------------------------------------------------------------------------*/
CCIF unsigned long
unsigned long
clock_seconds(void)
{
return rt_ticks_epoch / RTIMER_SECOND;

View File

@ -0,0 +1,196 @@
/*
* Copyright (c) 2017, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc2538-gpio-hal
* @{
*
* \file
* Implementation file for the CC2538 GPIO HAL functions
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "dev/gpio-hal.h"
#include "dev/gpio.h"
#include "dev/ioc.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
void
gpio_hal_arch_pin_cfg_set(gpio_hal_pin_t pin, gpio_hal_pin_cfg_t cfg)
{
uint8_t port, pin_num, pin_mask;
uint32_t port_base;
port = PIN_TO_PORT(pin);
port_base = PIN_TO_PORT_BASE(pin);
pin_num = pin % 8;
pin_mask = GPIO_PIN_MASK(pin_num);
gpio_hal_pin_cfg_t tmp;
tmp = cfg & GPIO_HAL_PIN_CFG_EDGE_BOTH;
if(tmp == GPIO_HAL_PIN_CFG_EDGE_NONE) {
GPIO_DISABLE_INTERRUPT(port_base, pin_mask);
} else if(tmp == GPIO_HAL_PIN_CFG_EDGE_RISING) {
GPIO_DETECT_EDGE(port_base, pin_mask);
GPIO_TRIGGER_SINGLE_EDGE(port_base, pin_mask);
GPIO_DETECT_RISING(port_base, pin_mask);
} else if(tmp == GPIO_HAL_PIN_CFG_EDGE_FALLING) {
GPIO_DETECT_EDGE(port_base, pin_mask);
GPIO_TRIGGER_SINGLE_EDGE(port_base, pin_mask);
GPIO_DETECT_FALLING(port_base, pin_mask);
} else if(tmp == GPIO_HAL_PIN_CFG_EDGE_BOTH) {
GPIO_DETECT_EDGE(port_base, pin_mask);
GPIO_TRIGGER_BOTH_EDGES(port_base, pin_mask);
}
tmp = cfg & GPIO_HAL_PIN_CFG_PULL_MASK;
if(tmp == GPIO_HAL_PIN_CFG_PULL_NONE) {
ioc_set_over(port, pin_num, IOC_OVERRIDE_DIS);
} else if(tmp == GPIO_HAL_PIN_CFG_PULL_DOWN) {
ioc_set_over(port, pin_num, IOC_OVERRIDE_PDE);
} else if(tmp == GPIO_HAL_PIN_CFG_PULL_UP) {
ioc_set_over(port, pin_num, IOC_OVERRIDE_PUE);
}
tmp = cfg & GPIO_HAL_PIN_CFG_INT_MASK;
if(tmp == GPIO_HAL_PIN_CFG_INT_DISABLE) {
GPIO_DISABLE_INTERRUPT(port_base, pin_mask);
} else if(tmp == GPIO_HAL_PIN_CFG_INT_ENABLE) {
GPIO_ENABLE_INTERRUPT(port_base, pin_mask);
}
GPIO_SOFTWARE_CONTROL(port_base, pin_mask);
}
/*---------------------------------------------------------------------------*/
gpio_hal_pin_cfg_t
gpio_hal_arch_pin_cfg_get(gpio_hal_pin_t pin)
{
uint8_t port, pin_num, pin_mask;
uint32_t port_base;
gpio_hal_pin_cfg_t cfg;
uint32_t tmp;
port = PIN_TO_PORT(pin);
port_base = PIN_TO_PORT_BASE(pin);
pin_num = pin % 8;
pin_mask = GPIO_PIN_MASK(pin_num);
cfg = 0;
/* Pull */
tmp = ioc_get_over(port, pin_num);
if(tmp == IOC_OVERRIDE_PUE) {
cfg |= GPIO_HAL_PIN_CFG_PULL_UP;
} else if(tmp == IOC_OVERRIDE_PDE) {
cfg |= GPIO_HAL_PIN_CFG_PULL_DOWN;
} else {
cfg |= GPIO_HAL_PIN_CFG_PULL_NONE;
}
/* Interrupt enable/disable */
tmp = REG((port_base) + GPIO_IE) & pin_mask;
if(tmp == 0) {
cfg |= GPIO_HAL_PIN_CFG_INT_DISABLE;
} else {
cfg |= GPIO_HAL_PIN_CFG_INT_ENABLE;
}
/* Edge detection */
if(REG((port_base) + GPIO_IS) & pin_mask) {
cfg |= GPIO_HAL_PIN_CFG_EDGE_NONE;
} else {
if(REG((port_base) + GPIO_IBE) & pin_mask) {
cfg |= GPIO_HAL_PIN_CFG_EDGE_BOTH;
} else {
if(REG((port_base) + GPIO_IEV) & pin_mask) {
cfg |= GPIO_HAL_PIN_CFG_EDGE_RISING;
} else {
cfg |= GPIO_HAL_PIN_CFG_EDGE_FALLING;
}
}
}
return cfg;
}
/*---------------------------------------------------------------------------*/
void
gpio_hal_arch_write_pin(gpio_hal_pin_t pin, uint8_t value)
{
if(value == 1) {
gpio_hal_arch_set_pin(pin);
return;
}
gpio_hal_arch_clear_pin(pin);
}
/*---------------------------------------------------------------------------*/
void
gpio_hal_arch_set_pins(gpio_hal_pin_mask_t pins)
{
GPIO_SET_PIN(GPIO_A_BASE, pins & 0xFF);
GPIO_SET_PIN(GPIO_B_BASE, (pins >> 8) & 0xFF);
GPIO_SET_PIN(GPIO_C_BASE, (pins >> 16) & 0xFF);
GPIO_SET_PIN(GPIO_D_BASE, (pins >> 24) & 0xFF);
}
/*---------------------------------------------------------------------------*/
void
gpio_hal_arch_clear_pins(gpio_hal_pin_mask_t pins)
{
GPIO_CLR_PIN(GPIO_A_BASE, pins & 0xFF);
GPIO_CLR_PIN(GPIO_B_BASE, (pins >> 8) & 0xFF);
GPIO_CLR_PIN(GPIO_C_BASE, (pins >> 16) & 0xFF);
GPIO_CLR_PIN(GPIO_D_BASE, (pins >> 24) & 0xFF);
}
/*---------------------------------------------------------------------------*/
gpio_hal_pin_mask_t
gpio_hal_arch_read_pins(gpio_hal_pin_mask_t pins)
{
gpio_hal_pin_mask_t rv = 0;
rv |= GPIO_READ_PIN(GPIO_A_BASE, pins & 0xFF);
rv |= GPIO_READ_PIN(GPIO_B_BASE, (pins >> 8) & 0xFF) << 8;
rv |= GPIO_READ_PIN(GPIO_C_BASE, (pins >> 16) & 0xFF) << 16;
rv |= GPIO_READ_PIN(GPIO_D_BASE, (pins >> 24) & 0xFF) << 24;
return rv;
}
/*---------------------------------------------------------------------------*/
void
gpio_hal_arch_write_pins(gpio_hal_pin_mask_t pins, gpio_hal_pin_mask_t value)
{
GPIO_WRITE_PIN(GPIO_A_BASE, pins & 0xFF, value & 0xFF);
GPIO_WRITE_PIN(GPIO_B_BASE, (pins >> 8) & 0xFF, (value >> 8) & 0xFF);
GPIO_WRITE_PIN(GPIO_C_BASE, (pins >> 16) & 0xFF, (value >> 16) & 0xFF);
GPIO_WRITE_PIN(GPIO_D_BASE, (pins >> 24) & 0xFF, (value >> 24) & 0xFF);
}
/*---------------------------------------------------------------------------*/
/** @} */

View File

@ -0,0 +1,88 @@
/*
* Copyright (c) 2017, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc2538
* @{
*
* \defgroup cc2538-gpio-hal CC2538 GPIO HAL implementation
*
* @{
*
* \file
* Header file for the CC2538 GPIO HAL functions
*
* \note
* Do not include this header directly
*/
/*---------------------------------------------------------------------------*/
#ifndef GPIO_HAL_ARCH_H_
#define GPIO_HAL_ARCH_H_
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "dev/gpio.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
#define PIN_TO_PORT(pin) (pin >> 3)
#define PIN_TO_PORT_BASE(pin) GPIO_PORT_TO_BASE(PIN_TO_PORT(pin))
/*---------------------------------------------------------------------------*/
#define gpio_hal_arch_interrupt_enable(p) \
GPIO_ENABLE_INTERRUPT(PIN_TO_PORT_BASE(p), GPIO_PIN_MASK((p) % 8))
#define gpio_hal_arch_interrupt_disable(p) \
GPIO_DISABLE_INTERRUPT(PIN_TO_PORT_BASE(p), GPIO_PIN_MASK((p) % 8))
#define gpio_hal_arch_pin_set_input(p) do { \
GPIO_SOFTWARE_CONTROL(PIN_TO_PORT_BASE(p), GPIO_PIN_MASK((p) % 8)); \
GPIO_SET_INPUT(PIN_TO_PORT_BASE(p), GPIO_PIN_MASK((p) % 8)); \
} while(0);
#define gpio_hal_arch_pin_set_output(p) do { \
GPIO_SOFTWARE_CONTROL(PIN_TO_PORT_BASE(p), GPIO_PIN_MASK((p) % 8)); \
GPIO_SET_OUTPUT(PIN_TO_PORT_BASE(p), GPIO_PIN_MASK((p) % 8)); \
} while(0);
#define gpio_hal_arch_set_pin(p) \
GPIO_SET_PIN(PIN_TO_PORT_BASE(p), GPIO_PIN_MASK((p) % 8))
#define gpio_hal_arch_clear_pin(p) \
GPIO_CLR_PIN(PIN_TO_PORT_BASE(p), GPIO_PIN_MASK((p) % 8))
#define gpio_hal_arch_read_pin(p) \
(GPIO_READ_PIN(PIN_TO_PORT_BASE(p), GPIO_PIN_MASK((p) % 8)) == 0 ? 0 : 1)
/*---------------------------------------------------------------------------*/
#endif /* GPIO_HAL_ARCH_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View File

@ -37,46 +37,13 @@
*/
#include "contiki.h"
#include "dev/leds.h"
#include "dev/gpio-hal.h"
#include "dev/gpio.h"
#include "dev/nvic.h"
#include "reg.h"
#include "lpm.h"
#include <string.h>
/**
* \brief Pointer to a function to be called when a GPIO interrupt is detected.
* Callbacks for Port A, Pins[0:7] are stored in positions [0:7] of this
* buffer, Port B callbacks in [8:15] and so on
*/
static gpio_callback_t gpio_callbacks[32];
/*---------------------------------------------------------------------------*/
void
gpio_register_callback(gpio_callback_t f, uint8_t port, uint8_t pin)
{
gpio_callbacks[(port << 3) + pin] = f;
}
/*---------------------------------------------------------------------------*/
/** \brief Run through all registered GPIO callbacks and invoke those
* associated with the \a port and the pins specified by \a mask
* \param mask Search callbacks associated with pins specified by this mask
* \param port Search callbacks associated with this port. Here, port is
* specified as a number between 0 and 3. Port A: 0, Port B: 1 etc */
void
notify(uint8_t mask, uint8_t port)
{
uint8_t i;
gpio_callback_t *f = &gpio_callbacks[port << 3];
for(i = 0; i < 8; i++) {
if(mask & (1 << i)) {
if((*f) != NULL) {
(*f)(port, i);
}
}
f++;
}
}
/*---------------------------------------------------------------------------*/
/** \brief Interrupt service routine for Port \a port
* \param port Number between 0 and 3. Port A: 0, Port B: 1, etc.
@ -93,7 +60,7 @@ gpio_port_isr(uint8_t port)
int_status = GPIO_GET_MASKED_INT_STATUS(base);
power_up_int_status = GPIO_GET_POWER_UP_INT_STATUS(port);
notify(int_status | power_up_int_status, port);
gpio_hal_event_handler((int_status | power_up_int_status) << (port << 3));
GPIO_CLEAR_INTERRUPT(base, int_status);
GPIO_CLEAR_POWER_UP_INTERRUPT(port, power_up_int_status);
@ -110,9 +77,4 @@ GPIO_PORT_ISR(b, B)
GPIO_PORT_ISR(c, C)
GPIO_PORT_ISR(d, D)
/*---------------------------------------------------------------------------*/
void
gpio_init()
{
memset(gpio_callbacks, 0, sizeof(gpio_callbacks));
}
/** @} */

View File

@ -42,27 +42,12 @@
*/
#ifndef GPIO_H_
#define GPIO_H_
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "dev/gpio-hal.h"
#include "reg.h"
#include <stdint.h>
/**
* \brief Type definition for callbacks invoked by the GPIO ISRs
* \param port The port that triggered the GPIO interrupt. \e port is passed
* by its numeric representation (Port A:0, B:1 etc). Defines for
* these numeric representations are GPIO_x_NUM
* \param pin The pin that triggered the interrupt, specified by number
* (0, 1, ..., 7)
*
* This is the prototype of a function pointer passed to
* gpio_register_callback(). These callbacks are registered on a port/pin
* basis. When a GPIO port generates an interrupt, if a callback has been
* registered for the port/pin combination, the ISR will invoke it. The ISR
* will pass the port/pin as arguments in that call, so that a developer can
* re-use the same callback for multiple port/pin combinations
*/
typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
/*---------------------------------------------------------------------------*/
/** \name Base addresses for the GPIO register instances
* @{
@ -612,21 +597,6 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
#define GPIO_IRQ_DETECT_UNMASK_PAIACK0 0x00000001 /**< Port A bit 0 */
/** @} */
/*---------------------------------------------------------------------------*/
/** \brief Initialise the GPIO module */
void gpio_init();
/**
* \brief Register GPIO callback
* \param f Pointer to a function to be called when \a pin of \a port
* generates an interrupt
* \param port Associate \a f with this port. \e port must be specified with
* its numeric representation (Port A:0, B:1 etc). Defines for these
* numeric representations are GPIO_x_NUM
* \param pin Associate \a f with this pin, which is specified by number
* (0, 1, ..., 7)
*/
void gpio_register_callback(gpio_callback_t f, uint8_t port, uint8_t pin);
#endif /* GPIO_H_ */
/**

View File

@ -56,6 +56,12 @@ ioc_set_over(uint8_t port, uint8_t pin, uint8_t over)
ioc_over[(port << 3) + pin] = over;
}
/*---------------------------------------------------------------------------*/
uint32_t
ioc_get_over(uint8_t port, uint8_t pin)
{
return ioc_over[(port << 3) + pin] & 0x0F;
}
/*---------------------------------------------------------------------------*/
void
ioc_set_sel(uint8_t port, uint8_t pin, uint8_t sel)
{

View File

@ -249,6 +249,22 @@ void ioc_init();
*/
void ioc_set_over(uint8_t port, uint8_t pin, uint8_t over);
/**
* \brief Get Port:Pin override function
* \param port The port as a number (PA: 0, PB: 1 etc)
* \param pin The pin as a number
* \return The override function
*
* The return value can be one of
*
* - IOC_OVERRIDE_OE: Output
* - IOC_OVERRIDE_PUE: Pull-Up
* - IOC_OVERRIDE_PDE: Pull-Down
* - IOC_OVERRIDE_ANA: Analog
* - IOC_OVERRIDE_DIS: Disabled
*/
uint32_t ioc_get_over(uint8_t port, uint8_t pin);
/**
* \brief Function select for Port:Pin
* \param port The port as a number (PA: 0, PB: 1 etc)

View File

@ -41,6 +41,7 @@
#include "dev/ioc.h"
#include "dev/nvic.h"
#include "dev/sys-ctrl.h"
#include "dev/gpio-hal.h"
#include "lpm.h"
#include "reg.h"
#include "soc.h"
@ -123,7 +124,7 @@ soc_init()
clock_init();
lpm_init();
rtimer_init();
gpio_init();
gpio_hal_init();
}
/*----------------------------------------------------------------------------*/
/** @} */

View File

@ -32,7 +32,7 @@ CONTIKI_CPU_SOURCEFILES += clock.c rtimer-arch.c soc-rtc.c uart.c
CONTIKI_CPU_SOURCEFILES += contiki-watchdog.c aux-ctrl.c
CONTIKI_CPU_SOURCEFILES += putchar.c ieee-addr.c batmon-sensor.c adc-sensor.c
CONTIKI_CPU_SOURCEFILES += slip-arch.c slip.c cc26xx-uart.c lpm.c
CONTIKI_CPU_SOURCEFILES += gpio-interrupt.c oscillators.c
CONTIKI_CPU_SOURCEFILES += gpio-interrupt.c gpio-hal-arch.c oscillators.c
CONTIKI_CPU_SOURCEFILES += rf-core.c rf-ble.c ieee-mode.c
CONTIKI_CPU_SOURCEFILES += random.c soc-trng.c int-master.c

View File

@ -99,6 +99,10 @@
/* Path to headers with implementation of mutexes and memory barriers */
#define MUTEX_CONF_ARCH_HEADER_PATH "mutex-cortex.h"
#define MEMORY_BARRIER_CONF_ARCH_HEADER_PATH "memory-barrier-cortex.h"
#define GPIO_HAL_CONF_ARCH_HDR_PATH "dev/gpio-hal-arch.h"
/*---------------------------------------------------------------------------*/
#define GPIO_HAL_CONF_ARCH_SW_TOGGLE 0
/*---------------------------------------------------------------------------*/
#endif /* CC13XX_CC26XX_DEF_H_ */
/*---------------------------------------------------------------------------*/

View File

@ -124,7 +124,7 @@ update_clock_variable(void)
count = (aon_rtc_secs_now * CLOCK_SECOND) + (aon_rtc_ticks_now >> 9);
}
/*---------------------------------------------------------------------------*/
CCIF clock_time_t
clock_time_t
clock_time(void)
{
update_clock_variable();
@ -142,7 +142,7 @@ clock_update(void)
}
}
/*---------------------------------------------------------------------------*/
CCIF unsigned long
unsigned long
clock_seconds(void)
{
bool interrupts_disabled;

View File

@ -39,7 +39,6 @@
#include "contiki.h"
#include "lib/sensors.h"
#include "dev/adc-sensor.h"
#include "gpio-interrupt.h"
#include "sys/timer.h"
#include "lpm.h"

View File

@ -0,0 +1,156 @@
/*
* Copyright (c) 2017, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx-gpio-hal
* @{
*
* \file
* Implementation file for the CC13xx/CC26xx GPIO HAL functions
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "ti-lib.h"
#include "ti-lib-rom.h"
#include "dev/gpio-hal.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
#define CONFIG_MASK (IOC_IOPULL_M | IOC_INT_M | IOC_IOMODE_OPEN_SRC_INV)
/*---------------------------------------------------------------------------*/
void
gpio_hal_arch_pin_cfg_set(gpio_hal_pin_t pin, gpio_hal_pin_cfg_t cfg)
{
uint32_t config;
gpio_hal_pin_cfg_t tmp;
/* Clear settings that we are about to change, keep everything else */
config = ti_lib_rom_ioc_port_configure_get(pin);
config &= ~CONFIG_MASK;
tmp = cfg & GPIO_HAL_PIN_CFG_EDGE_BOTH;
if(tmp == GPIO_HAL_PIN_CFG_EDGE_NONE) {
config |= IOC_NO_EDGE;
} else if(tmp == GPIO_HAL_PIN_CFG_EDGE_RISING) {
config |= IOC_RISING_EDGE;
} else if(tmp == GPIO_HAL_PIN_CFG_EDGE_FALLING) {
config |= IOC_FALLING_EDGE;
} else if(tmp == GPIO_HAL_PIN_CFG_EDGE_BOTH) {
config |= IOC_BOTH_EDGES;
}
tmp = cfg & GPIO_HAL_PIN_CFG_PULL_MASK;
if(tmp == GPIO_HAL_PIN_CFG_PULL_NONE) {
config |= IOC_NO_IOPULL;
} else if(tmp == GPIO_HAL_PIN_CFG_PULL_DOWN) {
config |= IOC_IOPULL_DOWN;
} else if(tmp == GPIO_HAL_PIN_CFG_PULL_UP) {
config |= IOC_IOPULL_UP;
}
tmp = cfg & GPIO_HAL_PIN_CFG_INT_MASK;
if(tmp == GPIO_HAL_PIN_CFG_INT_DISABLE) {
config |= IOC_INT_DISABLE;
} else if(tmp == GPIO_HAL_PIN_CFG_INT_ENABLE) {
config |= IOC_INT_ENABLE;
}
ti_lib_rom_ioc_port_configure_set(pin, IOC_PORT_GPIO, config);
}
/*---------------------------------------------------------------------------*/
gpio_hal_pin_cfg_t
gpio_hal_arch_pin_cfg_get(gpio_hal_pin_t pin)
{
gpio_hal_pin_cfg_t cfg;
uint32_t tmp;
uint32_t config;
cfg = 0;
config = ti_lib_rom_ioc_port_configure_get(pin);
/* Pull */
tmp = config & IOC_IOPULL_M;
if(tmp == IOC_IOPULL_UP) {
cfg |= GPIO_HAL_PIN_CFG_PULL_UP;
} else if(tmp == IOC_IOPULL_DOWN) {
cfg |= GPIO_HAL_PIN_CFG_PULL_DOWN;
} else if(tmp == IOC_NO_IOPULL) {
cfg |= GPIO_HAL_PIN_CFG_PULL_NONE;
}
/* Interrupt enable/disable */
tmp = config & IOC_INT_ENABLE;
if(tmp == IOC_INT_DISABLE) {
cfg |= GPIO_HAL_PIN_CFG_INT_DISABLE;
} else if(tmp == IOC_INT_ENABLE) {
cfg |= GPIO_HAL_PIN_CFG_INT_ENABLE;
}
/* Edge detection */
tmp = config & IOC_BOTH_EDGES;
if(tmp == IOC_NO_EDGE) {
cfg |= GPIO_HAL_PIN_CFG_EDGE_NONE;
} else if(tmp == IOC_FALLING_EDGE) {
cfg |= GPIO_HAL_PIN_CFG_EDGE_FALLING;
} else if(tmp == IOC_RISING_EDGE) {
cfg |= GPIO_HAL_PIN_CFG_EDGE_RISING;
} else if(tmp == IOC_BOTH_EDGES) {
cfg |= GPIO_HAL_PIN_CFG_EDGE_BOTH;
}
return cfg;
}
/*---------------------------------------------------------------------------*/
gpio_hal_pin_mask_t
gpio_hal_arch_read_pins(gpio_hal_pin_mask_t pins)
{
gpio_hal_pin_mask_t oe_pins;
/* For pins configured as output we need to read DOUT31_0 */
oe_pins = ti_lib_gpio_get_output_enable_multi_dio(pins);
pins &= ~oe_pins;
return (HWREG(GPIO_BASE + GPIO_O_DOUT31_0) & oe_pins) |
ti_lib_gpio_read_multi_dio(pins);
}
/*---------------------------------------------------------------------------*/
uint8_t
gpio_hal_arch_read_pin(gpio_hal_pin_t pin)
{
if(ti_lib_gpio_get_output_enable_dio(pin)) {
return (HWREG(GPIO_BASE + GPIO_O_DOUT31_0) >> pin) & 1;
}
return ti_lib_gpio_read_dio(pin);
}
/*---------------------------------------------------------------------------*/
/** @} */

View File

@ -0,0 +1,84 @@
/*
* Copyright (c) 2017, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx
* @{
*
* \defgroup cc26xx-gpio-hal CC13xx/CC26xx GPIO HAL implementation
*
* @{
*
* \file
* Header file for the CC13xx/CC26xx GPIO HAL functions
*
* \note
* Do not include this header directly
*/
/*---------------------------------------------------------------------------*/
#ifndef GPIO_HAL_ARCH_H_
#define GPIO_HAL_ARCH_H_
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "ti-lib.h"
#include "ti-lib-rom.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
#define gpio_hal_arch_interrupt_enable(p) interrupt_enable(p)
#define gpio_hal_arch_interrupt_disable(p) ti_lib_rom_ioc_int_disable(p)
#define gpio_hal_arch_pin_set_input(p) ti_lib_rom_ioc_pin_type_gpio_input(p)
#define gpio_hal_arch_pin_set_output(p) ti_lib_rom_ioc_pin_type_gpio_output(p)
#define gpio_hal_arch_set_pin(p) ti_lib_gpio_set_dio(p)
#define gpio_hal_arch_clear_pin(p) ti_lib_gpio_clear_dio(p)
#define gpio_hal_arch_toggle_pin(p) ti_lib_gpio_toggle_dio(p)
#define gpio_hal_arch_write_pin(p, v) ti_lib_gpio_write_dio(p, v)
#define gpio_hal_arch_set_pins(p) ti_lib_gpio_set_multi_dio(p)
#define gpio_hal_arch_clear_pins(p) ti_lib_gpio_clear_multi_dio(p)
#define gpio_hal_arch_toggle_pins(p) ti_lib_gpio_toggle_multi_dio(p)
#define gpio_hal_arch_write_pins(p, v) ti_lib_gpio_write_multi_dio(p, v)
/*---------------------------------------------------------------------------*/
static inline void
interrupt_enable(gpio_hal_pin_t pin)
{
ti_lib_gpio_clear_event_dio(pin);
ti_lib_rom_ioc_int_enable(pin);
}
/*---------------------------------------------------------------------------*/
#endif /* GPIO_HAL_ARCH_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View File

@ -29,72 +29,33 @@
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx-gpio-interrupts
* \addtogroup cc26xx
* @{
*
* \file
* Implementation of CC13xx/CC26xx GPIO interrupt handling.
* CC13xx/CC26xx GPIO interrupt ISR.
*/
/*---------------------------------------------------------------------------*/
#include "ioc.h"
#include "gpio-interrupt.h"
#include "lpm.h"
#include "contiki.h"
#include "dev/gpio-hal.h"
#include "ti-lib.h"
#include <string.h>
/*---------------------------------------------------------------------------*/
#define gpio_interrupt_isr GPIOIntHandler
/*---------------------------------------------------------------------------*/
/* Handler array */
static gpio_interrupt_handler_t handlers[NUM_IO_MAX];
/*---------------------------------------------------------------------------*/
void
gpio_interrupt_register_handler(uint8_t ioid, gpio_interrupt_handler_t f)
{
uint8_t interrupts_disabled = ti_lib_int_master_disable();
/* Clear interrupts on specified pins */
ti_lib_gpio_clear_event_dio(ioid);
handlers[ioid] = f;
/* Re-enable interrupts */
if(!interrupts_disabled) {
ti_lib_int_master_enable();
}
}
/*---------------------------------------------------------------------------*/
void
gpio_interrupt_init()
{
int i;
for(i = 0; i < NUM_IO_MAX; i++) {
handlers[i] = NULL;
}
ti_lib_int_enable(INT_AON_GPIO_EDGE);
}
/*---------------------------------------------------------------------------*/
void
gpio_interrupt_isr(void)
{
uint32_t pin_mask;
uint8_t i;
gpio_hal_pin_mask_t pin_mask;
/* Read interrupt flags */
pin_mask = (HWREG(GPIO_BASE + GPIO_O_EVFLAGS31_0) & GPIO_DIO_ALL_MASK);
gpio_hal_event_handler(pin_mask);
/* Clear the interrupt flags */
HWREG(GPIO_BASE + GPIO_O_EVFLAGS31_0) = pin_mask;
/* Run custom ISRs */
for(i = 0; i < NUM_IO_MAX; i++) {
/* Call the handler if there is one registered for this event */
if((pin_mask & (1 << i)) && handlers[i] != NULL) {
handlers[i](i);
}
}
}
/*---------------------------------------------------------------------------*/
/** @} */

View File

@ -79,9 +79,6 @@ typedef long off_t;
/* Our clock resolution, this is the same as Unix HZ. */
#define CLOCK_CONF_SECOND 128UL
#define CCIF
#define CLIF
typedef int spl_t;
spl_t splhigh_(void);

View File

@ -116,7 +116,7 @@ clock_init(void)
rtc_config();
}
/*---------------------------------------------------------------------------*/
CCIF clock_time_t
clock_time_t
clock_time(void)
{
return (clock_time_t)(ticks & 0xFFFFFFFF);
@ -131,7 +131,7 @@ clock_update(void)
}
}
/*---------------------------------------------------------------------------*/
CCIF unsigned long
unsigned long
clock_seconds(void)
{
return (unsigned long)ticks/CLOCK_CONF_SECOND;

View File

@ -41,6 +41,7 @@
#include <stdint.h>
#include <string.h>
#include <inttypes.h>
/*---------------------------------------------------------------------------*/
/* Include Project Specific conf */
#ifdef PROJECT_CONF_PATH

View File

@ -88,15 +88,8 @@ config(uint32_t port_base, uint32_t pin_mask)
GPIO_ENABLE_INTERRUPT(port_base, pin_mask);
}
/*---------------------------------------------------------------------------*/
/**
* \brief Callback registered with the GPIO module. Gets fired with a button
* port/pin generates an interrupt
* \param port The port number that generated the interrupt
* \param pin The pin number that generated the interrupt. This is the pin
* absolute number (i.e. 0, 1, ..., 7), not a mask
*/
static void
btn_callback(uint8_t port, uint8_t pin)
button_press_handler(gpio_hal_pin_mask_t pin_mask)
{
if(!timer_expired(&debouncetimer)) {
return;
@ -104,19 +97,39 @@ btn_callback(uint8_t port, uint8_t pin)
timer_set(&debouncetimer, CLOCK_SECOND / 8);
if((port == BUTTON_SELECT_PORT) && (pin == BUTTON_SELECT_PIN)) {
if(pin_mask &
(gpio_hal_pin_to_mask(BUTTON_SELECT_PIN) << (BUTTON_SELECT_PORT << 3))) {
sensors_changed(&button_select_sensor);
} else if((port == BUTTON_LEFT_PORT) && (pin == BUTTON_LEFT_PIN)) {
} else if(pin_mask &
(gpio_hal_pin_to_mask(BUTTON_LEFT_PIN) << (BUTTON_LEFT_PORT << 3))) {
sensors_changed(&button_left_sensor);
} else if((port == BUTTON_RIGHT_PORT) && (pin == BUTTON_RIGHT_PIN)) {
} else if(pin_mask &
(gpio_hal_pin_to_mask(BUTTON_RIGHT_PIN) << (BUTTON_RIGHT_PORT << 3))) {
sensors_changed(&button_right_sensor);
} else if((port == BUTTON_UP_PORT) && (pin == BUTTON_UP_PIN)) {
} else if(pin_mask &
(gpio_hal_pin_to_mask(BUTTON_UP_PIN) << (BUTTON_UP_PORT << 3))) {
sensors_changed(&button_up_sensor);
} else if((port == BUTTON_DOWN_PORT) && (pin == BUTTON_DOWN_PIN)) {
} else if(pin_mask &
(gpio_hal_pin_to_mask(BUTTON_DOWN_PIN) << (BUTTON_DOWN_PORT << 3))) {
sensors_changed(&button_down_sensor);
}
}
/*---------------------------------------------------------------------------*/
static gpio_hal_event_handler_t press_handler = {
.next = NULL,
.handler = button_press_handler,
.pin_mask = 0,
};
/*---------------------------------------------------------------------------*/
static void
register_btn_callback(uint8_t port_num, uint8_t pin)
{
press_handler.pin_mask |=
gpio_hal_pin_to_mask(pin) << (port_num << 3);
gpio_hal_register_handler(&press_handler);
}
/*---------------------------------------------------------------------------*/
/**
* \brief Init function for the select button.
*
@ -137,7 +150,7 @@ config_select(int type, int value)
NVIC_EnableIRQ(BUTTON_SELECT_VECTOR);
gpio_register_callback(btn_callback, BUTTON_SELECT_PORT, BUTTON_SELECT_PIN);
register_btn_callback(BUTTON_SELECT_PORT, BUTTON_SELECT_PIN);
return 1;
}
/*---------------------------------------------------------------------------*/
@ -161,7 +174,7 @@ config_left(int type, int value)
NVIC_EnableIRQ(BUTTON_LEFT_VECTOR);
gpio_register_callback(btn_callback, BUTTON_LEFT_PORT, BUTTON_LEFT_PIN);
register_btn_callback(BUTTON_LEFT_PORT, BUTTON_LEFT_PIN);
return 1;
}
/*---------------------------------------------------------------------------*/
@ -185,7 +198,7 @@ config_right(int type, int value)
NVIC_EnableIRQ(BUTTON_RIGHT_VECTOR);
gpio_register_callback(btn_callback, BUTTON_RIGHT_PORT, BUTTON_RIGHT_PIN);
register_btn_callback(BUTTON_RIGHT_PORT, BUTTON_RIGHT_PIN);
return 1;
}
/*---------------------------------------------------------------------------*/
@ -209,7 +222,7 @@ config_up(int type, int value)
NVIC_EnableIRQ(BUTTON_UP_VECTOR);
gpio_register_callback(btn_callback, BUTTON_UP_PORT, BUTTON_UP_PIN);
register_btn_callback(BUTTON_UP_PORT, BUTTON_UP_PIN);
return 1;
}
/*---------------------------------------------------------------------------*/
@ -233,7 +246,7 @@ config_down(int type, int value)
NVIC_EnableIRQ(BUTTON_DOWN_VECTOR);
gpio_register_callback(btn_callback, BUTTON_DOWN_PORT, BUTTON_DOWN_PIN);
register_btn_callback(BUTTON_DOWN_PORT, BUTTON_DOWN_PIN);
return 1;
}
/*---------------------------------------------------------------------------*/

View File

@ -98,9 +98,6 @@
#define CC_CONF_VA_ARGS 1
#define CC_CONF_INLINE inline
#define CCIF
#define CLIF
/* These names are deprecated, use C99 names. */
#include <inttypes.h>
typedef uint8_t u8_t;

View File

@ -217,9 +217,6 @@ typedef uint32_t rtimer_clock_t;
#define CC_CONF_VA_ARGS 1
#define CC_CONF_INLINE inline
#define CCIF
#define CLIF
#ifdef HAVE_STDINT_H
#include <stdint.h>
#else

View File

@ -58,9 +58,6 @@ int select_set_callback(int fd, const struct select_callback *callback);
#define EEPROM_CONF_SIZE 1024
#endif
#define CCIF
#define CLIF
/* These names are deprecated, use C99 names. */
typedef uint8_t u8_t;
typedef uint16_t u16_t;

View File

@ -111,7 +111,12 @@
static const struct select_callback *select_callback[SELECT_MAX];
static int select_max = 0;
static uint8_t serial_id[] = {0x01,0x02,0x03,0x04,0x05,0x06,0x07,0x08};
#ifdef PLATFORM_CONF_MAC_ADDR
static uint8_t mac_addr[] = PLATFORM_CONF_MAC_ADDR;
#else /* PLATFORM_CONF_MAC_ADDR */
static uint8_t mac_addr[] = { 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08 };
#endif /* PLATFORM_CONF_MAC_ADDR */
#if !NETSTACK_CONF_WITH_IPV6
static uint16_t node_id = 0x0102;
#endif /* !NETSTACK_CONF_WITH_IPV6 */
@ -177,12 +182,12 @@ set_lladdr(void)
memset(&addr, 0, sizeof(linkaddr_t));
#if NETSTACK_CONF_WITH_IPV6
memcpy(addr.u8, serial_id, sizeof(addr.u8));
memcpy(addr.u8, mac_addr, sizeof(addr.u8));
#else
if(node_id == 0) {
int i;
for(i = 0; i < sizeof(linkaddr_t); ++i) {
addr.u8[i] = serial_id[7 - i];
addr.u8[i] = mac_addr[7 - i];
}
} else {
addr.u8[0] = node_id & 0xff;

View File

@ -41,6 +41,7 @@
#define CONTIKI_CONF_H
#include <stdint.h>
#include <inttypes.h>
/*---------------------------------------------------------------------------*/
/* Include Project Specific conf */
#ifdef PROJECT_CONF_PATH

View File

@ -50,6 +50,7 @@
#include <stdint.h>
#include <string.h>
#include <inttypes.h>
/*---------------------------------------------------------------------------*/
/* Include Project Specific conf */
#ifdef PROJECT_CONF_PATH

View File

@ -95,15 +95,8 @@ value(int type)
return 0;
}
/*---------------------------------------------------------------------------*/
/**
* \brief Callback registered with the GPIO module. Gets fired with a button
* port/pin generates an interrupt
* \param port The port number that generated the interrupt
* \param pin The pin number that generated the interrupt. This is the pin
* absolute number (i.e. 0, 1, ..., 7), not a mask
*/
static void
btn_callback(uint8_t port, uint8_t pin)
button_press_handler(gpio_hal_pin_mask_t pin_mask)
{
if(!timer_expired(&debouncetimer)) {
return;
@ -124,6 +117,12 @@ btn_callback(uint8_t port, uint8_t pin)
sensors_changed(&button_sensor);
}
/*---------------------------------------------------------------------------*/
static gpio_hal_event_handler_t press_handler = {
.next = NULL,
.handler = button_press_handler,
.pin_mask = gpio_hal_pin_to_mask(BUTTON_USER_PIN) << (BUTTON_USER_PORT << 3),
};
/*---------------------------------------------------------------------------*/
/**
* \brief Init function for the User button.
* \param type SENSORS_ACTIVE: Activate / Deactivate the sensor (value == 1
@ -153,7 +152,7 @@ config_user(int type, int value)
ioc_set_over(BUTTON_USER_PORT, BUTTON_USER_PIN, IOC_OVERRIDE_PUE);
gpio_register_callback(btn_callback, BUTTON_USER_PORT, BUTTON_USER_PIN);
gpio_hal_register_handler(&press_handler);
break;
case SENSORS_ACTIVE:
if(value) {

View File

@ -38,6 +38,7 @@
#define CONTIKI_CONF_H
#include <stdint.h>
#include <inttypes.h>
/*---------------------------------------------------------------------------*/
/* Include Project Specific conf */
#ifdef PROJECT_CONF_PATH

View File

@ -39,7 +39,7 @@
#include "contiki.h"
#include "lib/sensors.h"
#include "launchpad/button-sensor.h"
#include "gpio-interrupt.h"
#include "gpio-hal.h"
#include "sys/timer.h"
#include "lpm.h"
@ -70,9 +70,9 @@ struct btn_timer {
static struct btn_timer left_timer, right_timer;
/*---------------------------------------------------------------------------*/
static void
button_press_handler(uint8_t ioid)
button_press_handler(gpio_hal_pin_mask_t pin_mask)
{
if(ioid == BOARD_IOID_KEY_LEFT) {
if(pin_mask & gpio_hal_pin_to_mask(BOARD_IOID_KEY_LEFT)) {
if(!timer_expired(&left_timer.debounce)) {
return;
}
@ -92,7 +92,7 @@ button_press_handler(uint8_t ioid)
}
}
if(ioid == BOARD_IOID_KEY_RIGHT) {
if(pin_mask & gpio_hal_pin_to_mask(BOARD_IOID_KEY_RIGHT)) {
if(BUTTON_SENSOR_ENABLE_SHUTDOWN == 0) {
if(!timer_expired(&right_timer.debounce)) {
return;
@ -117,6 +117,12 @@ button_press_handler(uint8_t ioid)
}
}
/*---------------------------------------------------------------------------*/
static gpio_hal_event_handler_t press_handler = {
.next = NULL,
.handler = button_press_handler,
.pin_mask = 0,
};
/*---------------------------------------------------------------------------*/
static void
config_buttons(int type, int c, uint32_t key)
{
@ -125,7 +131,8 @@ config_buttons(int type, int c, uint32_t key)
ti_lib_gpio_clear_event_dio(key);
ti_lib_rom_ioc_pin_type_gpio_input(key);
ti_lib_rom_ioc_port_configure_set(key, IOC_PORT_GPIO, BUTTON_GPIO_CFG);
gpio_interrupt_register_handler(key, button_press_handler);
press_handler.pin_mask |= gpio_hal_pin_to_mask(key);
gpio_hal_register_handler(&press_handler);
break;
case SENSORS_ACTIVE:
if(c) {

View File

@ -49,7 +49,7 @@
#include "contiki-net.h"
#include "leds.h"
#include "lpm.h"
#include "gpio-interrupt.h"
#include "dev/gpio-hal.h"
#include "dev/oscillators.h"
#include "ieee-addr.h"
#include "vims.h"
@ -138,7 +138,7 @@ platform_init_stage_one()
board_init();
gpio_interrupt_init();
gpio_hal_init();
leds_init();
fade(LEDS_RED);
@ -151,6 +151,7 @@ platform_init_stage_one()
*/
ti_lib_pwr_ctrl_io_freeze_disable();
ti_lib_rom_int_enable(INT_AON_GPIO_EDGE);
ti_lib_int_master_enable();
soc_rtc_init();

View File

@ -39,7 +39,7 @@
#include "contiki.h"
#include "lib/sensors.h"
#include "sensortag/button-sensor.h"
#include "gpio-interrupt.h"
#include "gpio-hal.h"
#include "sys/timer.h"
#include "lpm.h"
@ -73,9 +73,9 @@ static struct btn_timer left_timer, right_timer;
* \brief Handler for Sensortag-CC26XX button presses
*/
static void
button_press_handler(uint8_t ioid)
button_press_handler(gpio_hal_pin_mask_t pin_mask)
{
if(ioid == BOARD_IOID_KEY_LEFT) {
if(pin_mask & gpio_hal_pin_to_mask(BOARD_IOID_KEY_LEFT)) {
if(!timer_expired(&left_timer.debounce)) {
return;
}
@ -95,7 +95,7 @@ button_press_handler(uint8_t ioid)
}
}
if(ioid == BOARD_IOID_KEY_RIGHT) {
if(pin_mask & gpio_hal_pin_to_mask(BOARD_IOID_KEY_RIGHT)) {
if(BUTTON_SENSOR_ENABLE_SHUTDOWN == 0) {
if(!timer_expired(&right_timer.debounce)) {
return;
@ -120,6 +120,12 @@ button_press_handler(uint8_t ioid)
}
}
/*---------------------------------------------------------------------------*/
static gpio_hal_event_handler_t press_handler = {
.next = NULL,
.handler = button_press_handler,
.pin_mask = 0,
};
/*---------------------------------------------------------------------------*/
/**
* \brief Configuration function for the button sensor for all buttons.
*
@ -135,7 +141,8 @@ config_buttons(int type, int c, uint32_t key)
ti_lib_gpio_clear_event_dio(key);
ti_lib_rom_ioc_pin_type_gpio_input(key);
ti_lib_rom_ioc_port_configure_set(key, IOC_PORT_GPIO, BUTTON_GPIO_CFG);
gpio_interrupt_register_handler(key, button_press_handler);
press_handler.pin_mask |= gpio_hal_pin_to_mask(key);
gpio_hal_register_handler(&press_handler);
break;
case SENSORS_ACTIVE:
if(c) {

View File

@ -39,9 +39,9 @@
#include "contiki.h"
#include "sys/clock.h"
#include "sys/timer.h"
#include "dev/gpio-hal.h"
#include "lib/sensors.h"
#include "sensortag/reed-relay.h"
#include "gpio-interrupt.h"
#include "sys/timer.h"
#include "ti-lib.h"
@ -60,7 +60,7 @@ static struct timer debouncetimer;
* \brief Handler for Sensortag-CC26XX reed interrupts
*/
static void
reed_interrupt_handler(uint8_t ioid)
reed_interrupt_handler(gpio_hal_pin_mask_t pin_mask)
{
if(!timer_expired(&debouncetimer)) {
return;
@ -76,6 +76,12 @@ value(int type)
return (int)ti_lib_gpio_read_dio(BOARD_IOID_REED_RELAY);
}
/*---------------------------------------------------------------------------*/
static gpio_hal_event_handler_t event_handler = {
.next = NULL,
.handler = reed_interrupt_handler,
.pin_mask = gpio_hal_pin_to_mask(BOARD_IOID_REED_RELAY),
};
/*---------------------------------------------------------------------------*/
/**
* \brief Configuration function for the button sensor for all buttons.
*
@ -99,8 +105,7 @@ configure(int type, int value)
ti_lib_ioc_port_configure_set(BOARD_IOID_REED_RELAY, IOC_PORT_GPIO,
REED_IO_CFG);
gpio_interrupt_register_handler(BOARD_IOID_REED_RELAY,
reed_interrupt_handler);
gpio_hal_register_handler(&event_handler);
break;
case SENSORS_ACTIVE:
if(value) {

View File

@ -39,7 +39,7 @@
#include "contiki.h"
#include "lib/sensors.h"
#include "srf06/button-sensor.h"
#include "gpio-interrupt.h"
#include "gpio-hal.h"
#include "sys/timer.h"
#include "lpm.h"
@ -74,9 +74,9 @@ static struct btn_timer sel_timer, left_timer, right_timer, up_timer,
* \brief Handler for SmartRF button presses
*/
static void
button_press_handler(uint8_t ioid)
button_press_handler(gpio_hal_pin_mask_t pin_mask)
{
if(ioid == BOARD_IOID_KEY_SELECT) {
if(pin_mask & gpio_hal_pin_to_mask(BOARD_IOID_KEY_SELECT)) {
if(!timer_expired(&sel_timer.debounce)) {
return;
}
@ -96,7 +96,7 @@ button_press_handler(uint8_t ioid)
}
}
if(ioid == BOARD_IOID_KEY_LEFT) {
if(pin_mask & gpio_hal_pin_to_mask(BOARD_IOID_KEY_LEFT)) {
if(!timer_expired(&left_timer.debounce)) {
return;
}
@ -116,7 +116,7 @@ button_press_handler(uint8_t ioid)
}
}
if(ioid == BOARD_IOID_KEY_RIGHT) {
if(pin_mask & gpio_hal_pin_to_mask(BOARD_IOID_KEY_RIGHT)) {
if(BUTTON_SENSOR_ENABLE_SHUTDOWN == 0) {
if(!timer_expired(&right_timer.debounce)) {
return;
@ -140,7 +140,7 @@ button_press_handler(uint8_t ioid)
}
}
if(ioid == BOARD_IOID_KEY_UP) {
if(pin_mask & gpio_hal_pin_to_mask(BOARD_IOID_KEY_UP)) {
if(!timer_expired(&up_timer.debounce)) {
return;
}
@ -160,7 +160,7 @@ button_press_handler(uint8_t ioid)
}
}
if(ioid == BOARD_IOID_KEY_DOWN) {
if(pin_mask & gpio_hal_pin_to_mask(BOARD_IOID_KEY_DOWN)) {
if(!timer_expired(&down_timer.debounce)) {
return;
}
@ -181,6 +181,12 @@ button_press_handler(uint8_t ioid)
}
}
/*---------------------------------------------------------------------------*/
static gpio_hal_event_handler_t press_handler = {
.next = NULL,
.handler = button_press_handler,
.pin_mask = 0,
};
/*---------------------------------------------------------------------------*/
/**
* \brief Configuration function for the button sensor for all buttons.
*
@ -196,7 +202,8 @@ config_buttons(int type, int c, uint32_t key)
ti_lib_gpio_clear_event_dio(key);
ti_lib_rom_ioc_pin_type_gpio_input(key);
ti_lib_rom_ioc_port_configure_set(key, IOC_PORT_GPIO, BUTTON_GPIO_CFG);
gpio_interrupt_register_handler(key, button_press_handler);
press_handler.pin_mask |= gpio_hal_pin_to_mask(key);
gpio_hal_register_handler(&press_handler);
break;
case SENSORS_ACTIVE:
if(c) {

View File

@ -47,6 +47,7 @@
#include <stdint.h>
#include <string.h>
#include <inttypes.h>
/*---------------------------------------------------------------------------*/
/* Include Project Specific conf */
#ifdef PROJECT_CONF_PATH

View File

@ -43,6 +43,7 @@
#include "dev/nvic.h"
#include "dev/ioc.h"
#include "dev/gpio.h"
#include "dev/gpio-hal.h"
#include "dev/button-sensor.h"
#include "sys/timer.h"
#include "sys/ctimer.h"
@ -94,15 +95,8 @@ value(int type)
return 0;
}
/*---------------------------------------------------------------------------*/
/**
* \brief Callback registered with the GPIO module. Gets fired with a button
* port/pin generates an interrupt
* \param port The port number that generated the interrupt
* \param pin The pin number that generated the interrupt. This is the pin
* absolute number (i.e. 0, 1, ..., 7), not a mask
*/
static void
btn_callback(uint8_t port, uint8_t pin)
button_press_handler(gpio_hal_pin_mask_t pin_mask)
{
if(!timer_expired(&debouncetimer)) {
return;
@ -123,6 +117,12 @@ btn_callback(uint8_t port, uint8_t pin)
sensors_changed(&button_sensor);
}
/*---------------------------------------------------------------------------*/
static gpio_hal_event_handler_t press_handler = {
.next = NULL,
.handler = button_press_handler,
.pin_mask = gpio_hal_pin_to_mask(BUTTON_USER_PIN) << (BUTTON_USER_PORT << 3),
};
/*---------------------------------------------------------------------------*/
/**
* \brief Init function for the User button.
* \param type SENSORS_ACTIVE: Activate / Deactivate the sensor (value == 1
@ -152,7 +152,7 @@ config_user(int type, int value)
ioc_set_over(BUTTON_USER_PORT, BUTTON_USER_PIN, IOC_OVERRIDE_PUE);
gpio_register_callback(btn_callback, BUTTON_USER_PORT, BUTTON_USER_PIN);
gpio_hal_register_handler(&press_handler);
break;
case SENSORS_ACTIVE:
if(value) {

View File

@ -52,6 +52,7 @@
#include "dev/spi.h"
#include "dev/ssi.h"
#include "dev/gpio.h"
#include "dev/gpio-hal.h"
#include <stdio.h>
/*---------------------------------------------------------------------------*/
#define CC1200_SPI_CLK_PORT_BASE GPIO_PORT_TO_BASE(SPI0_CLK_PORT)
@ -92,7 +93,7 @@
extern int cc1200_rx_interrupt(void);
/*---------------------------------------------------------------------------*/
void
cc1200_int_handler(uint8_t port, uint8_t pin)
cc1200_int_handler(gpio_hal_pin_mask_t pin_mask)
{
/* To keep the gpio_register_callback happy */
cc1200_rx_interrupt();
@ -166,6 +167,14 @@ cc1200_arch_spi_rw(uint8_t *inbuf, const uint8_t *write_buf, uint16_t len)
return 0;
}
/*---------------------------------------------------------------------------*/
static gpio_hal_event_handler_t interrupt_handler = {
.next = NULL,
.handler = cc1200_int_handler,
.pin_mask =
(gpio_hal_pin_to_mask(CC1200_GDO0_PIN) << (CC1200_GDO0_PORT << 3)) |
(gpio_hal_pin_to_mask(CC1200_GDO2_PIN) << (CC1200_GDO2_PORT << 3))
};
/*---------------------------------------------------------------------------*/
void
cc1200_arch_gpio0_setup_irq(int rising)
{
@ -184,8 +193,7 @@ cc1200_arch_gpio0_setup_irq(int rising)
GPIO_ENABLE_INTERRUPT(CC1200_GDO0_PORT_BASE, CC1200_GDO0_PIN_MASK);
ioc_set_over(CC1200_GDO0_PORT, CC1200_GDO0_PIN, IOC_OVERRIDE_PUE);
NVIC_EnableIRQ(CC1200_GPIOx_VECTOR);
gpio_register_callback(cc1200_int_handler, CC1200_GDO0_PORT,
CC1200_GDO0_PIN);
gpio_hal_register_handler(&interrupt_handler);
}
/*---------------------------------------------------------------------------*/
void
@ -206,8 +214,7 @@ cc1200_arch_gpio2_setup_irq(int rising)
GPIO_ENABLE_INTERRUPT(CC1200_GDO2_PORT_BASE, CC1200_GDO2_PIN_MASK);
ioc_set_over(CC1200_GDO2_PORT, CC1200_GDO2_PIN, IOC_OVERRIDE_PUE);
NVIC_EnableIRQ(CC1200_GPIOx_VECTOR);
gpio_register_callback(cc1200_int_handler, CC1200_GDO2_PORT,
CC1200_GDO2_PIN);
gpio_hal_register_handler(&interrupt_handler);
}
/*---------------------------------------------------------------------------*/
void

View File

@ -735,7 +735,7 @@ rtcc_print(uint8_t value)
}
/*---------------------------------------------------------------------------*/
static void
rtcc_interrupt_handler(uint8_t port, uint8_t pin)
rtcc_interrupt_handler(gpio_hal_pin_mask_t pin_mask)
{
process_poll(&rtcc_int_process);
}
@ -912,6 +912,12 @@ rtcc_set_calibration(uint8_t mode, int32_t adjust)
return AB08_SUCCESS;
}
/*---------------------------------------------------------------------------*/
static gpio_hal_event_handler_t rtcc_handler = {
.next = NULL,
.handler = rtcc_interrupt_handler,
.pin_mask = gpio_hal_pin_to_mask(RTC_INT1_PIN) << (RTC_INT1_PORT << 3),
};
/*---------------------------------------------------------------------------*/
int8_t
rtcc_init(void)
{
@ -937,7 +943,7 @@ rtcc_init(void)
GPIO_DETECT_EDGE(RTC_INT1_PORT_BASE, RTC_INT1_PIN_MASK);
GPIO_TRIGGER_SINGLE_EDGE(RTC_INT1_PORT_BASE, RTC_INT1_PIN_MASK);
GPIO_DETECT_FALLING(RTC_INT1_PORT_BASE, RTC_INT1_PIN_MASK);
gpio_register_callback(rtcc_interrupt_handler, RTC_INT1_PORT, RTC_INT1_PIN);
gpio_hal_register_handler(&rtcc_handler);
/* Spin process until an interrupt is received */
process_start(&rtcc_int_process, NULL);

View File

@ -99,9 +99,18 @@
*/
/*---------------------------------------------------------------------------*/
/* In leds.h the LEDS_BLUE is defined by LED_YELLOW definition */
#define LEDS_GREEN (1 << 4) /**< LED1 (Green) -> PD4 */
#define LEDS_BLUE (1 << 3) /**< LED2 (Blue) -> PD3 */
#define LEDS_RED (1 << 5) /**< LED3 (Red) -> PD5 */
#define LEDS_GREEN_PIN 4
#define LEDS_GREEN (1 << LEDS_GREEN_PIN) /**< LED1 (Green) -> PD4 */
#define LEDS_BLUE_PIN 3
#define LEDS_BLUE (1 << LEDS_BLUE_PIN) /**< LED2 (Blue) -> PD3 */
#define LEDS_RED_PIN 5
#define LEDS_RED (1 << LEDS_RED_PIN) /**< LED3 (Red) -> PD5 */
#define LEDS_GREEN_PORT_BASE GPIO_D_BASE
#define LEDS_BLUE_PORT_BASE GPIO_D_BASE
#define LEDS_RED_PORT_BASE GPIO_D_BASE
#define LEDS_CONF_ALL (LEDS_GREEN | LEDS_BLUE | LEDS_RED)

View File

@ -99,9 +99,18 @@
*/
/*---------------------------------------------------------------------------*/
/* In leds.h the LEDS_BLUE is defined by LED_YELLOW definition */
#define LEDS_GREEN (1 << 4) /**< LED1 (Green) -> PD4 */
#define LEDS_BLUE (1 << 3) /**< LED2 (Blue) -> PD3 */
#define LEDS_RED (1 << 5) /**< LED3 (Red) -> PD5 */
#define LEDS_GREEN_PIN 4
#define LEDS_GREEN (1 << LEDS_GREEN_PIN) /**< LED1 (Green) -> PD4 */
#define LEDS_BLUE_PIN 3
#define LEDS_BLUE (1 << LEDS_BLUE_PIN) /**< LED2 (Blue) -> PD3 */
#define LEDS_RED_PIN 5
#define LEDS_RED (1 << LEDS_RED_PIN) /**< LED3 (Red) -> PD5 */
#define LEDS_GREEN_PORT_BASE GPIO_D_BASE
#define LEDS_BLUE_PORT_BASE GPIO_D_BASE
#define LEDS_RED_PORT_BASE GPIO_D_BASE
#define LEDS_CONF_ALL (LEDS_GREEN | LEDS_BLUE | LEDS_RED)

View File

@ -68,9 +68,18 @@
*/
/*---------------------------------------------------------------------------*/
/* In leds.h the LEDS_BLUE is defined by LED_YELLOW definition */
#define LEDS_GREEN (1 << 4) /**< LED1 (Green) -> PD4 */
#define LEDS_BLUE (1 << 3) /**< LED2 (Blue) -> PD3 */
#define LEDS_RED (1 << 5) /**< LED3 (Red) -> PD5 */
#define LEDS_GREEN_PIN 4
#define LEDS_GREEN (1 << LEDS_GREEN_PIN) /**< LED1 (Green) -> PD4 */
#define LEDS_BLUE_PIN 3
#define LEDS_BLUE (1 << LEDS_BLUE_PIN) /**< LED2 (Blue) -> PD3 */
#define LEDS_RED_PIN 5
#define LEDS_RED (1 << LEDS_RED_PIN) /**< LED3 (Red) -> PD5 */
#define LEDS_GREEN_PORT_BASE GPIO_D_BASE
#define LEDS_BLUE_PORT_BASE GPIO_D_BASE
#define LEDS_RED_PORT_BASE GPIO_D_BASE
#define LEDS_CONF_ALL (LEDS_GREEN | LEDS_BLUE | LEDS_RED)

View File

@ -103,9 +103,18 @@
*/
/*---------------------------------------------------------------------------*/
/* In leds.h the LEDS_BLUE is defined by LED_YELLOW definition */
#define LEDS_GREEN (1 << 4) /**< LED1 (Green) -> PD4 */
#define LEDS_BLUE (1 << 3) /**< LED2 (Blue) -> PD3 */
#define LEDS_RED (1 << 5) /**< LED3 (Red) -> PD5 */
#define LEDS_GREEN_PIN 4
#define LEDS_GREEN (1 << LEDS_GREEN_PIN) /**< LED1 (Green) -> PD4 */
#define LEDS_BLUE_PIN 3
#define LEDS_BLUE (1 << LEDS_BLUE_PIN) /**< LED2 (Blue) -> PD3 */
#define LEDS_RED_PIN 5
#define LEDS_RED (1 << LEDS_RED_PIN) /**< LED3 (Red) -> PD5 */
#define LEDS_GREEN_PORT_BASE GPIO_D_BASE
#define LEDS_BLUE_PORT_BASE GPIO_D_BASE
#define LEDS_RED_PORT_BASE GPIO_D_BASE
#define LEDS_CONF_ALL (LEDS_GREEN | LEDS_BLUE | LEDS_RED)

View File

@ -106,15 +106,18 @@
*/
/*---------------------------------------------------------------------------*/
#define LEDS_RED 1 /**< LED1 (Red) -> PD4 */
#define LEDS_RED_PIN_MASK (1 << 4)
#define LEDS_RED_PIN 4
#define LEDS_RED_PIN_MASK (1 << LEDS_RED_PIN)
#define LEDS_RED_PORT_BASE GPIO_D_BASE
#define LEDS_GREEN 2 /**< LED2 (Green) -> PB7 */
#define LEDS_GREEN_PIN_MASK (1 << 7)
#define LEDS_GREEN_PIN 7
#define LEDS_GREEN_PIN_MASK (1 << LEDS_GREEN_PIN)
#define LEDS_GREEN_PORT_BASE GPIO_B_BASE
#define LEDS_BLUE 4 /**< LED3 (Blue) -> PB6 */
#define LEDS_BLUE_PIN_MASK (1 << 6)
#define LEDS_BLUE_PIN 6
#define LEDS_BLUE_PIN_MASK (1 << LEDS_BLUE_PIN)
#define LEDS_BLUE_PORT_BASE GPIO_B_BASE
#define LEDS_CONF_ALL (LEDS_GREEN | LEDS_BLUE | LEDS_RED) /* 7 */

View File

@ -314,7 +314,7 @@ add_req_handler(const linkaddr_t *peer_addr,
sizeof(sixp_pkt_cell_options_t) +
sizeof(sixp_pkt_num_cells_t) +
sizeof(sf_plugtest_cell_t))) {
LOG_ERR("invalid Add Request length: %u\n", (unsigned int)body_len);
LOG_ERR("invalid Add Request length: %lu\n", (unsigned long)body_len);
}
assert(
sixp_pkt_get_cell_options(SIXP_PKT_TYPE_REQUEST,
@ -359,7 +359,7 @@ add_res_handler(const linkaddr_t *peer_addr, sixp_pkt_rc_t rc,
struct tsch_slotframe *slotframe;
if(body_len != 4) {
LOG_ERR("invalid Add Response length: %u\n", (unsigned int)body_len);
LOG_ERR("invalid Add Response length: %lu\n", (unsigned long)body_len);
return;
}
@ -399,7 +399,7 @@ delete_req_handler(const linkaddr_t *peer_addr,
sizeof(sixp_pkt_cell_options_t) +
sizeof(sixp_pkt_num_cells_t) +
sizeof(sf_plugtest_cell_t))) {
LOG_ERR("invalid Delete Request length: %u\n", (unsigned int)body_len);
LOG_ERR("invalid Delete Request length: %lu\n", (unsigned long)body_len);
}
assert(
sixp_pkt_get_cell_options(SIXP_PKT_TYPE_REQUEST,
@ -446,7 +446,7 @@ delete_res_handler(const linkaddr_t *peer_addr, sixp_pkt_rc_t rc,
uint16_t timeslot;
if(body_len != 4) {
LOG_ERR("invalid Delete Response length: %u\n", (unsigned int)body_len);
LOG_ERR("invalid Delete Response length: %lu\n", (unsigned long)body_len);
return;
}
@ -489,7 +489,7 @@ count_req_handler(const linkaddr_t *peer_addr,
assert(peer_addr != NULL && body != NULL);
if(body_len != (sizeof(sixp_pkt_metadata_t) +
sizeof(sixp_pkt_cell_options_t))) {
LOG_ERR("invalid Count Request length: %u\n", (unsigned int)body_len);
LOG_ERR("invalid Count Request length: %lu\n", (unsigned long)body_len);
}
assert(
sixp_pkt_get_cell_options(SIXP_PKT_TYPE_REQUEST,
@ -534,7 +534,7 @@ count_res_handler(const linkaddr_t *peer_addr, sixp_pkt_rc_t rc,
sixp_pkt_total_num_cells_t total_num_cells;
if(body_len != 2) {
LOG_ERR("invalid Count Response length: %u\n", (unsigned int)body_len);
LOG_ERR("invalid Count Response length: %lu\n", (unsigned long)body_len);
return;
}
@ -570,7 +570,7 @@ list_req_handler(const linkaddr_t *peer_addr,
sizeof(sixp_pkt_reserved_t) +
sizeof(sixp_pkt_offset_t) +
sizeof(sixp_pkt_max_num_cells_t))) {
LOG_ERR("invalid List Request length: %u\n", (unsigned int)body_len);
LOG_ERR("invalid List Request length: %lu\n", (unsigned long)body_len);
}
assert(
@ -679,7 +679,7 @@ clear_req_handler(const linkaddr_t *peer_addr,
assert(peer_addr != NULL && body != NULL);
if(body_len != sizeof(sixp_pkt_metadata_t)) {
LOG_ERR("invalid Clear Request length: %u\n", (unsigned int)body_len);
LOG_ERR("invalid Clear Request length: %lu\n", (unsigned long)body_len);
}
if((slotframe = tsch_schedule_get_slotframe_by_handle(0)) == NULL) {
@ -717,7 +717,7 @@ clear_res_handler(const linkaddr_t *peer_addr, sixp_pkt_rc_t rc,
}
if(body_len != 0) {
LOG_ERR("invalid Clear Response length: %u\n", (unsigned int)body_len);
LOG_ERR("invalid Clear Response length: %lu\n", (unsigned long)body_len);
return;
}

View File

@ -82,7 +82,7 @@
/* Save some space to fit the limited RAM of the z1 */
#define UIP_CONF_TCP 0
#define QUEUEBUF_CONF_NUM 2
#define RPL_NS_CONF_LINK_NUM 2
#define NETSTACK_MAX_ROUTE_ENTRIES 2
#define NBR_TABLE_CONF_MAX_NEIGHBORS 2
#define UIP_CONF_ND6_SEND_NA 0
#define SICSLOWPAN_CONF_FRAG 0

View File

@ -0,0 +1,10 @@
CONTIKI_PROJECT = gpio-hal-example
CONTIKI = ../../..
include $(CONTIKI)/Makefile.identify-target
MODULES_REL += $(TARGET)
all: $(CONTIKI_PROJECT)
include $(CONTIKI)/Makefile.include

View File

@ -0,0 +1,36 @@
# GPIO HAL Example
This example demonstrates and tests the functionality of the GPIO HAL. You can
use it to:
* Understand the logic of the GPIO HAL.
* Test your implementation of arch-specific GPIO HAL components if you are
developing a new port.
This example assumes a device with:
* 3 output pins (e.g. LEDs).
* 1 button.
# Supported devices
This example is expected to work off-the-shelf on the following boards:
* All CC13xx/CC26xx devices
* All CC2538 devices
# Extending for other platforms
Create a sub-directory with the same name as your platform. For example, for
platform `my-new-platform` create a subdirectory called `my-new-platform`.
Source files in this directory will be compiled automatically. In the most
simple case, all you will need is a source file called e.g. `pins.c` (it's OK
to use a different filename). In this file, you will need to provide
definitions of the variables used by the example to manipulate pins. These
variables are:
* `out_pin1`, `out_pin2` and `out_pin3` for output pins.
* `btn_pin` for the button pin.
Assign to those variables a value that corresponds to the output pin in your
board that you wish to test with the example. For example, if you have a LED
connected to pin 20, then you will need to
gpio_hal_pin_t out_pin1 = 20;

View File

@ -1,10 +1,11 @@
/*
* Copyright (c) 2014, Texas Instruments Incorporated - http://www.ti.com/
* Copyright (c) 2017, George Oikonomou - http://www.spd.gr
* 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
@ -28,44 +29,23 @@
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup cc26xx
* @{
#include "contiki.h"
#include "dev/gpio-hal.h"
/*---------------------------------------------------------------------------*/
/*
* LEDs on the SmartRF06 (EB and BB) are connected as follows:
* - LED1 (Red) -> PC0
* - LED2 (Yellow) -> PC1 (gpio_hal_pin_t 17)
* - LED3 (Green) -> PC2 (gpio_hal_pin_t 18)
* - LED4 (Orange) -> PC3 (gpio_hal_pin_t 19)
*
* \defgroup cc26xx-gpio-interrupts CC13xx/CC26xx GPIO interrupt handling
*
* The CC13xx/CC26xx GPIO interrupt handler and an API which can be used by
* other parts of the code when they wish to be notified of a GPIO interrupt
*
* @{
*
* \file
* Header file for the CC13xx/CC26xx GPIO interrupt management
* LED1 shares the same pin with the USB pullup, so here we'll use PC1, PC2
* and PC3.
*/
gpio_hal_pin_t out_pin1 = 17;
gpio_hal_pin_t out_pin2 = 18;
gpio_hal_pin_t out_pin3 = 19;
/*---------------------------------------------------------------------------*/
#ifndef GPIO_INTERRUPT_H_
#define GPIO_INTERRUPT_H_
/* Button pin: Button select, PA3 */
gpio_hal_pin_t btn_pin = 3;
/*---------------------------------------------------------------------------*/
#include <stdint.h>
/*---------------------------------------------------------------------------*/
typedef void (*gpio_interrupt_handler_t)(uint8_t ioid);
/*---------------------------------------------------------------------------*/
/** \brief Initialise the GPIO interrupt handling module */
void gpio_interrupt_init(void);
/**
* \brief Register a GPIO interrupt handler
* \param f Pointer to a handler to be called when an interrupt is raised on
* ioid
* \param ioid Associate \a f with this ioid. \e ioid must be specified with
* its numeric representation (0, 1, .. 31). Defines for these
* numeric representations are IOID_x
*/
void gpio_interrupt_register_handler(uint8_t ioid, gpio_interrupt_handler_t f);
#endif /* GPIO_INTERRUPT_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View File

@ -0,0 +1,139 @@
/*
* Copyright (c) 2017, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "dev/gpio-hal.h"
#include "sys/etimer.h"
#include "lib/sensors.h"
#include "dev/button-sensor.h"
#include <stdio.h>
/*---------------------------------------------------------------------------*/
extern gpio_hal_pin_t out_pin1, out_pin2, out_pin3;
extern gpio_hal_pin_t btn_pin;
/*---------------------------------------------------------------------------*/
static struct etimer et;
static uint8_t counter;
/*---------------------------------------------------------------------------*/
PROCESS(gpio_hal_example, "GPIO HAL Example");
AUTOSTART_PROCESSES(&gpio_hal_example);
/*---------------------------------------------------------------------------*/
PROCESS_THREAD(gpio_hal_example, ev, data)
{
PROCESS_BEGIN();
counter = 0;
etimer_set(&et, CLOCK_SECOND);
while(1) {
PROCESS_YIELD();
if(ev == PROCESS_EVENT_TIMER && data == &et) {
if((counter & 7) == 0) {
/* Set output and test write, high */
gpio_hal_arch_pin_set_output(out_pin1);
gpio_hal_arch_pin_set_output(out_pin2);
gpio_hal_arch_pin_set_output(out_pin3);
gpio_hal_arch_write_pin(out_pin1, 1);
gpio_hal_arch_write_pins(
gpio_hal_pin_to_mask(out_pin2) | gpio_hal_pin_to_mask(out_pin3),
gpio_hal_pin_to_mask(out_pin2) | gpio_hal_pin_to_mask(out_pin3));
} else if((counter & 7) == 1) {
/* Test write, low */
gpio_hal_arch_write_pin(out_pin1, 0);
gpio_hal_arch_write_pins(
gpio_hal_pin_to_mask(out_pin2) | gpio_hal_pin_to_mask(out_pin3), 0);
} else if((counter & 7) == 2) {
/* Test set */
gpio_hal_arch_set_pin(out_pin1);
gpio_hal_arch_set_pins(
gpio_hal_pin_to_mask(out_pin2) | gpio_hal_pin_to_mask(out_pin3));
} else if((counter & 7) == 3) {
/* Test clear */
gpio_hal_arch_clear_pin(out_pin1);
gpio_hal_arch_clear_pins(
gpio_hal_pin_to_mask(out_pin2) | gpio_hal_pin_to_mask(out_pin3));
} else if((counter & 7) == 4) {
/* Test toggle (should go high) */
gpio_hal_arch_toggle_pin(out_pin1);
gpio_hal_arch_toggle_pins(
gpio_hal_pin_to_mask(out_pin2) | gpio_hal_pin_to_mask(out_pin3));
} else if((counter & 7) == 5) {
/* Test toggle (should go low) */
gpio_hal_arch_toggle_pin(out_pin1);
gpio_hal_arch_toggle_pins(
gpio_hal_pin_to_mask(out_pin2) | gpio_hal_pin_to_mask(out_pin3));
} else if((counter & 7) == 6) {
/* Set to input and then set. Should stay off */
gpio_hal_arch_pin_set_input(out_pin1);
gpio_hal_arch_pin_set_input(out_pin2);
gpio_hal_arch_pin_set_input(out_pin3);
gpio_hal_arch_set_pin(out_pin1);
gpio_hal_arch_set_pins(
gpio_hal_pin_to_mask(out_pin2) | gpio_hal_pin_to_mask(out_pin3));
} else if((counter & 7) == 7) {
/* Toggle button interrupt */
gpio_hal_pin_cfg_t interrupt;
interrupt = gpio_hal_arch_pin_cfg_get(btn_pin) &
GPIO_HAL_PIN_CFG_INT_ENABLE;
if(interrupt == 0) {
printf("Enabling button interrupt\n");
gpio_hal_arch_interrupt_enable(btn_pin);
} else {
printf("Disabling button interrupt\n");
gpio_hal_arch_interrupt_disable(btn_pin);
}
}
/* Test read */
printf("%u: Pins are 1-%u, 2=%u, 3=%u, mask=0x%08lx\n", counter & 7,
gpio_hal_arch_read_pin(out_pin1),
gpio_hal_arch_read_pin(out_pin2),
gpio_hal_arch_read_pin(out_pin3),
gpio_hal_arch_read_pins(gpio_hal_pin_to_mask(out_pin1) |
gpio_hal_pin_to_mask(out_pin2) |
gpio_hal_pin_to_mask(out_pin3)));
counter++;
etimer_set(&et, CLOCK_SECOND);
} else if(ev == sensors_event && data == &button_sensor) {
printf("Button event\n");
}
}
PROCESS_END();
}
/*---------------------------------------------------------------------------*/

View File

@ -0,0 +1,48 @@
/*
* Copyright (c) 2017, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "dev/gpio-hal.h"
/*---------------------------------------------------------------------------*/
/*
* LEDs on the OpenMote-CC2538 are connected as follows:
* - LED1 (Red) -> PC4 (gpio_hal_pin_t 20)
* - LED2 (Yellow) -> PC6 (gpio_hal_pin_t 22)
* - LED3 (Green) -> PC7 (gpio_hal_pin_t 23)
* - LED4 (Orange) -> PC5
*/
gpio_hal_pin_t out_pin1 = 20;
gpio_hal_pin_t out_pin2 = 22;
gpio_hal_pin_t out_pin3 = 23;
/*---------------------------------------------------------------------------*/
/* Button pin: PC3 */
gpio_hal_pin_t btn_pin = 19;
/*---------------------------------------------------------------------------*/

View File

@ -0,0 +1,45 @@
/*
* Copyright (c) 2017, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "dev/gpio-hal.h"
/*---------------------------------------------------------------------------*/
#if CONTIKI_BOARD_SENSORTAG_CC1350
#define PINS2_AND_3 BOARD_IOID_LED_1
#else
#define PINS2_AND_3 BOARD_IOID_LED_2
#endif
gpio_hal_pin_t out_pin1 = BOARD_IOID_LED_1;
gpio_hal_pin_t out_pin2 = PINS2_AND_3;
gpio_hal_pin_t out_pin3 = PINS2_AND_3;
/*---------------------------------------------------------------------------*/
gpio_hal_pin_t btn_pin = BOARD_IOID_KEY_LEFT;
/*---------------------------------------------------------------------------*/

View File

@ -0,0 +1,42 @@
/*
* Copyright (c) 2017, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "dev/gpio-hal.h"
/*---------------------------------------------------------------------------*/
#define BASE_TO_PORT_NUM(base) (((base) - GPIO_A_BASE) >> 12)
gpio_hal_pin_t out_pin1 = (BASE_TO_PORT_NUM(LEDS_GREEN_PORT_BASE) << 3) + LEDS_GREEN_PIN;
gpio_hal_pin_t out_pin2 = (BASE_TO_PORT_NUM(LEDS_BLUE_PORT_BASE) << 3) + LEDS_BLUE_PIN;
gpio_hal_pin_t out_pin3 = (BASE_TO_PORT_NUM(LEDS_RED_PORT_BASE) << 3) + LEDS_RED_PIN;
/*---------------------------------------------------------------------------*/
gpio_hal_pin_t btn_pin = (BUTTON_USER_PORT << 3) + BUTTON_USER_PIN;
/*---------------------------------------------------------------------------*/

View File

@ -83,7 +83,7 @@ multicast_send(void)
PRINTF("Send to: ");
PRINT6ADDR(&mcast_conn->ripaddr);
PRINTF(" Remote Port %u,", uip_ntohs(mcast_conn->rport));
PRINTF(" (msg=0x%08lx)", (unsigned long)uip_ntohl(*((uint32_t *)buf)));
PRINTF(" (msg=0x%08"PRIx32")", uip_ntohl(*((uint32_t *)buf)));
PRINTF(" %lu bytes\n", (unsigned long)sizeof(id));
seq_id++;

97
os/dev/gpio-hal.c Normal file
View File

@ -0,0 +1,97 @@
/*
* Copyright (c) 2017, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup gpio-hal
* @{
*
* \file
* Implementation of the platform-independent aspects of the GPIO HAL
*/
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include "dev/gpio-hal.h"
#include "lib/list.h"
#include <stdint.h>
#include <string.h>
/*---------------------------------------------------------------------------*/
LIST(handlers);
/*---------------------------------------------------------------------------*/
void
gpio_hal_register_handler(gpio_hal_event_handler_t *handler)
{
list_add(handlers, handler);
}
/*---------------------------------------------------------------------------*/
void
gpio_hal_event_handler(gpio_hal_pin_mask_t pins)
{
gpio_hal_event_handler_t *this;
for(this = list_head(handlers); this != NULL; this = this->next) {
if(pins & this->pin_mask) {
if(this->handler != NULL) {
this->handler(pins & this->pin_mask);
}
}
}
}
/*---------------------------------------------------------------------------*/
void
gpio_hal_init()
{
list_init(handlers);
}
/*---------------------------------------------------------------------------*/
#if GPIO_HAL_ARCH_SW_TOGGLE
/*---------------------------------------------------------------------------*/
void
gpio_hal_arch_toggle_pin(gpio_hal_pin_t pin)
{
if(pin >= GPIO_HAL_PIN_COUNT) {
return;
}
gpio_hal_arch_write_pin(pin, gpio_hal_arch_read_pin(pin) ^ 1);
}
/*---------------------------------------------------------------------------*/
void
gpio_hal_arch_toggle_pins(gpio_hal_pin_mask_t pins)
{
gpio_hal_arch_write_pins(pins, ~gpio_hal_arch_read_pins(pins));
}
/*---------------------------------------------------------------------------*/
#endif /* GPIO_HAL_ARCH_SW_TOGGLE */
/*---------------------------------------------------------------------------*/
/**
* @}
*/

495
os/dev/gpio-hal.h Normal file
View File

@ -0,0 +1,495 @@
/*
* Copyright (c) 2017, George Oikonomou - http://www.spd.gr
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
* STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
* OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*---------------------------------------------------------------------------*/
/**
* \addtogroup dev
* @{
*
* \defgroup gpio-hal GPIO Hardware Abstraction Layer
*
* The GPIO HAL provides a set of common functions that can be used in a
* platform-independent fashion.
*
* Internally, the GPIO HAL handles edge detection handling and also provides
* fallback functions for GPIO pin toggling if the hardware does not have
* a direct method of toggling pins through direct register access.
*
* @{
*
* \file
* Header file for the GPIO HAL
*/
/*---------------------------------------------------------------------------*/
#ifndef GPIO_HAL_H_
#define GPIO_HAL_H_
/*---------------------------------------------------------------------------*/
#include "contiki.h"
#include <stdint.h>
/*---------------------------------------------------------------------------*/
/**
* \brief Specifies whether software-based pin toggle is required
*
* Some MCUs allow GPIO pin toggling via direct register access. For these
* MCUs, define GPIO_HAL_CONF_ARCH_SW_TOGGLE to 0 and then implement
* gpio_hal_arch_toggle_pin() and gpio_hal_arch_toggle_pins()
*
* \sa gpio_hal_arch_toggle_pin()
* \sa gpio_hal_arch_toggle_pins()
*/
#ifdef GPIO_HAL_CONF_ARCH_SW_TOGGLE
#define GPIO_HAL_ARCH_SW_TOGGLE GPIO_HAL_CONF_ARCH_SW_TOGGLE
#else
#define GPIO_HAL_ARCH_SW_TOGGLE 1
#endif
/*---------------------------------------------------------------------------*/
/**
* \brief GPIO pin number representation
*/
typedef uint8_t gpio_hal_pin_t;
/**
* \brief GPIO pin configuration
*
* A logical representation of a pin's configuration. It is an OR combination
* of GPIO_HAL_PIN_CFG_xyz macros.
*/
typedef uint8_t gpio_hal_pin_cfg_t;
#ifdef GPIO_HAL_CONF_PIN_COUNT
#define GPIO_HAL_PIN_COUNT GPIO_HAL_CONF_PIN_COUNT
#else
#define GPIO_HAL_PIN_COUNT 32
#endif
#if GPIO_HAL_PIN_COUNT > 32
typedef uint64_t gpio_hal_pin_mask_t;
#else
/**
* \brief GPIO pin mask representation
*/
typedef uint32_t gpio_hal_pin_mask_t;
#endif
typedef void (*gpio_hal_callback_t)(gpio_hal_pin_mask_t pin_mask);
/*---------------------------------------------------------------------------*/
#define GPIO_HAL_PIN_CFG_PULL_NONE 0x00
#define GPIO_HAL_PIN_CFG_PULL_UP 0x01
#define GPIO_HAL_PIN_CFG_PULL_DOWN 0x02
#define GPIO_HAL_PIN_CFG_PULL_MASK (GPIO_HAL_PIN_CFG_PULL_UP | \
GPIO_HAL_PIN_CFG_PULL_DOWN)
#define GPIO_HAL_PIN_CFG_EDGE_NONE 0x00
#define GPIO_HAL_PIN_CFG_EDGE_RISING 0x04
#define GPIO_HAL_PIN_CFG_EDGE_FALLING 0x08
#define GPIO_HAL_PIN_CFG_EDGE_BOTH (GPIO_HAL_PIN_CFG_EDGE_RISING | \
GPIO_HAL_PIN_CFG_EDGE_FALLING)
#define GPIO_HAL_PIN_CFG_INT_DISABLE 0x00
#define GPIO_HAL_PIN_CFG_INT_ENABLE 0x80
#define GPIO_HAL_PIN_CFG_INT_MASK 0x80
/*---------------------------------------------------------------------------*/
/**
* \brief Datatype for GPIO event handlers
*
* A GPIO event handler is a function that gets called whenever a pin triggers
* an event. The same handler can be registered to handle events for more than
* one pin by setting the respective pin's position but in \e pin_mask.
*/
typedef struct gpio_hal_event_handler_s {
struct gpio_hal_event_handler_s *next;
gpio_hal_callback_t handler;
gpio_hal_pin_mask_t pin_mask;
} gpio_hal_event_handler_t;
/*---------------------------------------------------------------------------*/
/**
* \name Core GPIO functions
*
* Functions implemented by the HAL itself
* @{
*/
/**
* \brief Initialise the GPIO HAL
*/
void gpio_hal_init(void);
/**
* \brief Register a function to be called whenever a pin triggers an event
* \param handler The handler representation
*
* The handler must be pre-allocated statically by the caller.
*
* This function can be used to register a function to be called by the HAL
* whenever a GPIO interrupt occurs.
*
* \sa gpio_hal_event_handler
*/
void gpio_hal_register_handler(gpio_hal_event_handler_t *handler);
/**
* \brief The platform-independent GPIO event handler
* \param pins OR mask of pins that generated an event
*
* Whenever a GPIO input interrupt occurs (edge or level detection) and an ISR
* is triggered, the ISR must call this function, passing as argument an ORd
* mask of the pins that triggered the interrupt. This function will then
* call the registered event handlers (if any) for the pins that triggered the
* event. The platform code should make no assumptions as to the order that
* the handlers will be called.
*
* If a pin set in the mask has an event handler registered, this function
* will call the registered handler.
*
* This function will not clear any CPU interrupt flags, this should be done
* by the calling ISR.
*
* \sa gpio_hal_register_handler
*/
void gpio_hal_event_handler(gpio_hal_pin_mask_t pins);
/**
* \brief Convert a pin to a pin mask
* \param pin The pin
* \return The corresponding mask
*/
#define gpio_hal_pin_to_mask(pin) (1 << (pin))
/** @} */
/*---------------------------------------------------------------------------*/
/**
* \name Functions to be provided by the platform
*
* All the functions below must be provided by the platform's developer. The
* HAL offers the developer a number of options of how to provide the required
* functionality.
*
* - The developer can provide a symbol. For example, the developer can create
* a .c file and implement a function called gpio_hal_arch_set_pin()
* - The developer can provide a function-like macro that has the same name as
* the function declared here. In this scenario, the declaration here will
* be removed by the pre-processor. For example, the developer can do
* something like:
*
* \code
* #define gpio_hal_arch_write_pin(p, v) platform_sdk_function(p, v)
* \endcode
*
* - The developer can provide a static inline implementation. For this to
* work, the developer can do something like:
*
* \code
* #define gpio_hal_arch_set_pin(p) set_pin(p)
* static inline void set_pin(gpio_hal_pin_t pin) { ... }
* \endcode
*
* In the latter two cases, the developer will likely provide implementations
* in a header file. In this scenario, one of the platform's configuration
* files must define GPIO_HAL_CONF_ARCH_HDR_PATH to the name of this header
* file. For example:
*
* \code
* #define GPIO_HAL_CONF_ARCH_HDR_PATH "dev/gpio-hal-arch.h"
* \endcode
*
* @{
*/
/*---------------------------------------------------------------------------*/
/* Include Arch-Specific conf */
#ifdef GPIO_HAL_CONF_ARCH_HDR_PATH
#include GPIO_HAL_CONF_ARCH_HDR_PATH
#endif /* GPIO_HAL_CONF_ARCH_HDR_PATH */
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_interrupt_enable
/**
* \brief Enable interrupts for a gpio pin
* \param pin The GPIO pin number (0...GPIO_HAL_PIN_COUNT - 1)
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_interrupt_enable(gpio_hal_pin_t pin);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_interrupt_disable
/**
* \brief Disable interrupts for a gpio pin
* \param pin The GPIO pin number (0...GPIO_HAL_PIN_COUNT - 1)
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_interrupt_disable(gpio_hal_pin_t pin);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_pin_cfg_set
/**
* \brief Configure a gpio pin
* \param pin The GPIO pin number (0...GPIO_HAL_PIN_COUNT - 1)
* \param cfg The configuration
*
* \e cfg is an OR mask of GPIO_HAL_PIN_CFG_xyz
*
* The implementation of this function also has to make sure that \e pin is
* configured as software-controlled GPIO.
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_pin_cfg_set(gpio_hal_pin_t pin, gpio_hal_pin_cfg_t cfg);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_pin_cfg_get
/**
* \brief Read the configuration of a GPIO pin
* \param pin The GPIO pin number (0...GPIO_HAL_PIN_COUNT - 1)
* \return An OR mask of GPIO_HAL_PIN_CFG_xyz
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
gpio_hal_pin_cfg_t gpio_hal_arch_pin_cfg_get(gpio_hal_pin_t pin);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_pin_set_input
/**
* \brief Configure a pin as GPIO input
* \param pin The GPIO pin number (0...GPIO_HAL_PIN_COUNT - 1)
*
* The implementation of this function also has to make sure that \e pin is
* configured as software-controlled GPIO.
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_pin_set_input(gpio_hal_pin_t pin);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_pin_set_output
/**
* \brief Configure a pin as GPIO output
* \param pin The GPIO pin number (0...GPIO_HAL_PIN_COUNT - 1)
*
* The implementation of this function also has to make sure that \e pin is
* configured as software-controlled GPIO.
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_pin_set_output(gpio_hal_pin_t pin);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_set_pin
/**
* \brief Set a GPIO pin to logical high
* \param pin The GPIO pin number (0...GPIO_HAL_PIN_COUNT - 1)
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_set_pin(gpio_hal_pin_t pin);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_clear_pin
/**
* \brief Clear a GPIO pin (logical low)
* \param pin The GPIO pin number (0...GPIO_HAL_PIN_COUNT - 1)
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_clear_pin(gpio_hal_pin_t pin);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_toggle_pin
/**
* \brief Toggle a GPIO pin
* \param pin The GPIO pin number (0...GPIO_HAL_PIN_COUNT - 1)
*
* Some MCUs allow GPIO pin toggling directly via register access. In this
* case, it is a good idea to provide an implementation of this function.
* However, a default, software-based implementation is also provided by the
* HAL and can be used if the MCU does not have a pin toggle register. To use
* the HAL function, define GPIO_HAL_ARCH_SW_TOGGLE as 1. To provide your own
* implementation, define GPIO_HAL_ARCH_SW_TOGGLE as 0.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_toggle_pin(gpio_hal_pin_t pin);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_read_pin
/**
* \brief Read a GPIO pin
* \param pin The GPIO pin number (0...GPIO_HAL_PIN_COUNT - 1)
* \retval 0 The pin is logical low
* \retval 1 The pin is logical high
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
uint8_t gpio_hal_arch_read_pin(gpio_hal_pin_t pin);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_write_pin
/**
* \brief Write a GPIO pin
* \param pin The GPIO pin number (0...GPIO_HAL_PIN_COUNT - 1)
* \param value 0: Logical low; 1: Logical high
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_write_pin(gpio_hal_pin_t pin, uint8_t value);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_set_pins
/**
* \brief Set multiple pins to logical high
* \param pins An ORd pin mask of the pins to set
*
* A pin will be set to logical high if its position in \e pins is set. For
* example you can set pins 0 and 3 by passing 0x09.
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_set_pins(gpio_hal_pin_mask_t pins);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_clear_pins
/**
* \brief Clear multiple pins to logical low
* \param pins An ORd pin mask of the pins to clear
*
* A pin will be set to logical low if its position in \e pins is set. For
* example you can clear pins 0 and 3 by passing 0x09.
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_clear_pins(gpio_hal_pin_mask_t pins);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_toggle_pins
/**
* \brief Toggle multiple pins
* \param pins An ORd pin mask of the pins to toggle
*
* A pin will be toggled if its position in \e pins is set. For example you
* can toggle pins 0 and 3 by passing 0x09.
*
* Some MCUs allow GPIO pin toggling directly via register access. In this
* case, it is a good idea to provide an implementation of this function.
* However, a default, software-based implementation is also provided by the
* HAL and can be used if the MCU does not have a pin toggle register. To use
* the HAL function, define GPIO_HAL_ARCH_SW_TOGGLE as 1. To provide your own
* implementation, define GPIO_HAL_ARCH_SW_TOGGLE as 0.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_toggle_pins(gpio_hal_pin_mask_t pins);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_read_pins
/**
* \brief Read multiple pins
* \param pins An ORd pin mask of the pins to read
* \retval An ORd mask of the pins that are high
*
* If the position of the pin in \e pins is set and the pin is logical high
* then the position of the pin in the return value will be set. For example,
* if you pass 0x09 as the value of \e pins and the return value is 0x08 then
* pin 3 is logical high and pin 0 is logical low.
*
* It is the platform developer's responsibility to provide an implementation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
gpio_hal_pin_mask_t gpio_hal_arch_read_pins(gpio_hal_pin_mask_t pins);
#endif
/*---------------------------------------------------------------------------*/
#ifndef gpio_hal_arch_write_pins
/**
* \brief Write multiple pins
* \param pins An ORd pin mask of the pins to write
* \param value An ORd mask of the value to write
*
* The function will modify GPIO pins that have their position in the mask set.
* pins, the function will write the value specified in the corresponding
* position in \e value.
* For example, you can set pin 3 and clear pin 0 by a single call to this
* function. To achieve this, \e pins must be 0x09 and \e value 0x08.
*
* It is the platform developer's responsibility to provide an implementation.
*
* There is no guarantee that this function will result in an atomic operation.
*
* The implementation can be provided as a global symbol, an inline function
* or a function-like macro, as described above.
*/
void gpio_hal_arch_write_pins(gpio_hal_pin_mask_t pins,
gpio_hal_pin_mask_t value);
#endif
/** @} */
/*---------------------------------------------------------------------------*/
#endif /* GPIO_HAL_H_ */
/*---------------------------------------------------------------------------*/
/**
* @}
* @}
*/

View File

@ -347,7 +347,7 @@ heapmem_alloc(size_t size)
chunk->line = line;
#endif
PRINTF("%s ptr %p size %u\n", __func__, GET_PTR(chunk), (unsigned)size);
PRINTF("%s ptr %p size %lu\n", __func__, GET_PTR(chunk), (unsigned long)size);
return GET_PTR(chunk);
}

View File

@ -82,8 +82,7 @@ progress_request(coap_request_state_t *state) {
coap_serialize_message(request, state->transaction->message);
coap_send_transaction(state->transaction);
LOG_DBG("Requested #%lu (MID %u)\n", (unsigned long)state->block_num,
request->mid);
LOG_DBG("Requested #%"PRIu32" (MID %u)\n", state->block_num, request->mid);
}
}
@ -120,8 +119,7 @@ coap_request_callback(void *callback_data, coap_message_t *response)
/* this is only for counting BLOCK2 blocks.*/
++(state->block_num);
} else {
LOG_WARN("WRONG BLOCK %lu/%lu\n", (unsigned long)res_block,
(unsigned long)state->block_num);
LOG_WARN("WRONG BLOCK %"PRIu32"/%"PRIu32"\n", res_block, state->block_num);
++block_error;
}

View File

@ -507,7 +507,7 @@ output_to_peer(struct dtls_context_t *ctx,
struct uip_udp_conn *udp_connection = dtls_get_app_data(ctx);
LOG_DBG("output_to DTLS peer [");
LOG_DBG_6ADDR(&session->ipaddr);
LOG_DBG_("]:%u %d bytes\n", uip_ntohs(session->port), (int)len);
LOG_DBG_("]:%u %ld bytes\n", uip_ntohs(session->port), (long)len);
uip_udp_packet_sendto(udp_connection, data, len,
&session->ipaddr, session->port);
return len;

View File

@ -528,7 +528,7 @@ coap_parse_message(coap_message_t *coap_pkt, uint8_t *data, uint16_t data_len)
case COAP_OPTION_MAX_AGE:
coap_pkt->max_age = coap_parse_int_option(current_option,
option_length);
LOG_DBG_("Max-Age [%lu]\n", (unsigned long)coap_pkt->max_age);
LOG_DBG_("Max-Age [%"PRIu32"]\n", coap_pkt->max_age);
break;
case COAP_OPTION_ETAG:
coap_pkt->etag_len = MIN(COAP_ETAG_LEN, option_length);
@ -638,7 +638,7 @@ coap_parse_message(coap_message_t *coap_pkt, uint8_t *data, uint16_t data_len)
case COAP_OPTION_OBSERVE:
coap_pkt->observe = coap_parse_int_option(current_option,
option_length);
LOG_DBG_("Observe [%lu]\n", (unsigned long)coap_pkt->observe);
LOG_DBG_("Observe [%"PRId32"]\n", coap_pkt->observe);
break;
case COAP_OPTION_BLOCK2:
coap_pkt->block2_num = coap_parse_int_option(current_option,
@ -666,11 +666,11 @@ coap_parse_message(coap_message_t *coap_pkt, uint8_t *data, uint16_t data_len)
break;
case COAP_OPTION_SIZE2:
coap_pkt->size2 = coap_parse_int_option(current_option, option_length);
LOG_DBG_("Size2 [%lu]\n", (unsigned long)coap_pkt->size2);
LOG_DBG_("Size2 [%"PRIu32"]\n", coap_pkt->size2);
break;
case COAP_OPTION_SIZE1:
coap_pkt->size1 = coap_parse_int_option(current_option, option_length);
LOG_DBG_("Size1 [%lu]\n", (unsigned long)coap_pkt->size1);
LOG_DBG_("Size1 [%"PRIu32"]\n", coap_pkt->size1);
break;
default:
LOG_DBG_("unknown (%u)\n", option_number);

View File

@ -55,7 +55,7 @@
/**
* Event that is broadcasted when a DNS name has been resolved.
*/
CCIF extern process_event_t resolv_event_found;
extern process_event_t resolv_event_found;
enum {
/** Hostname is fresh and usable. This response is cached and will eventually
@ -91,14 +91,14 @@ enum {
typedef uint8_t resolv_status_t;
/* Functions. */
CCIF resolv_status_t resolv_lookup(const char *name, uip_ipaddr_t ** ipaddr);
resolv_status_t resolv_lookup(const char *name, uip_ipaddr_t ** ipaddr);
CCIF void resolv_query(const char *name);
void resolv_query(const char *name);
#if RESOLV_CONF_SUPPORTS_MDNS
CCIF void resolv_set_hostname(const char *hostname);
void resolv_set_hostname(const char *hostname);
CCIF const char *resolv_get_hostname(void);
const char *resolv_get_hostname(void);
#endif
PROCESS_NAME(resolv_process);

View File

@ -671,8 +671,8 @@ compress_hdr_iphc(linkaddr_t *link_destaddr)
int ext_hdr_len;
struct uip_udp_hdr *udp_buf;
#if LOG_DBG_ENABLED
{ uint16_t ndx;
if(LOG_DBG_ENABLED) {
uint16_t ndx;
LOG_DBG("before compression (%d): ", UIP_IP_BUF->len[1]);
for(ndx = 0; ndx < UIP_IP_BUF->len[1] + 40; ndx++) {
uint8_t data = ((uint8_t *) (UIP_IP_BUF))[ndx];
@ -680,7 +680,6 @@ compress_hdr_iphc(linkaddr_t *link_destaddr)
}
LOG_DBG("\n");
}
#endif /* LOG_DBG_ENABLED */
hc06_ptr = PACKETBUF_IPHC_BUF + 2;
/*
@ -996,16 +995,15 @@ compress_hdr_iphc(linkaddr_t *link_destaddr)
PACKETBUF_IPHC_BUF[0] = iphc0;
PACKETBUF_IPHC_BUF[1] = iphc1;
#if LOG_DBG_ENABLED
{ uint16_t ndx;
if(LOG_DBG_ENABLED) {
uint16_t ndx;
LOG_DBG("after compression %d: ", (int)(hc06_ptr - packetbuf_ptr));
for(ndx = 0; ndx < hc06_ptr - packetbuf_ptr; ndx++) {
uint8_t data = ((uint8_t *) packetbuf_ptr)[ndx];
LOG_DBG("%02x", data);
}
LOG_DBG("\n");
}
#endif
}
packetbuf_hdr_len = hc06_ptr - packetbuf_ptr;
}
@ -1906,8 +1904,7 @@ input(void)
LOG_INFO("input: IP packet ready (length %d)\n",
uip_len);
#if LOG_DBG_ENABLED
{
if(LOG_DBG_ENABLED) {
uint16_t ndx;
LOG_DBG("after decompression %u:", UIP_IP_BUF->len[1]);
for (ndx = 0; ndx < UIP_IP_BUF->len[1] + 40; ndx++) {
@ -1916,7 +1913,6 @@ input(void)
}
LOG_DBG("\n");
}
#endif /* LOG_DBG_ENABLED */
/* if callback is set then set attributes and call */
if(callback) {

View File

@ -108,8 +108,7 @@ void tcpip_uipcall(void);
* process whenever an event occurs on the connection.
*
*/
CCIF void tcp_attach(struct uip_conn *conn,
void *appstate);
void tcp_attach(struct uip_conn *conn, void *appstate);
#define tcp_markconn(conn, appstate) tcp_attach(conn, appstate)
/**
@ -126,7 +125,7 @@ CCIF void tcp_attach(struct uip_conn *conn,
* \param port The port number in network byte order.
*
*/
CCIF void tcp_listen(uint16_t port);
void tcp_listen(uint16_t port);
/**
* Close a listening TCP port.
@ -140,7 +139,7 @@ CCIF void tcp_listen(uint16_t port);
* \param port The port number in network byte order.
*
*/
CCIF void tcp_unlisten(uint16_t port);
void tcp_unlisten(uint16_t port);
/**
* Open a TCP connection to the specified IP address and port.
@ -165,8 +164,8 @@ CCIF void tcp_unlisten(uint16_t port);
* memory could not be allocated for the connection.
*
*/
CCIF struct uip_conn *tcp_connect(const uip_ipaddr_t *ripaddr, uint16_t port,
void *appstate);
struct uip_conn *tcp_connect(const uip_ipaddr_t *ripaddr, uint16_t port,
void *appstate);
/**
* Cause a specified TCP connection to be polled.
@ -226,8 +225,8 @@ void udp_attach(struct uip_udp_conn *conn,
* \return A pointer to the newly created connection, or NULL if
* memory could not be allocated for the connection.
*/
CCIF struct uip_udp_conn *udp_new(const uip_ipaddr_t *ripaddr, uint16_t port,
void *appstate);
struct uip_udp_conn *udp_new(const uip_ipaddr_t *ripaddr, uint16_t port,
void *appstate);
/**
* Create a new UDP broadcast connection.
@ -272,7 +271,7 @@ struct uip_udp_conn *udp_broadcast_new(uint16_t port, void *appstate);
* \param conn A pointer to the UDP connection that should be polled.
*
*/
CCIF void tcpip_poll_udp(struct uip_udp_conn *conn);
void tcpip_poll_udp(struct uip_udp_conn *conn);
/** @} */
@ -288,7 +287,7 @@ CCIF void tcpip_poll_udp(struct uip_udp_conn *conn);
*
* This event is posted to a process whenever a uIP ICMP event has occurred.
*/
CCIF extern process_event_t tcpip_icmp6_event;
extern process_event_t tcpip_icmp6_event;
/**
* \brief register an ICMPv6 callback
@ -318,7 +317,7 @@ void tcpip_icmp6_call(uint8_t type);
*
* This event is posted to a process whenever a uIP event has occurred.
*/
CCIF extern process_event_t tcpip_event;
extern process_event_t tcpip_event;
/**
@ -335,7 +334,7 @@ CCIF extern process_event_t tcpip_event;
* and the length of the packet must be in the global
* uip_len variable.
*/
CCIF void tcpip_input(void);
void tcpip_input(void);
/**
* \brief Output packet to layer 2

View File

@ -103,7 +103,6 @@ LIST(notificationlist);
#endif
/*---------------------------------------------------------------------------*/
#if LOG_DBG_ENABLED
static void
assert_nbr_routes_list_sane(void)
{
@ -131,7 +130,6 @@ assert_nbr_routes_list_sane(void)
}
#endif /* (UIP_MAX_ROUTES != 0) */
}
#endif /* LOG_DBG_ENABLED */
/*---------------------------------------------------------------------------*/
#if UIP_DS6_NOTIFICATIONS
static void
@ -330,9 +328,9 @@ uip_ds6_route_add(uip_ipaddr_t *ipaddr, uint8_t length,
uip_ds6_route_t *r;
struct uip_ds6_route_neighbor_route *nbrr;
#if LOG_DBG_ENABLED
assert_nbr_routes_list_sane();
#endif /* LOG_DBG_ENABLED */
if(LOG_DBG_ENABLED) {
assert_nbr_routes_list_sane();
}
if(ipaddr == NULL || nexthop == NULL) {
return NULL;
@ -473,9 +471,9 @@ uip_ds6_route_add(uip_ipaddr_t *ipaddr, uint8_t length,
call_route_callback(UIP_DS6_NOTIFICATION_ROUTE_ADD, ipaddr, nexthop);
#endif
#if LOG_DBG_ENABLED
assert_nbr_routes_list_sane();
#endif /* LOG_DBG_ENABLED */
if(LOG_DBG_ENABLED) {
assert_nbr_routes_list_sane();
}
return r;
#else /* (UIP_MAX_ROUTES != 0) */
@ -489,9 +487,11 @@ uip_ds6_route_rm(uip_ds6_route_t *route)
{
#if (UIP_MAX_ROUTES != 0)
struct uip_ds6_route_neighbor_route *neighbor_route;
#if LOG_DBG_ENABLED
assert_nbr_routes_list_sane();
#endif /* LOG_DBG_ENABLED */
if(LOG_DBG_ENABLED) {
assert_nbr_routes_list_sane();
}
if(route != NULL && route->neighbor_routes != NULL) {
LOG_INFO("Rm: removing route: ");
@ -541,9 +541,9 @@ uip_ds6_route_rm(uip_ds6_route_t *route)
#endif
}
#if LOG_DBG_ENABLED
assert_nbr_routes_list_sane();
#endif /* LOG_DBG_ENABLED */
if(LOG_DBG_ENABLED) {
assert_nbr_routes_list_sane();
}
#endif /* (UIP_MAX_ROUTES != 0) */
return;
@ -553,9 +553,10 @@ uip_ds6_route_rm(uip_ds6_route_t *route)
static void
rm_routelist(struct uip_ds6_route_neighbor_routes *routes)
{
#if LOG_DBG_ENABLED
assert_nbr_routes_list_sane();
#endif /* LOG_DBG_ENABLED */
if(LOG_DBG_ENABLED) {
assert_nbr_routes_list_sane();
}
if(routes != NULL && routes->route_list != NULL) {
struct uip_ds6_route_neighbor_route *r;
r = list_head(routes->route_list);
@ -565,9 +566,10 @@ rm_routelist(struct uip_ds6_route_neighbor_routes *routes)
}
nbr_table_remove(nbr_routes, routes);
}
#if LOG_DBG_ENABLED
assert_nbr_routes_list_sane();
#endif /* LOG_DBG_ENABLED */
if(LOG_DBG_ENABLED) {
assert_nbr_routes_list_sane();
}
}
/*---------------------------------------------------------------------------*/
static void
@ -603,9 +605,9 @@ uip_ds6_defrt_add(uip_ipaddr_t *ipaddr, unsigned long interval)
{
uip_ds6_defrt_t *d;
#if LOG_DBG_ENABLED
assert_nbr_routes_list_sane();
#endif /* LOG_DBG_ENABLED */
if(LOG_DBG_ENABLED) {
assert_nbr_routes_list_sane();
}
if(ipaddr == NULL) {
return NULL;
@ -643,9 +645,9 @@ uip_ds6_defrt_add(uip_ipaddr_t *ipaddr, unsigned long interval)
call_route_callback(UIP_DS6_NOTIFICATION_DEFRT_ADD, ipaddr, ipaddr);
#endif
#if LOG_DBG_ENABLED
if(LOG_DBG_ENABLED) {
assert_nbr_routes_list_sane();
#endif /* LOG_DBG_ENABLED */
}
return d;
}
@ -655,9 +657,9 @@ uip_ds6_defrt_rm(uip_ds6_defrt_t *defrt)
{
uip_ds6_defrt_t *d;
#if LOG_DBG_ENABLED
assert_nbr_routes_list_sane();
#endif /* LOG_DBG_ENABLED */
if(LOG_DBG_ENABLED) {
assert_nbr_routes_list_sane();
}
/* Make sure that the defrt is in the list before we remove it. */
for(d = list_head(defaultrouterlist);
@ -675,10 +677,10 @@ uip_ds6_defrt_rm(uip_ds6_defrt_t *defrt)
return;
}
}
#if LOG_DBG_ENABLED
assert_nbr_routes_list_sane();
#endif /* LOG_DBG_ENABLED */
if(LOG_DBG_ENABLED) {
assert_nbr_routes_list_sane();
}
}
/*---------------------------------------------------------------------------*/
uip_ds6_defrt_t *

View File

@ -973,7 +973,7 @@ ra_input(void)
default:
LOG_DBG("Updating timer of prefix ");
LOG_DBG_6ADDR(&prefix->ipaddr);
LOG_DBG_(" new value %lu\n", (unsigned long)uip_ntohl(nd6_opt_prefix_info->validlt));
LOG_DBG_(" new value %"PRIu32"\n", uip_ntohl(nd6_opt_prefix_info->validlt));
stimer_set(&prefix->vlifetime,
uip_ntohl(nd6_opt_prefix_info->validlt));
prefix->isinfinite = 0;
@ -1034,7 +1034,7 @@ ra_input(void)
while(naddr-- > 0) {
LOG_DBG("nameserver: ");
LOG_DBG_6ADDR(ip);
LOG_DBG_(" lifetime: %lx\n", (unsigned long)uip_ntohl(UIP_ND6_OPT_RDNSS_BUF->lifetime));
LOG_DBG_(" lifetime: %"PRIx32"\n", uip_ntohl(UIP_ND6_OPT_RDNSS_BUF->lifetime));
uip_nameserver_update(ip, uip_ntohl(UIP_ND6_OPT_RDNSS_BUF->lifetime));
ip++;
}

View File

@ -217,13 +217,13 @@ uip_sr_periodic(unsigned seconds)
break;
}
}
#if LOG_INFO_ENABLED
uip_ipaddr_t node_addr;
NETSTACK_ROUTING.get_sr_node_ipaddr(&node_addr, l);
LOG_INFO("NS: removing expired node ");
LOG_INFO_6ADDR(&node_addr);
LOG_INFO_("\n");
#endif /* LOG_INFO_ENABLED */
if(LOG_INFO_ENABLED) {
uip_ipaddr_t node_addr;
NETSTACK_ROUTING.get_sr_node_ipaddr(&node_addr, l);
LOG_INFO("NS: removing expired node ");
LOG_INFO_6ADDR(&node_addr);
LOG_INFO_("\n");
}
/* No child found, deallocate node */
list_remove(nodelist, l);
memb_free(&nodememb, l);

View File

@ -500,7 +500,7 @@ typedef union {
uint8_t u8[UIP_BUFSIZE];
} uip_buf_t;
CCIF extern uip_buf_t uip_aligned_buf;
extern uip_buf_t uip_aligned_buf;
/** Macro to access uip_aligned_buf as an array of bytes */
#define uip_buf (uip_aligned_buf.u8)
@ -620,7 +620,7 @@ struct uip_conn *uip_connect(const uip_ipaddr_t *ripaddr, uint16_t port);
*
* \hideinitializer
*/
CCIF void uip_send(const void *data, int len);
void uip_send(const void *data, int len);
/**
* The length of any incoming data that is currently available (if available)
@ -1238,14 +1238,14 @@ struct uip_udp_conn *uip_udp_new(const uip_ipaddr_t *ripaddr, uint16_t rport);
* network byte order, use the UIP_HTONS() macro instead.
*/
#ifndef uip_htons
CCIF uint16_t uip_htons(uint16_t val);
uint16_t uip_htons(uint16_t val);
#endif /* uip_htons */
#ifndef uip_ntohs
#define uip_ntohs uip_htons
#endif
#ifndef uip_htonl
CCIF uint32_t uip_htonl(uint32_t val);
uint32_t uip_htonl(uint32_t val);
#endif /* uip_htonl */
#ifndef uip_ntohl
#define uip_ntohl uip_htonl
@ -1260,7 +1260,7 @@ CCIF uint32_t uip_htonl(uint32_t val);
* called. If the application wishes to send data, the application may
* use this space to write the data into before calling uip_send().
*/
CCIF extern void *uip_appdata;
extern void *uip_appdata;
#if UIP_URGDATA > 0
/* uint8_t *uip_urgdata:
@ -1295,7 +1295,7 @@ extern void *uip_urgdata;
* packet.
*
*/
CCIF extern uint16_t uip_len;
extern uint16_t uip_len;
/**
* The length of the extension headers
@ -1367,10 +1367,10 @@ struct uip_conn {
* connection.
*/
CCIF extern struct uip_conn *uip_conn;
extern struct uip_conn *uip_conn;
#if UIP_TCP
/* The array containing all uIP connections. */
CCIF extern struct uip_conn uip_conns[UIP_TCP_CONNS];
extern struct uip_conn uip_conns[UIP_TCP_CONNS];
#endif
/**
@ -1522,7 +1522,7 @@ struct uip_eth_hdr {
* that are defined in this file. Please read below for more
* information.
*/
CCIF extern uint8_t uip_flags;
extern uint8_t uip_flags;
/* The following flags may be set in the global variable uip_flags
before calling the application callback. The UIP_ACKDATA,
@ -1934,17 +1934,17 @@ struct uip_udp_hdr {
#if UIP_FIXEDADDR
CCIF extern const uip_ipaddr_t uip_hostaddr, uip_netmask, uip_draddr;
extern const uip_ipaddr_t uip_hostaddr, uip_netmask, uip_draddr;
#else /* UIP_FIXEDADDR */
CCIF extern uip_ipaddr_t uip_hostaddr, uip_netmask, uip_draddr;
extern uip_ipaddr_t uip_hostaddr, uip_netmask, uip_draddr;
#endif /* UIP_FIXEDADDR */
CCIF extern const uip_ipaddr_t uip_broadcast_addr;
CCIF extern const uip_ipaddr_t uip_all_zeroes_addr;
extern const uip_ipaddr_t uip_broadcast_addr;
extern const uip_ipaddr_t uip_all_zeroes_addr;
#if UIP_FIXEDETHADDR
CCIF extern const uip_lladdr_t uip_lladdr;
extern const uip_lladdr_t uip_lladdr;
#else
CCIF extern uip_lladdr_t uip_lladdr;
extern uip_lladdr_t uip_lladdr;
#endif

View File

@ -73,8 +73,8 @@
#define uiplib_ipaddrconv uiplib_ip4addrconv
#endif /* NETSTACK_CONF_WITH_IPV6 */
CCIF int uiplib_ip4addrconv(const char *addrstr, uip_ip4addr_t *addr);
CCIF int uiplib_ip6addrconv(const char *addrstr, uip_ip6addr_t *addr);
int uiplib_ip4addrconv(const char *addrstr, uip_ip4addr_t *addr);
int uiplib_ip6addrconv(const char *addrstr, uip_ip6addr_t *addr);
/** @} */
/**

View File

@ -118,7 +118,7 @@ tsch_log_process_pending(void)
if(log->rx.drift_used) {
printf(", dr %d", log->rx.drift);
}
printf(", edr %d\n", (int)log->rx.estimated_drift);
printf(", edr %d\n", log->rx.estimated_drift);
break;
case tsch_log_message:
printf("%s\n", log->message);

View File

@ -29,7 +29,7 @@
* This file is part of the Contiki operating system.
*
*/
/**
* \addtogroup rpl-lite
* @{
@ -73,17 +73,6 @@
#define RPL_WITH_NON_STORING (RPL_MOP_DEFAULT == RPL_MOP_NON_STORING)
#endif /* RPL_CONF_WITH_NON_STORING */
/* The number of non-storing nodes, i.e. the maximum netwrok size at the root */
#ifdef RPL_NS_CONF_LINK_NUM
#define RPL_NS_LINK_NUM RPL_NS_CONF_LINK_NUM
#else /* RPL_NS_CONF_LINK_NUM */
#if RPL_WITH_NON_STORING
#define RPL_NS_LINK_NUM NETSTACK_MAX_ROUTE_ENTRIES
#else
#define RPL_NS_LINK_NUM 0
#endif
#endif /* RPL_NS_CONF_LINK_NUM */
/*
* The objective function (OF) used by a RPL root is configurable through
* the RPL_CONF_OF_OCP parameter. This is defined as the objective code

View File

@ -185,9 +185,9 @@ rpl_global_repair(const char *str)
if(rpl_dag_root_is_root()) {
LOG_WARN("initiating global repair (%s), version %u, rank %u)\n",
str, curr_instance.dag.version, curr_instance.dag.rank);
#if LOG_INFO_ENABLED
rpl_neighbor_print_list("Global repair (before)");
#endif /* LOG_INFO_ENABLED */
if(LOG_INFO_ENABLED) {
rpl_neighbor_print_list("Global repair (before)");
}
/* Initiate global repair */
RPL_LOLLIPOP_INCREMENT(curr_instance.dag.version); /* New DAG version */
@ -202,9 +202,9 @@ global_repair_non_root(rpl_dio_t *dio)
if(!rpl_dag_root_is_root()) {
LOG_WARN("participating in global repair, version %u, rank %u)\n",
curr_instance.dag.version, curr_instance.dag.rank);
#if LOG_INFO_ENABLED
rpl_neighbor_print_list("Global repair (before)");
#endif /* LOG_INFO_ENABLED */
if(LOG_INFO_ENABLED) {
rpl_neighbor_print_list("Global repair (before)");
}
/* Re-initialize configuration from DIO */
init_dag_from_dio(dio);
rpl_local_repair("Global repair");
@ -325,9 +325,9 @@ rpl_dag_update_state(void)
rpl_timers_schedule_leaving();
}
#if LOG_INFO_ENABLED
rpl_neighbor_print_list("Parent switch");
#endif /* LOG_INFO_ENABLED */
if(LOG_INFO_ENABLED) {
rpl_neighbor_print_list("Parent switch");
}
}
}

View File

@ -65,19 +65,7 @@ static int num_parents; /* all nodes that are possible parents */
static int num_free;
static linkaddr_t *worst_rank_nbr_lladdr; /* lladdr of the the neighbor with the worst rank */
static rpl_rank_t worst_rank;
/*---------------------------------------------------------------------------*/
#if LOG_DBG_ENABLED
/* Print out state periodically */
static void update_state(void);
static struct ctimer periodic_timer;
static int timer_init = 0;
static void
handle_periodic_timer(void *ptr)
{
update_state();
ctimer_restart(&periodic_timer);
}
#endif /* LOG_DBG_ENABLED */
/*---------------------------------------------------------------------------*/
static void
update_state(void)
@ -87,14 +75,6 @@ update_state(void)
rpl_rank_t nbr_rank;
int num_used = 0;
#if LOG_DBG_ENABLED
if(!timer_init) {
timer_init = 1;
ctimer_set(&periodic_timer, 60 * CLOCK_SECOND,
&handle_periodic_timer, NULL);
}
#endif /* LOG_DBG_ENABLED */
worst_rank = 0;
worst_rank_nbr_lladdr = NULL;
num_parents = 0;

View File

@ -514,9 +514,9 @@ handle_periodic_timer(void *ptr)
the meaning of last_advertised_rank changes with time */
rpl_dag_update_state();
#if LOG_INFO_ENABLED
rpl_neighbor_print_list("Periodic");
#endif /* LOG_INFO_ENABLED */
if(LOG_INFO_ENABLED) {
rpl_neighbor_print_list("Periodic");
}
ctimer_reset(&periodic_timer);
}

View File

@ -767,7 +767,7 @@ perform_multi_resource_read_op(lwm2m_object_t *object,
/* Now we need to initialize the object writing for this new object */
len = ctx->writer->init_write(ctx);
ctx->outbuf->len += len;
LOG_DBG("INIT WRITE len:%d size:%d\n", len, (int) ctx->outbuf->size);
LOG_DBG("INIT WRITE len:%d size:%"PRIu16"\n", len, ctx->outbuf->size);
initialized = 1;
}
@ -1516,10 +1516,10 @@ lwm2m_handler_callback(coap_message_t *request, coap_message_t *response,
/* for debugging */
LOG_DBG("[");
LOG_DBG_COAP_STRING(url, url_len);
LOG_DBG_("] %s Format:%d ID:%d bsize:%u offset:%d\n",
LOG_DBG_("] %s Format:%d ID:%d bsize:%u offset:%"PRId32"\n",
get_method_as_string(coap_get_method_type(request)),
format, context.object_id, buffer_size,
offset != NULL ? ((int)*offset) : 0);
offset != NULL ? *offset : 0);
if(format == TEXT_PLAIN) {
/* a string */
const uint8_t *data;
@ -1573,8 +1573,8 @@ lwm2m_handler_callback(coap_message_t *request, coap_message_t *response,
if(success == LWM2M_STATUS_OK) {
/* Handle blockwise 1 */
if(coap_is_option(request, COAP_OPTION_BLOCK1)) {
LOG_DBG("Setting BLOCK 1 num:%d o2:%d o:%d\n", (int) bnum, (int) boffset,
(int) (offset != NULL ? *offset : 0));
LOG_DBG("Setting BLOCK 1 num:%"PRIu32" o2:%"PRIu32" o:%"PRId32"\n", bnum, boffset,
(offset != NULL ? *offset : 0));
coap_set_header_block1(response, bnum, 0, bsize);
}

View File

@ -219,9 +219,9 @@ write_int(lwm2m_context_t *ctx, uint8_t *outbuf, size_t outlen,
char *sep = (ctx->writer_flags & WRITER_OUTPUT_VALUE) ? "," : "";
int len;
if(ctx->writer_flags & WRITER_RESOURCE_INSTANCE) {
len = snprintf((char *)outbuf, outlen, "%s{\"n\":\"%u/%u\",\"v\":%" PRId32 "}", sep, ctx->resource_id, ctx->resource_instance_id, value);
len = snprintf((char *)outbuf, outlen, "%s{\"n\":\"%u/%u\",\"v\":%"PRId32"}", sep, ctx->resource_id, ctx->resource_instance_id, value);
} else {
len = snprintf((char *)outbuf, outlen, "%s{\"n\":\"%u\",\"v\":%" PRId32 "}", sep, ctx->resource_id, value);
len = snprintf((char *)outbuf, outlen, "%s{\"n\":\"%u\",\"v\":%"PRId32"}", sep, ctx->resource_id, value);
}
if((len < 0) || (len >= outlen)) {
return 0;

View File

@ -177,7 +177,7 @@ lwm2m_callback(lwm2m_object_instance_t *object,
/* Handle the writes */
switch(ctx->resource_id) {
case LWM2M_SECURITY_SERVER_URI_ID:
LOG_DBG("Writing security URI value: len: %d\n", (int)ctx->inbuf->size);
LOG_DBG("Writing security URI value: len: %"PRId16"\n", ctx->inbuf->size);
value = lwm2m_object_read_string(ctx, ctx->inbuf->buffer, ctx->inbuf->size, security->server_uri, LWM2M_SECURITY_URI_SIZE);
/* This is string... */
security->server_uri_len = ctx->last_value_len;
@ -204,7 +204,7 @@ lwm2m_callback(lwm2m_object_instance_t *object,
value = lwm2m_object_read_string(ctx, ctx->inbuf->buffer, ctx->inbuf->size, security->public_key, LWM2M_SECURITY_KEY_SIZE);
security->public_key_len = ctx->last_value_len;
LOG_DBG("Writing client PKI: len: %d '", (int)ctx->last_value_len);
LOG_DBG("Writing client PKI: len: %"PRIu16" '", ctx->last_value_len);
LOG_DBG_COAP_STRING((const char *)security->public_key,
ctx->last_value_len);
LOG_DBG_("'\n");
@ -213,7 +213,7 @@ lwm2m_callback(lwm2m_object_instance_t *object,
value = lwm2m_object_read_string(ctx, ctx->inbuf->buffer, ctx->inbuf->size, security->secret_key, LWM2M_SECURITY_KEY_SIZE);
security->secret_key_len = ctx->last_value_len;
LOG_DBG("Writing secret key: len: %d '", (int)ctx->last_value_len);
LOG_DBG("Writing secret key: len: %"PRIu16" '", ctx->last_value_len);
LOG_DBG_COAP_STRING((const char *)security->secret_key,
ctx->last_value_len);
LOG_DBG_("'\n");

View File

@ -205,7 +205,7 @@ lwm2m_tlv_write_int32(uint8_t type, int16_t id, int32_t value, uint8_t *buffer,
int i;
int v;
int last_bit;
LOG_DBG("Exporting int32 %d %ld ", id, (long)value);
LOG_DBG("Exporting int32 %d %"PRId32" ", id, value);
v = value < 0 ? -1 : 0;
i = 0;
@ -252,9 +252,9 @@ lwm2m_tlv_write_float32(uint8_t type, int16_t id, int32_t value, int bits,
e++;
}
LOG_DBG("Sign: %d, Fraction: %06lx 0b", value < 0, (long)val);
LOG_DBG("Sign: %d, Fraction: %06"PRIx32" 0b", value < 0, val);
for(i = 0; i < 23; i++) {
LOG_DBG_("%d", (int)((val >> (22 - i)) & 1));
LOG_DBG_("%"PRId32"", ((val >> (22 - i)) & 1));
}
LOG_DBG_("\nExp:%d\n", e);
@ -292,9 +292,9 @@ lwm2m_tlv_float32_to_fix(const lwm2m_tlv_t *tlv, int32_t *value, int bits)
e = ((tlv->value[0] << 1) & 0xff) | (tlv->value[1] >> 7);
val = (((long)tlv->value[1] & 0x7f) << 16) | (tlv->value[2] << 8) | tlv->value[3];
LOG_DBG("Sign: %d, Fraction: %06lx 0b", val < 0, (long)val);
LOG_DBG("Sign: %d, Fraction: %06"PRIx32" 0b", val < 0, val);
for(i = 0; i < 23; i++) {
LOG_DBG_("%d", (int)((val >> (22 - i)) & 1));
LOG_DBG_("%"PRId32"", ((val >> (22 - i)) & 1));
}
LOG_DBG("\nExp:%d => %d\n", e, e - 127);

View File

@ -29,7 +29,7 @@
/**
* \file
* This component forwards index calls using the generic index
* This component forwards index calls using the generic index
* API to specific implementations.
* \author
* Nicolas Tsiftes <nvt@sics.se>
@ -241,7 +241,7 @@ index_delete(index_t *index, attribute_value_t *value)
}
db_result_t
index_get_iterator(index_iterator_t *iterator, index_t *index,
index_get_iterator(index_iterator_t *iterator, index_t *index,
attribute_value_t *min_value,
attribute_value_t *max_value)
{
@ -266,15 +266,15 @@ index_get_iterator(index_iterator_t *iterator, index_t *index,
range = (unsigned long)max - min;
if(range > 0) {
/*
* Index structures that do not have a natural ability to handle
* Index structures that do not have a natural ability to handle
* range queries (e.g., a hash index) can nevertheless emulate them.
*
* The range query emulation attempts to look up the key for each
* value in the search range. If the search range is sparse, this
* The range query emulation attempts to look up the key for each
* value in the search range. If the search range is sparse, this
* iteration will incur a considerable overhead per found key.
*
* Hence, the emulation is preferable when an external module wants
* to iterate over a narrow range of keys, for which the total
* Hence, the emulation is preferable when an external module wants
* to iterate over a narrow range of keys, for which the total
* search cost is smaller than that of an iteration over all tuples
* in the relation.
*/
@ -294,7 +294,7 @@ index_get_iterator(index_iterator_t *iterator, index_t *index,
iterator->max_value = *max_value;
iterator->next_item_no = 0;
PRINTF("DB: Acquired an index iterator for %s.%s over the range (%ld,%ld)\n",
PRINTF("DB: Acquired an index iterator for %s.%s over the range (%ld,%ld)\n",
index->rel->name, index->attr->name,
min_value->u.long_value, max_value->u.long_value);
@ -380,7 +380,7 @@ PROCESS_THREAD(db_indexer, ev, data)
PRINTF("DB: Loading the index for %s.%s...\n",
index->rel->name, index->attr->name);
/* Project the values of the indexed attribute from all tuples in
/* Project the values of the indexed attribute from all tuples in
the relation, and insert them into the index again. */
if(DB_ERROR(db_query(&handle, "SELECT %s FROM %s;", index->attr->name, index->rel->name))) {
index->flags |= INDEX_LOAD_ERROR;

View File

@ -105,7 +105,7 @@ db_result_t index_load(relation_t *, attribute_t *);
db_result_t index_release(index_t *);
db_result_t index_insert(index_t *, attribute_value_t *, tuple_id_t);
db_result_t index_delete(index_t *, attribute_value_t *);
db_result_t index_get_iterator(index_iterator_t *, index_t *,
db_result_t index_get_iterator(index_iterator_t *, index_t *,
attribute_value_t *, attribute_value_t *);
tuple_id_t index_get_next(index_iterator_t *);
int index_exists(attribute_t *);

View File

@ -1094,7 +1094,7 @@ cfs_read(int fd, void *buf, unsigned size)
fdp = &coffee_fd_set[fd];
file = fdp->file;
if(fdp->io_flags & CFS_COFFEE_IO_ENSURE_READ_LENGTH) {
while(fdp->offset + size > file->end) {
((char *)buf)[--size] = '\0';

View File

@ -166,7 +166,7 @@ struct cfs_dirent {
* \sa cfs_close()
*/
#ifndef cfs_open
CCIF int cfs_open(const char *name, int flags);
int cfs_open(const char *name, int flags);
#endif
/**
@ -177,7 +177,7 @@ CCIF int cfs_open(const char *name, int flags);
* opened with cfs_open().
*/
#ifndef cfs_close
CCIF void cfs_close(int fd);
void cfs_close(int fd);
#endif
/**
@ -192,7 +192,7 @@ CCIF void cfs_close(int fd);
* cfs_open() and the CFS_READ flag.
*/
#ifndef cfs_read
CCIF int cfs_read(int fd, void *buf, unsigned int len);
int cfs_read(int fd, void *buf, unsigned int len);
#endif
/**
@ -207,7 +207,7 @@ CCIF int cfs_read(int fd, void *buf, unsigned int len);
* cfs_open() and the CFS_WRITE flag.
*/
#ifndef cfs_write
CCIF int cfs_write(int fd, const void *buf, unsigned int len);
int cfs_write(int fd, const void *buf, unsigned int len);
#endif
/**
@ -228,7 +228,7 @@ CCIF int cfs_write(int fd, const void *buf, unsigned int len);
* \sa CFS_SEEK_SET
*/
#ifndef cfs_seek
CCIF cfs_offset_t cfs_seek(int fd, cfs_offset_t offset, int whence);
cfs_offset_t cfs_seek(int fd, cfs_offset_t offset, int whence);
#endif
/**
@ -238,7 +238,7 @@ CCIF cfs_offset_t cfs_seek(int fd, cfs_offset_t offset, int whence);
* \return -1 If the file could not be removed or if it doesn't exist.
*/
#ifndef cfs_remove
CCIF int cfs_remove(const char *name);
int cfs_remove(const char *name);
#endif
/**
@ -251,7 +251,7 @@ CCIF int cfs_remove(const char *name);
* \sa cfs_closedir()
*/
#ifndef cfs_opendir
CCIF int cfs_opendir(struct cfs_dir *dirp, const char *name);
int cfs_opendir(struct cfs_dir *dirp, const char *name);
#endif
/**
@ -265,7 +265,7 @@ CCIF int cfs_opendir(struct cfs_dir *dirp, const char *name);
* \sa cfs_closedir()
*/
#ifndef cfs_readdir
CCIF int cfs_readdir(struct cfs_dir *dirp, struct cfs_dirent *dirent);
int cfs_readdir(struct cfs_dir *dirp, struct cfs_dirent *dirent);
#endif
/**
@ -276,7 +276,7 @@ CCIF int cfs_readdir(struct cfs_dir *dirp, struct cfs_dirent *dirent);
* \sa cfs_readdir()
*/
#ifndef cfs_closedir
CCIF void cfs_closedir(struct cfs_dir *dirp);
void cfs_closedir(struct cfs_dir *dirp);
#endif
#endif /* CFS_H_ */

View File

@ -50,7 +50,7 @@ struct process * const autostart_processes[] = {__VA_ARGS__, NULL}
#error "C compiler must support __VA_ARGS__ macro"
#endif
CLIF extern struct process * const autostart_processes[];
extern struct process * const autostart_processes[];
void autostart_start(struct process * const processes[]);
void autostart_exit(struct process * const processes[]);

View File

@ -98,7 +98,7 @@ void clock_init(void);
*
* \return The current clock time, measured in system ticks.
*/
CCIF clock_time_t clock_time(void);
clock_time_t clock_time(void);
/**
* Get the current value of the platform seconds.
@ -108,7 +108,7 @@ CCIF clock_time_t clock_time(void);
*
* \return The value.
*/
CCIF unsigned long clock_seconds(void);
unsigned long clock_seconds(void);
/**
* Set the value of the platform seconds.

View File

@ -106,7 +106,7 @@ void
ctimer_set_with_process(struct ctimer *c, clock_time_t t,
void (*f)(void *), void *ptr, struct process *p)
{
PRINTF("ctimer_set %p %u\n", c, (unsigned)t);
PRINTF("ctimer_set %p %lu\n", c, (unsigned long)t);
c->p = p;
c->f = f;
c->ptr = ptr;

View File

@ -94,7 +94,7 @@ struct etimer {
* process that called the etimer_set() function.
*
*/
CCIF void etimer_set(struct etimer *et, clock_time_t interval);
void etimer_set(struct etimer *et, clock_time_t interval);
/**
* \brief Reset an event timer with the same interval as was
@ -111,7 +111,7 @@ CCIF void etimer_set(struct etimer *et, clock_time_t interval);
*
* \sa etimer_restart()
*/
CCIF void etimer_reset(struct etimer *et);
void etimer_reset(struct etimer *et);
/**
* \brief Reset an event timer with a new interval.
@ -192,7 +192,7 @@ clock_time_t etimer_start_time(struct etimer *et);
* This function tests if an event timer has expired and
* returns true or false depending on its status.
*/
CCIF int etimer_expired(struct etimer *et);
int etimer_expired(struct etimer *et);
/**
* \brief Stop a pending event timer.

View File

@ -169,7 +169,12 @@ extern struct log_module all_modules[];
#define LOG_INFO_6ADDR(...) LOG_6ADDR(LOG_LEVEL_INFO, __VA_ARGS__)
#define LOG_DBG_6ADDR(...) LOG_6ADDR(LOG_LEVEL_DBG, __VA_ARGS__)
/* For testing log level */
/* For checking log level.
As this builds on curr_log_level variables, this should not be used
in pre-processor macros. Use in a C 'if' statement instead, e.g.:
if(LOG_INFO_ENABLED) { ... }
Note that most compilers will still be able to strip the code out
for low enough log levels configurations. */
#define LOG_ERR_ENABLED ((LOG_LEVEL) >= LOG_LEVEL_ERR)
#define LOG_WARN_ENABLED ((LOG_LEVEL) >= LOG_LEVEL_WARN)
#define LOG_INFO_ENABLED ((LOG_LEVEL) >= LOG_LEVEL_INFO)

View File

@ -339,7 +339,7 @@ struct process {
* process
*
*/
CCIF void process_start(struct process *p, process_data_t data);
void process_start(struct process *p, process_data_t data);
/**
* Post an asynchronous event.
@ -362,7 +362,7 @@ CCIF void process_start(struct process *p, process_data_t data);
* \retval PROCESS_ERR_FULL The event queue was full and the event could
* not be posted.
*/
CCIF int process_post(struct process *p, process_event_t ev, process_data_t data);
int process_post(struct process *p, process_event_t ev, process_data_t data);
/**
* Post a synchronous event to a process.
@ -374,8 +374,8 @@ CCIF int process_post(struct process *p, process_event_t ev, process_data_t data
* \param data A pointer to additional data that is posted together
* with the event.
*/
CCIF void process_post_synch(struct process *p,
process_event_t ev, process_data_t data);
void process_post_synch(struct process *p,
process_event_t ev, process_data_t data);
/**
* \brief Cause a process to exit
@ -387,7 +387,7 @@ CCIF void process_post_synch(struct process *p,
*
* \sa PROCESS_CURRENT()
*/
CCIF void process_exit(struct process *p);
void process_exit(struct process *p);
/**
@ -400,7 +400,7 @@ CCIF void process_exit(struct process *p);
* \hideinitializer
*/
#define PROCESS_CURRENT() process_current
CCIF extern struct process *process_current;
extern struct process *process_current;
/**
* Switch context to another process
@ -450,7 +450,7 @@ process_current = p
* \note There currently is no way to deallocate an allocated event
* number.
*/
CCIF process_event_t process_alloc_event(void);
process_event_t process_alloc_event(void);
/** @} */
@ -467,7 +467,7 @@ CCIF process_event_t process_alloc_event(void);
*
* \param p A pointer to the process' process structure.
*/
CCIF void process_poll(struct process *p);
void process_poll(struct process *p);
/** @} */
@ -509,7 +509,7 @@ int process_run(void);
* \retval Non-zero if the process is running.
* \retval Zero if the process is not running.
*/
CCIF int process_is_running(struct process *p);
int process_is_running(struct process *p);
/**
* Number of events waiting to be processed.
@ -521,7 +521,7 @@ int process_nevents(void);
/** @} */
CCIF extern struct process *process_list;
extern struct process *process_list;
#define PROCESS_LIST() process_list

View File

@ -84,10 +84,10 @@ struct timer {
clock_time_t interval;
};
CCIF void timer_set(struct timer *t, clock_time_t interval);
void timer_set(struct timer *t, clock_time_t interval);
void timer_reset(struct timer *t);
void timer_restart(struct timer *t);
CCIF int timer_expired(struct timer *t);
int timer_expired(struct timer *t);
clock_time_t timer_remaining(struct timer *t);

View File

@ -14,6 +14,13 @@ platform-specific/cc26xx/very-sleepy-demo/srf06-cc26xx \
rpl-border-router/srf06-cc26xx:BOARD=launchpad/cc2650 \
sensniff/srf06-cc26xx \
sensniff/srf06-cc26xx:BOARD=launchpad/cc1310 \
dev/gpio-hal/srf06-cc26xx:BOARD=srf06/cc13xx \
dev/gpio-hal/srf06-cc26xx:BOARD=srf06/cc26xx \
dev/gpio-hal/srf06-cc26xx:BOARD=sensortag/cc1350 \
dev/gpio-hal/srf06-cc26xx:BOARD=sensortag/cc2650 \
dev/gpio-hal/srf06-cc26xx:BOARD=launchpad/cc1310 \
dev/gpio-hal/srf06-cc26xx:BOARD=launchpad/cc1350 \
dev/gpio-hal/srf06-cc26xx:BOARD=launchpad/cc2650 \
6tisch/etsi-plugtest-2017/srf06-cc26xx:BOARD=launchpad/cc2650 \
storage/cfs-coffee/cc2538dk \
sensniff/cc2538dk \
@ -22,6 +29,7 @@ coap/cc2538dk \
slip-radio/cc2538dk \
ipso-objects/cc2538dk \
multicast/cc2538dk \
dev/gpio-hal/cc2538dk \
platform-specific/cc2538-common/cc2538dk \
platform-specific/cc2538-common/mqtt-demo/cc2538dk \
platform-specific/cc2538-common/crypto/cc2538dk \

View File

@ -30,10 +30,16 @@ libs/trickle-library/zoul \
libs/data-structures/zoul \
nullnet/zoul \
slip-radio/zoul \
dev/gpio-hal/zoul:BOARD=remote-reva \
dev/gpio-hal/zoul:BOARD=remote-revb \
dev/gpio-hal/zoul:BOARD=firefly-reva \
dev/gpio-hal/zoul:BOARD=firefly \
dev/gpio-hal/zoul:BOARD=orion \
storage/cfs-coffee/openmote-cc2538 \
sensniff/openmote-cc2538 \
hello-world/openmote-cc2538 \
rpl-udp/openmote-cc2538 \
dev/gpio-hal/openmote-cc2538 \
rpl-border-router/openmote-cc2538
TOOLS=

View File

@ -1,8 +1,6 @@
#ifndef CONTIKI_CONF_H_
#define CONTIKI_CONF_H_
#include <stdint.h>
#define CCIF
#define CLIF
/* These names are deprecated, use C99 names. */
typedef uint8_t u8_t;