diff --git a/.gitignore b/.gitignore index 74f62f59b..6ff425546 100644 --- a/.gitignore +++ b/.gitignore @@ -103,3 +103,27 @@ regression-tests/[0-9][0-9]-*/org/ # rl78 build artifacts *.eval-adf7xxxmb4z *.eval-adf7xxxmb4z.srec + +# cscope files +cscope.* + +# vim swap files +*.swp +*.swo + +# x86 UEFI files +cpu/x86/uefi/Makefile.uefi +cpu/x86/uefi/edk2 + +# galileo bsp files +platform/galileo/bsp/libc/Makefile.libc +platform/galileo/bsp/libc/i586-elf/ +platform/galileo/bsp/libc/newlib-2.2.0-1* +platform/galileo/bsp/grub/src/ +platform/galileo/bsp/grub/bin/ + +# galileo build and debug artefacts +*.galileo +*.galileo.dll +*.galileo.efi +LOG_OPENOCD diff --git a/cpu/x86/Makefile.x86 b/cpu/x86/Makefile.x86 deleted file mode 100644 index 0aececd4d..000000000 --- a/cpu/x86/Makefile.x86 +++ /dev/null @@ -1,32 +0,0 @@ -CONTIKI_CPU_DIRS = . - -CONTIKI_SOURCEFILES += mtarch.c elfloader-x86.c - -### Compiler definitions -CC = gcc -LD = gcc -AS = as -OBJCOPY = objcopy -STRIP = strip -CFLAGSNO = -Wall -g -I/usr/local/include -CFLAGS += $(CFLAGSNO) -ifeq ($(HOST_OS),Linux) - LDFLAGS = -Wl,-Map=contiki-$(TARGET).map,-export-dynamic -else - LDFLAGS = -Wl -endif - -### Compilation rules - -%.so: $(OBJECTDIR)/%.o - $(LD) -shared -o $@ $^ - -ifdef CORE -.PHONY: symbols.c symbols.h -symbols.c symbols.h: - $(NM) $(CORE) | awk -f $(CONTIKI)/tools/mknmlist > symbols.c -else -symbols.c symbols.h: - cp ${CONTIKI}/tools/empty-symbols.c symbols.c - cp ${CONTIKI}/tools/empty-symbols.h symbols.h -endif diff --git a/cpu/x86/Makefile.x86_common b/cpu/x86/Makefile.x86_common new file mode 100644 index 000000000..d6e692e9a --- /dev/null +++ b/cpu/x86/Makefile.x86_common @@ -0,0 +1,42 @@ +CONTIKI_CPU_DIRS += . init/common + +CONTIKI_SOURCEFILES += gdt.c helpers.S idt.c cpu.c + +CC = gcc +LD = gcc +AS = as +OBJCOPY = objcopy +SIZE = size +STRIP = strip + +# Omit exception handling unwind tables (see +# http://wiki.dwarfstd.org/index.php?title=Exception_Handling). Removing these +# tables saves space and has not caused any readily-apparent functional +# changes. +# +# Furthermore, the .eh_frame and .eh_frame_hdr sections that are otherwise +# generated are treated as code sections by the UEFI GenFw program, since they +# are read-only alloc sections. They get grouped with the actual code +# sections, ahead of the data sections. This perturbs symbols and complicates +# debugging. +# +# Synchronize the unwind table options here with the CFLAGS and CXXFLAGS in +# ./bsp/libc/build_newlib.sh. +CFLAGS += -Wall -fno-asynchronous-unwind-tables -fno-unwind-tables +LDFLAGS += -Wl,-Map=contiki-$(TARGET).map,--build-id=none + +ifeq ($(BUILD_RELEASE),1) + CFLAGS += -Os -fno-strict-aliasing -ffunction-sections -fdata-sections +# XXX: --gc-sections can be very tricky sometimes. If somehow the release +# binary seems to be broken, check if removing this option fixes the issue. +# Applying the --strip-all option to the UEFI build may induce an "Invalid operation" error. +# The UEFI GenFw program strips symbols. + MULTIBOOT_LDFLAGS += -Wl,--strip-all,--gc-sections +else + CFLAGS += -O0 + ifeq ($(findstring clang,$(CC)),clang) + CFLAGS += -g + else + CFLAGS += -ggdb3 + endif +endif diff --git a/cpu/x86/Makefile.x86_quarkX1000 b/cpu/x86/Makefile.x86_quarkX1000 new file mode 100644 index 000000000..00f352102 --- /dev/null +++ b/cpu/x86/Makefile.x86_quarkX1000 @@ -0,0 +1,33 @@ +include $(CONTIKI)/cpu/x86/Makefile.x86_common + +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 + +CFLAGS += -m32 -march=i586 -mtune=i586 +LDFLAGS += -m32 -Xlinker -T -Xlinker $(CONTIKI)/cpu/x86/quarkX1000.ld +ASFLAGS += --32 -march=i586 -mtune=i586 + +### UEFI support + +UEFI_DIR = $(CONTIKI_CPU)/uefi + +ifndef EN_UEFI +# Include a Makefile generated by the build_uefi.sh script, if available. +# If that script was not run, then UEFI support will not be built. +-include $(UEFI_DIR)/Makefile.uefi +endif + +ifeq ($(EN_UEFI),1) + EDK2_DIR = $(UEFI_DIR)/edk2 + + GEN_FW = $(EDK2_DIR)/BaseTools/Source/C/bin/GenFw + + CONTIKI_CPU_DIRS += uefi + CONTIKI_SOURCEFILES += bootstrap_uefi.c + CFLAGS += -I$(EDK2_DIR)/MdePkg/Include -I$(EDK2_DIR)/MdePkg/Include/Ia32 +else + $(info Note: UEFI support is disabled.) + $(info To enable UEFI support, run $(CONTIKI_CPU)/uefi/build_uefi.sh prior) + $(info to building Contiki.) +endif diff --git a/cpu/x86/bootstrap_quarkX1000.S b/cpu/x86/bootstrap_quarkX1000.S new file mode 100644 index 000000000..8def35843 --- /dev/null +++ b/cpu/x86/bootstrap_quarkX1000.S @@ -0,0 +1,56 @@ +/* + * Copyright (C) 2015, 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. + */ + +# Kernel +.set STACK_SIZE, 8192 + +# Multiboot +.set MAGIC_NUMBER, 0x1BADB002 +.set FLAGS, 0x0 +.set CHECKSUM, -MAGIC_NUMBER + +.section .multiboot +.align 4 +.long MAGIC_NUMBER +.long FLAGS +.long CHECKSUM + +# Reserve space for the C stack. +.lcomm c_stack, STACK_SIZE + +.section .text +.global start +start: + cli + movl $(c_stack + STACK_SIZE), %esp + call main + + /* We're not expected to return from main(). But if we do we halt */ + call halt diff --git a/cpu/x86/drivers/legacy_pc/nmi.c b/cpu/x86/drivers/legacy_pc/nmi.c new file mode 100644 index 000000000..e57d93325 --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/nmi.c @@ -0,0 +1,47 @@ +/* + * Copyright (C) 2015, 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 "helpers.h" + +#define NMI_ENABLE_PORT 0x70 + +void +nmi_enable(void) +{ + uint8_t value = inb(NMI_ENABLE_PORT); + outb(NMI_ENABLE_PORT, value & ~BIT(8)); +} +/*---------------------------------------------------------------------------*/ +void +nmi_disable(void) +{ + uint8_t value = inb(NMI_ENABLE_PORT); + outb(NMI_ENABLE_PORT, value | BIT(8)); +} diff --git a/cpu/x86/drivers/legacy_pc/nmi.h b/cpu/x86/drivers/legacy_pc/nmi.h new file mode 100644 index 000000000..3b5544cf0 --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/nmi.h @@ -0,0 +1,38 @@ +/* + * Copyright (C) 2015, 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 NMI_H +#define NMI_H + +void nmi_enable(void); + +void nmi_disable(void); + +#endif /* NMI_H */ diff --git a/cpu/x86/drivers/legacy_pc/pci.c b/cpu/x86/drivers/legacy_pc/pci.c new file mode 100644 index 000000000..0507ad231 --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/pci.c @@ -0,0 +1,243 @@ +/* + * Copyright (C) 2015, 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 + +#include "pci.h" +#include "helpers.h" + +/* I/O port for PCI configuration address */ +#define PCI_CONFIG_ADDR_PORT 0xCF8 +/* I/O port for PCI configuration data */ +#define PCI_CONFIG_DATA_PORT 0xCFC + +/*---------------------------------------------------------------------------*/ +/* Initialize PCI configuration register address in preparation for accessing + * the specified register. + */ +static void +set_addr(pci_config_addr_t addr) +{ + addr.en_mapping = 1; + + outl(PCI_CONFIG_ADDR_PORT, addr.raw); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Read from the specified PCI configuration register. + * \param addr Address of PCI configuration register. + * \return Value read from PCI configuration register. + */ +uint32_t +pci_config_read(pci_config_addr_t addr) +{ + set_addr(addr); + + return inl(PCI_CONFIG_DATA_PORT); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Write to the PCI configuration data port. + * \param addr Address of PCI configuration register. + * \param data Value to write. + */ +void +pci_config_write(pci_config_addr_t addr, uint32_t data) +{ + set_addr(addr); + + outl(PCI_CONFIG_DATA_PORT, data); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Enable PCI command bits of the specified PCI configuration + * register. + * \param addr Address of PCI configuration register. + * \param flags Flags used to enable PCI command bits. + */ +void +pci_command_enable(pci_config_addr_t addr, uint32_t flags) +{ + uint32_t data; + + addr.reg_off = 0x04; /* PCI COMMAND_REGISTER */ + + data = pci_config_read(addr); + pci_config_write(addr, data | flags); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Set current PIRQ to interrupt queue agent. PCI based interrupts + * PIRQ[A:H] are then available for consumption by either the 8259 + * PICs or the IO-APIC depending on configuration of the 8 PIRQx + * Routing Control Registers PIRQ[A:H]. See also pci_pirq_set_irq(). + * \param agent Interrupt Queue Agent to be used, IRQAGENT[0:3]. + * \param pin Interrupt Pin Route to be used, INT[A:D]. + * \param pirq PIRQ to be used, PIRQ[A:H]. + * \return Returns 0 on success and a negative number otherwise. + */ +int +pci_irq_agent_set_pirq(IRQAGENT agent, INTR_PIN pin, PIRQ pirq) +{ + pci_config_addr_t pci; + uint16_t value; + uint32_t rcba_addr, offset = 0; + + assert(agent >= IRQAGENT0 && agent <= IRQAGENT3); + assert(pin >= INTA && pin <= INTD); + assert(pirq >= PIRQA && pirq <= PIRQH); + + pci.raw = 0; + pci.bus = 0; + pci.dev = 31; + pci.func = 0; + pci.reg_off = 0xF0; /* Root Complex Base Address Register */ + + /* masked to clear non-address bits. */ + rcba_addr = pci_config_read(pci) & ~0x3FFF; + + switch(agent) { + case IRQAGENT0: + if (pin != INTA) + return -1; + offset = 0x3140; + break; + case IRQAGENT1: + offset = 0x3142; + break; + case IRQAGENT2: + if (pin != INTA) + return -1; + offset = 0x3144; + break; + case IRQAGENT3: + offset = 0x3146; + } + + value = *(uint16_t*)(rcba_addr + offset); + + /* clear interrupt pin route and set corresponding pirq. */ + switch(pin) { + case INTA: + value &= ~0xF; + value |= pirq; + break; + case INTB: + value &= ~0xF0; + value |= (pirq << 4); + break; + case INTC: + value &= ~0xF00; + value |= (pirq << 8); + break; + case INTD: + value &= ~0xF000; + value |= (pirq << 12); + } + + *(uint16_t*)(rcba_addr + offset) = value; + + return 0; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Set current IRQ to PIRQ. The interrupt router can be + * programmed to allow PIRQ[A:H] to be routed internally + * to the 8259 as ISA compatible interrupts. See also + * pci_irq_agent_set_pirq(). + * \param pirq PIRQ to be used, PIRQ[A:H]. + * \param pin IRQ to be used, IRQ[0:15]. + * \param route_to_legacy Whether or not the interrupt should be routed to PIC 8259. + */ +void +pci_pirq_set_irq(PIRQ pirq, uint8_t irq, uint8_t route_to_legacy) +{ + pci_config_addr_t pci; + uint32_t value; + + assert(pirq >= PIRQA && pirq <= PIRQH); + assert(irq >= 0 && irq <= 0xF); + assert(route_to_legacy == 0 || route_to_legacy == 1); + + pci.raw = 0; + pci.bus = 0; + pci.dev = 31; + pci.func = 0; + pci.reg_off = (pirq <= PIRQD) ? 0x60 : 0x64; /* PABCDRC and PEFGHRC Registers */ + + value = pci_config_read(pci); + + switch(pirq) { + case PIRQA: + case PIRQE: + value &= ~0x8F; + value |= irq; + value |= (!route_to_legacy << 7); + break; + case PIRQB: + case PIRQF: + value &= ~0x8F00; + value |= (irq << 8); + value |= (!route_to_legacy << 15); + break; + case PIRQC: + case PIRQG: + value &= ~0x8F0000; + value |= (irq << 16); + value |= (!route_to_legacy << 23); + break; + case PIRQD: + case PIRQH: + value &= ~0x8F000000; + value |= (irq << 24); + value |= (!route_to_legacy << 31); + } + + set_addr(pci); + outl(PCI_CONFIG_DATA_PORT, value); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialize a structure for a PCI device driver that performs + * MMIO to address range 0. Assumes that device has already + * been configured with an MMIO address range 0, e.g. by + * firmware. + * \param c_this Structure that will be initialized to represent the driver. + * \param pci_addr PCI base address of device. + * \param meta Base address of optional driver-defined metadata. + */ +void +pci_init(pci_driver_t *c_this, pci_config_addr_t pci_addr, uintptr_t meta) +{ + /* The BAR value is masked to clear non-address bits. */ + c_this->mmio = pci_config_read(pci_addr) & ~0xFFF; + c_this->meta = meta; +} +/*---------------------------------------------------------------------------*/ diff --git a/cpu/x86/drivers/legacy_pc/pci.h b/cpu/x86/drivers/legacy_pc/pci.h new file mode 100644 index 000000000..c938f9c6c --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/pci.h @@ -0,0 +1,119 @@ +/* + * Copyright (C) 2015, 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_PCI_H_ +#define CPU_X86_DRIVERS_LEGACY_PC_PCI_H_ + +#include +#include "helpers.h" + +/** PCI configuration register identifier for Base Address Registers */ +#define PCI_CONFIG_REG_BAR0 0x10 +#define PCI_CONFIG_REG_BAR1 0x14 + +/** PCI Interrupt Routing is mapped using Interrupt Queue Agents */ +typedef enum { + IRQAGENT0, + IRQAGENT1, + IRQAGENT2, + IRQAGENT3 +} IRQAGENT; + +/** PCI Interupt Pins */ +typedef enum { + INTA, + INTB, + INTC, + INTD +} INTR_PIN; + +/** + * PCI based interrupts PIRQ[A:H] are then available for consumption by either + * the 8259 PICs or the IO-APIC. + */ +typedef enum { + PIRQA, + PIRQB, + PIRQC, + PIRQD, + PIRQE, + PIRQF, + PIRQG, + PIRQH, +} PIRQ; + +/** PCI command register bit to enable bus mastering */ +#define PCI_CMD_2_BUS_MST_EN BIT(2) +/** PCI command register bit to enable memory space */ +#define PCI_CMD_1_MEM_SPACE_EN BIT(1) + +/** + * PCI configuration address + * + * Refer to Intel Quark SoC X1000 Datasheet, Section 5.5 for more details on + * PCI configuration register access. + */ +typedef union pci_config_addr { + struct { + /** Register/offset number. Least-significant two bits should be zero. */ + uint32_t reg_off : 8; + uint32_t func : 3; /**< Function number */ + uint32_t dev : 5; /**< Device number */ + uint32_t bus : 8; /**< Bus number */ + uint32_t : 7; + /** Must be set to perform PCI configuration access. */ + uint32_t en_mapping : 1; + }; + uint32_t raw; +} pci_config_addr_t; + +uint32_t pci_config_read(pci_config_addr_t addr); +void pci_config_write(pci_config_addr_t addr, uint32_t data); +void pci_command_enable(pci_config_addr_t addr, uint32_t flags); + +/** + * PCI device driver instance with an optional single MMIO range and optional + * metadata. + */ +typedef struct pci_driver { + uintptr_t mmio; /**< MMIO range base address */ + uintptr_t meta; /**< Driver-defined metadata base address */ +} pci_driver_t; + +void pci_init(pci_driver_t *c_this, pci_config_addr_t pci_addr, uintptr_t meta); +int pci_irq_agent_set_pirq(IRQAGENT agent, INTR_PIN pin, PIRQ pirq); +void pci_pirq_set_irq(PIRQ pirq, uint8_t irq, uint8_t route_to_legacy); + +#define PCI_MMIO_READL(c_this, dest, reg_addr) \ + dest = *((volatile uint32_t *)((c_this).mmio + (reg_addr))) +#define PCI_MMIO_WRITEL(c_this, reg_addr, src) \ + *((volatile uint32_t *)((c_this).mmio + (reg_addr))) = (src) + +#endif /* CPU_X86_DRIVERS_LEGACY_PC_PCI_H_ */ diff --git a/cpu/x86/drivers/legacy_pc/pic.c b/cpu/x86/drivers/legacy_pc/pic.c new file mode 100644 index 000000000..1acb351d1 --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/pic.c @@ -0,0 +1,60 @@ +/* + * Copyright (C) 2015, 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 "drivers/legacy_pc/pic.h" + +#define PIC_ACK 0x20 + +void +pic_unmask_irq(unsigned int num) +{ + uint16_t port; + uint8_t bitmap; + + if(num <= 7) { + port = PIC1_DATA_PORT; + } else { + port = PIC2_DATA_PORT; + num -= 8; + } + + bitmap = inb(port); + outb(port, bitmap & ~BIT(num)); +} +/*---------------------------------------------------------------------------*/ +void +pic_eoi(unsigned int irq) +{ + if(irq >= 8) { + outb(PIC2_CMD_PORT, PIC_ACK); + } + + outb(PIC1_CMD_PORT, PIC_ACK); +} diff --git a/cpu/x86/drivers/legacy_pc/pic.h b/cpu/x86/drivers/legacy_pc/pic.h new file mode 100644 index 000000000..d39942438 --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/pic.h @@ -0,0 +1,86 @@ +/* + * Copyright (C) 2015, 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 PIC_H +#define PIC_H + +#include "helpers.h" + +#define PIC1_CMD_PORT 0x20 +#define PIC1_DATA_PORT 0x21 +#define PIC2_CMD_PORT 0xA0 +#define PIC2_DATA_PORT 0xA1 +#define PIC1_OFFSET 0x20 +#define PIC2_OFFSET PIC1_OFFSET + 8 + +/* + * Returns the actual interrupt number of a given IRQ, + * no matter which PIC it is part of. + */ +#define PIC_INT(a) (a + PIC1_OFFSET) + +void pic_unmask_irq(unsigned int num); + +/* This function initializes the daisy-chained Master and Slave 8259 PICs. + * It is only called once, so let's give the compiler the option to inline it. + * For more information about the ICWs, please refer to http://stanislavs.org/helppc/8259.html. + */ +static inline void +pic_init(void) +{ + /* ICW1: Initialization. */ + outb(PIC1_CMD_PORT, 0x11); + outb(PIC2_CMD_PORT, 0x11); + + /* ICW2: Remap IRQs by setting an IDT Offset for each PIC. */ + outb(PIC1_DATA_PORT, PIC1_OFFSET); + outb(PIC2_DATA_PORT, PIC2_OFFSET); + + /* ICW3: Setup Slave to Master's IRQ2. */ + outb(PIC1_DATA_PORT, 0x04); + outb(PIC2_DATA_PORT, 0x02); + + /* ICW4: Environment setup. Set PIC1 as master and PIC2 as slave. */ + outb(PIC1_DATA_PORT, 0x01); + outb(PIC2_DATA_PORT, 0x01); + + /* Set the IMR register, masking all hardware interrupts but IRQ 2. + * We will have to unmask each IRQ when registering them. */ + outb(PIC1_DATA_PORT, 0xfb); + outb(PIC2_DATA_PORT, 0xff); +} + +/* + * This function sends an end-of-interrupt (EOI) to the correct PIC according + * to the IRQ line number. + */ +void pic_eoi(unsigned int irq); + +#endif /* PIC_H */ diff --git a/cpu/x86/drivers/legacy_pc/pit.c b/cpu/x86/drivers/legacy_pc/pit.c new file mode 100644 index 000000000..3d7b2816d --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/pit.c @@ -0,0 +1,80 @@ +/* + * Copyright (C) 2015, 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 + +#include "drivers/legacy_pc/pic.h" +#include "drivers/legacy_pc/pit.h" +#include "helpers.h" +#include "interrupt.h" + +/* PCs usually provide an 8254 PIT chip with maximum clock of 1.193182 MHz. */ +#define PIT_CONTROL_PORT 0x43 +#define PIT_COUNTER0_PORT 0x40 +#define PIT_CLOCK_FREQUENCY 1193182 +#define PIT_IRQ 0 +#define PIT_INT PIC_INT(PIT_IRQ) + +static pit_int_callback interrupt_cb; + +static void +pit_int_handler(void) +{ + interrupt_cb(); + + pic_eoi(PIT_IRQ); +} +/*---------------------------------------------------------------------------*/ +void +pit_init(uint32_t ticks_rate, pit_int_callback cb) +{ + SET_INTERRUPT_HANDLER(PIT_INT, 0, pit_int_handler); + + interrupt_cb = cb; + + /* Calculate the 16bit divisor that can provide the chosen clock tick rate + * (CLOCK_CONF_SECOND in contiki-conf.h). For reference --> tick rate = clock frequency / divisor. + * If we provide an odd divisor to the Square Wave generator (Mode 3) of + * the Counter0, the duty cycle won't be exactly 50%, so we always round + * it to nearest even integer. + */ + uint16_t divisor = rint(PIT_CLOCK_FREQUENCY / ticks_rate); + + /* Setup Control register flags in a didactic way. */ + uint8_t flags = 0x30; /* Set bits 7:6 to select Counter0 and 5:4 to select "write 7:0 bits first". */ + flags |= 0x6; /* Set bits 3:1 to Mode 3 and bit 0 to BCD off. */ + + outb(PIT_CONTROL_PORT, flags); + + outb(PIT_COUNTER0_PORT, divisor & 0xFF); /* Write least significant bytes first. */ + outb(PIT_COUNTER0_PORT, (divisor >> 8) & 0xFF); + + pic_unmask_irq(PIT_IRQ); +} diff --git a/cpu/x86/drivers/legacy_pc/pit.h b/cpu/x86/drivers/legacy_pc/pit.h new file mode 100644 index 000000000..0a16b8929 --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/pit.h @@ -0,0 +1,45 @@ +/* + * Copyright (C) 2015, 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 PIT_H +#define PIT_H + +#include + +typedef void (*pit_int_callback)(void); + +/** + * Initializes the 8254 Programmable Interrupt Timer chip (Counter 0 only). + * The PIT Interrupt callback is implemented by the driver's users. It is + * called from interrupt context, so it has to return as soon as possible. + */ +void pit_init(uint32_t ticks_rate, pit_int_callback c); + +#endif /* PIT_H */ diff --git a/cpu/x86/drivers/legacy_pc/rtc.c b/cpu/x86/drivers/legacy_pc/rtc.c new file mode 100644 index 000000000..cf059315b --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/rtc.c @@ -0,0 +1,95 @@ +/* + * Copyright (C) 2015, 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 "drivers/legacy_pc/rtc.h" +#include "drivers/legacy_pc/pic.h" +#include "drivers/legacy_pc/nmi.h" +#include "helpers.h" +#include "interrupt.h" + +#define RTC_INDEX_REGISTER 0x70 +#define RTC_TARGET_REGISTER 0x71 +#define RTC_IRQ 8 +#define RTC_INT PIC_INT(RTC_IRQ) + +static void (*user_callback)(void); + +static void +rtc_handler() +{ + user_callback(); + + /* Clear Register C otherwise interrupts will not happen again. + * Register C is automatically cleared when it is read so we do + * a dummy read to clear it. + */ + outb(RTC_INDEX_REGISTER, 0x0C); + inb(RTC_TARGET_REGISTER); + + /* Issue the End of Interrupt to PIC */ + pic_eoi(RTC_IRQ); +} +/*---------------------------------------------------------------------------*/ +/* Initialize the Real Time Clock. + * @frequency: RTC has very specific values for frequency. They are: 2, 4, 8, + * 16, 32, 64, 128, 256, 512, 1024, 2048, 4096, and 8192 Hz. + * value otherwise it will not work properly. + * @callback: This callback is called every time the RTC IRQ is raised. + * It is executed in interrupt context. + */ +void +rtc_init(rtc_frequency_t frequency, void (*callback)(void)) +{ + uint8_t reg_a, reg_b; + + user_callback = callback; + + SET_INTERRUPT_HANDLER(RTC_INT, 0, rtc_handler); + + nmi_disable(); + + /* Select interrupt period to 7.8125 ms */ + outb(RTC_INDEX_REGISTER, 0x8A); + reg_a = inb(RTC_TARGET_REGISTER); + reg_a &= 0xF0; + reg_a |= frequency; + outb(RTC_INDEX_REGISTER, 0x8A); + outb(RTC_TARGET_REGISTER, reg_a); + + /* Enable periodic interrupt */ + outb(RTC_INDEX_REGISTER, 0x8B); + reg_b = inb(RTC_TARGET_REGISTER); + outb(RTC_INDEX_REGISTER, 0x8B); + outb(RTC_TARGET_REGISTER, reg_b | BIT(6)); + + nmi_enable(); + + pic_unmask_irq(RTC_IRQ); +} diff --git a/cpu/x86/drivers/legacy_pc/rtc.h b/cpu/x86/drivers/legacy_pc/rtc.h new file mode 100644 index 000000000..257accb43 --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/rtc.h @@ -0,0 +1,52 @@ +/* + * Copyright (C) 2015, 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 RTC_H +#define RTC_H + +typedef enum { + RTC_8192_HZ = 2, + RTC_4096_HZ = 3, + RTC_2048_HZ = 4, + RTC_1024_HZ = 5, + RTC_512_HZ = 6, + RTC_256_HZ = 7, + RTC_128_HZ = 8, + RTC_64_HZ = 9, + RTC_32_HZ = 10, + RTC_16_HZ = 11, + RTC_8_HZ = 12, + RTC_4_HZ = 13, + RTC_2_HZ = 14, +} rtc_frequency_t; + +void rtc_init(rtc_frequency_t frequency, void (*callback)(void)); + +#endif /* RTC_H */ diff --git a/cpu/x86/drivers/legacy_pc/uart-16x50.c b/cpu/x86/drivers/legacy_pc/uart-16x50.c new file mode 100644 index 000000000..296719faa --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/uart-16x50.c @@ -0,0 +1,123 @@ +/* + * Copyright (C) 2015, 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 "uart-16x50.h" +#include +#include "helpers.h" + +/* Refer to Intel Quark SoC X1000 Datasheet, Chapter 18 for more details on + * UART operation. + */ + +/* Divisor Latch Access Bit (DLAB) mask for Line Control Register (LCR). + * + * When bit is set, enables access to divisor registers to set baud rate. When + * clear, enables access to other registers mapped to the same addresses as the + * divisor registers. + */ +#define UART_LCR_7_DLAB BIT(7) +/* Setting for LCR that configures the UART to operate with no parity, 1 stop + * bit, and eight bits per character. + */ +#define UART_LCR_8BITS 0x03 + +/* FIFO Control Register (FCR) bitmasks */ +#define UART_FCR_0_FIFOE BIT(0) /*< enable FIFOs */ +#define UART_FCR_1_RFIFOR BIT(1) /*< reset RX FIFO */ +#define UART_FCR_2_XFIFOR BIT(2) /*< reset TX FIFO */ + +/* Line Status Register (LSR) Transmit Holding Register Empty bitmask to check + * whether the Transmit Holding Register (THR) or TX FIFO is empty. + */ +#define UART_LSR_5_THRE BIT(5) + +/* MMIO registers for UART */ +typedef struct uart_16x50_regs { + volatile uint32_t rbr_thr_dll, ier_dlh, iir_fcr, lcr; + volatile uint32_t mcr, lsr, msr, scr, usr, htx, dmasa; +} uart_16x50_regs_t; + +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialize an MMIO-programmable 16X50 UART. + * \param c_this Structure that will be initialized to represent the device. + * \param pci_addr PCI address of device. + * \param dl Divisor setting to configure the baud rate. + */ +void +uart_16x50_init(uart_16x50_driver_t *c_this, + pci_config_addr_t pci_addr, + uint16_t dl) +{ + /* This assumes that the UART had an MMIO range assigned to it by the + * firmware during boot. + */ + pci_init(c_this, pci_addr, 0); + + uart_16x50_regs_t *regs = (uart_16x50_regs_t *)c_this->mmio; + + /* Set the DLAB bit to enable access to divisor settings. */ + regs->lcr = UART_LCR_7_DLAB; + + /* The divisor settings configure the baud rate, and may need to be defined + * on a per-device basis. + */ + regs->rbr_thr_dll = dl & UINT8_MAX; + regs->ier_dlh = dl >> 8; + + /* Clear the DLAB bit to enable access to other settings and configure other + * UART parameters. + */ + regs->lcr = UART_LCR_8BITS; + + /* Enable the FIFOs. */ + regs->iir_fcr = UART_FCR_0_FIFOE | UART_FCR_1_RFIFOR | UART_FCR_2_XFIFOR; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Transmit a character through a UART. + * \param c_this Initialized structure representing the device. + * \param c Character to be transmitted. + * + * This procedure will block indefinitely until the UART is ready + * to accept the character to be transmitted. + */ +void +uart_16x50_tx(uart_16x50_driver_t c_this, uint8_t c) +{ + struct uart_16x50_regs *regs = (uart_16x50_regs_t *)c_this.mmio; + + /* Wait for space in TX FIFO. */ + while((regs->lsr & UART_LSR_5_THRE) == 0); + + /* Add character to TX FIFO. */ + regs->rbr_thr_dll = c; +} +/*---------------------------------------------------------------------------*/ diff --git a/cpu/x86/drivers/legacy_pc/uart-16x50.h b/cpu/x86/drivers/legacy_pc/uart-16x50.h new file mode 100644 index 000000000..615806518 --- /dev/null +++ b/cpu/x86/drivers/legacy_pc/uart-16x50.h @@ -0,0 +1,44 @@ +/* + * Copyright (C) 2015, 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_UART_16X50_H_ +#define CPU_X86_DRIVERS_LEGACY_PC_UART_16X50_H_ + +#include "pci.h" + +typedef pci_driver_t uart_16x50_driver_t; + +void uart_16x50_init(uart_16x50_driver_t *c_this, + pci_config_addr_t pci_addr, + uint16_t dl); + +void uart_16x50_tx(uart_16x50_driver_t c_this, uint8_t c); + +#endif /* CPU_X86_DRIVERS_LEGACY_PC_UART_16X50_H_ */ diff --git a/cpu/x86/drivers/quarkX1000/eth.c b/cpu/x86/drivers/quarkX1000/eth.c new file mode 100644 index 000000000..2f02213ea --- /dev/null +++ b/cpu/x86/drivers/quarkX1000/eth.c @@ -0,0 +1,372 @@ +/* + * Copyright (C) 2015, 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 +#include +#include +#include "contiki-net.h" +#include "eth.h" +#include "helpers.h" +#include "net/ip/uip.h" +#include "pci.h" + +typedef pci_driver_t quarkX1000_eth_driver_t; + +/* Refer to Intel Quark SoC X1000 Datasheet, Chapter 15 for more details on + * Ethernet device operation. + * + * This driver puts the Ethernet device into a very simple and space-efficient + * mode of operation. It only allocates a single packet descriptor for each of + * the transmit and receive directions, computes checksums on the CPU, and + * enables store-and-forward mode for both transmit and receive directions. + */ + +/* Transmit descriptor */ +typedef struct quarkX1000_eth_tx_desc { + /* First word of transmit descriptor */ + union { + struct { + /* Only valid in half-duplex mode. */ + uint32_t deferred_bit : 1; + uint32_t err_underflow : 1; + uint32_t err_excess_defer : 1; + uint32_t coll_cnt_slot_num : 4; + uint32_t vlan_frm : 1; + uint32_t err_excess_coll : 1; + uint32_t err_late_coll : 1; + uint32_t err_no_carrier : 1; + uint32_t err_carrier_loss : 1; + uint32_t err_ip_payload : 1; + uint32_t err_frm_flushed : 1; + uint32_t err_jabber_tout : 1; + /* OR of all other error bits. */ + uint32_t err_summary : 1; + uint32_t err_ip_hdr : 1; + uint32_t tx_timestamp_stat : 1; + uint32_t vlan_ins_ctrl : 2; + uint32_t addr2_chained : 1; + uint32_t tx_end_of_ring : 1; + uint32_t chksum_ins_ctrl : 2; + uint32_t replace_crc : 1; + uint32_t tx_timestamp_en : 1; + uint32_t dis_pad : 1; + uint32_t dis_crc : 1; + uint32_t first_seg_in_frm : 1; + uint32_t last_seg_in_frm : 1; + uint32_t intr_on_complete : 1; + /* When set, descriptor is owned by DMA. */ + uint32_t own : 1; + }; + uint32_t tdes0; + }; + /* Second word of transmit descriptor */ + union { + struct { + uint32_t tx_buf1_sz : 13; + uint32_t : 3; + uint32_t tx_buf2_sz : 13; + uint32_t src_addr_ins_ctrl : 3; + }; + uint32_t tdes1; + }; + /* Pointer to frame data buffer */ + uint8_t *buf1_ptr; + /* Unused, since this driver initializes only a single descriptor for each + * direction. + */ + uint8_t *buf2_ptr; +} quarkX1000_eth_tx_desc_t; + +/* Transmit descriptor */ +typedef struct quarkX1000_eth_rx_desc { + /* First word of receive descriptor */ + union { + struct { + uint32_t ext_stat : 1; + uint32_t err_crc : 1; + uint32_t err_dribble_bit : 1; + uint32_t err_rx_mii : 1; + uint32_t err_rx_wdt : 1; + uint32_t frm_type : 1; + uint32_t err_late_coll : 1; + uint32_t giant_frm : 1; + uint32_t last_desc : 1; + uint32_t first_desc : 1; + uint32_t vlan_tag : 1; + uint32_t err_overflow : 1; + uint32_t length_err : 1; + uint32_t s_addr_filt_fail : 1; + uint32_t err_desc : 1; + uint32_t err_summary : 1; + uint32_t frm_len : 14; + uint32_t d_addr_filt_fail : 1; + uint32_t own : 1; + }; + uint32_t rdes0; + }; + /* Second word of receive descriptor */ + union { + struct { + uint32_t rx_buf1_sz : 13; + uint32_t : 1; + uint32_t addr2_chained : 1; + uint32_t rx_end_of_ring : 1; + uint32_t rx_buf2_sz : 13; + uint32_t : 2; + uint32_t dis_int_compl : 1; + }; + uint32_t rdes1; + }; + /* Pointer to frame data buffer */ + uint8_t *buf1_ptr; + /* Unused, since this driver initializes only a single descriptor for each + * direction. + */ + uint8_t *buf2_ptr; +} quarkX1000_eth_rx_desc_t; + +/* Driver metadata associated with each Ethernet device */ +typedef struct quarkX1000_eth_meta { + /* Transmit descriptor */ + volatile quarkX1000_eth_tx_desc_t tx_desc; + /* Transmit DMA packet buffer */ + volatile uint8_t tx_buf[UIP_BUFSIZE]; + /* Receive descriptor */ + volatile quarkX1000_eth_rx_desc_t rx_desc; + /* Receive DMA packet buffer */ + volatile uint8_t rx_buf[UIP_BUFSIZE]; +} quarkX1000_eth_meta_t; + +#define LOG_PFX "quarkX1000_eth: " + +#define MMIO_SZ 0x2000 + +#define MAC_CONF_14_RMII_100M BIT(14) +#define MAC_CONF_11_DUPLEX BIT(11) +#define MAC_CONF_3_TX_EN BIT(3) +#define MAC_CONF_2_RX_EN BIT(2) + +#define OP_MODE_25_RX_STORE_N_FORWARD BIT(25) +#define OP_MODE_21_TX_STORE_N_FORWARD BIT(21) +#define OP_MODE_13_START_TX BIT(13) +#define OP_MODE_1_START_RX BIT(1) + +#define REG_ADDR_MAC_CONF 0x0000 +#define REG_ADDR_MACADDR_HI 0x0040 +#define REG_ADDR_MACADDR_LO 0x0044 +#define REG_ADDR_TX_POLL_DEMAND 0x1004 +#define REG_ADDR_RX_POLL_DEMAND 0x1008 +#define REG_ADDR_RX_DESC_LIST 0x100C +#define REG_ADDR_TX_DESC_LIST 0x1010 +#define REG_ADDR_DMA_OPERATION 0x1018 + +static quarkX1000_eth_driver_t drv; +static quarkX1000_eth_meta_t meta; + +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialize the first Quark X1000 Ethernet MAC. + * + * This procedure assumes that an MMIO range for the device was + * previously assigned, e.g. by firmware. + */ +void +quarkX1000_eth_init(void) +{ + pci_config_addr_t pci_addr = { .raw = 0 }; + uip_eth_addr mac_addr; + uint32_t mac_tmp1, mac_tmp2; + + /* PCI address from section 15.4 of Intel Quark SoC X1000 Datasheet. */ + + pci_addr.dev = 20; + pci_addr.func = 6; + + /* Activate MMIO and DMA access. */ + pci_command_enable(pci_addr, PCI_CMD_2_BUS_MST_EN | PCI_CMD_1_MEM_SPACE_EN); + + printf(LOG_PFX "Activated MMIO and DMA access.\n"); + + pci_addr.reg_off = PCI_CONFIG_REG_BAR0; + + /* Configure the device MMIO range and initialize the driver structure. */ + pci_init(&drv, pci_addr, (uintptr_t)&meta); + + /* Read the MAC address from the device. */ + PCI_MMIO_READL(drv, mac_tmp1, REG_ADDR_MACADDR_HI); + PCI_MMIO_READL(drv, mac_tmp2, REG_ADDR_MACADDR_LO); + + /* Convert the data read from the device into the format expected by + * Contiki. + */ + mac_addr.addr[5] = (uint8_t)(mac_tmp1 >> 8); + mac_addr.addr[4] = (uint8_t)mac_tmp1; + mac_addr.addr[3] = (uint8_t)(mac_tmp2 >> 24); + mac_addr.addr[2] = (uint8_t)(mac_tmp2 >> 16); + mac_addr.addr[1] = (uint8_t)(mac_tmp2 >> 8); + mac_addr.addr[0] = (uint8_t)mac_tmp2; + + printf(LOG_PFX "MAC address = %02x:%02x:%02x:%02x:%02x:%02x.\n", + mac_addr.addr[0], + mac_addr.addr[1], + mac_addr.addr[2], + mac_addr.addr[3], + mac_addr.addr[4], + mac_addr.addr[5] + ); + + uip_setethaddr(mac_addr); + + /* Initialize transmit descriptor. */ + meta.tx_desc.tdes0 = 0; + meta.tx_desc.tdes1 = 0; + + meta.tx_desc.buf1_ptr = (uint8_t *)meta.tx_buf; + meta.tx_desc.tx_end_of_ring = 1; + meta.tx_desc.first_seg_in_frm = 1; + meta.tx_desc.last_seg_in_frm = 1; + meta.tx_desc.tx_end_of_ring = 1; + + /* Initialize receive descriptor. */ + meta.rx_desc.rdes0 = 0; + meta.rx_desc.rdes1 = 0; + + meta.rx_desc.buf1_ptr = (uint8_t *)meta.rx_buf; + meta.rx_desc.own = 1; + meta.rx_desc.first_desc = 1; + meta.rx_desc.last_desc = 1; + meta.rx_desc.rx_buf1_sz = UIP_BUFSIZE; + meta.rx_desc.rx_end_of_ring = 1; + + /* Install transmit and receive descriptors. */ + PCI_MMIO_WRITEL(drv, REG_ADDR_RX_DESC_LIST, (uint32_t)&meta.rx_desc); + PCI_MMIO_WRITEL(drv, REG_ADDR_TX_DESC_LIST, (uint32_t)&meta.tx_desc); + + PCI_MMIO_WRITEL(drv, REG_ADDR_MAC_CONF, + /* Set the RMII speed to 100Mbps */ + MAC_CONF_14_RMII_100M | + /* Enable full-duplex mode */ + MAC_CONF_11_DUPLEX | + /* Enable transmitter */ + MAC_CONF_3_TX_EN | + /* Enable receiver */ + MAC_CONF_2_RX_EN); + + PCI_MMIO_WRITEL(drv, REG_ADDR_DMA_OPERATION, + /* Enable receive store-and-forward mode for simplicity. */ + OP_MODE_25_RX_STORE_N_FORWARD | + /* Enable transmit store-and-forward mode for simplicity. */ + OP_MODE_21_TX_STORE_N_FORWARD | + /* Place the transmitter state machine in the Running + state. */ + OP_MODE_13_START_TX | + /* Place the receiver state machine in the Running state. */ + OP_MODE_1_START_RX); + + printf(LOG_PFX "Enabled 100M full-duplex mode.\n"); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Poll for a received Ethernet frame. + * \param frame_len Will be set to the size of the received Ethernet frame or + * zero if no frame is available. + * + * If a frame is received, this procedure copies it into the + * global uip_buf buffer. + */ +void +quarkX1000_eth_poll(uint16_t *frame_len) +{ + uint16_t frm_len = 0; + + /* Check whether the RX descriptor is still owned by the device. If not, + * process the received frame or an error that may have occurred. + */ + if(meta.rx_desc.own == 0) { + if(meta.rx_desc.err_summary) { + fprintf(stderr, + LOG_PFX "Error receiving frame: RDES0 = %08x, RDES1 = %08x.\n", + meta.rx_desc.rdes0, meta.rx_desc.rdes1); + assert(0); + } + + frm_len = meta.rx_desc.frm_len; + assert(frm_len <= UIP_BUFSIZE); + memcpy(uip_buf, (void *)meta.rx_buf, frm_len); + + /* Return ownership of the RX descriptor to the device. */ + meta.rx_desc.own = 1; + + /* Request that the device check for an available RX descriptor, since + * ownership of the descriptor was just transferred to the device. + */ + PCI_MMIO_WRITEL(drv, REG_ADDR_RX_POLL_DEMAND, 1); + } + + *frame_len = frm_len; +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Transmit the current Ethernet frame. + * + * This procedure will block indefinitely until the Ethernet device is + * ready to accept a new outgoing frame. It then copies the current + * Ethernet frame from the global uip_buf buffer to the device DMA + * buffer and signals to the device that a new frame is available to be + * transmitted. + */ +void +quarkX1000_eth_send(void) +{ + /* Wait until the TX descriptor is no longer owned by the device. */ + while(meta.tx_desc.own == 1); + + /* Check whether an error occurred transmitting the previous frame. */ + if(meta.tx_desc.err_summary) { + fprintf(stderr, + LOG_PFX "Error transmitting frame: TDES0 = %08x, TDES1 = %08x.\n", + meta.tx_desc.tdes0, meta.tx_desc.tdes1); + assert(0); + } + + /* Transmit the next frame. */ + assert(uip_len <= UIP_BUFSIZE); + memcpy((void *)meta.tx_buf, uip_buf, uip_len); + + meta.tx_desc.tx_buf1_sz = uip_len; + + meta.tx_desc.own = 1; + + /* Request that the device check for an available TX descriptor, since + * ownership of the descriptor was just transferred to the device. + */ + PCI_MMIO_WRITEL(drv, REG_ADDR_TX_POLL_DEMAND, 1); +} +/*---------------------------------------------------------------------------*/ diff --git a/cpu/x86/drivers/quarkX1000/eth.h b/cpu/x86/drivers/quarkX1000/eth.h new file mode 100644 index 000000000..e94267466 --- /dev/null +++ b/cpu/x86/drivers/quarkX1000/eth.h @@ -0,0 +1,40 @@ +/* + * Copyright (C) 2015, 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_QUARKX1000_ETH_H_ +#define CPU_X86_DRIVERS_QUARKX1000_ETH_H_ + +#include + +void quarkX1000_eth_init(void); +void quarkX1000_eth_poll(uint16_t *frame_len); +void quarkX1000_eth_send(void); + +#endif /* CPU_X86_DRIVERS_QUARKX1000_ETH_H_ */ diff --git a/cpu/x86/drivers/quarkX1000/gpio.c b/cpu/x86/drivers/quarkX1000/gpio.c new file mode 100644 index 000000000..92438b456 --- /dev/null +++ b/cpu/x86/drivers/quarkX1000/gpio.c @@ -0,0 +1,256 @@ +/* + * Copyright (C) 2015, 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 "gpio.h" +#include "helpers.h" +#include "interrupt.h" +#include "pic.h" + +/* GPIO Controler Registers */ +#define SWPORTA_DR 0x00 +#define SWPORTA_DDR 0x04 +#define INTEN 0x30 +#define INTMASK 0x34 +#define INTTYPE_LEVEL 0x38 +#define INT_POLARITY 0x3c +#define INTSTATUS 0x40 +#define RAW_INTSTATUS 0x44 +#define DEBOUNCE 0x48 +#define PORTA_EOI 0x4c +#define EXT_PORTA 0x50 +#define LS_SYNC 0x60 + +#define PINS 8 + +#define GPIO_IRQ 10 +#define GPIO_INT PIC_INT(GPIO_IRQ) + +struct gpio_internal_data { + pci_driver_t pci; + quarkX1000_gpio_callback callback; +}; + +static struct gpio_internal_data data; + +static inline uint32_t +read(uint32_t offset) +{ + uint32_t res; + PCI_MMIO_READL(data.pci, res, offset); + return res; +} + +static inline void +write(uint32_t offset, uint32_t val) +{ + PCI_MMIO_WRITEL(data.pci, offset, val); +} + +/* value must be 0x0 or 0x1 */ +static void +set_bit(uint32_t offset, uint32_t bit, uint32_t value) +{ + uint32_t reg; + + reg = read(offset); + + reg &= ~BIT(bit); + reg |= value << bit; + + write(offset, reg); +} + +static void +gpio_isr(void) +{ + uint32_t int_status; + + int_status = read(INTSTATUS); + + if (data.callback) + data.callback(int_status); + + write(PORTA_EOI, -1); +} + +static void +gpio_interrupt_config(uint8_t pin, int flags) +{ + /* set as input */ + set_bit(SWPORTA_DDR, pin, 0); + + /* set interrupt enabled */ + set_bit(INTEN, pin, 1); + + /* unmask interrupt */ + set_bit(INTMASK, pin, 0); + + /* set active high/low */ + set_bit(INT_POLARITY, pin, !!(flags & QUARKX1000_GPIO_ACTIVE_HIGH)); + + /* set level/edge */ + set_bit(INTTYPE_LEVEL, pin, !!(flags & QUARKX1000_GPIO_EDGE)); + + /* set debounce */ + set_bit(DEBOUNCE, pin, !!(flags & QUARKX1000_GPIO_DEBOUNCE)); + + /* set clock synchronous */ + set_bit(LS_SYNC, 0, !!(flags & QUARKX1000_GPIO_CLOCK_SYNC)); +} + +int +quarkX1000_gpio_config(uint8_t pin, int flags) +{ + if (((flags & QUARKX1000_GPIO_IN) && (flags & QUARKX1000_GPIO_OUT)) || + ((flags & QUARKX1000_GPIO_INT) && (flags & QUARKX1000_GPIO_OUT))) { + return -1; + } + + if (flags & QUARKX1000_GPIO_INT) { + gpio_interrupt_config(pin, flags); + } else { + /* set direction */ + set_bit(SWPORTA_DDR, pin, !!(flags & QUARKX1000_GPIO_OUT)); + + /* set interrupt disabled */ + set_bit(INTEN, pin, 0); + } + + return 0; +} + +int +quarkX1000_gpio_config_port(int flags) +{ + uint8_t i; + + for (i = 0; i < PINS; i++) { + if (quarkX1000_gpio_config(i, flags) < 0) { + return -1; + } + } + + return 0; +} + +int +quarkX1000_gpio_read(uint8_t pin, uint8_t *value) +{ + uint32_t value32 = read(EXT_PORTA); + *value = !!(value32 & BIT(pin)); + + return 0; +} + +int +quarkX1000_gpio_write(uint8_t pin, uint8_t value) +{ + set_bit(SWPORTA_DR, pin, !!value); + return 0; +} + +int +quarkX1000_gpio_read_port(uint8_t *value) +{ + uint32_t value32 = read(EXT_PORTA); + *value = value32 & ~0xFFFFFF00; + + return 0; +} + +int +quarkX1000_gpio_write_port(uint8_t value) +{ + write(SWPORTA_DR, value); + return 0; +} + +int +quarkX1000_gpio_set_callback(quarkX1000_gpio_callback callback) +{ + data.callback = callback; + return 0; +} + +void +quarkX1000_gpio_clock_enable(void) +{ + set_bit(LS_SYNC, 0, 1); +} + +void +quarkX1000_gpio_clock_disable(void) +{ + set_bit(LS_SYNC, 0, 0); +} + +static void +gpio_handler(void) +{ + gpio_isr(); + + pic_eoi(GPIO_IRQ); +} + +int +quarkX1000_gpio_init(void) +{ + pci_config_addr_t pci_addr; + + pci_addr.raw = 0; + pci_addr.bus = 0; + pci_addr.dev = 21; + pci_addr.func = 2; + pci_addr.reg_off = PCI_CONFIG_REG_BAR1; + + 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); + + data.callback = 0; + + quarkX1000_gpio_clock_enable(); + + /* clear registers */ + write(INTEN, 0); + write(INTMASK, 0); + write(PORTA_EOI, 0); + + pic_unmask_irq(GPIO_IRQ); + + return 0; +} diff --git a/cpu/x86/drivers/quarkX1000/gpio.h b/cpu/x86/drivers/quarkX1000/gpio.h new file mode 100644 index 000000000..61ef11aab --- /dev/null +++ b/cpu/x86/drivers/quarkX1000/gpio.h @@ -0,0 +1,74 @@ +/* + * Copyright (C) 2015, 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_QUARKX1000_GPIO_H_ +#define CPU_X86_DRIVERS_QUARKX1000_GPIO_H_ + +#include + +#include "pci.h" + +#define QUARKX1000_GPIO_IN (0 << 0) +#define QUARKX1000_GPIO_OUT (1 << 0) +#define QUARKX1000_GPIO_INT (1 << 1) +#define QUARKX1000_GPIO_ACTIVE_LOW (0 << 2) +#define QUARKX1000_GPIO_ACTIVE_HIGH (1 << 2) +#define QUARKX1000_GPIO_LEVEL (0 << 3) +#define QUARKX1000_GPIO_EDGE (1 << 3) +#define QUARKX1000_GPIO_DEBOUNCE (1 << 4) +#define QUARKX1000_GPIO_CLOCK_SYNC (1 << 5) +#define QUARKX1000_GPIO_POL_NORMAL (0 << 6) +#define QUARKX1000_GPIO_POL_INV (1 << 6) +#define QUARKX1000_GPIO_PUD_NORMAL (0 << 7) +#define QUARKX1000_GPIO_PUD_PULL_UP (1 << 7) +#define QUARKX1000_GPIO_PUD_PULL_DOWN (2 << 7) + +#define QUARKX1000_GPIO_DIR_MASK (1 << 0) +#define QUARKX1000_GPIO_POL_MASK (1 << 6) +#define QUARKX1000_GPIO_PUD_MASK (3 << 7) + +typedef void (*quarkX1000_gpio_callback)(uint32_t); + +int quarkX1000_gpio_init(void); + +int quarkX1000_gpio_config(uint8_t pin, int flags); +int quarkX1000_gpio_read(uint8_t pin, uint8_t *value); +int quarkX1000_gpio_write(uint8_t pin, uint8_t value); + +int quarkX1000_gpio_config_port(int flags); +int quarkX1000_gpio_read_port(uint8_t *value); +int quarkX1000_gpio_write_port(uint8_t value); + +int quarkX1000_gpio_set_callback(quarkX1000_gpio_callback callback); + +void quarkX1000_gpio_clock_enable(void); +void quarkX1000_gpio_clock_disable(void); + +#endif /* CPU_X86_DRIVERS_QUARKX1000_GPIO_H_ */ diff --git a/cpu/x86/drivers/quarkX1000/i2c-registers.h b/cpu/x86/drivers/quarkX1000/i2c-registers.h new file mode 100644 index 000000000..7b9e4cec0 --- /dev/null +++ b/cpu/x86/drivers/quarkX1000/i2c-registers.h @@ -0,0 +1,156 @@ +/* + * Copyright (C) 2015, 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_QUARKX1000_I2C_REGISTERS_H_ +#define CPU_X86_DRIVERS_QUARKX1000_I2C_REGISTERS_H_ + +#define QUARKX1000_IC_CON 0x00 +#define QUARKX1000_IC_TAR 0x04 +#define QUARKX1000_IC_DATA_CMD 0x10 +#define QUARKX1000_IC_SS_SCL_HCNT 0x14 +#define QUARKX1000_IC_SS_SCL_LCNT 0x18 +#define QUARKX1000_IC_FS_SCL_HCNT 0x1C +#define QUARKX1000_IC_FS_SCL_LCNT 0x20 +#define QUARKX1000_IC_INTR_STAT 0x2C +#define QUARKX1000_IC_INTR_MASK 0x30 +#define QUARKX1000_IC_RAW_INTR_STAT 0x34 +#define QUARKX1000_IC_RX_TL 0x38 +#define QUARKX1000_IC_TX_TL 0x3C +#define QUARKX1000_IC_CLR_INTR 0x40 +#define QUARKX1000_IC_CLR_RX_UNDER 0x44 +#define QUARKX1000_IC_CLR_RX_OVER 0x48 +#define QUARKX1000_IC_CLR_TX_OVER 0x4C +#define QUARKX1000_IC_CLR_RD_REQ 0x50 +#define QUARKX1000_IC_CLR_TX_ABRT 0x54 +#define QUARKX1000_IC_CLR_ACTIVITY 0x5C +#define QUARKX1000_IC_CLR_STOP_DET 0x60 +#define QUARKX1000_IC_CLR_START_DET 0x64 +#define QUARKX1000_IC_ENABLE 0x6C +#define QUARKX1000_IC_STATUS 0x70 +#define QUARKX1000_IC_TXFLR 0x74 +#define QUARKX1000_IC_RXFLR 0x78 +#define QUARKX1000_IC_SDA_HOLD 0x7C +#define QUARKX1000_IC_TX_ABRT_SOURCE 0x80 +#define QUARKX1000_IC_ENABLE_STATUS 0x9C +#define QUARKX1000_IC_FS_SPKLEN 0xA0 + +/* IC_CON */ +#define QUARKX1000_IC_CON_MASTER_MODE_SHIFT 0 +#define QUARKX1000_IC_CON_MASTER_MODE_MASK 0x01 +#define QUARKX1000_IC_CON_SPEED_SHIFT 1 +#define QUARKX1000_IC_CON_SPEED_MASK 0x06 +#define QUARKX1000_IC_CON_10BITADDR_MASTER_SHIFT 4 +#define QUARKX1000_IC_CON_10BITADDR_MASTER_MASK 0x10 +#define QUARKX1000_IC_CON_RESTART_EN_SHIFT 5 +#define QUARKX1000_IC_CON_RESTART_EN_MASK 0x20 + +/* IC_TAR */ +#define QUARKX1000_IC_TAR_SHIFT 0 +#define QUARKX1000_IC_TAR_MASK 0x3FF + +/* IC_DATA_CMD */ +#define QUARKX1000_IC_DATA_CMD_DAT_SHIFT 0 +#define QUARKX1000_IC_DATA_CMD_DAT_MASK 0x0FF +#define QUARKX1000_IC_DATA_CMD_CMD_SHIFT 8 +#define QUARKX1000_IC_DATA_CMD_CMD_MASK 0x100 +#define QUARKX1000_IC_DATA_CMD_STOP_SHIFT 9 +#define QUARKX1000_IC_DATA_CMD_STOP_MASK 0x200 +#define QUARKX1000_IC_DATA_CMD_RESTART_SHIFT 10 +#define QUARKX1000_IC_DATA_CMD_RESTART_MASK 0x400 + +/* IC_SS_SCL_HCNT */ +#define QUARKX1000_IC_SS_SCL_HCNT_SHIFT 0 +#define QUARKX1000_IC_SS_SCL_HCNT_MASK 0xFFFF + +/* IC_SS_SCL_LCNT */ +#define QUARKX1000_IC_SS_SCL_LCNT_SHIFT 0 +#define QUARKX1000_IC_SS_SCL_LCNT_MASK 0xFFFF + +/* IC_FS_SCL_HCNT */ +#define QUARKX1000_IC_FS_SCL_HCNT_SHIFT 0 +#define QUARKX1000_IC_FS_SCL_HCNT_MASK 0xFFFF + +/* IC_FS_SCL_LCNT */ +#define QUARKX1000_IC_FS_SCL_LCNT_SHIFT 0 +#define QUARKX1000_IC_FS_SCL_LCNT_MASK 0xFFFF + +/* IC_INTR_STAT */ +#define QUARKX1000_IC_INTR_STAT_RX_UNDER_SHIFT 0 +#define QUARKX1000_IC_INTR_STAT_RX_UNDER_MASK 0x001 +#define QUARKX1000_IC_INTR_STAT_RX_OVER_SHIFT 1 +#define QUARKX1000_IC_INTR_STAT_RX_OVER_MASK 0x002 +#define QUARKX1000_IC_INTR_STAT_RX_FULL_SHIFT 2 +#define QUARKX1000_IC_INTR_STAT_RX_FULL_MASK 0x004 +#define QUARKX1000_IC_INTR_STAT_TX_OVER_SHIFT 3 +#define QUARKX1000_IC_INTR_STAT_TX_OVER_MASK 0x008 +#define QUARKX1000_IC_INTR_STAT_TX_EMPTY_SHIFT 4 +#define QUARKX1000_IC_INTR_STAT_TX_EMPTY_MASK 0x010 +#define QUARKX1000_IC_INTR_STAT_RD_REQ_SHIFT 5 +#define QUARKX1000_IC_INTR_STAT_RD_REQ_MASK 0x020 +#define QUARKX1000_IC_INTR_STAT_TX_ABRT_SHIFT 6 +#define QUARKX1000_IC_INTR_STAT_TX_ABRT_MASK 0x040 +#define QUARKX1000_IC_INTR_STAT_ACTIVITY_SHIFT 8 +#define QUARKX1000_IC_INTR_STAT_ACTIVITY_MASK 0x100 +#define QUARKX1000_IC_INTR_STAT_STOP_DET_SHIFT 9 +#define QUARKX1000_IC_INTR_STAT_STOP_DET_MASK 0x200 +#define QUARKX1000_IC_INTR_STAT_START_DET_SHIFT 10 +#define QUARKX1000_IC_INTR_STAT_START_DET_MASK 0x400 + +/* IC_ENABLE */ +#define QUARKX1000_IC_ENABLE_SHIFT 0 +#define QUARKX1000_IC_ENABLE_MASK 0x01 + +/* IC_STATUS */ +#define QUARKX1000_IC_STATUS_ACTIVITY_SHIFT 0 +#define QUARKX1000_IC_STATUS_ACTIVITY_MASK 0x01 +#define QUARKX1000_IC_STATUS_TFNF_SHIFT 1 +#define QUARKX1000_IC_STATUS_TFNF_MASK 0x02 +#define QUARKX1000_IC_STATUS_TFE_SHIFT 2 +#define QUARKX1000_IC_STATUS_TFE_MASK 0x04 +#define QUARKX1000_IC_STATUS_RFNE_SHIFT 3 +#define QUARKX1000_IC_STATUS_RFNE_MASK 0x08 +#define QUARKX1000_IC_STATUS_RFF_SHIFT 4 +#define QUARKX1000_IC_STATUS_RFF_MASK 0x10 +#define QUARKX1000_IC_STATUS_MST_ACTIVITY_SHIFT 5 +#define QUARKX1000_IC_STATUS_MST_ACTIVITY_MASK 0x20 + +/* IC_TXFLR */ +#define QUARKX1000_IC_TXFLR_SHIFT 0 +#define QUARKX1000_IC_TXFLR_MASK 0x1F + +/* IC_RXFLR */ +#define QUARKX1000_IC_RXFLR_SHIFT 0 +#define QUARKX1000_IC_RXFLR_MASK 0x1F + +/* IC_FS_SPKLEN */ +#define QUARKX1000_IC_FS_SPKLEN_SHIFT 0 +#define QUARKX1000_IC_FS_SPKLEN_MASK 0xFF + +#endif /* CPU_X86_DRIVERS_QUARKX1000_I2C_REGISTERS_H_ */ diff --git a/cpu/x86/drivers/quarkX1000/i2c.c b/cpu/x86/drivers/quarkX1000/i2c.c new file mode 100644 index 000000000..b781bcc35 --- /dev/null +++ b/cpu/x86/drivers/quarkX1000/i2c.c @@ -0,0 +1,516 @@ +/* + * Copyright (C) 2015, 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 "contiki.h" +#include "i2c.h" +#include "i2c-registers.h" +#include "interrupt.h" +#include "pic.h" + +#define I2C_CLOCK_SPEED 25 /* kHz */ +#define I2C_FIFO_DEPTH 16 + +#define I2C_STD_HCNT (I2C_CLOCK_SPEED * 4) +#define I2C_STD_LCNT (I2C_CLOCK_SPEED * 5) +#define I2C_FS_HCNT (I2C_CLOCK_SPEED) +#define I2C_FS_LCNT (I2C_CLOCK_SPEED) + +#define I2C_FS_SPKLEN_LCNT_OFFSET 8 +#define I2C_FS_SPKLEN_HCNT_OFFSET 6 + +#define I2C_POLLING_TIMEOUT (CLOCK_SECOND / 10) + +#define I2C_IRQ 9 +#define I2C_INT PIC_INT(I2C_IRQ) + +typedef enum { + I2C_DIRECTION_READ, + I2C_DIRECTION_WRITE +} I2C_DIRECTION; + +struct i2c_internal_data { + struct quarkX1000_i2c_config config; + + pci_driver_t pci; + + I2C_DIRECTION direction; + + uint8_t rx_len; + uint8_t *rx_buffer; + uint8_t tx_len; + uint8_t *tx_buffer; + uint8_t rx_tx_len; + + uint32_t hcnt; + uint32_t lcnt; +}; + +static struct i2c_internal_data device; + +static uint32_t +read(uint32_t offset) +{ + uint32_t res; + PCI_MMIO_READL(device.pci, res, offset); + return res; +} + +static void +write(uint32_t offset, uint32_t val) +{ + PCI_MMIO_WRITEL(device.pci, offset, val); +} + +static uint32_t +get_value(uint32_t offset, uint32_t mask, uint32_t shift) +{ + uint32_t register_value = read(offset); + + register_value &= ~(0xFFFFFFFF - mask); + + return register_value >> shift; +} + +static void +set_value(uint32_t offset, uint32_t mask, uint32_t shift, uint32_t value) +{ + uint32_t register_value = read(offset); + + register_value &= ~mask; + register_value |= value << shift; + + write(offset, register_value); +} + +static void +i2c_data_read(void) +{ + uint8_t i, rx_cnt; + + if (device.rx_len == 0) + return; + + rx_cnt = get_value(QUARKX1000_IC_RXFLR, + QUARKX1000_IC_RXFLR_MASK, QUARKX1000_IC_RXFLR_SHIFT); + + if (rx_cnt > device.rx_len) + rx_cnt = device.rx_len; + + for (i = 0; i < rx_cnt; i++) { + device.rx_buffer[i] = get_value(QUARKX1000_IC_DATA_CMD, + QUARKX1000_IC_DATA_CMD_DAT_MASK, QUARKX1000_IC_DATA_CMD_DAT_SHIFT); + } + + device.rx_buffer += i; + device.rx_len -= i; +} + +static void +i2c_data_send(void) +{ + uint32_t data = 0; + uint8_t i, tx_cnt; + + if (device.rx_tx_len == 0) + return; + + tx_cnt = I2C_FIFO_DEPTH - get_value(QUARKX1000_IC_TXFLR, + QUARKX1000_IC_TXFLR_MASK, QUARKX1000_IC_TXFLR_SHIFT); + + if (tx_cnt > device.rx_tx_len) + tx_cnt = device.rx_tx_len; + + for (i = 0; i < tx_cnt; i++) { + if (device.tx_len > 0) { + data = device.tx_buffer[i]; + + if (device.tx_len == 1) + data |= (device.rx_len > 0) ? QUARKX1000_IC_DATA_CMD_RESTART_MASK : QUARKX1000_IC_DATA_CMD_STOP_MASK; + + device.tx_len -= 1; + } else { + data = QUARKX1000_IC_DATA_CMD_CMD_MASK; + + if (device.rx_tx_len == 1) + data |= QUARKX1000_IC_DATA_CMD_STOP_MASK; + } + + write(QUARKX1000_IC_DATA_CMD, data); + device.rx_tx_len -= 1; + } + + device.tx_buffer += i; +} + +static void +i2c_isr(void) +{ + if (read(QUARKX1000_IC_INTR_STAT) & QUARKX1000_IC_INTR_STAT_STOP_DET_MASK) { + i2c_data_read(); + + write(QUARKX1000_IC_INTR_MASK, 0); + read(QUARKX1000_IC_CLR_INTR); + + if (device.direction == I2C_DIRECTION_WRITE) { + if (device.config.cb_tx) + device.config.cb_tx(); + } else { + if (device.config.cb_rx) + device.config.cb_rx(); + } + } + + if (read(QUARKX1000_IC_INTR_STAT) & QUARKX1000_IC_INTR_STAT_TX_EMPTY_MASK) { + i2c_data_send(); + if (device.rx_tx_len <= 0) { + set_value(QUARKX1000_IC_INTR_MASK, + QUARKX1000_IC_INTR_STAT_TX_EMPTY_MASK, QUARKX1000_IC_INTR_STAT_TX_EMPTY_SHIFT, 0); + set_value(QUARKX1000_IC_INTR_MASK, + QUARKX1000_IC_INTR_STAT_STOP_DET_MASK, QUARKX1000_IC_INTR_STAT_STOP_DET_SHIFT, 1); + } + } + + if (read(QUARKX1000_IC_INTR_STAT) & QUARKX1000_IC_INTR_STAT_RX_FULL_MASK) + i2c_data_read(); + + 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_RX_UNDER_MASK)) { + write(QUARKX1000_IC_INTR_MASK, 0); + read(QUARKX1000_IC_CLR_INTR); + + if (device.config.cb_err) + device.config.cb_err(); + } +} + +int +quarkX1000_i2c_configure(struct quarkX1000_i2c_config *config) +{ + uint32_t hcnt, lcnt; + uint8_t ic_fs_spklen; + + device.config.speed = config->speed; + device.config.addressing_mode = config->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) { + lcnt = I2C_STD_LCNT; + hcnt = I2C_STD_HCNT; + } else { + lcnt = I2C_FS_LCNT; + hcnt = I2C_FS_HCNT; + } + + ic_fs_spklen = get_value(QUARKX1000_IC_FS_SPKLEN, + QUARKX1000_IC_FS_SPKLEN_MASK, QUARKX1000_IC_FS_SPKLEN_SHIFT); + + /* We adjust the Low Count and High Count based on the Spike Suppression Limit */ + device.lcnt = (lcnt < (ic_fs_spklen + I2C_FS_SPKLEN_LCNT_OFFSET)) ? ic_fs_spklen + I2C_FS_SPKLEN_LCNT_OFFSET : lcnt; + device.hcnt = (hcnt < (ic_fs_spklen + I2C_FS_SPKLEN_HCNT_OFFSET)) ? ic_fs_spklen + I2C_FS_SPKLEN_HCNT_OFFSET : hcnt; + + /* Clear interrupts. */ + read(QUARKX1000_IC_CLR_INTR); + + return 0; +} + +static int +i2c_setup(void) +{ + /* Clear all values */ + write(QUARKX1000_IC_CON, 0); + + /* Clear interrupts */ + read(QUARKX1000_IC_CLR_INTR); + + /* Quark X1000 SoC I2C only supports master mode. */ + set_value(QUARKX1000_IC_CON, + QUARKX1000_IC_CON_MASTER_MODE_MASK, QUARKX1000_IC_CON_MASTER_MODE_SHIFT, 1); + + /* Set restart enable */ + set_value(QUARKX1000_IC_CON, + QUARKX1000_IC_CON_RESTART_EN_MASK, QUARKX1000_IC_CON_RESTART_EN_SHIFT, 1); + + /* Set addressing mode */ + if (device.config.addressing_mode == QUARKX1000_I2C_ADDR_MODE_10BIT) { + set_value(QUARKX1000_IC_CON, + QUARKX1000_IC_CON_10BITADDR_MASTER_MASK, QUARKX1000_IC_CON_10BITADDR_MASTER_SHIFT, 1); + } + + if (device.config.speed == QUARKX1000_I2C_SPEED_STANDARD) { + set_value(QUARKX1000_IC_SS_SCL_LCNT, + QUARKX1000_IC_SS_SCL_LCNT_MASK, QUARKX1000_IC_SS_SCL_LCNT_SHIFT, device.lcnt); + set_value(QUARKX1000_IC_SS_SCL_HCNT, + QUARKX1000_IC_SS_SCL_HCNT_MASK, QUARKX1000_IC_SS_SCL_HCNT_SHIFT, device.hcnt); + set_value(QUARKX1000_IC_CON, + QUARKX1000_IC_CON_SPEED_MASK, QUARKX1000_IC_CON_SPEED_SHIFT, 0x1); + } else { + set_value(QUARKX1000_IC_FS_SCL_LCNT, + QUARKX1000_IC_FS_SCL_LCNT_MASK, QUARKX1000_IC_FS_SCL_LCNT_SHIFT, device.lcnt); + set_value(QUARKX1000_IC_FS_SCL_HCNT, + QUARKX1000_IC_FS_SCL_HCNT_MASK, QUARKX1000_IC_FS_SCL_HCNT_SHIFT, device.hcnt); + set_value(QUARKX1000_IC_CON, + QUARKX1000_IC_CON_SPEED_MASK, QUARKX1000_IC_CON_SPEED_SHIFT, 0x2); + } + + return 0; +} + +static void +i2c_operation_setup(uint8_t *write_buf, uint8_t write_len, + uint8_t *read_buf, uint8_t read_len, uint16_t addr) +{ + device.rx_len = read_len; + device.rx_buffer = read_buf; + device.tx_len = write_len; + device.tx_buffer = write_buf; + device.rx_tx_len = device.rx_len + device.tx_len; + + /* Disable controller */ + set_value(QUARKX1000_IC_ENABLE, + QUARKX1000_IC_ENABLE_MASK, QUARKX1000_IC_ENABLE_SHIFT, 0); + + i2c_setup(); + + /* Disable interrupts */ + write(QUARKX1000_IC_INTR_MASK, 0); + + /* Clear interrupts */ + read(QUARKX1000_IC_CLR_INTR); + + /* Set address of target slave */ + set_value(QUARKX1000_IC_TAR, + QUARKX1000_IC_TAR_MASK, QUARKX1000_IC_TAR_SHIFT, addr); +} + +/* This is an interrupt based operation */ +static int +i2c_operation(uint8_t *write_buf, uint8_t write_len, + uint8_t *read_buf, uint8_t read_len, uint16_t addr) +{ + if (read(QUARKX1000_IC_STATUS) & QUARKX1000_IC_STATUS_ACTIVITY_MASK) + return -1; + + i2c_operation_setup(write_buf, write_len, read_buf, read_len, addr); + + /* Enable master TX and RX interrupts */ + set_value(QUARKX1000_IC_INTR_MASK, + QUARKX1000_IC_INTR_STAT_TX_OVER_MASK, QUARKX1000_IC_INTR_STAT_TX_OVER_SHIFT, 1); + set_value(QUARKX1000_IC_INTR_MASK, + QUARKX1000_IC_INTR_STAT_TX_EMPTY_MASK, QUARKX1000_IC_INTR_STAT_TX_EMPTY_SHIFT, 1); + set_value(QUARKX1000_IC_INTR_MASK, + QUARKX1000_IC_INTR_STAT_TX_ABRT_MASK, QUARKX1000_IC_INTR_STAT_TX_ABRT_SHIFT, 1); + set_value(QUARKX1000_IC_INTR_MASK, + QUARKX1000_IC_INTR_STAT_RX_UNDER_MASK, QUARKX1000_IC_INTR_STAT_RX_UNDER_SHIFT, 1); + set_value(QUARKX1000_IC_INTR_MASK, + QUARKX1000_IC_INTR_STAT_RX_OVER_MASK, QUARKX1000_IC_INTR_STAT_RX_OVER_SHIFT, 1); + set_value(QUARKX1000_IC_INTR_MASK, + QUARKX1000_IC_INTR_STAT_RX_FULL_MASK, QUARKX1000_IC_INTR_STAT_RX_FULL_SHIFT, 1); + set_value(QUARKX1000_IC_INTR_MASK, + QUARKX1000_IC_INTR_STAT_STOP_DET_MASK, QUARKX1000_IC_INTR_STAT_STOP_DET_SHIFT, 1); + + /* Enable controller */ + set_value(QUARKX1000_IC_ENABLE, + QUARKX1000_IC_ENABLE_MASK, QUARKX1000_IC_ENABLE_SHIFT, 1); + + return 0; +} + +/* This is an interrupt based write */ +int +quarkX1000_i2c_write(uint8_t *buf, uint8_t len, uint16_t addr) +{ + device.direction = I2C_DIRECTION_WRITE; + return i2c_operation(buf, len, 0, 0, addr); +} + +/* This is an interrupt based read */ +int +quarkX1000_i2c_read(uint8_t *buf, uint8_t len, uint16_t addr) +{ + device.direction = I2C_DIRECTION_READ; + return i2c_operation(0, 0, buf, len, addr); +} + +static int +i2c_polling_operation(uint8_t *write_buf, uint8_t write_len, + uint8_t *read_buf, uint8_t read_len, uint16_t addr) +{ + uint32_t start_time, intr_mask_stat; + + if (!(read(QUARKX1000_IC_CON) & QUARKX1000_IC_CON_MASTER_MODE_MASK)) + return -1; + + /* Wait i2c idle */ + start_time = clock_seconds(); + while (read(QUARKX1000_IC_STATUS) & QUARKX1000_IC_STATUS_ACTIVITY_MASK) { + if ((clock_seconds() - start_time) > I2C_POLLING_TIMEOUT) { + return -1; + } + } + + /* Get interrupt mask to restore in the end of polling operation */ + intr_mask_stat = read(QUARKX1000_IC_INTR_MASK); + + i2c_operation_setup(write_buf, write_len, read_buf, read_len, addr); + + /* Enable controller */ + set_value(QUARKX1000_IC_ENABLE, + QUARKX1000_IC_ENABLE_MASK, QUARKX1000_IC_ENABLE_SHIFT, 1); + + /* Transmit */ + if (device.tx_len != 0) { + while (device.tx_len > 0) { + start_time = clock_seconds(); + while (!(read(QUARKX1000_IC_STATUS) & QUARKX1000_IC_STATUS_TFNF_MASK)) { + if ((clock_seconds() - start_time) > I2C_POLLING_TIMEOUT) { + set_value(QUARKX1000_IC_ENABLE, + QUARKX1000_IC_ENABLE_MASK, QUARKX1000_IC_ENABLE_SHIFT, 0); + return -1; + } + } + i2c_data_send(); + } + + start_time = clock_seconds(); + while (!(read(QUARKX1000_IC_STATUS) & QUARKX1000_IC_STATUS_TFE_MASK)) { + if ((clock_seconds() - start_time) > I2C_POLLING_TIMEOUT) { + set_value(QUARKX1000_IC_ENABLE, + QUARKX1000_IC_ENABLE_MASK, QUARKX1000_IC_ENABLE_SHIFT, 0); + return -1; + } + } + } + + i2c_data_send(); + + /* Receive */ + if (device.rx_len != 0) { + while (device.rx_len > 0) { + start_time = clock_seconds(); + while (!(read(QUARKX1000_IC_STATUS) & QUARKX1000_IC_STATUS_RFNE_MASK)) { + if ((clock_seconds() - start_time) > I2C_POLLING_TIMEOUT) { + set_value(QUARKX1000_IC_ENABLE, + QUARKX1000_IC_ENABLE_MASK, QUARKX1000_IC_ENABLE_SHIFT, 0); + return -1; + } + } + i2c_data_read(); + } + } + + /* Stop Det */ + start_time = clock_seconds(); + while (!(read(QUARKX1000_IC_RAW_INTR_STAT) & QUARKX1000_IC_INTR_STAT_STOP_DET_MASK)) { + if ((clock_seconds() - start_time) > I2C_POLLING_TIMEOUT) { + set_value(QUARKX1000_IC_ENABLE, + QUARKX1000_IC_ENABLE_MASK, QUARKX1000_IC_ENABLE_SHIFT, 0); + return -1; + } + } + read(QUARKX1000_IC_CLR_STOP_DET); + + /* Wait i2c idle */ + start_time = clock_seconds(); + while (read(QUARKX1000_IC_STATUS) & QUARKX1000_IC_STATUS_ACTIVITY_MASK) { + if ((clock_seconds() - start_time) > I2C_POLLING_TIMEOUT) { + set_value(QUARKX1000_IC_ENABLE, + QUARKX1000_IC_ENABLE_MASK, QUARKX1000_IC_ENABLE_SHIFT, 0); + return -1; + } + } + + /* Disable controller */ + set_value(QUARKX1000_IC_ENABLE, + QUARKX1000_IC_ENABLE_MASK, QUARKX1000_IC_ENABLE_SHIFT, 0); + + /* Restore interrupt mask */ + write(QUARKX1000_IC_INTR_MASK, intr_mask_stat); + + return 0; +} + +int +quarkX1000_i2c_polling_write(uint8_t *buf, uint8_t len, uint16_t addr) +{ + device.direction = I2C_DIRECTION_WRITE; + return i2c_polling_operation(buf, len, 0, 0, addr); +} + +int +quarkX1000_i2c_polling_read(uint8_t *buf, uint8_t len, uint16_t addr) +{ + device.direction = I2C_DIRECTION_READ; + return i2c_polling_operation(0, 0, buf, len ,addr); +} + +int +quarkX1000_i2c_is_available(void) +{ + return device.pci.mmio ? 1 : 0; +} + +static void +i2c_handler() +{ + i2c_isr(); + + pic_eoi(I2C_IRQ); +} + +int +quarkX1000_i2c_init(void) +{ + pci_config_addr_t pci_addr; + + pci_addr.raw = 0; + pci_addr.bus = 0; + pci_addr.dev = 21; + pci_addr.func = 2; + pci_addr.reg_off = PCI_CONFIG_REG_BAR0; + + 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); + + pic_unmask_irq(I2C_IRQ); + + return 0; +} diff --git a/cpu/x86/drivers/quarkX1000/i2c.h b/cpu/x86/drivers/quarkX1000/i2c.h new file mode 100644 index 000000000..b5292524f --- /dev/null +++ b/cpu/x86/drivers/quarkX1000/i2c.h @@ -0,0 +1,67 @@ +/* + * Copyright (C) 2015, 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_QUARKX1000_I2C_H_ +#define CPU_X86_DRIVERS_QUARKX1000_I2C_H_ + +#include "pci.h" + +typedef enum { + QUARKX1000_I2C_SPEED_STANDARD, + QUARKX1000_I2C_SPEED_FAST +} QUARKX1000_I2C_SPEED; + +typedef enum { + QUARKX1000_I2C_ADDR_MODE_7BIT, + QUARKX1000_I2C_ADDR_MODE_10BIT +} QUARKX1000_I2C_ADDR_MODE; + +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_configure(struct quarkX1000_i2c_config *config); +int quarkX1000_i2c_is_available(void); + +int quarkX1000_i2c_read(uint8_t *buf, uint8_t len, uint16_t addr); +int quarkX1000_i2c_write(uint8_t *buf, uint8_t len, uint16_t addr); + +int quarkX1000_i2c_polling_read(uint8_t *buf, uint8_t len, uint16_t addr); +int quarkX1000_i2c_polling_write(uint8_t *buf, uint8_t len, uint16_t addr); + +#endif /* CPU_X86_DRIVERS_QUARKX1000_I2C_H_ */ diff --git a/cpu/x86/drivers/quarkX1000/uart.c b/cpu/x86/drivers/quarkX1000/uart.c new file mode 100644 index 000000000..23731ba93 --- /dev/null +++ b/cpu/x86/drivers/quarkX1000/uart.c @@ -0,0 +1,76 @@ +/* + * Copyright (C) 2015, 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 "uart.h" +#include "uart-16x50.h" +#include + +static uart_16x50_driver_t quarkX1000_uart0; +static uart_16x50_driver_t quarkX1000_uart1; + +/* Divisor setting for 115200 baud from section 18.2.2 of Intel Quark SoC + * X1000 Datasheet. + */ +#define QUARK_X1000_UART_DL_115200 24 + +/*---------------------------------------------------------------------------*/ +/** + * \brief Initialize a UART. + * \param dev Device to initialize. + */ +void +quarkX1000_uart_init(quarkX1000_uart_dev_t dev) +{ + pci_config_addr_t pci_addr; + + assert((dev == QUARK_X1000_UART_0) || (dev == QUARK_X1000_UART_1)); + + pci_addr.raw = 0; + + /* PCI addresses from section 18.4 of Intel Quark SoC X1000 Datasheet. */ + pci_addr.dev = 20; + pci_addr.func = (dev == QUARK_X1000_UART_0) ? 1 : 5; + pci_addr.reg_off = PCI_CONFIG_REG_BAR0; + + uart_16x50_init((dev == QUARK_X1000_UART_0) ? &quarkX1000_uart0 : &quarkX1000_uart1, pci_addr, QUARK_X1000_UART_DL_115200); +} +/*---------------------------------------------------------------------------*/ +/** + * \brief Transmit a character via a UART. + * \param dev Device to use. + * \param c Character to transmit. + */ +void +quarkX1000_uart_tx(quarkX1000_uart_dev_t dev, uint8_t c) +{ + assert((dev == QUARK_X1000_UART_0) || (dev == QUARK_X1000_UART_1)); + uart_16x50_tx((dev == QUARK_X1000_UART_0) ? quarkX1000_uart0 : quarkX1000_uart1, c); +} +/*---------------------------------------------------------------------------*/ diff --git a/cpu/x86/drivers/quarkX1000/uart.h b/cpu/x86/drivers/quarkX1000/uart.h new file mode 100644 index 000000000..8b545d8cd --- /dev/null +++ b/cpu/x86/drivers/quarkX1000/uart.h @@ -0,0 +1,44 @@ +/* + * Copyright (C) 2015, 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_QUARKX1000_UART_H_ +#define CPU_X86_DRIVERS_QUARKX1000_UART_H_ + +#include + +typedef enum { + QUARK_X1000_UART_0, + QUARK_X1000_UART_1 +} quarkX1000_uart_dev_t; + +void quarkX1000_uart_init(quarkX1000_uart_dev_t dev); +void quarkX1000_uart_tx(quarkX1000_uart_dev_t dev, uint8_t c); + +#endif /* CPU_X86_DRIVERS_QUARKX1000_UART_H_ */ diff --git a/cpu/x86/helpers.S b/cpu/x86/helpers.S new file mode 100644 index 000000000..c1c73130f --- /dev/null +++ b/cpu/x86/helpers.S @@ -0,0 +1,63 @@ +/* + * Copyright (C) 2015, 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. + */ + +.text + +.global halt +halt: + cli +die: hlt + jmp die + +.global outb +outb: + mov 4(%esp), %dx + mov 8(%esp), %al + out %al, %dx + ret + +.global outl +outl: + mov 4(%esp), %dx + mov 8(%esp), %eax + out %eax, %dx + ret + +.global inb +inb: + mov 4(%esp), %dx + in %dx, %al + ret + +.global inl +inl: + mov 4(%esp), %dx + in %dx, %eax + ret diff --git a/cpu/x86/helpers.h b/cpu/x86/helpers.h new file mode 100644 index 000000000..91b120a9e --- /dev/null +++ b/cpu/x86/helpers.h @@ -0,0 +1,48 @@ +/* + * Copyright (C) 2015, 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 HELPERS_H +#define HELPERS_H + +#include + +#define BIT(n) (1UL << (n)) + +void halt(void) __attribute__((__noreturn__)); + +/** Wrappers for the assembly 'out' instruction. */ +void outb(uint16_t port, uint8_t val); +void outl(uint16_t port, uint32_t val); + +/** Wrappers for the assembly 'in' instruction */ +uint8_t inb(uint16_t port); +uint32_t inl(uint16_t port); + +#endif /* HELPERS_H */ diff --git a/cpu/x86/init/common/cpu.c b/cpu/x86/init/common/cpu.c new file mode 100644 index 000000000..a174853cc --- /dev/null +++ b/cpu/x86/init/common/cpu.c @@ -0,0 +1,55 @@ +/* + * Copyright (C) 2015, 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 "gdt.h" +#include "helpers.h" +#include "idt.h" +#include "interrupt.h" +#include "irq.h" + +static void +double_fault_handler(struct interrupt_context context) +{ + halt(); +} +/*---------------------------------------------------------------------------*/ +void +cpu_init(void) +{ + gdt_init(); + idt_init(); + + /* Set an interrupt handler for Double Fault exception. This way, we avoid + * the system to triple fault, leaving no trace about what happened. + */ + SET_INTERRUPT_HANDLER(8, 1, double_fault_handler); + + irq_init(); +} diff --git a/cpu/x86/init/common/cpu.h b/cpu/x86/init/common/cpu.h new file mode 100644 index 000000000..a56d0db5a --- /dev/null +++ b/cpu/x86/init/common/cpu.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2015, 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_H +#define CPU_H + +void cpu_init(void); + +#endif /* CPU_H */ diff --git a/cpu/x86/init/common/gdt.c b/cpu/x86/init/common/gdt.c new file mode 100644 index 000000000..39a8a7ce4 --- /dev/null +++ b/cpu/x86/init/common/gdt.c @@ -0,0 +1,148 @@ +/* + * Copyright (C) 2015, 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 + +#define NUM_DESC 3 + +#define GDT_IDX_NULL 0 +#define GDT_IDX_CODE 1 +#define GDT_IDX_DATA 2 + +/* All code in the x86 port of Contiki runs at ring (privilege) level 0 */ +#define PRIV_LVL 0 + +/* Compute GDT selector from descriptor index and requested privilege level */ +#define GDT_SEL(IDX, RPL) (((IDX) << 3) | (RPL)) + +#define GDT_SEL_NULL GDT_SEL(GDT_IDX_NULL, 0) +#define GDT_SEL_CODE GDT_SEL(GDT_IDX_CODE, PRIV_LVL) +#define GDT_SEL_DATA GDT_SEL(GDT_IDX_DATA, PRIV_LVL) + +/* Each define here is for a specific flag in the descriptor. Refer to Intel + * Combined Manual (Intel 64 and IA-32 Architectures Software Developer's + * Manual), Vol. 3, Section 3.4.5 for a description of each flag. + */ +#define SEG_DESCTYPE(x) ((x) << 0x04) /* Descriptor type (0 for system, 1 for code/data) */ +#define SEG_PRES(x) ((x) << 0x07) /* Present */ +#define SEG_SAVL(x) ((x) << 0x0C) /* Available for system use */ +#define SEG_LONG(x) ((x) << 0x0D) /* Long mode */ +#define SEG_SIZE(x) ((x) << 0x0E) /* Size (0 for 16-bit, 1 for 32) */ +#define SEG_GRAN(x) ((x) << 0x0F) /* Granularity (0 for 1B - 1MB, 1 for 4KB - 4GB) */ +#define SEG_PRIV(x) (((x) & 0x03) << 0x05) /* Set privilege level (0 - 3) */ + +#define SEG_DATA_RDWR 0x02 /* Read/Write */ +#define SEG_CODE_EXRD 0x0A /* Execute/Read */ + +#define GDT_CODE_PL0 SEG_DESCTYPE(1) | SEG_PRES(1) | SEG_SAVL(0) | \ + SEG_LONG(0) | SEG_SIZE(1) | SEG_GRAN(1) | \ + SEG_PRIV(0) | SEG_CODE_EXRD + +#define GDT_DATA_PL0 SEG_DESCTYPE(1) | SEG_PRES(1) | SEG_SAVL(0) | \ + SEG_LONG(0) | SEG_SIZE(1) | SEG_GRAN(1) | \ + SEG_PRIV(0) | SEG_DATA_RDWR + +typedef struct gdtr +{ + uint16_t limit; + uint32_t base; +} __attribute__((packed)) gdtr_t; + +typedef uint64_t segment_desc_t; + +/* From Intel Combined Manual, Vol. 3 , Section 3.5.1: The base addresses of + * the GDT should be aligned on an eight-byte boundary to yield the best + * processor performance. + */ +static segment_desc_t gdt[NUM_DESC] __attribute__ ((aligned (8))); + +static void +set_descriptor(unsigned int index, uint32_t base, uint32_t limit, uint16_t flag) +{ + segment_desc_t descriptor; + + if (index >= NUM_DESC) + return; + + /* Create the high 32 bit segment */ + descriptor = limit & 0x000F0000; /* set limit bits 19:16 */ + descriptor |= (flag << 8) & 0x00F0FF00; /* set type, p, dpl, s, g, d/b, l and avl fields */ + descriptor |= (base >> 16) & 0x000000FF; /* set base bits 23:16 */ + descriptor |= base & 0xFF000000; /* set base bits 31:24 */ + + /* Shift by 32 to allow for low part of segment */ + descriptor <<= 32; + + /* Create the low 32 bit segment */ + descriptor |= base << 16; /* set base bits 15:0 */ + descriptor |= limit & 0x0000FFFF; /* set limit bits 15:0 */ + + /* Save descriptor into gdt */ + gdt[index] = descriptor; +} + + +/* This function initializes the Global Offset Table. For simplicity, the + * memory is organized following the flat model. Thus, memory appears to + * Contiki as a single continuous address space. Code, data, and stack + * are all contained in this address space (so called linear address space). + */ +void +gdt_init(void) +{ + gdtr_t gdtr; + + /* Initialize gdtr structure */ + gdtr.limit = sizeof(segment_desc_t) * NUM_DESC - 1; + gdtr.base = (uint32_t) &gdt; + + /* Initialize descriptors */ + set_descriptor(GDT_IDX_NULL, 0, 0, 0); + set_descriptor(GDT_IDX_CODE, 0, 0x0FFFFF, GDT_CODE_PL0); + set_descriptor(GDT_IDX_DATA, 0, 0x0FFFFF, GDT_DATA_PL0); + + /* Load GDTR register and update segment registers. + * + * CS register cannot be changed directly. For that reason, we do a far jump. + */ + __asm__ ("lgdt %[_gdtr_]\n\t" + "jmp %[_cs_], $1f\n\t" + "1:\n\t" + "mov %[_ds_], %%ds\n\t" + "mov %[_ds_], %%ss\n\t" + "mov %[_ds_], %%es\n\t" + "mov %[_ds_], %%fs\n\t" + "mov %[_ds_], %%gs\n\t" + : + : [_gdtr_] "m" (gdtr), + [_cs_] "i" (GDT_SEL_CODE), + [_ds_] "r" (GDT_SEL_DATA) + ); +} diff --git a/cpu/x86/init/common/gdt.h b/cpu/x86/init/common/gdt.h new file mode 100644 index 000000000..3db17f08c --- /dev/null +++ b/cpu/x86/init/common/gdt.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2015, 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 GDT_H +#define GDT_H + +void gdt_init(void); + +#endif /* GDT_H */ diff --git a/cpu/x86/init/common/idt.c b/cpu/x86/init/common/idt.c new file mode 100644 index 000000000..d561f49f7 --- /dev/null +++ b/cpu/x86/init/common/idt.c @@ -0,0 +1,93 @@ +/* + * Copyright (C) 2015, 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 + +#include "helpers.h" + +#define NUM_DESC 256 + +typedef struct idtr { + uint16_t limit; + uint32_t base; +} __attribute__((packed)) idtr_t; + +typedef struct intr_gate_desc { + uint16_t offset_low; + uint16_t selector; /* Segment Selector for destination code segment */ + uint16_t fixed:11; + uint16_t d:1; /* Size of gate: 1 = 32 bits; 0 = 16 bits */ + uint16_t pad:1; + uint16_t dpl:2; /* Descriptor Privilege Level */ + uint16_t p:1; /* Segment Present flag */ + uint16_t offset_high; + +} __attribute__((packed)) intr_gate_desc_t; + +/* According to Intel Combined Manual, Vol. 3, Section 6.10, the base addresses + * of the IDT should be aligned on an 8-byte boundary to maximize performance + * of cache line fills. + */ +static intr_gate_desc_t idt[NUM_DESC] __attribute__ ((aligned(8))); + +/* XXX: If you change this function prototype, make sure you fix the assembly + * code in SET_INTERRUPT_HANDLER macro in interrupt.h. Otherwise, you might + * face a very-hard-to-find bug in the interrupt handling system. + */ +void +idt_set_intr_gate_desc(int intr_num, uint32_t offset) +{ + intr_gate_desc_t *desc = &idt[intr_num]; + + desc->offset_low = offset & 0xFFFF; + desc->selector = 0x08; /* Offset in GDT for code segment */ + desc->fixed = BIT(9) | BIT(10); + desc->d = 1; + desc->dpl = 0; + desc->p = 1; + desc->offset_high = (offset >> 16) & 0xFFFF; +} +/*---------------------------------------------------------------------------*/ +/* Initialize Interrupt Descriptor Table. The IDT is initialized with + * null descriptors. Therefore, any interrupt at this point will cause + * a triple fault. + */ +void +idt_init(void) +{ + idtr_t idtr; + + /* Initialize idtr structure */ + idtr.limit = (sizeof(intr_gate_desc_t) * NUM_DESC) - 1; + idtr.base = (uint32_t)&idt; + + /* Load IDTR register */ + __asm__("lidt %0\n\t" :: "m" (idtr)); +} diff --git a/cpu/x86/init/common/idt.h b/cpu/x86/init/common/idt.h new file mode 100644 index 000000000..d29b97153 --- /dev/null +++ b/cpu/x86/init/common/idt.h @@ -0,0 +1,39 @@ +/* + * Copyright (C) 2015, 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 IDT_H +#define IDT_H + +#include + +void idt_init(void); +void idt_set_intr_gate_desc(int intr_num, uint32_t offset); + +#endif /* IDT_H */ diff --git a/cpu/x86/init/common/interrupt.h b/cpu/x86/init/common/interrupt.h new file mode 100644 index 000000000..2ab228c72 --- /dev/null +++ b/cpu/x86/init/common/interrupt.h @@ -0,0 +1,106 @@ +/* + * Copyright (C) 2015, 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 INTERRUPT_H +#define INTERRUPT_H + +#include + +#include "idt.h" + +struct interrupt_context { + uint32_t edi; + uint32_t esi; + uint32_t ebp; + uint32_t esp; + uint32_t ebx; + uint32_t edx; + uint32_t ecx; + uint32_t eax; + uint32_t error_code; + uint32_t eip; +}; + +/* Helper macro to register interrupt handler function. + * + * num: Interrupt number (0-255) + * has_error_code: 0 if interrupt doesn't push error code onto the + * stack. Otherwise, set this argument to 1. + * handler: Pointer to function that should be called once the + * interrupt is raised. In case has_error_code == 0 + * the function prototype should be the following: + * void handler(void) + * Otherwise, it should be: + * void handler(struct interrupt_context context) + * + * Since there is no easy way to write an Interrupt Service Routines + * (ISR) in C (for further information on this, see [1]), we provide + * this helper macro. It basically provides an assembly trampoline + * to a C function (handler parameter) which, indeed, handles the + * interrupt. + * + * [1] http://wiki.osdev.org/Interrupt_Service_Routines + */ +#define SET_INTERRUPT_HANDLER(num, has_error_code, handler) \ + do { \ + __asm__ __volatile__ ( \ + "push $1f\n\t" \ + "push %0\n\t" \ + "call %P1\n\t" \ + "add $8, %%esp\n\t" \ + "jmp 2f\n\t" \ + ".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) \ + : "eax", "ecx", "edx" \ + ); \ + } while (0) + +/* Disable maskable hardware interrupts */ +#define DISABLE_IRQ() \ + do { \ + __asm__ ("cli"); \ + } while (0) + +/* Enable maskable hardware interrupts */ +#define ENABLE_IRQ() \ + do { \ + __asm__ ("sti"); \ + } while (0) + +#endif /* INTERRUPT_H */ diff --git a/cpu/x86/init/common/irq.h b/cpu/x86/init/common/irq.h new file mode 100644 index 000000000..94af19b74 --- /dev/null +++ b/cpu/x86/init/common/irq.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2015, 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 IRQ_H +#define IRQ_H + +void irq_init(void); + +#endif /* IRQ_H */ diff --git a/cpu/x86/init/legacy_pc/irq.c b/cpu/x86/init/legacy_pc/irq.c new file mode 100644 index 000000000..04cfa1c13 --- /dev/null +++ b/cpu/x86/init/legacy_pc/irq.c @@ -0,0 +1,60 @@ +/* + * Copyright (C) 2015, 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 "drivers/legacy_pc/pic.h" +#include "interrupt.h" +#include "irq.h" + +#define IRQ7_INT PIC_INT(7) + +static void +spurious_irq7_handler(void) +{ + /* + * NOTE: Originally IRQ7 was used for the parallel port interrupts. Nowadays, + * though, it is only used if some other IRQ (i.e.: a PCIx interrupt) is + * mapped to it. In this case we will have to check the PIC ISR register in + * order to confirm this was a real interrupt. + * + * In case of a spurious interrupt, we should NEVER send an EOI here so the PIC + * doesn't trigger the next queued interrupt. + */ +} +/*---------------------------------------------------------------------------*/ +void +irq_init(void) +{ + pic_init(); + + /* Set a 'fake' handler for the Spurious IRQ7 interrupts. + * Refer to http://wiki.osdev.org/PIC . + */ + SET_INTERRUPT_HANDLER(IRQ7_INT, 0, spurious_irq7_handler); +} diff --git a/cpu/x86/mtarch.c b/cpu/x86/mtarch.c deleted file mode 100644 index 6dd72c61f..000000000 --- a/cpu/x86/mtarch.c +++ /dev/null @@ -1,187 +0,0 @@ - -#include -#include "sys/mt.h" - -#ifndef __WORDSIZE -#define __WORDSIZE 32 -#endif /* __WORDSIZE */ - -#ifndef ON_64BIT_ARCH -#if __WORDSIZE == 64 -#define ON_64BIT_ARCH 1 -#else /* ON_64BIT_ARCH */ -#define ON_64BIT_ARCH 0 -#endif /* __WORDSIZE == 64 */ -#endif /* ON_64BIT_ARCH */ - -struct frame { - unsigned long flags; -#if ON_64BIT_ARCH - unsigned long rbp; - unsigned long rdi; - unsigned long rsi; - unsigned long rdx; - unsigned long rcx; - unsigned long rbx; - unsigned long rax; -#else /* ON_64BIT_ARCH */ - unsigned long ebp; - unsigned long edi; - unsigned long esi; - unsigned long edx; - unsigned long ecx; - unsigned long ebx; - unsigned long eax; -#endif /* ON_64BIT_ARCH */ - unsigned long retaddr; - unsigned long retaddr2; - unsigned long data; -}; -/*--------------------------------------------------------------------------*/ -void -mtarch_init(void) -{ -} -/*--------------------------------------------------------------------------*/ -void -mtarch_start(struct mtarch_thread *t, - void (*function)(void *), void *data) -{ - struct frame *f = (struct frame *)&t->stack[MTARCH_STACKSIZE - sizeof(struct frame)/sizeof(unsigned long)]; - int i; - - for(i = 0; i < MTARCH_STACKSIZE; ++i) { - t->stack[i] = i; - } - - memset(f, 0, sizeof(struct frame)); - f->retaddr = (unsigned long)function; - f->data = (unsigned long)data; - t->sp = (unsigned long)&f->flags; -#if ON_64BIT_ARCH - f->rbp = (unsigned long)&f->rax; -#else /* ON_64BIT_ARCH */ - f->ebp = (unsigned long)&f->eax; -#endif /* ON_64BIT_ARCH */ -} -/*--------------------------------------------------------------------------*/ -static struct mtarch_thread *running_thread; -/*--------------------------------------------------------------------------*/ -static void -sw(void) -{ - /* Store registers */ -#if ON_64BIT_ARCH - __asm__ ( - "pushq %rax\n\t" - "pushq %rbx\n\t" - "pushq %rcx\n\t" - "pushq %rdx\n\t" - "pushq %rsi\n\t" - "pushq %rdi\n\t" - "pushq %rbp\n\t" - "pushq %rbp\n\t"); -#else /* ON_64BIT_ARCH */ - __asm__ ( - "pushl %eax\n\t" - "pushl %ebx\n\t" - "pushl %ecx\n\t" - "pushl %edx\n\t" - "pushl %esi\n\t" - "pushl %edi\n\t" - "pushl %ebp\n\t" - "pushl %ebp\n\t"); -#endif /* ON_64BIT_ARCH */ - - /* Switch stack pointer */ -#if ON_64BIT_ARCH - __asm__ ("movq %0, %%rax\n\t" : : "m" (running_thread)); - __asm__ ( - "movq (%rax), %rbx\n\t" - "movq %rsp, (%rax)\n\t" - "movq %rbx, %rsp\n\t" - ); -#else /* ON_64BIT_ARCH */ - __asm__ ("movl %0, %%eax\n\t" : : "m" (running_thread)); - __asm__ ( - "movl (%eax), %ebx\n\t" - "movl %esp, (%eax)\n\t" - "movl %ebx, %esp\n\t" - ); -#endif /* ON_64BIT_ARCH */ - - /* Restore previous registers */ -#if ON_64BIT_ARCH - __asm__ ( - "popq %rbp\n\t" - "popq %rbp\n\t" - "popq %rdi\n\t" - "popq %rsi\n\t" - "popq %rdx\n\t" - "popq %rcx\n\t" - "popq %rbx\n\t" - "popq %rax\n\t" - - "leave\n\t" - "ret\n\t" - ); -#else /* ON_64BIT_ARCH */ - __asm__ ( - "popl %ebp\n\t" - "popl %ebp\n\t" - "popl %edi\n\t" - "popl %esi\n\t" - "popl %edx\n\t" - "popl %ecx\n\t" - "popl %ebx\n\t" - "popl %eax\n\t" - - "leave\n\t" - "ret\n\t" - ); -#endif /* ON_64BIT_ARCH */ - -} - -/*--------------------------------------------------------------------------*/ -void -mtarch_exec(struct mtarch_thread *t) -{ - running_thread = t; - sw(); - running_thread = NULL; -} -/*--------------------------------------------------------------------------*/ -void -mtarch_remove(void) -{ -} -/*--------------------------------------------------------------------------*/ -void -mtarch_yield(void) -{ - sw(); -} -/*--------------------------------------------------------------------------*/ -void -mtarch_pstop(void) -{ -} -/*--------------------------------------------------------------------------*/ -void -mtarch_pstart(void) -{ -} -/*--------------------------------------------------------------------------*/ -int -mtarch_stack_usage(struct mt_thread *t) -{ - int i; - for(i = 0; i < MTARCH_STACKSIZE; ++i) { - if(t->thread.stack[i] != i) { - return MTARCH_STACKSIZE - i; - } - } - return -1; -} -/*--------------------------------------------------------------------------*/ diff --git a/cpu/x86/mtarch.h b/cpu/x86/mtarch.h deleted file mode 100644 index 9f982828a..000000000 --- a/cpu/x86/mtarch.h +++ /dev/null @@ -1,49 +0,0 @@ -/* - * Copyright (c) 2003, Adam Dunkels. - * 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. The name of the author may not be used to endorse or promote - * products derived from this software without specific prior - * written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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 MTARCH_H_ -#define MTARCH_H_ - -#ifndef MTARCH_STACKSIZE -#define MTARCH_STACKSIZE 1024 -#endif /* MTARCH_STACKSIZE */ - -struct mtarch_thread { - /* Note: stack must be aligned on 4-byte boundary. */ - unsigned long stack[MTARCH_STACKSIZE]; - unsigned long sp; -}; - -struct mt_thread; - -int mtarch_stack_usage(struct mt_thread *t); - -#endif /* MTARCH_H_ */ - diff --git a/cpu/x86/quarkX1000.ld b/cpu/x86/quarkX1000.ld new file mode 100644 index 000000000..b50c47bb8 --- /dev/null +++ b/cpu/x86/quarkX1000.ld @@ -0,0 +1,76 @@ +/* + * Copyright (C) 2015, 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. + */ + +OUTPUT_FORMAT("elf32-i386") + +ENTRY(start) + +SECTIONS { + /* + OS-Dev Wiki says it is common for kernels to start at 1M. Addresses before that + are used by BIOS/EFI, the bootloader and memory-mapped I/O. + + The UEFI GenFw program inserts a 0x240-byte offset between the image base and + the .text section. We add that same offset here to align the symbols in the + UEFI DLL with those in the final UEFI binary to make debugging easier. We also + apply 32-byte alignments to sections rather than more conventional 4K-byte + alignments to avoid symbols being shifted from the intermediate DLL to the + final UEFI image as would occur if the GenFw program shifted the .text section + from a higher, 4K-aligned offset to the 0x240-byte offset from the image base. + Such shifting may make debugging more difficult by preventing the DLL from + being a directly-useful source of symbol information. The debugging symbols + are not included in the final UEFI image. The GenFw program uses a minimum + section alignment of 32 bytes, so smaller alignment granularities may also + result in symbol perturbation. + */ + . = 1M + 0x240; + + .text ALIGN (32) : + { + KEEP(*(.multiboot)) + *(.text*) + } + + .rodata ALIGN (32) : + { + *(.rodata*) + } + + .data ALIGN (32) : + { + *(.data*) + } + + .bss ALIGN (32) : + { + *(COMMON) + *(.bss*) + } +} diff --git a/cpu/x86/uefi/bootstrap_uefi.c b/cpu/x86/uefi/bootstrap_uefi.c new file mode 100644 index 000000000..f6981eb96 --- /dev/null +++ b/cpu/x86/uefi/bootstrap_uefi.c @@ -0,0 +1,67 @@ +/* + * Copyright (C) 2015, 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 +#include + +#define MAX_MEM_DESC 128 + +void start(void); + +EFI_STATUS EFIAPI +uefi_start(IN EFI_HANDLE ImageHandle, IN EFI_SYSTEM_TABLE *SystemTable) +{ + EFI_MEMORY_DESCRIPTOR mem_map[MAX_MEM_DESC]; + UINTN mem_map_len = sizeof(mem_map); + UINTN mem_map_key; + UINTN mem_map_desc_sz; + UINT32 mem_map_rev; + + EFI_STATUS res; + + res = SystemTable->BootServices->GetMemoryMap(&mem_map_len, + mem_map, + &mem_map_key, + &mem_map_desc_sz, + &mem_map_rev); + if(res != EFI_SUCCESS) { + return EFI_ABORTED; + } + + res = SystemTable->BootServices->ExitBootServices(ImageHandle, mem_map_key); + if(res != EFI_SUCCESS) { + return EFI_ABORTED; + } + + start(); + + /* Should not be reachable: */ + return EFI_SUCCESS; +} diff --git a/cpu/x86/uefi/build_uefi.sh b/cpu/x86/uefi/build_uefi.sh new file mode 100755 index 000000000..c49718f93 --- /dev/null +++ b/cpu/x86/uefi/build_uefi.sh @@ -0,0 +1,27 @@ +#!/bin/bash + +SCRIPT_DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd ) + +# This script will always run on its own basepath, no matter where you call it from. +pushd ${SCRIPT_DIR} + +if [ "$(uname -m)" = "x86_64" ]; then + export ARCH=X64 +fi + +# Download the UEFI tool and library sources: +if [ -e edk2 ]; then + make -C edk2/BaseTools/Source/C/Common clean + make -C edk2/BaseTools/Source/C/GenFw clean +else + git clone --depth=1 https://github.com/tianocore/edk2 || exit +fi +# Build common sources required by the GenFw tool: +make -C edk2/BaseTools/Source/C/Common || exit +# Build the GenFw tool that is used to generate UEFI binaries: +make -C edk2/BaseTools/Source/C/GenFw || exit +# Create a makefile that indicates to the Contiki build system that UEFI support +# should be built: +echo "EN_UEFI = 1" > Makefile.uefi + +popd diff --git a/examples/galileo/Makefile b/examples/galileo/Makefile new file mode 100644 index 000000000..19a29f78a --- /dev/null +++ b/examples/galileo/Makefile @@ -0,0 +1,18 @@ +TARGET=galileo + +KNOWN_EXAMPLES = gpio-input gpio-output gpio-interrupt i2c-LSM9DS0 + +ifneq ($(filter $(EXAMPLE),$(KNOWN_EXAMPLES)),) + CONTIKI_PROJECT = $(EXAMPLE) +else + CONTIKI_PROJECT = help +endif + +all: $(CONTIKI_PROJECT) + +CONTIKI = ../.. +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 diff --git a/examples/galileo/README b/examples/galileo/README new file mode 100644 index 000000000..643a2e418 --- /dev/null +++ b/examples/galileo/README @@ -0,0 +1,73 @@ +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 + diff --git a/examples/galileo/gpio-input.c b/examples/galileo/gpio-input.c new file mode 100644 index 000000000..8728d5088 --- /dev/null +++ b/examples/galileo/gpio-input.c @@ -0,0 +1,96 @@ +/* + * Copyright (C) 2015, 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 + +#include "contiki.h" +#include "sys/ctimer.h" + +#include "galileo-pinmux.h" +#include "gpio.h" +#include "i2c.h" + +#define PIN_OUTPUT 5 +#define PIN_INPUT 6 + +static uint32_t value; +static struct ctimer timer; +static struct quarkX1000_i2c_config i2c_config; + +PROCESS(gpio_input_process, "GPIO Input Process"); +AUTOSTART_PROCESSES(&gpio_input_process); +/*---------------------------------------------------------------------------*/ +static void +timeout(void *data) +{ + uint8_t value_in; + + /* toggle pin state */ + value = !value; + quarkX1000_gpio_write(PIN_OUTPUT, value); + + quarkX1000_gpio_read(PIN_INPUT, &value_in); + + if (value == value_in) + printf("GPIO pin value match!\n"); + else + printf("GPIO pin value DOESN'T match!\n"); + + ctimer_reset(&timer); +} +/*---------------------------------------------------------------------------*/ +PROCESS_THREAD(gpio_input_process, ev, data) +{ + 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_INPUT, QUARKX1000_GPIO_IN); + + quarkX1000_gpio_clock_enable(); + + ctimer_set(&timer, CLOCK_SECOND / 2, timeout, NULL); + + printf("GPIO input example is running\n"); + PROCESS_YIELD(); + + quarkX1000_gpio_clock_disable(); + + PROCESS_END(); +} diff --git a/examples/galileo/gpio-interrupt.c b/examples/galileo/gpio-interrupt.c new file mode 100644 index 000000000..149279f6f --- /dev/null +++ b/examples/galileo/gpio-interrupt.c @@ -0,0 +1,94 @@ +/* + * Copyright (C) 2015, 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 + +#include "contiki.h" +#include "sys/ctimer.h" + +#include "gpio.h" +#include "i2c.h" +#include "galileo-pinmux.h" + +#define PIN_OUTPUT 5 +#define PIN_INTR 6 + +static struct ctimer timer; +static struct quarkX1000_i2c_config i2c_config; + +PROCESS(gpio_interrupt_process, "GPIO Interrupt Process"); +AUTOSTART_PROCESSES(&gpio_interrupt_process); +/*---------------------------------------------------------------------------*/ +static void +timeout(void *data) +{ + /* emulate an interrupt */ + quarkX1000_gpio_write(PIN_OUTPUT, 0); + quarkX1000_gpio_write(PIN_OUTPUT, 1); + + ctimer_reset(&timer); +} +/*---------------------------------------------------------------------------*/ +static void +callback(uint32_t status) +{ + printf("GPIO interrupt callback called, status: %d\n", status); +} +/*---------------------------------------------------------------------------*/ +PROCESS_THREAD(gpio_interrupt_process, ev, data) +{ + 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_INTR, QUARKX1000_GPIO_INT | QUARKX1000_GPIO_ACTIVE_HIGH | QUARKX1000_GPIO_EDGE); + + quarkX1000_gpio_set_callback(callback); + + quarkX1000_gpio_clock_enable(); + + ctimer_set(&timer, CLOCK_SECOND / 2, timeout, NULL); + + printf("GPIO interrupt example is running\n"); + PROCESS_YIELD(); + + quarkX1000_gpio_clock_disable(); + + PROCESS_END(); +} diff --git a/examples/galileo/gpio-output.c b/examples/galileo/gpio-output.c new file mode 100644 index 000000000..39a92516f --- /dev/null +++ b/examples/galileo/gpio-output.c @@ -0,0 +1,73 @@ +/* + * Copyright (C) 2015, 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 + +#include "contiki.h" +#include "sys/ctimer.h" + +#include "gpio.h" + +#define PIN 4 /* IO1 */ + +static uint32_t value; +static struct ctimer timer; + +PROCESS(gpio_output_process, "GPIO Output Process"); +AUTOSTART_PROCESSES(&gpio_output_process); +/*---------------------------------------------------------------------------*/ +static void +timeout(void *data) +{ + /* toggle pin state */ + value = !value; + quarkX1000_gpio_write(PIN, value); + + ctimer_reset(&timer); +} +/*---------------------------------------------------------------------------*/ +PROCESS_THREAD(gpio_output_process, ev, data) +{ + PROCESS_BEGIN(); + + quarkX1000_gpio_init(); + quarkX1000_gpio_config(PIN, QUARKX1000_GPIO_OUT); + + quarkX1000_gpio_clock_enable(); + + ctimer_set(&timer, CLOCK_SECOND / 2, timeout, NULL); + + printf("GPIO output example is running\n"); + PROCESS_YIELD(); + + quarkX1000_gpio_clock_disable(); + + PROCESS_END(); +} diff --git a/examples/galileo/i2c-LSM9DS0.c b/examples/galileo/i2c-LSM9DS0.c new file mode 100644 index 000000000..e5a47c458 --- /dev/null +++ b/examples/galileo/i2c-LSM9DS0.c @@ -0,0 +1,108 @@ +/* + * Copyright (C) 2015, 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 +#include + +#include "contiki.h" +#include "sys/ctimer.h" + +#include "galileo-pinmux.h" +#include "i2c.h" + +#define LSM9DS0_I2C_ADDR 0x6A +#define WHO_AM_I_ADDR 0x0F +#define WHO_AM_I_ANSWER 0xD4 + +static uint8_t tx_data = WHO_AM_I_ADDR; +static uint8_t rx_data = 0; +static struct ctimer timer; +static struct quarkX1000_i2c_config cfg; + +PROCESS(i2c_lsm9ds0_process, "I2C LSM9DS0 Who Am I Process"); +AUTOSTART_PROCESSES(&i2c_lsm9ds0_process); +/*---------------------------------------------------------------------------*/ +static void +rx(void) +{ + if (rx_data == WHO_AM_I_ANSWER) + printf("Who am I register value match!\n"); + else + printf("Who am I register value DOESN'T match! %u\n", rx_data); +} +/*---------------------------------------------------------------------------*/ +static void +tx(void) +{ + rx_data = 0; + + quarkX1000_i2c_read(&rx_data, sizeof(rx_data), LSM9DS0_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), LSM9DS0_I2C_ADDR); + + ctimer_reset(&timer); +} +/*---------------------------------------------------------------------------*/ +PROCESS_THREAD(i2c_lsm9ds0_process, ev, data) +{ + PROCESS_BEGIN(); + + cfg.speed = QUARKX1000_I2C_SPEED_STANDARD; + 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); + + printf("I2C LSM9DS0 example is running\n"); + + PROCESS_YIELD(); + + PROCESS_END(); +} diff --git a/examples/timers/Makefile b/examples/timers/Makefile new file mode 100644 index 000000000..d5b2a2846 --- /dev/null +++ b/examples/timers/Makefile @@ -0,0 +1,5 @@ +CONTIKI_PROJECT = all-timers +all: $(CONTIKI_PROJECT) + +CONTIKI = ../.. +include $(CONTIKI)/Makefile.include diff --git a/examples/timers/all-timers.c b/examples/timers/all-timers.c new file mode 100644 index 000000000..60eb56651 --- /dev/null +++ b/examples/timers/all-timers.c @@ -0,0 +1,131 @@ +/* + * Copyright (C) 2015, 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 + +#include "contiki.h" +#include "sys/etimer.h" +#include "sys/stimer.h" +#include "sys/timer.h" +#include "sys/rtimer.h" + +PROCESS(process1, "ETimer x Timer x STimer Process"); +PROCESS(process2, "CTimer Process 2"); +PROCESS(process3, "RTimer Process 3"); +AUTOSTART_PROCESSES(&process1, &process2, &process3); + +static int counter_etimer; +static int counter_timer; +static int counter_stimer; +static int counter_ctimer; +static int counter_rtimer; +static struct timer timer_timer; +static struct stimer timer_stimer; +static struct ctimer timer_ctimer; +static struct rtimer timer_rtimer; +static rtimer_clock_t timeout_rtimer = RTIMER_SECOND / 2; + +void +do_timeout1() +{ + counter_etimer++; + if(timer_expired(&timer_timer)) { + counter_timer++; + } + + if(stimer_expired(&timer_stimer)) { + counter_stimer++; + } + + printf("\nProcess 1: %s", counter_timer == counter_etimer + && counter_timer == counter_stimer ? "SUCCESS" : "FAIL"); +} +/*---------------------------------------------------------------------------*/ +void +do_timeout2() +{ + ctimer_reset(&timer_ctimer); + printf("\nProcess 2: CTimer callback called"); + counter_ctimer++; +} +/*---------------------------------------------------------------------------*/ +void +do_timeout3(struct rtimer *timer, void *ptr) +{ + counter_rtimer++; + + printf("\nProcess 3: RTimer callback called"); + + /* Re-arm rtimer */ + rtimer_set(&timer_rtimer, RTIMER_NOW() + timeout_rtimer, 0, do_timeout3, + NULL); +} +/*---------------------------------------------------------------------------*/ +PROCESS_THREAD(process1, ev, data) +{ + static struct etimer timer_etimer; + + PROCESS_BEGIN(); + + while(1) { + timer_set(&timer_timer, 3 * CLOCK_SECOND); + stimer_set(&timer_stimer, 3); + etimer_set(&timer_etimer, 3 * CLOCK_SECOND); + PROCESS_WAIT_EVENT_UNTIL(ev == PROCESS_EVENT_TIMER); + do_timeout1(); + } + + PROCESS_END(); +} +/*---------------------------------------------------------------------------*/ +PROCESS_THREAD(process2, ev, data) +{ + PROCESS_BEGIN(); + + while(1) { + ctimer_set(&timer_ctimer, 5 * CLOCK_SECOND, do_timeout2, NULL); + PROCESS_YIELD(); + } + + PROCESS_END(); +} +/*---------------------------------------------------------------------------*/ +PROCESS_THREAD(process3, ev, data) +{ + PROCESS_BEGIN(); + + while(1) { + rtimer_set(&timer_rtimer, RTIMER_NOW() + timeout_rtimer, 0, + do_timeout3, NULL); + PROCESS_YIELD(); + } + + PROCESS_END(); +} diff --git a/platform/cooja/Makefile.cooja b/platform/cooja/Makefile.cooja index c28dac608..d10979cd9 100644 --- a/platform/cooja/Makefile.cooja +++ b/platform/cooja/Makefile.cooja @@ -47,7 +47,7 @@ CONTIKI_TARGET_DIRS = . dev lib sys cfs net # (COOJA_SOURCEDIRS contains additional sources dirs set from simulator) vpath %.c $(COOJA_SOURCEDIRS) -COOJA_BASE = simEnvChange.c cooja_mt.c cooja_mtarch.c rtimer-arch.c slip.c watchdog.c rimestats.c +COOJA_BASE = simEnvChange.c cooja_mt.c cooja_mtarch.c rtimer-arch.c slip.c watchdog.c rimestats.c elfloader-x86.c COOJA_INTFS = beep.c button-sensor.c ip.c leds-arch.c moteid.c \ pir-sensor.c rs232.c vib-sensor.c \ diff --git a/platform/galileo/Makefile.customrules-galileo b/platform/galileo/Makefile.customrules-galileo new file mode 100644 index 000000000..cb5bc26a9 --- /dev/null +++ b/platform/galileo/Makefile.customrules-galileo @@ -0,0 +1,49 @@ +GDB ?= gdb +OPENOCD_SCRIPTS = $(CONTIKI)/platform/galileo/bsp/openocd-scripts + +.PHONY: debug $(CONTIKI_PROJECT) + +# Multiboot ELF binary +MULTIBOOT_SFX = $(TARGET) +MULTIBOOT = $(CONTIKI_PROJECT).$(MULTIBOOT_SFX) +# UEFI binary +UEFI_DLL_SFX = $(TARGET).dll +UEFI_DLL = $(CONTIKI_PROJECT).$(UEFI_SFX) +UEFI_LDFLAGS += -Xlinker --emit-relocs -Xlinker --entry=uefi_start +UEFI_SFX = $(TARGET).efi +UEFI = $(CONTIKI_PROJECT).$(UEFI_SFX) + +# Suffixes for final (non-intermediate) files to be built +FINAL_SFXS = $(MULTIBOOT_SFX) +ifeq ($(EN_UEFI),1) +FINAL_SFXS += $(UEFI_SFX) +endif + +debug: $(MULTIBOOT) + @openocd -s $(OPENOCD_SCRIPTS) -f debug.cfg &> $(shell pwd)/LOG_OPENOCD & + @$(GDB) $< -ex "target remote :3333" + +CUSTOM_RULE_LINK=1 + +%.$(MULTIBOOT_SFX): %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) contiki-$(TARGET).a + $(TRACE_LD) + $(Q)$(LD) $(LDFLAGS) $(MULTIBOOT_LDFLAGS) $(TARGET_STARTFILES) ${filter-out %.a,$^} \ + ${filter %.a,$^} $(TARGET_LIBFILES) -o $@ + +%.$(UEFI_DLL_SFX): %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) contiki-$(TARGET).a + $(TRACE_LD) + $(Q)$(LD) $(LDFLAGS) $(UEFI_LDFLAGS) $(TARGET_STARTFILES) ${filter-out %.a,$^} \ + ${filter %.a,$^} $(TARGET_LIBFILES) -o $@ + +%.$(UEFI_SFX): %.$(UEFI_DLL_SFX) + $(Q)$(GEN_FW) -o $@ -e UEFI_APPLICATION $^ + # The Intel Galileo firmware has been observed to not relocate the image + # if its base is set to the 1M boundary. This makes debugging easier, + # since the symbols in the intermediate DLL then correspond to the load + # addresses. + $(Q)$(GEN_FW) -o $@ --rebase 0x100000 $@ + +$(CONTIKI_PROJECT): $(addprefix $(CONTIKI_PROJECT).,$(FINAL_SFXS)) + @$(SIZE) $^ + +CLEAN += $(addprefix $(CONTIKI_PROJECT).,$(FINAL_SFXS)) diff --git a/platform/galileo/Makefile.galileo b/platform/galileo/Makefile.galileo new file mode 100644 index 000000000..189471fc2 --- /dev/null +++ b/platform/galileo/Makefile.galileo @@ -0,0 +1,28 @@ +BSP_PATH=$(CONTIKI)/platform/galileo/bsp +LIBC_PATH=$(BSP_PATH)/libc +LIBC=$(LIBC_PATH)/i586-elf +LIBGCC_PATH = /usr/lib/gcc/$(shell gcc -dumpmachine)/$(shell gcc -dumpversion) + +CONTIKI_TARGET_DIRS = . core/sys/ drivers/ net/ +CONTIKI_TARGET_MAIN = ${addprefix $(OBJECTDIR)/,contiki-main.o} +CONTIKI_SOURCEFILES += contiki-main.c clock.c rtimer-arch.c gpio-pcal9535a.c pwm-pca9685.c galileo-pinmux.c eth-proc.c eth-conf.c + +ifeq ($(CONTIKI_WITH_IPV6),1) + CONTIKI_SOURCEFILES += nbr-table.c packetbuf.c linkaddr.c +endif + +PROJECT_SOURCEFILES += newlib-syscalls.c + +CONTIKI_CPU=$(CONTIKI)/cpu/x86 +include $(CONTIKI)/cpu/x86/Makefile.x86_quarkX1000 + +CFLAGS += -fno-stack-protector -nostdinc -I$(LIBC)/include -isystem $(LIBGCC_PATH)/include -isystem $(LIBGCC_PATH)/include-fixed +LDFLAGS += -nostdlib -L$(LIBC)/lib -L$(LIBGCC_PATH)/32 + +TARGET_LIBFILES += -lm -lc -lgcc + +-include $(LIBC_PATH)/Makefile.libc + +ifndef BUILT_LIBC + $(error Build the C library by executing $(LIBC_PATH)/build_newlib.sh) +endif diff --git a/platform/galileo/README.md b/platform/galileo/README.md new file mode 100644 index 000000000..b99ad7d65 --- /dev/null +++ b/platform/galileo/README.md @@ -0,0 +1,212 @@ +Intel Galileo Board +=================== + +This README file contains general information about the Intel Galileo board +support. In the following lines you will find information about supported +features as well as instructions on how to build, run and debug applications +for this platform. The instructions were only test in Linux environment. + +Requirements +------------ + +In order to build and debug the following packages must be installed in your +system: + * gcc + * gdb + * openocd + +Moreover, in order to debug via JTAG or serial console, you will some extra +devices as described in [1] and [2]. + +Features +-------- + +This section presents the features currently supported (e.g. device drivers +and Contiki APIs) by the Galileo port. + +Device drivers: + * Programmable Interrupt Controller (PIC) + * Programmable Intergal Timer (PIT) + * Real-Time Clock (RTC) + * UART + * Ethernet + +Contiki APIs: + * Clock module + * Timer, Stimer, Etimer, Ctimer, and Rtimer libraries + +Standard APIs: + * Stdio library (stdout and stderr only). Console output through UART 1 + device (connected to Galileo Gen2 FTDI header) + +Building +-------- + +Prerequisites on all Ubuntu Linux systems include texinfo and uuid-dev. +Additional prerequisites on 64-bit Ubuntu Linux systems include +gcc-multilib and g++-multilib. + +To build applications for this platform you should first build newlib (in +case it wasn't already built). To build newlib you can run the following +command: +``` +$ ./platform/galileo/bsp/libc/build_newlib.sh +``` + +Once newlib is built, you are ready to build applications. By default, the +following steps will use gcc as the C compiler and to invoke the linker. To +use LLVM clang instead, change the values for both the CC and LD variables in +cpu/x86/Makefile.x86_common to 'clang'. + +To build applications for the Galileo platform you should set the TARGET +variable to 'galileo'. For instance, building the hello-world application +should look like this: +``` +$ cd examples/hello-world/ && make TARGET=galileo +``` + +This will generate the 'hello-world.galileo' file which is a multiboot- +compliant [3] ELF image. This image contains debugging information and it +should be used in your daily development. + +You can also build a "Release" image by setting the BUILD_RELEASE variable to +1. This will generate a Contiki stripped-image optimized for size. +``` +$ cd examples/hello-world/ && make TARGET=galileo BUILD_RELEASE=1 +``` + +To also generate an '.galileo.efi' file which is a UEFI [4] image, +you can run the following command prior to building applications: +``` +$ cpu/x86/uefi/build_uefi.sh +``` + +Running +------- + +In order to boot the Contiki image, you will need a multiboot-compliant +bootloader. In the bsp directory, we provide a helper script which builds the +Grub bootloader with multiboot support. To build the bootloader, just run the +following command: +``` +$ platform/galileo/bsp/grub/build_grub.sh +``` + +Once Grub is built, we have three main steps to run Contiki applications: +prepare SDcard, connect to console, and boot image. Below follows +detailed instructions. + +### Prepare SDcard + +Mount the sdcard in directory /mnt/sdcard. + +#### Approach for Multiboot-compliant ELF Image + +Copy Contiki binary image to sdcard +``` +$ cp examples/hello-world/hello-world.galileo /mnt/sdcard +``` + +Copy grub binary to sdcard +``` +$ cp platform/galileo/bsp/grub/bin/grub.efi /mnt/sdcard +``` + +#### Approach for UEFI Image + +Copy Contiki binary image to sdcard +``` +$ cp examples/hello-world/hello-world.galileo.efi /mnt/sdcard +``` + +### Connect to the console output + +Connect the serial cable to your computer as shown in [2]. + +Choose a terminal emulator such as PuTTY. Make sure you use the SCO keyboard +mode (on PuTTY that option is at Terminal -> Keyboard, on the left menu). +Connect to the appropriate serial port using a baud rate of 115200. + +### Boot Contiki Image + +Turn on your board. After a few seconds you should see the following text +in the screen: +``` +Press [Enter] to directly boot. +Press [F7] to show boot menu options. +``` + +Press and select the option "UEFI Internal Shell" within the menu. + +#### Boot Multiboot-compliant ELF Image + +Once you have a shell, run the following commands to run grub application: +``` +$ fs0: +$ grub.efi +``` + +You'll reach the grub shell. Now run the following commands to boot Contiki +image: +``` +$ multiboot /hello-world.galileo +$ boot +``` + +#### Boot UEFI Image + +Once you have a shell, run the following commands to boot Contiki image: +``` +$ fs0: +$ hello-world.galileo.efi +``` + +### Verify that Contiki is Running + +This should boot the Contiki image, resulting in the following messages being +sent to the serial console: +``` +Starting Contiki +Hello World +``` + +Debugging +--------- + +This section describes how to debug Contiki via JTAG. The following +instructions consider you have the devices: Flyswatter2 and ARM-JTAG-20-10 +adapter (see [1]). + +Attach the Flyswatter2 to your host computer with an USB cable. Connect the +Flyswatter2 and ARM-JTAG-20-10 adapter using the 20-pins head. Connect the +ARM-JTAG-20-10 adapter to Galileo Gen2 JTAG port using the 10-pins head. + +Once everything is connected, run Contiki as described in "Running" section, +but right after loading Contiki image (multiboot command), run the following +command: +``` +$ make TARGET=galileo debug +``` + +The 'debug' rule will run OpenOCD and gdb with the right parameters. OpenOCD +will run in background and its output will be redirected to a log file in the +application's path called LOG_OPENOCD. Once gdb client is detached, OpenOCD +is terminated. + +If you use a gdb front-end, you can define the "GDB" environment +variable and your gdb front-end will be used instead of default gdb. +For instance, if you want to use cgdb front-end, just run the command: +``` +$ make BOARD=galileo debug GDB=cgdb +``` + +References +---------- + +[1] https://communities.intel.com/message/211778 + +[2] https://software.intel.com/en-us/articles/intel-galileo-gen-2-board-assembly-using-eclipse-and-intel-xdk-iot-edition + +[3] https://www.gnu.org/software/grub/manual/multiboot/multiboot.html + +[4] http://www.uefi.org/ diff --git a/platform/galileo/bsp/grub/build_grub.sh b/platform/galileo/bsp/grub/build_grub.sh new file mode 100755 index 000000000..6d33799e3 --- /dev/null +++ b/platform/galileo/bsp/grub/build_grub.sh @@ -0,0 +1,60 @@ +#!/bin/bash + +set -e + +JOBS=5 +HEAD="bac5d1a64ab4191058a8fd4c05f6b3b339e249e7" +SCRIPT_DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd ) + +prepare() { + if [[ ! -d ./src ]]; then + git clone git://git.savannah.gnu.org/grub.git src + fi + + pushd src + git checkout $HEAD + git clean -fdx + popd +} + +build() { + pushd src + + ./autogen.sh + ./configure --with-platform=efi --target=i386 + + make -j${JOBS} + + ./grub-mkimage -p /EFI/BOOT -d ./grub-core/ -O i386-efi -o grub.efi \ + boot efifwsetup efi_gop efinet efi_uga lsefimmap lsefi lsefisystab \ + exfat fat multiboot2 multiboot terminal part_msdos part_gpt normal \ + all_video aout configfile echo file fixvideo fshelp gfxterm gfxmenu \ + gfxterm_background gfxterm_menu legacycfg video_bochs video_cirrus \ + video_colors video_fb videoinfo video + + popd +} + +setup() { + mkdir -p bin + cp src/grub.efi bin/ +} + +cleanup() { + rm -rf ./src + rm -rf ./bin +} + +# This script will always run on its own basepath, no matter where you call it from. +pushd ${SCRIPT_DIR} + +case $1 in + -c | --cleanup) + cleanup + ;; + *) + prepare && build && setup + ;; +esac + +popd diff --git a/platform/galileo/bsp/libc/build_newlib.sh b/platform/galileo/bsp/libc/build_newlib.sh new file mode 100755 index 000000000..cef167e14 --- /dev/null +++ b/platform/galileo/bsp/libc/build_newlib.sh @@ -0,0 +1,115 @@ +#!/bin/bash + +JOBS=5 +TARGET=i586-elf +VERSION=2.2.0-1 +MD5=94114fdc1d8391cdbc2653d89249cccf +PKG_NAME=newlib +SRC_DIR=${PKG_NAME}-${VERSION} +PATCH_DIR=../patches +TARBALL=${SRC_DIR}.tar.gz +DIST_SITE=ftp://sources.redhat.com/pub/newlib + +SCRIPT_DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd ) + +# This script will always run on its own basepath, no matter where you call it from. +pushd ${SCRIPT_DIR} + +prepare() { + # If the source tarball doesn't exist of its md5 checksum doesn't match, download it. + if [ ! -e ./${TARBALL} ] || [ "$(md5sum ./${TARBALL} | cut -d' ' -f1)" != $MD5 ]; then + wget -c ${DIST_SITE}/${TARBALL} + fi + if [ ! -e ./${TARBALL} ] || [ "$(md5sum ./${TARBALL} | cut -d' ' -f1)" != $MD5 ]; then + echo "Error obtaining tarball." + exit 1 + fi + + # Clean up the previous source dir, if any. + if [[ -d ./${SRC_DIR} ]]; then + rm -rf ./${SRC_DIR} + fi + + # Clean up the previous install dir, if any. + if [[ -d ./${TARGET} ]]; then + rm -rf ./${TARGET} + fi + + tar xf ${TARBALL} + cd ${SRC_DIR} + + for i in `ls ${PATCH_DIR}`; do patch -p0 < ${PATCH_DIR}/${i}; done +} + + +build() { + export AR_FOR_TARGET=ar + export AS_FOR_TARGET=as + export CC_FOR_TARGET=cc + export GCC_FOR_TARGET=gcc + export CXX_FOR_TARGET=c++ + export RAW_CXX_FOR_TARGET=c++ + export GCJ_FOR_TARGET=gcj + export GFORTRAN_FOR_TARGET=gfortran + export GOC_FOR_TARGET=gccgo + export DLLTOOL_FOR_TARGET=dlltool + export LD_FOR_TARGET=ld + export LIPO_FOR_TARGET=lipo + export NM_FOR_TARGET=nm + export OBJDUMP_FOR_TARGET=objdump + export RANLIB_FOR_TARGET=ranlib + export READELF_FOR_TARGET=readelf + export STRIP_FOR_TARGET=strip + export WINDRES_FOR_TARGET=windres + export WINDMC_FOR_TARGET=windmc + export COMPILER_AS_FOR_TARGET=as + export COMPILER_LD_FOR_TARGET=ld + export COMPILER_NM_FOR_TARGET=nm + export CFLAGS_FOR_TARGET="-Os -m32 -march=i586 -mtune=i586 -fno-stack-protector -DPREFER_SIZE_OVER_SPEED -ffunction-sections -fdata-sections -fno-asynchronous-unwind-tables -fno-unwind-tables" + export CXXFLAGS_FOR_TARGET="-Os -m32 -march=i586 -mtune=i586 -fno-stack-protector -DPREFER_SIZE_OVER_SPEED -ffunction-sections -fdata-sections -fno-asynchronous-unwind-tables -fno-unwind-tables" + + mkdir -p install + ./configure --target=${TARGET} \ + --prefix=`pwd`/install \ + --enable-newlib-nano-formatted-io \ + --enable-newlib-nano-malloc \ + --enable-multithread \ + --disable-newlib-fvwrite-in-streamio \ + --disable-newlib-fseek-optimization \ + --disable-newlib-wide-orient \ + --disable-newlib-unbuf-stream-opt \ + --disable-libstdcxx \ + --disable-multilib \ + --disable-newlib-mb \ + --disable-newlib-supplied-syscalls + + make -j${JOBS} all && make install + cd .. + + echo "BUILT_LIBC = newlib" > Makefile.libc +} + +setup() { + cp -r ./${SRC_DIR}/install/${TARGET} . +} + +cleanup() { + rm -rf ./${SRC_DIR}* +} + + +# By default we always call prepare, build and setup. +prepare && build && setup + +# But we only cleanup if -c is used. +case $1 in + -c | --cleanup) + cleanup + shift + ;; + *) + # unknown option + ;; +esac + +popd diff --git a/platform/galileo/bsp/libc/patches/large64_files.patch b/platform/galileo/bsp/libc/patches/large64_files.patch new file mode 100644 index 000000000..07d5aeeea --- /dev/null +++ b/platform/galileo/bsp/libc/patches/large64_files.patch @@ -0,0 +1,11 @@ +--- newlib/libc/include/sys/config.h 2015-01-14 07:25:15.000000000 -0200 ++++ newlib/libc/include/sys/config.h 2015-03-13 14:21:33.247980336 -0300 +@@ -94,9 +94,6 @@ + #define HAVE_GETDATE + #define _HAVE_SYSTYPES + #define _READ_WRITE_RETURN_TYPE _ssize_t +-#define __LARGE64_FILES 1 +-/* we use some glibc header files so turn on glibc large file feature */ +-#define _LARGEFILE64_SOURCE 1 + #endif + #endif diff --git a/platform/galileo/bsp/libc/patches/newlib_add_i586_elf.patch b/platform/galileo/bsp/libc/patches/newlib_add_i586_elf.patch new file mode 100644 index 000000000..20c444ba3 --- /dev/null +++ b/platform/galileo/bsp/libc/patches/newlib_add_i586_elf.patch @@ -0,0 +1,13 @@ +--- newlib/configure.host 2015-03-12 17:59:39.380318464 -0300 ++++ newlib/configure.host 2015-03-12 17:55:05.933645678 -0300 +@@ -810,6 +810,10 @@ + z8k-*-*) + syscall_dir=syscalls + ;; ++ i586-*-elf) ++ newlib_cflags="${newlib_cflags} -DREENTRANT_SYSCALLS_PROVIDED" ++ syscall_dir=syscalls ++ ;; + *) + newlib_cflags="${newlib_cflags} -DMISSING_SYSCALL_NAMES" + syscall_dir= diff --git a/platform/galileo/bsp/libc/patches/stdio_strengthen_syms.patch b/platform/galileo/bsp/libc/patches/stdio_strengthen_syms.patch new file mode 100644 index 000000000..97c7f4f3a --- /dev/null +++ b/platform/galileo/bsp/libc/patches/stdio_strengthen_syms.patch @@ -0,0 +1,19 @@ +--- newlib/libc/stdio/nano-vfprintf_local.h 2014-07-04 10:21:43.000000000 -0700 ++++ newlib/libc/stdio/nano-vfprintf_local.h 2015-07-17 12:51:12.974269921 -0700 +@@ -230,5 +230,5 @@ _printf_float (struct _reent *data, + FILE *fp, + int (*pfunc)(struct _reent *, FILE *, + _CONST char *, size_t len), +- va_list *ap) _ATTRIBUTE((__weak__)); ++ va_list *ap); + #endif +--- newlib/libc/stdio/nano-vfscanf_local.h 2014-07-04 10:21:44.000000000 -0700 ++++ newlib/libc/stdio/nano-vfscanf_local.h 2015-07-17 12:51:33.967362409 -0700 +@@ -173,6 +173,6 @@ _scanf_i (struct _reent *rptr, + extern int + _scanf_float (struct _reent *rptr, + struct _scan_data_t *pdata, +- FILE *fp, va_list *ap) _ATTRIBUTE((__weak__)); ++ FILE *fp, va_list *ap); + + #endif diff --git a/platform/galileo/bsp/openocd-scripts/debug.cfg b/platform/galileo/bsp/openocd-scripts/debug.cfg new file mode 100644 index 000000000..bbe8a5919 --- /dev/null +++ b/platform/galileo/bsp/openocd-scripts/debug.cfg @@ -0,0 +1,11 @@ +source [find interface/ftdi/flyswatter2.cfg]; +source [find board/quark_x10xx_board.cfg]; + +quark_x10xx.cpu configure -event gdb-attach { + halt +} + +quark_x10xx.cpu configure -event gdb-detach { + resume + shutdown +} diff --git a/platform/galileo/contiki-conf.h b/platform/galileo/contiki-conf.h new file mode 100644 index 000000000..dca42b8de --- /dev/null +++ b/platform/galileo/contiki-conf.h @@ -0,0 +1,63 @@ +/* + * Copyright (C) 2015, 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 CONTIKI_CONF_H +#define CONTIKI_CONF_H + +/* Include the default configuration file early here so that this file can + * unconfigure the IP buffer size. That will allow uipopt.h to define a + * default IP buffer size that is larger and more useful. + */ +#include "contiki-default-conf.h" + +#undef UIP_CONF_BUFFER_SIZE + +#include + +#define CLOCK_CONF_SECOND 128 +typedef unsigned long clock_time_t; + +typedef uint64_t rtimer_clock_t; +#define RTIMER_ARCH_SECOND 1024 +#define RTIMER_CLOCK_LT(a, b) ((int64_t)((a) - (b)) < 0) + +/* We define the following macros and types otherwise Contiki does not + * compile. + */ +#define CCIF +#define CLIF + +#define UIP_CONF_LLH_LEN 14 + +#define LINKADDR_CONF_SIZE 6 + +typedef unsigned short uip_stats_t; + +#endif /* CONTIKI_CONF_H */ diff --git a/platform/galileo/contiki-main.c b/platform/galileo/contiki-main.c new file mode 100644 index 000000000..943ac3174 --- /dev/null +++ b/platform/galileo/contiki-main.c @@ -0,0 +1,72 @@ +/* + * Copyright (C) 2015, 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 + +#include "contiki.h" +#include "contiki-net.h" +#include "cpu.h" +#include "interrupt.h" +#include "uart.h" +#include "eth-conf.h" + +PROCINIT( &etimer_process + , &tcpip_process +#if WITH_DNS + , &resolv_process +#endif + ); + +int +main(void) +{ + cpu_init(); + /* Initialize UART connected to Galileo Gen2 FTDI header */ + quarkX1000_uart_init(QUARK_X1000_UART_1); + clock_init(); + rtimer_init(); + + printf("Starting Contiki\n"); + + ENABLE_IRQ(); + + process_init(); + procinit_init(); + ctimer_init(); + autostart_start(autostart_processes); + + eth_init(); + + while(1) { + process_run(); + } + + return 0; +} diff --git a/platform/galileo/core/sys/clock.c b/platform/galileo/core/sys/clock.c new file mode 100644 index 000000000..e84ef20eb --- /dev/null +++ b/platform/galileo/core/sys/clock.c @@ -0,0 +1,119 @@ +/* + * Copyright (C) 2015, 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 "sys/clock.h" +#include "sys/etimer.h" + +#include "contiki-conf.h" +#include "drivers/legacy_pc/rtc.h" + +#if CLOCK_CONF_SECOND == 2 +#define FREQ RTC_2_HZ +#elif CLOCK_CONF_SECOND == 4 +#define FREQ RTC_4_HZ +#elif CLOCK_CONF_SECOND == 8 +#define FREQ RTC_8_HZ +#elif CLOCK_CONF_SECOND == 16 +#define FREQ RTC_16_HZ +#elif CLOCK_CONF_SECOND == 32 +#define FREQ RTC_32_HZ +#elif CLOCK_CONF_SECOND == 64 +#define FREQ RTC_64_HZ +#elif CLOCK_CONF_SECOND == 128 +#define FREQ RTC_128_HZ +#elif CLOCK_CONF_SECOND == 256 +#define FREQ RTC_256_HZ +#elif CLOCK_CONF_SECOND == 512 +#define FREQ RTC_512_HZ +#elif CLOCK_CONF_SECOND == 1024 +#define FREQ RTC_1024_HZ +#elif CLOCK_CONF_SECOND == 2048 +#define FREQ RTC_2048_HZ +#elif CLOCK_CONF_SECOND == 4096 +#define FREQ RTC_4096_HZ +#elif CLOCK_CONF_SECOND == 8192 +#define FREQ RTC_8192_HZ +#else +#define FREQ -1 +#error "RTC is being used thus CLOCK_CONF_SECOND has to be a value defined by rtc_frequency_t." +#endif + +static volatile clock_time_t tick_count = 0; + +static void +update_ticks(void) +{ + clock_time_t expire = etimer_next_expiration_time(); + + tick_count++; + + /* Notify etimer library if the next event timer has expired */ + if(expire != 0 && tick_count >= expire) { + etimer_request_poll(); + } +} +/*---------------------------------------------------------------------------*/ +void +clock_init(void) +{ + rtc_init(FREQ, update_ticks); +} +/*---------------------------------------------------------------------------*/ +clock_time_t +clock_time(void) +{ + return tick_count; +} +/*---------------------------------------------------------------------------*/ +unsigned long +clock_seconds(void) +{ + return tick_count / CLOCK_CONF_SECOND; +} +/*---------------------------------------------------------------------------*/ +void +clock_wait(clock_time_t t) +{ + clock_time_t initial = tick_count; + + while(tick_count < t + initial); +} +/*---------------------------------------------------------------------------*/ +void +clock_set_seconds(unsigned long sec) +{ + /* Stubbed function */ +} +/*---------------------------------------------------------------------------*/ +void +clock_delay_usec(uint16_t t) +{ + /* Stubbed function */ +} diff --git a/platform/galileo/core/sys/mtarch.h b/platform/galileo/core/sys/mtarch.h new file mode 100644 index 000000000..c8c3440df --- /dev/null +++ b/platform/galileo/core/sys/mtarch.h @@ -0,0 +1,37 @@ +/* + * Copyright (C) 2015, 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 MTARCH_H_ +#define MTARCH_H_ + +struct mtarch_thread { +}; + +#endif /* MTARCH_H_ */ diff --git a/platform/galileo/core/sys/rtimer-arch.c b/platform/galileo/core/sys/rtimer-arch.c new file mode 100644 index 000000000..71c4f13f5 --- /dev/null +++ b/platform/galileo/core/sys/rtimer-arch.c @@ -0,0 +1,65 @@ +/* + * Copyright (C) 2015, 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 "sys/rtimer.h" + +#include "contiki-conf.h" +#include "drivers/legacy_pc/pit.h" + +static volatile rtimer_clock_t tick_count = 0; +static rtimer_clock_t trigger = UINT64_MAX; + +static void +update_ticks(void) +{ + if(++tick_count >= trigger) { + /* Disable trigger by assigning it to the maximum value */ + trigger = UINT64_MAX; + rtimer_run_next(); + } +} +/*---------------------------------------------------------------------------*/ +void +rtimer_arch_init(void) +{ + pit_init(RTIMER_ARCH_SECOND, update_ticks); +} +/*---------------------------------------------------------------------------*/ +rtimer_clock_t +rtimer_arch_now() +{ + return tick_count; +} +/*---------------------------------------------------------------------------*/ +void +rtimer_arch_schedule(rtimer_clock_t t) +{ + trigger = t; +} diff --git a/platform/galileo/core/sys/rtimer-arch.h b/platform/galileo/core/sys/rtimer-arch.h new file mode 100644 index 000000000..3f12056e1 --- /dev/null +++ b/platform/galileo/core/sys/rtimer-arch.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2015, 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 RTIMER_ARCH_H +#define RTIMER_ARCH_H + +rtimer_clock_t rtimer_arch_now(); + +#endif /* RTIMER_ARCH_H */ diff --git a/platform/galileo/drivers/galileo-pinmux.c b/platform/galileo/drivers/galileo-pinmux.c new file mode 100644 index 000000000..c66036ea2 --- /dev/null +++ b/platform/galileo/drivers/galileo-pinmux.c @@ -0,0 +1,618 @@ +/* + * Copyright (C) 2015, 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 "galileo-pinmux.h" +#include "gpio.h" +#include "gpio-pcal9535a.h" +#include "i2c.h" +#include "pwm-pca9685.h" + +#define GPIO_PCAL9535A_0_I2C_ADDR 0x25 +#define GPIO_PCAL9535A_1_I2C_ADDR 0x26 +#define GPIO_PCAL9535A_2_I2C_ADDR 0x27 +#define PWM_PCA9685_0_I2C_ADDR 0x47 + +#define PINMUX_NUM_FUNCS 4 +#define PINMUX_NUM_PATHS 4 +#define PINMUX_NUM_PINS 20 + +typedef enum { + NONE, + EXP0, + EXP1, + EXP2, + PWM0 +} MUX_CHIP; + +typedef enum { + PIN_LOW = 0x00, + PIN_HIGH = 0x01, + DISABLED = 0xFF +} PIN_LEVEL; + +struct pin_config { + uint8_t pin_num; + GALILEO_PINMUX_FUNC func; +}; + +static struct pin_config default_pinmux_config[PINMUX_NUM_PINS] = { + { 0, GALILEO_PINMUX_FUNC_C }, /* UART0_RXD */ + { 1, GALILEO_PINMUX_FUNC_C }, /* UART0_TXD */ + { 2, GALILEO_PINMUX_FUNC_A }, /* GPIO5(out) */ + { 3, GALILEO_PINMUX_FUNC_B }, /* GPIO6(in) */ + { 4, GALILEO_PINMUX_FUNC_B }, /* GPIO_SUS4 (in) */ + { 5, GALILEO_PINMUX_FUNC_B }, /* GPIO8 (in) */ + { 6, GALILEO_PINMUX_FUNC_B }, /* GPIO9 (in) */ + { 7, GALILEO_PINMUX_FUNC_B }, /* EXP1.P0_6 (in) */ + { 8, GALILEO_PINMUX_FUNC_B }, /* EXP1.P1_0 (in) */ + { 9, GALILEO_PINMUX_FUNC_B }, /* GPIO_SUS2 (in) */ + { 10, GALILEO_PINMUX_FUNC_A }, /* GPIO2 (out) */ + { 11, GALILEO_PINMUX_FUNC_B }, /* GPIO_SUS3 (in) */ + { 12, GALILEO_PINMUX_FUNC_B }, /* GPIO7 (in) */ + { 13, GALILEO_PINMUX_FUNC_B }, /* GPIO_SUS5(in) */ + { 14, GALILEO_PINMUX_FUNC_B }, /* EXP2.P0_0 (in)/ADC.IN0 */ + { 15, GALILEO_PINMUX_FUNC_B }, /* EXP2.P0_2 (in)/ADC.IN1 */ + { 16, GALILEO_PINMUX_FUNC_B }, /* EXP2.P0_4 (in)/ADC.IN2 */ + { 17, GALILEO_PINMUX_FUNC_B }, /* EXP2.P0_6 (in)/ADC.IN3 */ + { 18, GALILEO_PINMUX_FUNC_C }, /* I2C_SDA */ + { 19, GALILEO_PINMUX_FUNC_C }, /* I2C_SCL */ +}; + +struct mux_pin { + MUX_CHIP chip; + uint8_t pin; + PIN_LEVEL level; + uint32_t cfg; +}; + +struct mux_path { + uint8_t io_pin; + GALILEO_PINMUX_FUNC func; + struct mux_pin path[PINMUX_NUM_PATHS]; +}; + +struct pinmux_internal_data { + struct gpio_pcal9535a_data exp0; + struct gpio_pcal9535a_data exp1; + struct gpio_pcal9535a_data exp2; + struct pwm_pca9685_data pwm0; +}; + +static struct pinmux_internal_data data; + +static struct mux_path galileo_pinmux_paths[PINMUX_NUM_PINS * PINMUX_NUM_FUNCS] = { + {0, GALILEO_PINMUX_FUNC_A, { + { EXP1, 0, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* GPIO3 out */ + { EXP1, 1, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {0, GALILEO_PINMUX_FUNC_B, { + { EXP1, 0, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO3 in */ + { EXP1, 1, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {0, GALILEO_PINMUX_FUNC_C, { + { EXP1, 0, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* UART0_RXD */ + { EXP1, 1, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {0, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {1, GALILEO_PINMUX_FUNC_A, { + { EXP1, 13, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO4 out */ + { EXP0, 12, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 13, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {1, GALILEO_PINMUX_FUNC_B, { + { EXP1, 13, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO4 in */ + { EXP0, 12, PIN_HIGH, (QUARKX1000_GPIO_OUT)}, + { EXP0, 13, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {1, GALILEO_PINMUX_FUNC_C, { + { EXP1, 13, PIN_HIGH, (QUARKX1000_GPIO_OUT)}, /* UART0_TXD */ + { EXP0, 12, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 13, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {1, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {2, GALILEO_PINMUX_FUNC_A, { + { PWM0, 13, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* GPIO5 out */ + { EXP1, 2, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP1, 3, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {2, GALILEO_PINMUX_FUNC_B, { + { PWM0, 13, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* GPIO5 in */ + { EXP1, 2, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP1, 3, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {2, GALILEO_PINMUX_FUNC_C, { + { PWM0, 13, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* UART1_RXD */ + { EXP1, 2, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP1, 3, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {2, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {3, GALILEO_PINMUX_FUNC_A, { + { PWM0, 0, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO6 out */ + { PWM0, 12, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 0, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 1, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + {3, GALILEO_PINMUX_FUNC_B, { + { PWM0, 0, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO6 in */ + { PWM0, 12, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 0, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP0, 1, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + {3, GALILEO_PINMUX_FUNC_C, { + { PWM0, 0, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* UART1_TXD */ + { PWM0, 12, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP0, 0, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 1, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + {3, GALILEO_PINMUX_FUNC_D, { + { PWM0, 0, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* PWM.LED1 */ + { PWM0, 12, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 0, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 1, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + + {4, GALILEO_PINMUX_FUNC_A, { + { EXP1, 4, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO_SUS4 out */ + { EXP1, 5, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {4, GALILEO_PINMUX_FUNC_B, { + { EXP1, 4, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* GPIO_SUS4 in */ + { EXP1, 5, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {4, GALILEO_PINMUX_FUNC_C, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {4, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {5, GALILEO_PINMUX_FUNC_A, { + { PWM0, 2, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO8 (out) */ + { EXP0, 2, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 3, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {5, GALILEO_PINMUX_FUNC_B, { + { PWM0, 2, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO8 (in) */ + { EXP0, 2, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP0, 3, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {5, GALILEO_PINMUX_FUNC_C, { + { PWM0, 2, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* PWM.LED3 */ + { EXP0, 2, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 3, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {5, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {6, GALILEO_PINMUX_FUNC_A, { + { PWM0, 4, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO9 (out) */ + { EXP0, 4, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 5, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {6, GALILEO_PINMUX_FUNC_B, { + { PWM0, 4, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO9 (in) */ + { EXP0, 4, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP0, 5, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {6, GALILEO_PINMUX_FUNC_C, { + { PWM0, 4, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* PWM.LED5 */ + { EXP0, 4, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 5, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {6, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {7, GALILEO_PINMUX_FUNC_A, { + { EXP1, 6, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO_SUS0 (out) */ + { EXP1, 7, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {7, GALILEO_PINMUX_FUNC_B, { + { EXP1, 6, PIN_LOW, (QUARKX1000_GPIO_IN ) }, /* GPIO_SUS0 (in) */ + { EXP1, 7, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {7, GALILEO_PINMUX_FUNC_C, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {7, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {8, GALILEO_PINMUX_FUNC_A, { + { EXP1, 8, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO_SUS1 (out) */ + { EXP1, 9, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {8, GALILEO_PINMUX_FUNC_B, { + { EXP1, 8, PIN_LOW, (QUARKX1000_GPIO_IN ) }, /* GPIO_SUS1 (in) */ + { EXP1, 9, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {8, GALILEO_PINMUX_FUNC_C, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {8, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {9, GALILEO_PINMUX_FUNC_A, { + { PWM0, 6, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO_SUS2 (out) */ + { EXP0, 6, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 7, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {9, GALILEO_PINMUX_FUNC_B, { + { PWM0, 6, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO_SUS2 (in) */ + { EXP0, 6, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP0, 7, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {9, GALILEO_PINMUX_FUNC_C, { + { PWM0, 6, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* PWM.LED7 */ + { EXP0, 6, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 7, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {9, GALILEO_PINMUX_FUNC_C, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {10, GALILEO_PINMUX_FUNC_A, { + { PWM0, 10, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO2 (out) */ + { EXP0, 10, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 11, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {10, GALILEO_PINMUX_FUNC_B, { + { PWM0, 10, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO2 (in) */ + { EXP0, 10, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP0, 11, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {10, GALILEO_PINMUX_FUNC_C, { + { PWM0, 10, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* PWM.LED11 */ + { EXP0, 10, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 11, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {10, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {11, GALILEO_PINMUX_FUNC_A, { + { EXP1, 12, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO_SUS3 (out) */ + { PWM0, 8, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 8, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 9, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + {11, GALILEO_PINMUX_FUNC_B, { + { EXP1, 12, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO_SUS3 (in) */ + { PWM0, 8, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 8, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP0, 9, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + {11, GALILEO_PINMUX_FUNC_C, { + { EXP1, 12, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* PWM.LED9 */ + { PWM0, 8, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP0, 8, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 9, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + {11, GALILEO_PINMUX_FUNC_D, { + { EXP1, 12, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* SPI1_MOSI */ + { PWM0, 8, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 8, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 9, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + + {12, GALILEO_PINMUX_FUNC_A, { + { EXP1, 10, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO7 (out) */ + { EXP1, 11, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {12, GALILEO_PINMUX_FUNC_B, { + { EXP1, 10, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* GPIO7 (in) */ + { EXP1, 11, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {12, GALILEO_PINMUX_FUNC_C, { + { EXP1, 10, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* SPI1_MISO */ + { EXP1, 11, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {12, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {13, GALILEO_PINMUX_FUNC_A, { + { EXP1, 14, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO_SUS5 (out) */ + { EXP0, 14, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 15, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {13, GALILEO_PINMUX_FUNC_B, { + { EXP1, 14, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* GPIO_SUS5 (in) */ + { EXP0, 14, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP0, 15, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {13, GALILEO_PINMUX_FUNC_C, { + { EXP1, 14, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* SPI1_CLK */ + { EXP0, 14, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP0, 15, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {13, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {14, GALILEO_PINMUX_FUNC_A, { + { EXP2, 0, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* EXP2.P0_0 (out)/ADC.IN0 */ + { EXP2, 1, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {14, GALILEO_PINMUX_FUNC_B, { + { EXP2, 0, PIN_LOW, (QUARKX1000_GPIO_IN ) }, /* EXP2.P0_0 (in)/ADC.IN0 */ + { EXP2, 1, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {14, GALILEO_PINMUX_FUNC_C, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {14, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {15, GALILEO_PINMUX_FUNC_A, { + { EXP2, 2, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* EXP2.P0_2 (out)/ADC.IN1 */ + { EXP2, 3, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {15, GALILEO_PINMUX_FUNC_B, { + { EXP2, 2, PIN_LOW, (QUARKX1000_GPIO_IN ) }, /* EXP2.P0_2 (in)/ADC.IN1 */ + { EXP2, 3, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {15, GALILEO_PINMUX_FUNC_C, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {15, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {16, GALILEO_PINMUX_FUNC_A, { + { EXP2, 4, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* EXP2.P0_4 (out)/ADC.IN2 */ + { EXP2, 5, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {16, GALILEO_PINMUX_FUNC_B, { + { EXP2, 4, PIN_LOW, (QUARKX1000_GPIO_IN ) }, /* EXP2.P0_4 (in)/ADC.IN2 */ + { EXP2, 5, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {16, GALILEO_PINMUX_FUNC_C, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {16, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {17, GALILEO_PINMUX_FUNC_A, { + { EXP2, 6, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* EXP2.P0_6 (out)/ADC.IN3 */ + { EXP2, 7, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {17, GALILEO_PINMUX_FUNC_B, { + { EXP2, 6, PIN_LOW, (QUARKX1000_GPIO_IN ) }, /* EXP2.P0_6 (in)/ADC.IN3 */ + { EXP2, 7, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {17, GALILEO_PINMUX_FUNC_C, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {17, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {18, GALILEO_PINMUX_FUNC_A, { + { PWM0, 14, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* EXP2.P1_0 (out)/ADC.IN4 */ + { EXP2, 12, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP2, 8, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP2, 9, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + {18, GALILEO_PINMUX_FUNC_B, { + { PWM0, 14, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* EXP2.P1_0 (in)/ADC.IN4 */ + { EXP2, 12, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP2, 8, PIN_LOW, (QUARKX1000_GPIO_IN ) }, + { EXP2, 9, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + {18, GALILEO_PINMUX_FUNC_C, { + { PWM0, 14, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* I2C SDA */ + { EXP2, 9, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP2, 12, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {18, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + + {19, GALILEO_PINMUX_FUNC_A, { + { PWM0, 15, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* EXP2.P1_2 (out)/ADC.IN5 */ + { EXP2, 12, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP2, 10, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP2, 11, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + {19, GALILEO_PINMUX_FUNC_B, { + { PWM0, 15, PIN_LOW, (QUARKX1000_GPIO_OUT) }, /* EXP2.P1_2 (in)/ADC.IN5 */ + { EXP2, 12, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, + { EXP2, 10, PIN_LOW, (QUARKX1000_GPIO_IN ) }, + { EXP2, 11, PIN_LOW, (QUARKX1000_GPIO_OUT) }}}, + {19, GALILEO_PINMUX_FUNC_C, { + { PWM0, 15, PIN_HIGH, (QUARKX1000_GPIO_OUT) }, /* I2C SCL */ + { EXP2, 11, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { EXP2, 12, PIN_LOW, (QUARKX1000_GPIO_OUT) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, + {19, GALILEO_PINMUX_FUNC_D, { + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, /* NONE */ + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }, + { NONE, 0, DISABLED, (QUARKX1000_GPIO_IN ) }}}, +}; + +int +galileo_pinmux_set_pin(uint8_t pin, GALILEO_PINMUX_FUNC func) +{ + struct mux_path *mux_path; + uint8_t index, i; + + if(pin > PINMUX_NUM_PINS) { + return -1; + } + + index = PINMUX_NUM_FUNCS * pin; + index += func; + + mux_path = &galileo_pinmux_paths[index]; + + for(i = 0; i < PINMUX_NUM_PATHS; i++) { + switch(mux_path->path[i].chip) { + case EXP0: + if(gpio_pcal9535a_write(&data.exp0, mux_path->path[i].pin, mux_path->path[i].level) < 0) { + return -1; + } + if(gpio_pcal9535a_config(&data.exp0, mux_path->path[i].pin, mux_path->path[i].cfg) < 0) { + return -1; + } + break; + case EXP1: + if(gpio_pcal9535a_write(&data.exp1, mux_path->path[i].pin, mux_path->path[i].level) < 0) { + return -1; + } + if(gpio_pcal9535a_config(&data.exp1, mux_path->path[i].pin, mux_path->path[i].cfg) < 0) { + return -1; + } + break; + case EXP2: + if(gpio_pcal9535a_write(&data.exp2, mux_path->path[i].pin, mux_path->path[i].level) < 0) { + return -1; + } + if(gpio_pcal9535a_config(&data.exp2, mux_path->path[i].pin, mux_path->path[i].cfg) < 0) { + return -1; + } + break; + case PWM0: + if(pwm_pca9685_set_duty_cycle(&data.pwm0, mux_path->path[i].pin, mux_path->path[i].level ? 100 : 0) < 0) { + return -1; + } + break; + case NONE: + break; + } + } + + return 0; +} +int +galileo_pinmux_initialize(void) +{ + uint8_t i; + + /* has to init after I2C master */ + if(!quarkX1000_i2c_is_available()) { + return -1; + } + + if(gpio_pcal9535a_init(&data.exp0, GPIO_PCAL9535A_0_I2C_ADDR) < 0) { + return -1; + } + + if(gpio_pcal9535a_init(&data.exp1, GPIO_PCAL9535A_1_I2C_ADDR) < 0) { + return -1; + } + + if(gpio_pcal9535a_init(&data.exp2, GPIO_PCAL9535A_2_I2C_ADDR) < 0) { + return -1; + } + + if(pwm_pca9685_init(&data.pwm0, PWM_PCA9685_0_I2C_ADDR) < 0) { + return -1; + } + + for(i = 0; i < PINMUX_NUM_PINS; i++) { + if(galileo_pinmux_set_pin(default_pinmux_config[i].pin_num, default_pinmux_config[i].func) < 0) { + return -1; + } + } + + return 0; +} diff --git a/platform/galileo/drivers/galileo-pinmux.h b/platform/galileo/drivers/galileo-pinmux.h new file mode 100644 index 000000000..f7d4fa39e --- /dev/null +++ b/platform/galileo/drivers/galileo-pinmux.h @@ -0,0 +1,46 @@ +/* + * Copyright (C) 2015, 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_GALILEO_PINMUX_H_ +#define CPU_X86_DRIVERS_GALILEO_PINMUX_H_ + +#include + +typedef enum { + GALILEO_PINMUX_FUNC_A, + GALILEO_PINMUX_FUNC_B, + GALILEO_PINMUX_FUNC_C, + GALILEO_PINMUX_FUNC_D +} GALILEO_PINMUX_FUNC; + +int galileo_pinmux_initialize(void); +int galileo_pinmux_set_pin(uint8_t pin, GALILEO_PINMUX_FUNC func); + +#endif /* CPU_X86_DRIVERS_GALILEO_PINMUX_H_ */ diff --git a/platform/galileo/drivers/gpio-pcal9535a.c b/platform/galileo/drivers/gpio-pcal9535a.c new file mode 100644 index 000000000..1fac7f74b --- /dev/null +++ b/platform/galileo/drivers/gpio-pcal9535a.c @@ -0,0 +1,357 @@ +/* + * Copyright (C) 2015, 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 "contiki.h" +#include "gpio.h" +#include "gpio-pcal9535a.h" +#include "i2c.h" +#include "stdio.h" + +#define REG_INPUT_PORT0 0x00 +#define REG_INPUT_PORT1 0x01 +#define REG_OUTPUT_PORT0 0x02 +#define REG_OUTPUT_PORT1 0x03 +#define REG_POL_INV_PORT0 0x04 +#define REG_POL_INV_PORT1 0x05 +#define REG_CONF_PORT0 0x06 +#define REG_CONG_PORT1 0x07 +#define REG_OUT_DRV_STRENGTH_PORT0_L 0x40 +#define REG_OUT_DRV_STRENGTH_PORT0_H 0x41 +#define REG_OUT_DRV_STRENGTH_PORT1_L 0x42 +#define REG_OUT_DRV_STRENGTH_PORT1_H 0x43 +#define REG_INPUT_LATCH_PORT0 0x44 +#define REG_INPUT_LATCH_PORT1 0x45 +#define REG_PUD_EN_PORT0 0x46 +#define REG_PUD_EN_PORT1 0x47 +#define REG_PUD_SEL_PORT0 0x48 +#define REG_PUD_SEL_PORT1 0x49 +#define REG_INT_MASK_PORT0 0x4A +#define REG_INT_MASK_PORT1 0x4B +#define REG_INT_STATUS_PORT0 0x4C +#define REG_INT_STATUS_PORT1 0x4D +#define REG_OUTPUT_PORT_CONF 0x4F + +#define READ_PORT_TIMEOUT (CLOCK_SECOND / 100) +#define READ_PORT_TRIES 5 + +static int +read_port_regs(struct gpio_pcal9535a_data *data, uint8_t reg, union gpio_pcal9535a_port_data *buf) +{ + int r; + uint8_t tries = READ_PORT_TRIES; + + buf->byte[0] = reg; + buf->byte[1] = 0; + + if(quarkX1000_i2c_write(buf->byte, 1, data->i2c_slave_addr) < 0) { + return -1; + } + + do { + clock_wait(READ_PORT_TIMEOUT); + + r = quarkX1000_i2c_read(buf->byte, 2, data->i2c_slave_addr); + if(r == 0) { + break; + } + } while(tries--); + + if(r < 0) { + return -1; + } + + return 0; +} +static int +write_port_regs(struct gpio_pcal9535a_data *data, uint8_t reg, union gpio_pcal9535a_port_data *buf) +{ + uint8_t cmd[] = { reg, buf->byte[0], buf->byte[1] }; + + if(quarkX1000_i2c_polling_write(cmd, sizeof(cmd), data->i2c_slave_addr) < 0) { + return -1; + } + + return 0; +} +static int +setup_pin_dir(struct gpio_pcal9535a_data *data, uint32_t pin, int flags) +{ + union gpio_pcal9535a_port_data *port = &data->reg_cache.dir; + uint16_t bit_mask, new_value = 0; + + bit_mask = 1 << pin; + + if((flags & QUARKX1000_GPIO_DIR_MASK) == QUARKX1000_GPIO_IN) { + new_value = 1 << pin; + } + + port->all &= ~bit_mask; + port->all |= new_value; + + return write_port_regs(data, REG_CONF_PORT0, port); +} +static int +setup_pin_pullupdown(struct gpio_pcal9535a_data *data, uint32_t pin, int flags) +{ + union gpio_pcal9535a_port_data *port; + uint16_t bit_mask, new_value = 0; + + if((flags & QUARKX1000_GPIO_PUD_MASK) != QUARKX1000_GPIO_PUD_NORMAL) { + port = &data->reg_cache.pud_sel; + bit_mask = 1 << pin; + + if((flags & QUARKX1000_GPIO_PUD_MASK) == QUARKX1000_GPIO_PUD_PULL_UP) { + new_value = 1 << pin; + } + + port->all &= ~bit_mask; + port->all |= new_value; + + if(write_port_regs(data, REG_PUD_SEL_PORT0, port) < 0) { + return -1; + } + } + + port = &data->reg_cache.pud_en; + bit_mask = 1 << pin; + + if((flags & QUARKX1000_GPIO_PUD_MASK) != QUARKX1000_GPIO_PUD_NORMAL) { + new_value = 1 << pin; + } + + port->all &= ~bit_mask; + port->all |= new_value; + + return write_port_regs(data, REG_PUD_EN_PORT0, port); +} +static int +setup_pin_polarity(struct gpio_pcal9535a_data *data, uint32_t pin, int flags) +{ + union gpio_pcal9535a_port_data *port = &data->reg_cache.pol_inv; + uint16_t bit_mask, new_value = 0; + + bit_mask = 1 << pin; + + if((flags & QUARKX1000_GPIO_POL_MASK) == QUARKX1000_GPIO_POL_INV) { + new_value = 1 << pin; + } + + port->all &= ~bit_mask; + port->all |= new_value; + + if(write_port_regs(data, REG_POL_INV_PORT0, port) < 0) { + return -1; + } + + data->out_pol_inv = port->all; + + return 0; +} +int +gpio_pcal9535a_write(struct gpio_pcal9535a_data *data, uint32_t pin, uint32_t value) +{ + union gpio_pcal9535a_port_data *port = &data->reg_cache.output; + uint16_t bit_mask, new_value; + + if(!quarkX1000_i2c_is_available()) { + return -1; + } + + bit_mask = 1 << pin; + + new_value = (value << pin) & bit_mask; + new_value ^= (data->out_pol_inv & bit_mask); + new_value &= bit_mask; + + port->all &= ~bit_mask; + port->all |= new_value; + + return write_port_regs(data, REG_OUTPUT_PORT0, port); +} +int +gpio_pcal9535a_read(struct gpio_pcal9535a_data *data, uint32_t pin, uint32_t *value) +{ + union gpio_pcal9535a_port_data buf; + + if(!quarkX1000_i2c_is_available()) { + return -1; + } + + if(read_port_regs(data, REG_INPUT_PORT0, &buf) < 0) { + return -1; + } + + *value = (buf.all >> pin) & 0x01; + + return 0; +} +int +gpio_pcal9535a_config(struct gpio_pcal9535a_data *data, uint32_t pin, int flags) +{ + if(!quarkX1000_i2c_is_available()) { + return -1; + } + + if(setup_pin_dir(data, pin, flags) < 0) { + return -1; + } + + if(setup_pin_polarity(data, pin, flags) < 0) { + return -1; + } + + if(setup_pin_pullupdown(data, pin, flags) < 0) { + return -1; + } + + return 0; +} +static int +setup_port_dir(struct gpio_pcal9535a_data *data, uint32_t pin, int flags) +{ + union gpio_pcal9535a_port_data *port = &data->reg_cache.dir; + + port->all = ((flags & QUARKX1000_GPIO_DIR_MASK) == QUARKX1000_GPIO_IN) ? 0xFFFF : 0x0; + + return write_port_regs(data, REG_CONF_PORT0, port); +} +static int +setup_port_pullupdown(struct gpio_pcal9535a_data *data, uint32_t pin, int flags) +{ + union gpio_pcal9535a_port_data *port; + + if((flags & QUARKX1000_GPIO_PUD_MASK) != QUARKX1000_GPIO_PUD_NORMAL) { + port = &data->reg_cache.pud_sel; + port->all = ((flags & QUARKX1000_GPIO_PUD_MASK) == QUARKX1000_GPIO_PUD_PULL_UP) ? 0xFFFF : 0x0; + + if(write_port_regs(data, REG_PUD_SEL_PORT0, port) < 0) { + return -1; + } + } + + port = &data->reg_cache.pud_en; + port->all = ((flags & QUARKX1000_GPIO_PUD_MASK) != QUARKX1000_GPIO_PUD_NORMAL) ? 0xFFFF : 0x0; + + return write_port_regs(data, REG_PUD_EN_PORT0, port); +} +static int +setup_port_polarity(struct gpio_pcal9535a_data *data, uint32_t pin, int flags) +{ + union gpio_pcal9535a_port_data *port = &data->reg_cache.pol_inv; + + port->all = ((flags & QUARKX1000_GPIO_POL_MASK) == QUARKX1000_GPIO_POL_INV) ? 0xFFFF : 0x0; + + if(write_port_regs(data, REG_POL_INV_PORT0, port) < 0) { + return -1; + } + + data->out_pol_inv = port->all; + + return 0; +} +int +gpio_pcal9535a_write_port(struct gpio_pcal9535a_data *data, uint32_t pin, uint32_t value) +{ + union gpio_pcal9535a_port_data *port = &data->reg_cache.output; + uint16_t bit_mask, new_value; + + if(!quarkX1000_i2c_is_available()) { + return -1; + } + + port->all = value; + bit_mask = data->out_pol_inv; + + new_value = value & bit_mask; + new_value ^= data->out_pol_inv; + new_value &= bit_mask; + + port->all &= ~bit_mask; + port->all |= new_value; + + return write_port_regs(data, REG_OUTPUT_PORT0, port); +} +int +gpio_pcal9535a_read_port(struct gpio_pcal9535a_data *data, uint32_t pin, uint32_t *value) +{ + union gpio_pcal9535a_port_data buf; + + if(!quarkX1000_i2c_is_available()) { + return -1; + } + + if(read_port_regs(data, REG_INPUT_PORT0, &buf) < 0) { + return -1; + } + + *value = buf.all; + + return 0; +} +int +gpio_pcal9535a_config_port(struct gpio_pcal9535a_data *data, uint32_t pin, int flags) +{ + if(!quarkX1000_i2c_is_available()) { + return -1; + } + + if(setup_port_dir(data, pin, flags) < 0) { + return -1; + } + + if(setup_port_polarity(data, pin, flags) < 0) { + return -1; + } + + if(setup_port_pullupdown(data, pin, flags) < 0) { + return -1; + } + + return 0; +} +int +gpio_pcal9535a_init(struct gpio_pcal9535a_data *data, uint16_t i2c_slave_addr) +{ + /* has to init after I2C master */ + if(!quarkX1000_i2c_is_available()) { + return -1; + } + + data->i2c_slave_addr = i2c_slave_addr; + + /* default for registers according to datasheet */ + data->reg_cache.output.all = 0xFFFF; + data->reg_cache.pol_inv.all = 0x0; + data->reg_cache.dir.all = 0xFFFF; + data->reg_cache.pud_en.all = 0x0; + data->reg_cache.pud_sel.all = 0xFFFF; + + return 0; +} diff --git a/platform/galileo/drivers/gpio-pcal9535a.h b/platform/galileo/drivers/gpio-pcal9535a.h new file mode 100644 index 000000000..f7f8ce699 --- /dev/null +++ b/platform/galileo/drivers/gpio-pcal9535a.h @@ -0,0 +1,65 @@ +/* + * Copyright (C) 2015, 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_GPIO_PCAL9535A_H_ +#define CPU_X86_DRIVERS_GPIO_PCAL9535A_H_ + +#include + +union gpio_pcal9535a_port_data { + uint16_t all; + uint8_t port[2]; + uint8_t byte[2]; +}; + +struct gpio_pcal9535a_data { + uint16_t i2c_slave_addr; + uint32_t out_pol_inv; + + struct { + union gpio_pcal9535a_port_data output; + union gpio_pcal9535a_port_data pol_inv; + union gpio_pcal9535a_port_data dir; + union gpio_pcal9535a_port_data pud_en; + union gpio_pcal9535a_port_data pud_sel; + } reg_cache; +}; + +int gpio_pcal9535a_init(struct gpio_pcal9535a_data *data, uint16_t i2c_slave_addr); + +int gpio_pcal9535a_config(struct gpio_pcal9535a_data *data, uint32_t pin, int flags); +int gpio_pcal9535a_read(struct gpio_pcal9535a_data *data, uint32_t pin, uint32_t *value); +int gpio_pcal9535a_write(struct gpio_pcal9535a_data *data, uint32_t pin, uint32_t value); + +int gpio_pcal9535a_config_port(struct gpio_pcal9535a_data *data, uint32_t pin, int flags); +int gpio_pcal9535a_read_port(struct gpio_pcal9535a_data *data, uint32_t pin, uint32_t *value); +int gpio_pcal9535a_write_port(struct gpio_pcal9535a_data *data, uint32_t pin, uint32_t value); + +#endif /* CPU_X86_DRIVERS_GPIO_PCAL9535A_H_ */ diff --git a/platform/galileo/drivers/pwm-pca9685.c b/platform/galileo/drivers/pwm-pca9685.c new file mode 100644 index 000000000..6a3d7ce2d --- /dev/null +++ b/platform/galileo/drivers/pwm-pca9685.c @@ -0,0 +1,120 @@ +/* + * Copyright (C) 2015, 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 "i2c.h" +#include "pwm-pca9685.h" + +#define REG_MODE1 0x00 +#define REG_MODE2 0x01 + +#define REG_LED_ON_L(n) ((4 * n) + 0x06) +#define REG_LED_ON_H(n) ((4 * n) + 0x07) +#define REG_LED_OFF_L(n) ((4 * n) + 0x08) +#define REG_LED_OFF_H(n) ((4 * n) + 0x09) + +#define MAX_PWM_OUT 16 +#define PWM_ONE_PERIOD_TICKS 4096 + +int +pwm_pca9685_set_values(struct pwm_pca9685_data *data, uint32_t pwm, uint32_t on, uint32_t off) +{ + uint8_t buf[5] = { 0 }; + + if(!quarkX1000_i2c_is_available()) { + return -1; + } + + if(pwm > MAX_PWM_OUT) { + return -1; + } + + buf[0] = REG_LED_ON_L(pwm); + + if((on >= PWM_ONE_PERIOD_TICKS) || (off >= PWM_ONE_PERIOD_TICKS)) { + /* Treat as 100% */ + buf[1] = 0x0; + buf[2] = (1 << 4); + buf[3] = 0x0; + buf[4] = 0x0; + } else if(off == 0) { + /* Treat it as 0% */ + buf[1] = 0x0; + buf[2] = 0x0; + buf[3] = 0x0; + buf[4] = (1 << 4); + } else { + /* Populate registers accordingly */ + buf[0] = (on & 0xFF); + buf[1] = ((on >> 8) & 0x0F); + buf[2] = (off & 0xFF); + buf[3] = ((off >> 8) & 0x0F); + } + + return quarkX1000_i2c_polling_write(buf, sizeof(buf), data->i2c_slave_addr); +} +int +pwm_pca9685_set_duty_cycle(struct pwm_pca9685_data *data, uint32_t pwm, uint8_t duty) +{ + uint32_t on, off; + + if(duty == 0) { + on = 0; + off = 0; + } else if(duty >= 100) { + on = PWM_ONE_PERIOD_TICKS + 1; + off = PWM_ONE_PERIOD_TICKS + 1; + } else { + on = PWM_ONE_PERIOD_TICKS * duty / 100; + off = PWM_ONE_PERIOD_TICKS - 1; + } + + return pwm_pca9685_set_values(data, pwm, on, off); +} +int +pwm_pca9685_init(struct pwm_pca9685_data *data, uint16_t i2c_slave_addr) +{ + uint8_t buf[2] = { 0 }; + + /* has to init after I2C master */ + if(!quarkX1000_i2c_is_available()) { + return -1; + } + + data->i2c_slave_addr = i2c_slave_addr; + + buf[0] = REG_MODE1; + buf[1] = (1 << 5); + + if(quarkX1000_i2c_polling_write(buf, 2, i2c_slave_addr) < 0) { + return -1; + } + + return 0; +} diff --git a/platform/galileo/drivers/pwm-pca9685.h b/platform/galileo/drivers/pwm-pca9685.h new file mode 100644 index 000000000..394e9357d --- /dev/null +++ b/platform/galileo/drivers/pwm-pca9685.h @@ -0,0 +1,44 @@ +/* + * Copyright (C) 2015, 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_PWM_PCA9685_H_ +#define CPU_X86_DRIVERS_PWM_PCA9685_H_ + +#include + +struct pwm_pca9685_data { + uint16_t i2c_slave_addr; +}; + +int pwm_pca9685_init(struct pwm_pca9685_data *data, uint16_t i2c_slave_addr); +int pwm_pca9685_set_duty_cycle(struct pwm_pca9685_data *data, uint32_t pwm, uint8_t duty); +int pwm_pca9685_set_values(struct pwm_pca9685_data *data, uint32_t pwm, uint32_t on, uint32_t off); + +#endif /* CPU_X86_DRIVERS_PWM_PCA9685_H_ */ diff --git a/platform/galileo/net/eth-conf.c b/platform/galileo/net/eth-conf.c new file mode 100644 index 000000000..ff3a771bf --- /dev/null +++ b/platform/galileo/net/eth-conf.c @@ -0,0 +1,75 @@ +/* + * Copyright (C) 2015, 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 "eth-conf.h" +#include "eth.h" +#include "net/eth-proc.h" +#include "contiki-net.h" +#include "net/linkaddr.h" + +#if NETSTACK_CONF_WITH_IPV6 +const linkaddr_t linkaddr_null = { { 0, 0, 0, 0, 0, 0 } }; +#else +/* 192.0.2.0/24 is a block reserved for documentation by RFC 5737. */ +#define SUBNET_IP 192, 0, 2 +#define NETMASK_IP 255, 255, 255, 0 +#define HOST_IP SUBNET_IP, 2 +#define GATEWAY_IP SUBNET_IP, 1 +#define NAMESERVER_IP GATEWAY_IP +#endif + +void +eth_init(void) +{ +#if !NETSTACK_CONF_WITH_IPV6 + uip_ipaddr_t ip_addr; + +#define SET_IP_ADDR(x) \ + uip_ipaddr(&ip_addr, x) + + SET_IP_ADDR(HOST_IP); + uip_sethostaddr(&ip_addr); + + SET_IP_ADDR(NETMASK_IP); + uip_setnetmask(&ip_addr); + + SET_IP_ADDR(GATEWAY_IP); + uip_setdraddr(&ip_addr); + +#if WITH_DNS + SET_IP_ADDR(NAMESERVER_IP); + uip_nameserver_update(&ip_addr, UIP_NAMESERVER_INFINITE_LIFETIME); +#endif +#endif + + quarkX1000_eth_init(); + + process_start(ð_process, NULL); +} diff --git a/platform/galileo/net/eth-conf.h b/platform/galileo/net/eth-conf.h new file mode 100644 index 000000000..e84091809 --- /dev/null +++ b/platform/galileo/net/eth-conf.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2015, 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 PLATFORM_GALILEO_ETH_CONF_H_ +#define PLATFORM_GALILEO_ETH_CONF_H_ + +void eth_init(void); + +#endif /* PLATFORM_GALILEO_ETH_CONF_H_ */ diff --git a/platform/galileo/net/eth-proc.c b/platform/galileo/net/eth-proc.c new file mode 100644 index 000000000..412d0c8cf --- /dev/null +++ b/platform/galileo/net/eth-proc.c @@ -0,0 +1,112 @@ +/* + * Copyright (C) 2015, 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 + +#include "contiki-net.h" +#include "net/ipv4/uip-neighbor.h" +#include "net/eth-proc.h" +#include "eth.h" + +#define BUF ((struct uip_eth_hdr *)&uip_buf[0]) +#define IPBUF ((struct uip_ip_hdr *)&uip_buf[UIP_LLH_LEN]) + +PROCESS(eth_process, "Ethernet"); + +/*---------------------------------------------------------------------------*/ +#if NETSTACK_CONF_WITH_IPV6 +static uint8_t +output(const uip_lladdr_t *dest_mac) +{ + if (dest_mac == NULL) { + /* broadcast packet */ + memset(&BUF->dest, 0xFF, UIP_LLH_LEN); + } else { + memcpy(&BUF->dest, dest_mac, UIP_LLH_LEN); + } + memcpy(&BUF->src, uip_lladdr.addr, UIP_LLH_LEN); + quarkX1000_eth_send(); + + return 0; +} +#else +static uint8_t +output(void) +{ + uip_arp_out(); + quarkX1000_eth_send(); + + return 0; +} +#endif /* NETSTACK_CONF_WITH_IPV6 */ +/*---------------------------------------------------------------------------*/ +static void +pollhandler(void) +{ + process_poll(ð_process); + quarkX1000_eth_poll(&uip_len); + + if(uip_len > 0) { +#if NETSTACK_CONF_WITH_IPV6 + if(BUF->type == uip_htons(UIP_ETHTYPE_IPV6)) { + tcpip_input(); + } +#else + if(BUF->type == uip_htons(UIP_ETHTYPE_IP)) { + uip_len -= sizeof(struct uip_eth_hdr); + tcpip_input(); + } else if(BUF->type == uip_htons(UIP_ETHTYPE_ARP)) { + uip_arp_arpin(); + /* If the above function invocation resulted in data that + should be sent out on the network, the global variable + uip_len is set to a value > 0. */ + if(uip_len > 0) { + quarkX1000_eth_send(); + } + } +#endif /* NETSTACK_CONF_WITH_IPV6 */ + } +} +/*---------------------------------------------------------------------------*/ +PROCESS_THREAD(eth_process, ev, data) +{ + PROCESS_POLLHANDLER(pollhandler()); + + PROCESS_BEGIN(); + + tcpip_set_outputfunc(output); + + process_poll(ð_process); + + PROCESS_WAIT_UNTIL(ev == PROCESS_EVENT_EXIT); + + PROCESS_END(); +} +/*---------------------------------------------------------------------------*/ diff --git a/platform/galileo/net/eth-proc.h b/platform/galileo/net/eth-proc.h new file mode 100644 index 000000000..88dbf4c7b --- /dev/null +++ b/platform/galileo/net/eth-proc.h @@ -0,0 +1,38 @@ +/* + * Copyright (C) 2015, 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 PLATFORM_GALILEO_NET_ETH_PROC_H_ +#define PLATFORM_GALILEO_NET_ETH_PROC_H_ + +#include "contiki.h" + +PROCESS_NAME(eth_process); + +#endif /* PLATFORM_GALILEO_NET_ETH_PROC_H_ */ diff --git a/platform/galileo/newlib-syscalls.c b/platform/galileo/newlib-syscalls.c new file mode 100644 index 000000000..fa098c6eb --- /dev/null +++ b/platform/galileo/newlib-syscalls.c @@ -0,0 +1,174 @@ +/* + * Copyright (C) 2015, 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 +#include + +#include "uart.h" +#include "helpers.h" + +#define CONSOLE_OUTPUT_DEV QUARK_X1000_UART_1 + +#define HEAP_MAX_SIZE 2048 + +static char _heap[HEAP_MAX_SIZE]; +static char *prog_break = _heap; + +int +_close_r(struct _reent *ptr, int file) +{ + /* Stubbed function */ + ptr->_errno = ENOTSUP; + return -1; +} +/*---------------------------------------------------------------------------*/ +void +_exit(int status) +{ + halt(); +} +/*---------------------------------------------------------------------------*/ +int +_getpid_r(struct _reent *ptr) +{ + /* Stubbed function */ + ptr->_errno = ENOTSUP; + return -1; +} +/*---------------------------------------------------------------------------*/ +int +_isatty_r(struct _reent *ptr, int file) +{ + /* Stubbed function */ + ptr->_errno = ENOTSUP; + return 0; +} +/*---------------------------------------------------------------------------*/ +int +_kill_r(struct _reent *ptr, int pid, int signal) +{ + /* Stubbed function */ + ptr->_errno = ENOTSUP; + return -1; +} +/*---------------------------------------------------------------------------*/ +int +_read_r(struct _reent *ptr, int file, char *buf, int len) +{ + /* Stubbed function */ + ptr->_errno = ENOTSUP; + return -1; +} +/*---------------------------------------------------------------------------*/ +int +_write_r(struct _reent *ptr, int file, const char *buf, int len) +{ + int ret; + int i; + + switch(file) { + case 0: + ptr->_errno = EBADF; + ret = -1; + break; + + case 1: + case 2: + for(i = 0; i < len; i++) { + /* Since file descriptors 1 and 2 (stdout and stderr) are mapped to a + * serial console, we should translate the 'newline' escape sequence + * to 'carriage return' (CR) followed by 'line feed' (LF) ASCII + * characters. + */ + if(buf[i] == '\n') { + quarkX1000_uart_tx(CONSOLE_OUTPUT_DEV, '\r'); + } + quarkX1000_uart_tx(CONSOLE_OUTPUT_DEV, buf[i]); + } + + ret = len; + break; + + default: + /* We don't support any filesystem yet. */ + ptr->_errno = ENOTSUP; + ret = -1; + break; + } + + return ret; +} +/*---------------------------------------------------------------------------*/ +int +_lseek_r(struct _reent *ptr, int file, int p, int dir) +{ + /* Stubbed function */ + ptr->_errno = ENOTSUP; + return -1; +} +/*---------------------------------------------------------------------------*/ +int +_fstat_r(struct _reent *ptr, int file, struct stat *st) +{ + /* We don't support the standard input yet so file descriptor 0 is not + * supported by this function. Additionally, we don't have support for + * any filesystem thus file descriptors greater than 2 are not supported + * as well. + * + * We support standard ouput and error (file descriptors 1 and 2) only. + */ + if(file == 0 || file > 2) { + ptr->_errno = ENOTSUP; + return -1; + } + + st->st_mode = S_IFCHR; + return 0; +} +/*---------------------------------------------------------------------------*/ +caddr_t +_sbrk_r(struct _reent *ptr, int incr) +{ + char *prev_prog_break; + + /* If the new program break overruns the maximum heap address, we return + * "Out of Memory" error to the user. + */ + if(prog_break + incr > _heap + HEAP_MAX_SIZE) { + ptr->_errno = ENOMEM; + return NULL; + } + + prev_prog_break = prog_break; + + prog_break += incr; + + return prev_prog_break; +}