Merge pull request #1444 from mdlemay/galileo-always-init-gpio
galileo: Enable I2C and GPIO interrupt sharing and centralize their initialization
This commit is contained in:
commit
9ab327090c
19 changed files with 471 additions and 208 deletions
|
@ -2,7 +2,7 @@ include $(CONTIKI)/cpu/x86/Makefile.x86_common
|
||||||
|
|
||||||
CONTIKI_CPU_DIRS += drivers/legacy_pc drivers/quarkX1000 init/legacy_pc
|
CONTIKI_CPU_DIRS += drivers/legacy_pc drivers/quarkX1000 init/legacy_pc
|
||||||
|
|
||||||
CONTIKI_SOURCEFILES += bootstrap_quarkX1000.S rtc.c pit.c pic.c irq.c nmi.c pci.c uart-16x50.c uart.c gpio.c i2c.c eth.c
|
CONTIKI_SOURCEFILES += bootstrap_quarkX1000.S rtc.c pit.c pic.c irq.c nmi.c pci.c uart-16x50.c uart.c gpio.c i2c.c eth.c shared-isr.c
|
||||||
|
|
||||||
CFLAGS += -m32 -march=i586 -mtune=i586
|
CFLAGS += -m32 -march=i586 -mtune=i586
|
||||||
LDFLAGS += -m32 -Xlinker -T -Xlinker $(CONTIKI)/cpu/x86/quarkX1000.ld
|
LDFLAGS += -m32 -Xlinker -T -Xlinker $(CONTIKI)/cpu/x86/quarkX1000.ld
|
||||||
|
|
107
cpu/x86/drivers/legacy_pc/shared-isr.c
Normal file
107
cpu/x86/drivers/legacy_pc/shared-isr.c
Normal file
|
@ -0,0 +1,107 @@
|
||||||
|
/*
|
||||||
|
* Copyright (C) 2016, Intel Corporation. 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 <assert.h>
|
||||||
|
#include "idt.h"
|
||||||
|
#include "interrupt.h"
|
||||||
|
#include "pic.h"
|
||||||
|
#include "shared-isr.h"
|
||||||
|
|
||||||
|
/* Defined in linker script */
|
||||||
|
extern shared_isr_client_t _sdata_shared_isr, _edata_shared_isr;
|
||||||
|
|
||||||
|
static void __attribute__((used))
|
||||||
|
shared_handler(void)
|
||||||
|
{
|
||||||
|
shared_isr_client_t *client;
|
||||||
|
for(client = &_sdata_shared_isr; client < &_edata_shared_isr; client++) {
|
||||||
|
if(client->handler()) {
|
||||||
|
pic_eoi(client->irq);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Initialize shared ISR by iterating through all of its clients and
|
||||||
|
* configuring their interrupts to route to the shared ISR.
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
shared_isr_init(void)
|
||||||
|
{
|
||||||
|
shared_isr_client_t *client = &_sdata_shared_isr;
|
||||||
|
shared_isr_client_t *consistency_check_client;
|
||||||
|
bool prev_conf;
|
||||||
|
|
||||||
|
void shared_isr_stub(void);
|
||||||
|
__asm__ __volatile__ (
|
||||||
|
ISR_STUB("shared_isr_stub", 0, "shared_handler")
|
||||||
|
);
|
||||||
|
|
||||||
|
while(client < &_edata_shared_isr) {
|
||||||
|
consistency_check_client = &_sdata_shared_isr;
|
||||||
|
|
||||||
|
prev_conf = false;
|
||||||
|
|
||||||
|
while(consistency_check_client < client) {
|
||||||
|
if((client->irq == consistency_check_client->irq) ||
|
||||||
|
(client->pin == consistency_check_client->pin) ||
|
||||||
|
(client->pirq == consistency_check_client->pirq)) {
|
||||||
|
|
||||||
|
prev_conf = true;
|
||||||
|
|
||||||
|
/* This interrupt was previously configured. */
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
consistency_check_client++;
|
||||||
|
}
|
||||||
|
|
||||||
|
if(prev_conf) {
|
||||||
|
/* The requested configurations for each IRQ must be consistent. */
|
||||||
|
assert((client->irq == consistency_check_client->irq) &&
|
||||||
|
(client->agent == consistency_check_client->agent) &&
|
||||||
|
(client->pin == consistency_check_client->pin) &&
|
||||||
|
(client->pirq == consistency_check_client->pirq));
|
||||||
|
} else {
|
||||||
|
idt_set_intr_gate_desc(PIC_INT(client->irq), (uint32_t)shared_isr_stub);
|
||||||
|
|
||||||
|
assert(pci_irq_agent_set_pirq(client->agent,
|
||||||
|
client->pin,
|
||||||
|
client->pirq) == 0);
|
||||||
|
|
||||||
|
pci_pirq_set_irq(client->pirq, client->irq, 1);
|
||||||
|
|
||||||
|
pic_unmask_irq(client->irq);
|
||||||
|
}
|
||||||
|
|
||||||
|
client++;
|
||||||
|
}
|
||||||
|
}
|
67
cpu/x86/drivers/legacy_pc/shared-isr.h
Normal file
67
cpu/x86/drivers/legacy_pc/shared-isr.h
Normal file
|
@ -0,0 +1,67 @@
|
||||||
|
/*
|
||||||
|
* Copyright (C) 2016, Intel Corporation. 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.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef CPU_X86_DRIVERS_LEGACY_PC_SHARED_ISR_H_
|
||||||
|
#define CPU_X86_DRIVERS_LEGACY_PC_SHARED_ISR_H_
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include "pci.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The handler function should return true if and only if it handled the
|
||||||
|
* interrupt.
|
||||||
|
*/
|
||||||
|
typedef bool (*shared_isr_handler_t)(void);
|
||||||
|
|
||||||
|
typedef struct shared_isr_client {
|
||||||
|
uint8_t irq;
|
||||||
|
IRQAGENT agent;
|
||||||
|
INTR_PIN pin;
|
||||||
|
PIRQ pirq;
|
||||||
|
shared_isr_handler_t handler;
|
||||||
|
} shared_isr_client_t;
|
||||||
|
|
||||||
|
/* Unlike a non-shared interrupt handler function, an individual interrupt
|
||||||
|
* handler for a shared interrupt must not issue an EOI. The EOI is issued by
|
||||||
|
* the shared-isr subsystem.
|
||||||
|
*/
|
||||||
|
#define DEFINE_SHARED_IRQ(irq_, agent_, pin_, pirq_, handler_) \
|
||||||
|
static struct shared_isr_client \
|
||||||
|
__attribute__((used, section(".shared_isr_data"))) _shared_irq_##irq_ = { \
|
||||||
|
.irq = irq_, \
|
||||||
|
.agent = agent_, \
|
||||||
|
.pin = pin_, \
|
||||||
|
.pirq = pirq_, \
|
||||||
|
.handler = handler_ \
|
||||||
|
}
|
||||||
|
|
||||||
|
void shared_isr_init(void);
|
||||||
|
|
||||||
|
#endif /* CPU_X86_DRIVERS_LEGACY_PC_SHARED_ISR_H_ */
|
|
@ -1,5 +1,5 @@
|
||||||
/*
|
/*
|
||||||
* Copyright (C) 2015, Intel Corporation. All rights reserved.
|
* Copyright (C) 2015-2016, Intel Corporation. All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -29,9 +29,9 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "gpio.h"
|
#include "gpio.h"
|
||||||
|
|
||||||
#include "helpers.h"
|
#include "helpers.h"
|
||||||
#include "interrupt.h"
|
#include "shared-isr.h"
|
||||||
#include "pic.h"
|
|
||||||
|
|
||||||
/* GPIO Controler Registers */
|
/* GPIO Controler Registers */
|
||||||
#define SWPORTA_DR 0x00
|
#define SWPORTA_DR 0x00
|
||||||
|
@ -49,8 +49,7 @@
|
||||||
|
|
||||||
#define PINS 8
|
#define PINS 8
|
||||||
|
|
||||||
#define GPIO_IRQ 10
|
#define GPIO_IRQ 9
|
||||||
#define GPIO_INT PIC_INT(GPIO_IRQ)
|
|
||||||
|
|
||||||
struct gpio_internal_data {
|
struct gpio_internal_data {
|
||||||
pci_driver_t pci;
|
pci_driver_t pci;
|
||||||
|
@ -87,17 +86,23 @@ set_bit(uint32_t offset, uint32_t bit, uint32_t value)
|
||||||
write(offset, reg);
|
write(offset, reg);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void
|
static bool
|
||||||
gpio_isr(void)
|
gpio_isr(void)
|
||||||
{
|
{
|
||||||
uint32_t int_status;
|
uint32_t int_status;
|
||||||
|
|
||||||
int_status = read(INTSTATUS);
|
int_status = read(INTSTATUS);
|
||||||
|
|
||||||
|
if(int_status == 0) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
if (data.callback)
|
if (data.callback)
|
||||||
data.callback(int_status);
|
data.callback(int_status);
|
||||||
|
|
||||||
write(PORTA_EOI, -1);
|
write(PORTA_EOI, -1);
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void
|
static void
|
||||||
|
@ -211,13 +216,7 @@ quarkX1000_gpio_clock_disable(void)
|
||||||
set_bit(LS_SYNC, 0, 0);
|
set_bit(LS_SYNC, 0, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void
|
DEFINE_SHARED_IRQ(GPIO_IRQ, IRQAGENT3, INTC, PIRQC, gpio_isr);
|
||||||
gpio_handler(void)
|
|
||||||
{
|
|
||||||
gpio_isr();
|
|
||||||
|
|
||||||
pic_eoi(GPIO_IRQ);
|
|
||||||
}
|
|
||||||
|
|
||||||
int
|
int
|
||||||
quarkX1000_gpio_init(void)
|
quarkX1000_gpio_init(void)
|
||||||
|
@ -232,13 +231,6 @@ quarkX1000_gpio_init(void)
|
||||||
|
|
||||||
pci_command_enable(pci_addr, PCI_CMD_1_MEM_SPACE_EN);
|
pci_command_enable(pci_addr, PCI_CMD_1_MEM_SPACE_EN);
|
||||||
|
|
||||||
SET_INTERRUPT_HANDLER(GPIO_INT, 0, gpio_handler);
|
|
||||||
|
|
||||||
if (pci_irq_agent_set_pirq(IRQAGENT3, INTA, PIRQC) < 0)
|
|
||||||
return -1;
|
|
||||||
|
|
||||||
pci_pirq_set_irq(PIRQC, GPIO_IRQ, 1);
|
|
||||||
|
|
||||||
pci_init(&data.pci, pci_addr, 0);
|
pci_init(&data.pci, pci_addr, 0);
|
||||||
|
|
||||||
data.callback = 0;
|
data.callback = 0;
|
||||||
|
@ -250,7 +242,5 @@ quarkX1000_gpio_init(void)
|
||||||
write(INTMASK, 0);
|
write(INTMASK, 0);
|
||||||
write(PORTA_EOI, 0);
|
write(PORTA_EOI, 0);
|
||||||
|
|
||||||
pic_unmask_irq(GPIO_IRQ);
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
/*
|
/*
|
||||||
* Copyright (C) 2015, Intel Corporation. All rights reserved.
|
* Copyright (C) 2015-2016, Intel Corporation. All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -30,9 +30,9 @@
|
||||||
|
|
||||||
#include "contiki.h"
|
#include "contiki.h"
|
||||||
#include "i2c.h"
|
#include "i2c.h"
|
||||||
|
|
||||||
#include "i2c-registers.h"
|
#include "i2c-registers.h"
|
||||||
#include "interrupt.h"
|
#include "shared-isr.h"
|
||||||
#include "pic.h"
|
|
||||||
|
|
||||||
#define I2C_CLOCK_SPEED 25 /* kHz */
|
#define I2C_CLOCK_SPEED 25 /* kHz */
|
||||||
#define I2C_FIFO_DEPTH 16
|
#define I2C_FIFO_DEPTH 16
|
||||||
|
@ -48,13 +48,21 @@
|
||||||
#define I2C_POLLING_TIMEOUT (CLOCK_SECOND / 10)
|
#define I2C_POLLING_TIMEOUT (CLOCK_SECOND / 10)
|
||||||
|
|
||||||
#define I2C_IRQ 9
|
#define I2C_IRQ 9
|
||||||
#define I2C_INT PIC_INT(I2C_IRQ)
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
I2C_DIRECTION_READ,
|
I2C_DIRECTION_READ,
|
||||||
I2C_DIRECTION_WRITE
|
I2C_DIRECTION_WRITE
|
||||||
} I2C_DIRECTION;
|
} I2C_DIRECTION;
|
||||||
|
|
||||||
|
struct quarkX1000_i2c_config {
|
||||||
|
QUARKX1000_I2C_SPEED speed;
|
||||||
|
QUARKX1000_I2C_ADDR_MODE addressing_mode;
|
||||||
|
|
||||||
|
quarkX1000_i2c_callback cb_rx;
|
||||||
|
quarkX1000_i2c_callback cb_tx;
|
||||||
|
quarkX1000_i2c_callback cb_err;
|
||||||
|
};
|
||||||
|
|
||||||
struct i2c_internal_data {
|
struct i2c_internal_data {
|
||||||
struct quarkX1000_i2c_config config;
|
struct quarkX1000_i2c_config config;
|
||||||
|
|
||||||
|
@ -169,9 +177,11 @@ i2c_data_send(void)
|
||||||
device.tx_buffer += i;
|
device.tx_buffer += i;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void
|
static bool
|
||||||
i2c_isr(void)
|
i2c_isr(void)
|
||||||
{
|
{
|
||||||
|
bool handled = false;
|
||||||
|
|
||||||
if (read(QUARKX1000_IC_INTR_STAT) & QUARKX1000_IC_INTR_STAT_STOP_DET_MASK) {
|
if (read(QUARKX1000_IC_INTR_STAT) & QUARKX1000_IC_INTR_STAT_STOP_DET_MASK) {
|
||||||
i2c_data_read();
|
i2c_data_read();
|
||||||
|
|
||||||
|
@ -185,6 +195,8 @@ i2c_isr(void)
|
||||||
if (device.config.cb_rx)
|
if (device.config.cb_rx)
|
||||||
device.config.cb_rx();
|
device.config.cb_rx();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
handled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (read(QUARKX1000_IC_INTR_STAT) & QUARKX1000_IC_INTR_STAT_TX_EMPTY_MASK) {
|
if (read(QUARKX1000_IC_INTR_STAT) & QUARKX1000_IC_INTR_STAT_TX_EMPTY_MASK) {
|
||||||
|
@ -195,11 +207,16 @@ i2c_isr(void)
|
||||||
set_value(QUARKX1000_IC_INTR_MASK,
|
set_value(QUARKX1000_IC_INTR_MASK,
|
||||||
QUARKX1000_IC_INTR_STAT_STOP_DET_MASK, QUARKX1000_IC_INTR_STAT_STOP_DET_SHIFT, 1);
|
QUARKX1000_IC_INTR_STAT_STOP_DET_MASK, QUARKX1000_IC_INTR_STAT_STOP_DET_SHIFT, 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
handled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (read(QUARKX1000_IC_INTR_STAT) & QUARKX1000_IC_INTR_STAT_RX_FULL_MASK)
|
if(read(QUARKX1000_IC_INTR_STAT) & QUARKX1000_IC_INTR_STAT_RX_FULL_MASK) {
|
||||||
i2c_data_read();
|
i2c_data_read();
|
||||||
|
|
||||||
|
handled = true;
|
||||||
|
}
|
||||||
|
|
||||||
if (read(QUARKX1000_IC_INTR_STAT) & (QUARKX1000_IC_INTR_STAT_TX_ABRT_MASK
|
if (read(QUARKX1000_IC_INTR_STAT) & (QUARKX1000_IC_INTR_STAT_TX_ABRT_MASK
|
||||||
| QUARKX1000_IC_INTR_STAT_TX_OVER_MASK | QUARKX1000_IC_INTR_STAT_RX_OVER_MASK
|
| QUARKX1000_IC_INTR_STAT_TX_OVER_MASK | QUARKX1000_IC_INTR_STAT_RX_OVER_MASK
|
||||||
| QUARKX1000_IC_INTR_STAT_RX_UNDER_MASK)) {
|
| QUARKX1000_IC_INTR_STAT_RX_UNDER_MASK)) {
|
||||||
|
@ -208,20 +225,22 @@ i2c_isr(void)
|
||||||
|
|
||||||
if (device.config.cb_err)
|
if (device.config.cb_err)
|
||||||
device.config.cb_err();
|
device.config.cb_err();
|
||||||
|
|
||||||
|
handled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
return handled;
|
||||||
}
|
}
|
||||||
|
|
||||||
int
|
void
|
||||||
quarkX1000_i2c_configure(struct quarkX1000_i2c_config *config)
|
quarkX1000_i2c_configure(QUARKX1000_I2C_SPEED speed,
|
||||||
|
QUARKX1000_I2C_ADDR_MODE addressing_mode)
|
||||||
{
|
{
|
||||||
uint32_t hcnt, lcnt;
|
uint32_t hcnt, lcnt;
|
||||||
uint8_t ic_fs_spklen;
|
uint8_t ic_fs_spklen;
|
||||||
|
|
||||||
device.config.speed = config->speed;
|
device.config.speed = speed;
|
||||||
device.config.addressing_mode = config->addressing_mode;
|
device.config.addressing_mode = addressing_mode;
|
||||||
device.config.cb_rx = config->cb_rx;
|
|
||||||
device.config.cb_tx = config->cb_tx;
|
|
||||||
device.config.cb_err = config->cb_err;
|
|
||||||
|
|
||||||
if (device.config.speed == QUARKX1000_I2C_SPEED_STANDARD) {
|
if (device.config.speed == QUARKX1000_I2C_SPEED_STANDARD) {
|
||||||
lcnt = I2C_STD_LCNT;
|
lcnt = I2C_STD_LCNT;
|
||||||
|
@ -240,8 +259,16 @@ quarkX1000_i2c_configure(struct quarkX1000_i2c_config *config)
|
||||||
|
|
||||||
/* Clear interrupts. */
|
/* Clear interrupts. */
|
||||||
read(QUARKX1000_IC_CLR_INTR);
|
read(QUARKX1000_IC_CLR_INTR);
|
||||||
|
}
|
||||||
|
|
||||||
return 0;
|
void
|
||||||
|
quarkX1000_i2c_set_callbacks(quarkX1000_i2c_callback rx,
|
||||||
|
quarkX1000_i2c_callback tx,
|
||||||
|
quarkX1000_i2c_callback err)
|
||||||
|
{
|
||||||
|
device.config.cb_rx = rx;
|
||||||
|
device.config.cb_tx = tx;
|
||||||
|
device.config.cb_err = err;
|
||||||
}
|
}
|
||||||
|
|
||||||
static int
|
static int
|
||||||
|
@ -480,13 +507,7 @@ quarkX1000_i2c_is_available(void)
|
||||||
return device.pci.mmio ? 1 : 0;
|
return device.pci.mmio ? 1 : 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void
|
DEFINE_SHARED_IRQ(I2C_IRQ, IRQAGENT3, INTC, PIRQC, i2c_isr);
|
||||||
i2c_handler()
|
|
||||||
{
|
|
||||||
i2c_isr();
|
|
||||||
|
|
||||||
pic_eoi(I2C_IRQ);
|
|
||||||
}
|
|
||||||
|
|
||||||
int
|
int
|
||||||
quarkX1000_i2c_init(void)
|
quarkX1000_i2c_init(void)
|
||||||
|
@ -501,16 +522,7 @@ quarkX1000_i2c_init(void)
|
||||||
|
|
||||||
pci_command_enable(pci_addr, PCI_CMD_1_MEM_SPACE_EN);
|
pci_command_enable(pci_addr, PCI_CMD_1_MEM_SPACE_EN);
|
||||||
|
|
||||||
SET_INTERRUPT_HANDLER(I2C_INT, 0, i2c_handler);
|
|
||||||
|
|
||||||
if (pci_irq_agent_set_pirq(IRQAGENT3, INTC, PIRQC) < 0)
|
|
||||||
return -1;
|
|
||||||
|
|
||||||
pci_pirq_set_irq(PIRQC, I2C_IRQ, 1);
|
|
||||||
|
|
||||||
pci_init(&device.pci, pci_addr, 0);
|
pci_init(&device.pci, pci_addr, 0);
|
||||||
|
|
||||||
pic_unmask_irq(I2C_IRQ);
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
/*
|
/*
|
||||||
* Copyright (C) 2015, Intel Corporation. All rights reserved.
|
* Copyright (C) 2015-2016, Intel Corporation. All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -45,17 +45,12 @@ typedef enum {
|
||||||
|
|
||||||
typedef void (*quarkX1000_i2c_callback)(void);
|
typedef void (*quarkX1000_i2c_callback)(void);
|
||||||
|
|
||||||
struct quarkX1000_i2c_config {
|
|
||||||
QUARKX1000_I2C_SPEED speed;
|
|
||||||
QUARKX1000_I2C_ADDR_MODE addressing_mode;
|
|
||||||
|
|
||||||
quarkX1000_i2c_callback cb_rx;
|
|
||||||
quarkX1000_i2c_callback cb_tx;
|
|
||||||
quarkX1000_i2c_callback cb_err;
|
|
||||||
};
|
|
||||||
|
|
||||||
int quarkX1000_i2c_init(void);
|
int quarkX1000_i2c_init(void);
|
||||||
int quarkX1000_i2c_configure(struct quarkX1000_i2c_config *config);
|
void quarkX1000_i2c_configure(QUARKX1000_I2C_SPEED speed,
|
||||||
|
QUARKX1000_I2C_ADDR_MODE addressing_mode);
|
||||||
|
void quarkX1000_i2c_set_callbacks(quarkX1000_i2c_callback rx,
|
||||||
|
quarkX1000_i2c_callback tx,
|
||||||
|
quarkX1000_i2c_callback err);
|
||||||
int quarkX1000_i2c_is_available(void);
|
int quarkX1000_i2c_is_available(void);
|
||||||
|
|
||||||
int quarkX1000_i2c_read(uint8_t *buf, uint8_t len, uint16_t addr);
|
int quarkX1000_i2c_read(uint8_t *buf, uint8_t len, uint16_t addr);
|
||||||
|
|
|
@ -48,6 +48,19 @@ struct interrupt_context {
|
||||||
uint32_t eip;
|
uint32_t eip;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#define ISR_STUB(label_str, has_error_code, handler_str) \
|
||||||
|
"jmp 2f\n\t" \
|
||||||
|
".align 4\n\t" \
|
||||||
|
label_str ":\n\t" \
|
||||||
|
" pushal\n\t" \
|
||||||
|
" call " handler_str "\n\t" \
|
||||||
|
" popal\n\t" \
|
||||||
|
" .if " #has_error_code "\n\t" \
|
||||||
|
" add $4, %%esp\n\t" \
|
||||||
|
" .endif\n\t" \
|
||||||
|
" iret\n\t" \
|
||||||
|
"2:\n\t"
|
||||||
|
|
||||||
/* Helper macro to register interrupt handler function.
|
/* Helper macro to register interrupt handler function.
|
||||||
*
|
*
|
||||||
* num: Interrupt number (0-255)
|
* num: Interrupt number (0-255)
|
||||||
|
@ -75,17 +88,7 @@ struct interrupt_context {
|
||||||
"push %0\n\t" \
|
"push %0\n\t" \
|
||||||
"call %P1\n\t" \
|
"call %P1\n\t" \
|
||||||
"add $8, %%esp\n\t" \
|
"add $8, %%esp\n\t" \
|
||||||
"jmp 2f\n\t" \
|
ISR_STUB("1", has_error_code, "%P2") \
|
||||||
".align 4\n\t" \
|
|
||||||
"1:\n\t" \
|
|
||||||
" pushal\n\t" \
|
|
||||||
" call %P2\n\t" \
|
|
||||||
" popal\n\t" \
|
|
||||||
" .if " #has_error_code "\n\t" \
|
|
||||||
" add $4, %%esp\n\t" \
|
|
||||||
" .endif\n\t" \
|
|
||||||
" iret\n\t" \
|
|
||||||
"2:\n\t" \
|
|
||||||
:: "g" (num), "i" (idt_set_intr_gate_desc), "i" (handler) \
|
:: "g" (num), "i" (idt_set_intr_gate_desc), "i" (handler) \
|
||||||
: "eax", "ecx", "edx" \
|
: "eax", "ecx", "edx" \
|
||||||
); \
|
); \
|
||||||
|
|
|
@ -61,6 +61,10 @@ SECTIONS {
|
||||||
.rodata ALIGN (32) :
|
.rodata ALIGN (32) :
|
||||||
{
|
{
|
||||||
*(.rodata*)
|
*(.rodata*)
|
||||||
|
|
||||||
|
_sdata_shared_isr = .;
|
||||||
|
KEEP(*(.shared_isr_data*))
|
||||||
|
_edata_shared_isr = .;
|
||||||
}
|
}
|
||||||
|
|
||||||
.data ALIGN (32) :
|
.data ALIGN (32) :
|
||||||
|
|
|
@ -1,18 +1,16 @@
|
||||||
TARGET=galileo
|
TARGET=galileo
|
||||||
|
|
||||||
KNOWN_EXAMPLES = gpio-input gpio-output gpio-interrupt i2c-LSM9DS0
|
KNOWN_EXAMPLES = gpio-input gpio-output gpio-interrupt i2c-LSM9DS0 i2c-callbacks
|
||||||
|
|
||||||
ifneq ($(filter $(EXAMPLE),$(KNOWN_EXAMPLES)),)
|
ifeq ($(filter $(EXAMPLE),$(KNOWN_EXAMPLES)),)
|
||||||
CONTIKI_PROJECT = $(EXAMPLE)
|
$(info Set the variable EXAMPLE to one of the following Galileo-specific examples:)
|
||||||
else
|
$(foreach EXAMPLE,$(KNOWN_EXAMPLES),$(info - $(EXAMPLE)))
|
||||||
CONTIKI_PROJECT = help
|
$(error Unable to proceed)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
CONTIKI_PROJECT = $(EXAMPLE)
|
||||||
|
|
||||||
all: $(CONTIKI_PROJECT)
|
all: $(CONTIKI_PROJECT)
|
||||||
|
|
||||||
CONTIKI = ../..
|
CONTIKI = ../..
|
||||||
include $(CONTIKI)/Makefile.include
|
include $(CONTIKI)/Makefile.include
|
||||||
|
|
||||||
help:
|
|
||||||
@echo -e "\nSet the variable EXAMPLE to one of the following Galileo-specific examples:"
|
|
||||||
@for EXAMPLE in $(KNOWN_EXAMPLES); do echo $$EXAMPLE; done
|
|
||||||
|
|
|
@ -1,73 +0,0 @@
|
||||||
Galileo Specific Examples
|
|
||||||
=======================
|
|
||||||
|
|
||||||
This directory contains galileo-specific example applications to illustrate
|
|
||||||
how to use galileo APIs.
|
|
||||||
|
|
||||||
In order to build a application, you should set the EXAMPLE environment
|
|
||||||
variable to the name of the application you want to build. For instance, if
|
|
||||||
you want to build gpio-output application, run the following command:
|
|
||||||
$ make TARGET=galileo EXAMPLE=gpio-output
|
|
||||||
|
|
||||||
============
|
|
||||||
= GPIO =
|
|
||||||
============
|
|
||||||
|
|
||||||
GPIO Output
|
|
||||||
===========
|
|
||||||
|
|
||||||
This application shows how to use the GPIO driver APIs to manipulate output
|
|
||||||
pins. This application sets the GPIO 4 pin as output pin and toggles its
|
|
||||||
state at every half second.
|
|
||||||
|
|
||||||
For a visual effect, you should wire shield pin IO1 to a led in a protoboard.
|
|
||||||
Once the application is running, you should see a blinking LED.
|
|
||||||
|
|
||||||
GPIO Input
|
|
||||||
==========
|
|
||||||
|
|
||||||
This application shows how to use the GPIO driver APIs to manipulate input
|
|
||||||
pins. This application uses default galileo pinmux initialization and sets
|
|
||||||
the GPIO 5 (IO2) as output pin and GPIO 6 (IO3) as input. It toggles the
|
|
||||||
output pin state at every half second and checks the value on input pin.
|
|
||||||
|
|
||||||
GPIO Interrupt
|
|
||||||
==============
|
|
||||||
|
|
||||||
This application shows how to use the GPIO driver APIs to manipulate interrupt
|
|
||||||
pins. This application uses default galileo pinmux initialization and sets
|
|
||||||
the GPIO 5 (IO2) as output pin and GPIO 6 (IO3) as interrupt. It toggles the
|
|
||||||
output pin stat at every half second in order to emulate an interrupt. This
|
|
||||||
triggers an interrupt and the application callback is called. You can confirm
|
|
||||||
that though the UART output.
|
|
||||||
|
|
||||||
=======
|
|
||||||
= I2C =
|
|
||||||
=======
|
|
||||||
|
|
||||||
I2C LSM9DS0
|
|
||||||
===========
|
|
||||||
This application shows how to use I2C driver APIs to configure I2C Master
|
|
||||||
controller and communicate with LSM9DS0 sensor. At every 5 seconds, the
|
|
||||||
application reads the "who am I" register from gyroscope sensor and prints if
|
|
||||||
the register value matches the expected value described in the spec [1].
|
|
||||||
|
|
||||||
According to the sensor spec, to read the value in "who am I" register, we
|
|
||||||
should first perform an i2c write operation to select the register we want
|
|
||||||
to read from and then we perform the i2c read operation to actually read
|
|
||||||
the register contents.
|
|
||||||
|
|
||||||
The wiring setup is as follows (left column from Galileo and right column from LSM9DS0):
|
|
||||||
- 3.3v and Vin
|
|
||||||
- GND and GND
|
|
||||||
- GND and SDOG
|
|
||||||
- 3.3v and CSG
|
|
||||||
- SDA and SDA
|
|
||||||
- SCL and SCL
|
|
||||||
|
|
||||||
==============
|
|
||||||
= References =
|
|
||||||
==============
|
|
||||||
|
|
||||||
[1] http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00087365.pdf
|
|
||||||
|
|
90
examples/galileo/README.md
Normal file
90
examples/galileo/README.md
Normal file
|
@ -0,0 +1,90 @@
|
||||||
|
Galileo Specific Examples
|
||||||
|
=========================
|
||||||
|
|
||||||
|
This directory contains galileo-specific example applications to illustrate
|
||||||
|
how to use galileo APIs.
|
||||||
|
|
||||||
|
In order to build a application, you should set the EXAMPLE environment
|
||||||
|
variable to the name of the application you want to build. For instance, if
|
||||||
|
you want to build gpio-output application, run the following command:
|
||||||
|
|
||||||
|
```
|
||||||
|
$ make TARGET=galileo EXAMPLE=gpio-output
|
||||||
|
```
|
||||||
|
|
||||||
|
The corresponding EXAMPLE variable setting for each application is
|
||||||
|
listed to the right of its heading.
|
||||||
|
|
||||||
|
GPIO
|
||||||
|
----
|
||||||
|
|
||||||
|
### GPIO Output (EXAMPLE=gpio-output)
|
||||||
|
|
||||||
|
This application shows how to use the GPIO driver APIs to manipulate output
|
||||||
|
pins. This application sets the GPIO 5 pin as output pin and toggles its
|
||||||
|
state at every half second.
|
||||||
|
|
||||||
|
For a visual effect, you should wire shield pin IO2 to a led in a protoboard.
|
||||||
|
Once the application is running, you should see a blinking LED.
|
||||||
|
|
||||||
|
### GPIO Input (EXAMPLE=gpio-input)
|
||||||
|
|
||||||
|
This application shows how to use the GPIO driver APIs to manipulate
|
||||||
|
input pins. This application uses default galileo pinmux
|
||||||
|
initialization and sets the GPIO 5 (shield pin IO2) as output pin and
|
||||||
|
GPIO 6 (shield pin IO3) as input. A jumper should be used to connect
|
||||||
|
the two pins. The application toggles the output pin state at every
|
||||||
|
half second and checks the value on input pin.
|
||||||
|
|
||||||
|
### GPIO Interrupt (EXAMPLE=gpio-interrupt)
|
||||||
|
|
||||||
|
This application shows how to use the GPIO driver APIs to manipulate
|
||||||
|
interrupt pins. This application uses default galileo pinmux
|
||||||
|
initialization and sets the GPIO 5 (shield pin IO2) as output pin and
|
||||||
|
GPIO 6 (shield pin IO3) as interrupt. A jumper should be used to
|
||||||
|
connect the two pins. It toggles the output pin stat at every half
|
||||||
|
second in order to emulate an interrupt. This triggers an interrupt
|
||||||
|
and the application callback is called. You can confirm that though
|
||||||
|
the UART output.
|
||||||
|
|
||||||
|
I2C
|
||||||
|
---
|
||||||
|
|
||||||
|
### I2C LSM9DS0 (EXAMPLE=i2c-LSM9DS0)
|
||||||
|
|
||||||
|
This application shows how to use I2C driver APIs to configure I2C
|
||||||
|
Master controller and communicate with an LSM9DS0 sensor if one has
|
||||||
|
been connected as described below. At every 5 seconds, the application
|
||||||
|
reads the "who am I" register from gyroscope sensor and prints if the
|
||||||
|
register value matches the expected value described in the spec [1].
|
||||||
|
|
||||||
|
According to the sensor spec, to read the value in "who am I" register, we
|
||||||
|
should first perform an i2c write operation to select the register we want
|
||||||
|
to read from and then we perform the i2c read operation to actually read
|
||||||
|
the register contents.
|
||||||
|
|
||||||
|
The wiring setup is as follows (left column from Galileo and right column from LSM9DS0):
|
||||||
|
- 3.3v and Vin
|
||||||
|
- GND and GND
|
||||||
|
- GND and SDOG
|
||||||
|
- 3.3v and CSG
|
||||||
|
- SDA and SDA
|
||||||
|
- SCL and SCL
|
||||||
|
|
||||||
|
### I2C Callbacks (EXAMPLE=i2c-callbacks)
|
||||||
|
|
||||||
|
This application is very similar to the previous one in that it also
|
||||||
|
shows how to use I2C callback functionality, but it can be run without
|
||||||
|
attaching any additional sensors to the platform since it simply
|
||||||
|
communicates with a built-in PWM controller.
|
||||||
|
|
||||||
|
Every five seconds, the application reads the current value of the
|
||||||
|
MODE1 register, which should have previously been initialized to the
|
||||||
|
value 0x20. The test verifies that this expected value is returned by
|
||||||
|
the read.
|
||||||
|
|
||||||
|
References
|
||||||
|
----------
|
||||||
|
|
||||||
|
[1] http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/DM00087365.pdf
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
/*
|
/*
|
||||||
* Copyright (C) 2015, Intel Corporation. All rights reserved.
|
* Copyright (C) 2015-2016, Intel Corporation. All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -33,16 +33,13 @@
|
||||||
#include "contiki.h"
|
#include "contiki.h"
|
||||||
#include "sys/ctimer.h"
|
#include "sys/ctimer.h"
|
||||||
|
|
||||||
#include "galileo-pinmux.h"
|
|
||||||
#include "gpio.h"
|
#include "gpio.h"
|
||||||
#include "i2c.h"
|
|
||||||
|
|
||||||
#define PIN_OUTPUT 5
|
#define PIN_OUTPUT 5
|
||||||
#define PIN_INPUT 6
|
#define PIN_INPUT 6
|
||||||
|
|
||||||
static uint32_t value;
|
static uint32_t value;
|
||||||
static struct ctimer timer;
|
static struct ctimer timer;
|
||||||
static struct quarkX1000_i2c_config i2c_config;
|
|
||||||
|
|
||||||
PROCESS(gpio_input_process, "GPIO Input Process");
|
PROCESS(gpio_input_process, "GPIO Input Process");
|
||||||
AUTOSTART_PROCESSES(&gpio_input_process);
|
AUTOSTART_PROCESSES(&gpio_input_process);
|
||||||
|
@ -70,16 +67,6 @@ PROCESS_THREAD(gpio_input_process, ev, data)
|
||||||
{
|
{
|
||||||
PROCESS_BEGIN();
|
PROCESS_BEGIN();
|
||||||
|
|
||||||
i2c_config.speed = QUARKX1000_I2C_SPEED_STANDARD;
|
|
||||||
i2c_config.addressing_mode = QUARKX1000_I2C_ADDR_MODE_7BIT;
|
|
||||||
|
|
||||||
quarkX1000_i2c_init();
|
|
||||||
quarkX1000_i2c_configure(&i2c_config);
|
|
||||||
|
|
||||||
/* use default pinmux configuration */
|
|
||||||
galileo_pinmux_initialize();
|
|
||||||
|
|
||||||
quarkX1000_gpio_init();
|
|
||||||
quarkX1000_gpio_config(PIN_OUTPUT, QUARKX1000_GPIO_OUT);
|
quarkX1000_gpio_config(PIN_OUTPUT, QUARKX1000_GPIO_OUT);
|
||||||
quarkX1000_gpio_config(PIN_INPUT, QUARKX1000_GPIO_IN);
|
quarkX1000_gpio_config(PIN_INPUT, QUARKX1000_GPIO_IN);
|
||||||
|
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
/*
|
/*
|
||||||
* Copyright (C) 2015, Intel Corporation. All rights reserved.
|
* Copyright (C) 2015-2016, Intel Corporation. All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -34,14 +34,11 @@
|
||||||
#include "sys/ctimer.h"
|
#include "sys/ctimer.h"
|
||||||
|
|
||||||
#include "gpio.h"
|
#include "gpio.h"
|
||||||
#include "i2c.h"
|
|
||||||
#include "galileo-pinmux.h"
|
|
||||||
|
|
||||||
#define PIN_OUTPUT 5
|
#define PIN_OUTPUT 5
|
||||||
#define PIN_INTR 6
|
#define PIN_INTR 6
|
||||||
|
|
||||||
static struct ctimer timer;
|
static struct ctimer timer;
|
||||||
static struct quarkX1000_i2c_config i2c_config;
|
|
||||||
|
|
||||||
PROCESS(gpio_interrupt_process, "GPIO Interrupt Process");
|
PROCESS(gpio_interrupt_process, "GPIO Interrupt Process");
|
||||||
AUTOSTART_PROCESSES(&gpio_interrupt_process);
|
AUTOSTART_PROCESSES(&gpio_interrupt_process);
|
||||||
|
@ -66,16 +63,6 @@ PROCESS_THREAD(gpio_interrupt_process, ev, data)
|
||||||
{
|
{
|
||||||
PROCESS_BEGIN();
|
PROCESS_BEGIN();
|
||||||
|
|
||||||
i2c_config.speed = QUARKX1000_I2C_SPEED_STANDARD;
|
|
||||||
i2c_config.addressing_mode = QUARKX1000_I2C_ADDR_MODE_7BIT;
|
|
||||||
|
|
||||||
quarkX1000_i2c_init();
|
|
||||||
quarkX1000_i2c_configure(&i2c_config);
|
|
||||||
|
|
||||||
/* use default pinmux configuration */
|
|
||||||
galileo_pinmux_initialize();
|
|
||||||
|
|
||||||
quarkX1000_gpio_init();
|
|
||||||
quarkX1000_gpio_config(PIN_OUTPUT, QUARKX1000_GPIO_OUT);
|
quarkX1000_gpio_config(PIN_OUTPUT, QUARKX1000_GPIO_OUT);
|
||||||
quarkX1000_gpio_config(PIN_INTR, QUARKX1000_GPIO_INT | QUARKX1000_GPIO_ACTIVE_HIGH | QUARKX1000_GPIO_EDGE);
|
quarkX1000_gpio_config(PIN_INTR, QUARKX1000_GPIO_INT | QUARKX1000_GPIO_ACTIVE_HIGH | QUARKX1000_GPIO_EDGE);
|
||||||
|
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
/*
|
/*
|
||||||
* Copyright (C) 2015, Intel Corporation. All rights reserved.
|
* Copyright (C) 2015-2016, Intel Corporation. All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -35,7 +35,7 @@
|
||||||
|
|
||||||
#include "gpio.h"
|
#include "gpio.h"
|
||||||
|
|
||||||
#define PIN 4 /* IO1 */
|
#define PIN 5 /* IO2 */
|
||||||
|
|
||||||
static uint32_t value;
|
static uint32_t value;
|
||||||
static struct ctimer timer;
|
static struct ctimer timer;
|
||||||
|
@ -57,7 +57,6 @@ PROCESS_THREAD(gpio_output_process, ev, data)
|
||||||
{
|
{
|
||||||
PROCESS_BEGIN();
|
PROCESS_BEGIN();
|
||||||
|
|
||||||
quarkX1000_gpio_init();
|
|
||||||
quarkX1000_gpio_config(PIN, QUARKX1000_GPIO_OUT);
|
quarkX1000_gpio_config(PIN, QUARKX1000_GPIO_OUT);
|
||||||
|
|
||||||
quarkX1000_gpio_clock_enable();
|
quarkX1000_gpio_clock_enable();
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
/*
|
/*
|
||||||
* Copyright (C) 2015, Intel Corporation. All rights reserved.
|
* Copyright (C) 2015-2016, Intel Corporation. All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -34,7 +34,6 @@
|
||||||
#include "contiki.h"
|
#include "contiki.h"
|
||||||
#include "sys/ctimer.h"
|
#include "sys/ctimer.h"
|
||||||
|
|
||||||
#include "galileo-pinmux.h"
|
|
||||||
#include "i2c.h"
|
#include "i2c.h"
|
||||||
|
|
||||||
#define LSM9DS0_I2C_ADDR 0x6A
|
#define LSM9DS0_I2C_ADDR 0x6A
|
||||||
|
@ -44,7 +43,6 @@
|
||||||
static uint8_t tx_data = WHO_AM_I_ADDR;
|
static uint8_t tx_data = WHO_AM_I_ADDR;
|
||||||
static uint8_t rx_data = 0;
|
static uint8_t rx_data = 0;
|
||||||
static struct ctimer timer;
|
static struct ctimer timer;
|
||||||
static struct quarkX1000_i2c_config cfg;
|
|
||||||
|
|
||||||
PROCESS(i2c_lsm9ds0_process, "I2C LSM9DS0 Who Am I Process");
|
PROCESS(i2c_lsm9ds0_process, "I2C LSM9DS0 Who Am I Process");
|
||||||
AUTOSTART_PROCESSES(&i2c_lsm9ds0_process);
|
AUTOSTART_PROCESSES(&i2c_lsm9ds0_process);
|
||||||
|
@ -84,19 +82,7 @@ PROCESS_THREAD(i2c_lsm9ds0_process, ev, data)
|
||||||
{
|
{
|
||||||
PROCESS_BEGIN();
|
PROCESS_BEGIN();
|
||||||
|
|
||||||
cfg.speed = QUARKX1000_I2C_SPEED_STANDARD;
|
quarkX1000_i2c_set_callbacks(rx, tx, err);
|
||||||
cfg.addressing_mode = QUARKX1000_I2C_ADDR_MODE_7BIT;
|
|
||||||
|
|
||||||
quarkX1000_i2c_init();
|
|
||||||
quarkX1000_i2c_configure(&cfg);
|
|
||||||
|
|
||||||
galileo_pinmux_initialize();
|
|
||||||
|
|
||||||
cfg.cb_rx = rx;
|
|
||||||
cfg.cb_tx = tx;
|
|
||||||
cfg.cb_err = err;
|
|
||||||
|
|
||||||
quarkX1000_i2c_configure(&cfg);
|
|
||||||
|
|
||||||
ctimer_set(&timer, CLOCK_SECOND * 5, timeout, NULL);
|
ctimer_set(&timer, CLOCK_SECOND * 5, timeout, NULL);
|
||||||
|
|
||||||
|
|
93
examples/galileo/i2c-callbacks.c
Normal file
93
examples/galileo/i2c-callbacks.c
Normal file
|
@ -0,0 +1,93 @@
|
||||||
|
/*
|
||||||
|
* Copyright (C) 2015-2016, Intel Corporation. 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 <stdio.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#include "contiki.h"
|
||||||
|
#include "sys/ctimer.h"
|
||||||
|
|
||||||
|
#include "i2c.h"
|
||||||
|
|
||||||
|
#define PWM_PCA9685_0_I2C_ADDR 0x47
|
||||||
|
#define MODE1_ADDR 0x00
|
||||||
|
|
||||||
|
static uint8_t tx_data = MODE1_ADDR;
|
||||||
|
static uint8_t rx_data = 0;
|
||||||
|
static struct ctimer timer;
|
||||||
|
|
||||||
|
PROCESS(i2c_callbacks_process, "I2C Callbacks Example Process");
|
||||||
|
AUTOSTART_PROCESSES(&i2c_callbacks_process);
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
static void
|
||||||
|
rx(void)
|
||||||
|
{
|
||||||
|
/* The value below is programmed into this register in pwm_pca9685_init(). */
|
||||||
|
printf("%s expected value: %x\n",
|
||||||
|
(rx_data == (1 << 5)) ? "Received" : "Did not receive",
|
||||||
|
(unsigned)rx_data);
|
||||||
|
}
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
static void
|
||||||
|
tx(void)
|
||||||
|
{
|
||||||
|
rx_data = 0;
|
||||||
|
|
||||||
|
quarkX1000_i2c_read(&rx_data, sizeof(rx_data), PWM_PCA9685_0_I2C_ADDR);
|
||||||
|
}
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
static void
|
||||||
|
err(void)
|
||||||
|
{
|
||||||
|
printf("Something went wrong. err() callback has been called.\n");
|
||||||
|
}
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
static void
|
||||||
|
timeout(void *data)
|
||||||
|
{
|
||||||
|
quarkX1000_i2c_write(&tx_data, sizeof(tx_data), PWM_PCA9685_0_I2C_ADDR);
|
||||||
|
|
||||||
|
ctimer_reset(&timer);
|
||||||
|
}
|
||||||
|
/*---------------------------------------------------------------------------*/
|
||||||
|
PROCESS_THREAD(i2c_callbacks_process, ev, data)
|
||||||
|
{
|
||||||
|
PROCESS_BEGIN();
|
||||||
|
|
||||||
|
quarkX1000_i2c_set_callbacks(rx, tx, err);
|
||||||
|
|
||||||
|
ctimer_set(&timer, CLOCK_SECOND * 5, timeout, NULL);
|
||||||
|
|
||||||
|
printf("I2C callbacks example is running\n");
|
||||||
|
|
||||||
|
PROCESS_YIELD();
|
||||||
|
|
||||||
|
PROCESS_END();
|
||||||
|
}
|
|
@ -30,6 +30,9 @@ Device drivers:
|
||||||
* Real-Time Clock (RTC)
|
* Real-Time Clock (RTC)
|
||||||
* UART
|
* UART
|
||||||
* Ethernet
|
* Ethernet
|
||||||
|
* I2C
|
||||||
|
* GPIO (default pinmux configuration is listed in
|
||||||
|
platform/galileo/drivers/galileo-pinmux.c)
|
||||||
|
|
||||||
Contiki APIs:
|
Contiki APIs:
|
||||||
* Clock module
|
* Clock module
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
/*
|
/*
|
||||||
* Copyright (C) 2015, Intel Corporation. All rights reserved.
|
* Copyright (C) 2015-2016, Intel Corporation. All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
@ -33,9 +33,13 @@
|
||||||
#include "contiki.h"
|
#include "contiki.h"
|
||||||
#include "contiki-net.h"
|
#include "contiki-net.h"
|
||||||
#include "cpu.h"
|
#include "cpu.h"
|
||||||
#include "interrupt.h"
|
|
||||||
#include "uart.h"
|
|
||||||
#include "eth-conf.h"
|
#include "eth-conf.h"
|
||||||
|
#include "galileo-pinmux.h"
|
||||||
|
#include "gpio.h"
|
||||||
|
#include "i2c.h"
|
||||||
|
#include "interrupt.h"
|
||||||
|
#include "shared-isr.h"
|
||||||
|
#include "uart.h"
|
||||||
|
|
||||||
PROCINIT( &etimer_process
|
PROCINIT( &etimer_process
|
||||||
, &tcpip_process
|
, &tcpip_process
|
||||||
|
@ -55,6 +59,15 @@ main(void)
|
||||||
|
|
||||||
printf("Starting Contiki\n");
|
printf("Starting Contiki\n");
|
||||||
|
|
||||||
|
quarkX1000_i2c_init();
|
||||||
|
quarkX1000_i2c_configure(QUARKX1000_I2C_SPEED_STANDARD,
|
||||||
|
QUARKX1000_I2C_ADDR_MODE_7BIT);
|
||||||
|
/* use default pinmux configuration */
|
||||||
|
if(galileo_pinmux_initialize() < 0) {
|
||||||
|
fprintf(stderr, "Failed to initialize pinmux\n");
|
||||||
|
}
|
||||||
|
quarkX1000_gpio_init();
|
||||||
|
|
||||||
ENABLE_IRQ();
|
ENABLE_IRQ();
|
||||||
|
|
||||||
process_init();
|
process_init();
|
||||||
|
@ -64,6 +77,8 @@ main(void)
|
||||||
|
|
||||||
eth_init();
|
eth_init();
|
||||||
|
|
||||||
|
shared_isr_init();
|
||||||
|
|
||||||
while(1) {
|
while(1) {
|
||||||
process_run();
|
process_run();
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
/*
|
/*
|
||||||
* Copyright (C) 2015, Intel Corporation. All rights reserved.
|
* Copyright (C) 2015-2016, Intel Corporation. All rights reserved.
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
|
|
Loading…
Add table
Reference in a new issue