qmsi: move drivers and hal to ext/hal

This is external source code maintained somewhere else. Put it
under ext/ for clarity and maintainability.

Change-Id: I9e7c9d0948a2ba893006e316dc21d9b1a9edfa93
Signed-off-by: Anas Nashif <anas.nashif@intel.com>
This commit is contained in:
Anas Nashif 2016-05-20 17:39:42 -04:00 committed by Anas Nashif
commit 489f42328c
92 changed files with 24 additions and 9 deletions

1
ext/Kbuild Normal file
View file

@ -0,0 +1 @@
obj-y += hal/

1
ext/hal/Makefile Normal file
View file

@ -0,0 +1 @@
obj-$(CONFIG_QMSI_BUILTIN) += qmsi/

12
ext/hal/README Normal file
View file

@ -0,0 +1,12 @@
This directory contains different HALs for SoCs supported by Zephyr.
The following HALs are supported:
qmsi
-------
Intel® Quark™ Microcontroller Software Interface (QMSI) is a Hardware
Abstraction Layer (HAL) for Intel® Quark™ Microcontroller products. It
currently support the following SoCs:
- Intel® Quark™ D2000 Microcontroller
- Intel® Quark™ SE Microcontroller

48
ext/hal/qmsi/Kconfig Normal file
View file

@ -0,0 +1,48 @@
# Kconfig - QMSI drivers configuration options
#
# Copyright (c) 2015 Intel Corporation
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
config QMSI_BUILTIN
bool "Enable QMSI drivers through integrated sources"
default n
select QMSI
help
Link with local QMSI sources instead of external library.
config QMSI_LIBRARY
bool "Enable QMSI drivers using external library"
default n
select QMSI
help
This option enables QMSI device drivers. These drivers are actually shim
drivers based on drivers provided by QMSI BSP. The BSP provides a static
library (libqmsi) which implements several drivers for peripherals from
Intel MCUs (e.g. Quark SE and Quark D2000).
config QMSI
bool
default n
help
automatically set when either of QMSI_LIBRARY or QMSI_BUILTIN
is selected.
config QMSI_INSTALL_PATH
depends on QMSI_LIBRARY
string "QMSI install path"
help
This option holds the path where the QMSI library and headers are
installed. Make sure this option is properly set when QMSI_LIBRARY
is enabled otherwise the build will fail.

23
ext/hal/qmsi/Makefile Normal file
View file

@ -0,0 +1,23 @@
subdir-ccflags-$(CONFIG_QMSI_BUILTIN) +=-DISR_HANDLED
include $(srctree)/ext/hal/qmsi/Makefile.include
obj-$(CONFIG_QMSI_BUILTIN) += drivers/clk.o
ifeq ($(CONFIG_ARC),y)
obj-$(CONFIG_QMSI_BUILTIN) += drivers/sensor/ss_clk.o
endif
obj-$(CONFIG_RTC_QMSI) += drivers/qm_rtc.o
obj-$(CONFIG_WDT_QMSI) += drivers/qm_wdt.o
obj-$(CONFIG_I2C_QMSI) += drivers/qm_i2c.o
obj-$(CONFIG_PWM_QMSI) += drivers/qm_pwm.o
obj-$(CONFIG_AIO_COMPARATOR_QMSI) += drivers/qm_comparator.o
obj-$(CONFIG_AON_COUNTER_QMSI) += drivers/qm_aon_counters.o
obj-$(CONFIG_GPIO_QMSI) += drivers/qm_gpio.o
obj-$(CONFIG_ADC_QMSI) += drivers/qm_adc.o
obj-$(CONFIG_UART_QMSI) += drivers/qm_uart.o
obj-$(CONFIG_SPI_QMSI) += drivers/qm_spi.o
obj-$(CONFIG_SOC_FLASH_QMSI) += drivers/qm_flash.o
obj-$(CONFIG_PINMUX_DEV_QMSI) += drivers/qm_pinmux.o
obj-$(CONFIG_SPI_QMSI_SS) += drivers/sensor/qm_ss_spi.o
obj-$(CONFIG_GPIO_QMSI_SS) += drivers/sensor/qm_ss_gpio.o
obj-$(CONFIG_I2C_QMSI_SS) += drivers/sensor/qm_ss_i2c.o
obj-$(CONFIG_ADC_QMSI_SS) += drivers/sensor/qm_ss_adc.o

View file

@ -0,0 +1,6 @@
subdir-ccflags-$(CONFIG_QMSI_LIBRARY) += -I$(CONFIG_QMSI_INSTALL_PATH)/include
subdir-ccflags-$(CONFIG_QMSI_BUILTIN) +=-I$(srctree)/ext/hal/qmsi/include
subdir-ccflags-$(CONFIG_QMSI_BUILTIN) +=-I$(srctree)/ext/hal/qmsi/drivers/include
subdir-ccflags-$(CONFIG_QMSI_BUILTIN) +=-I$(srctree)/ext/hal/qmsi/soc/$(SOC_NAME)/include/
subdir-ccflags-$(CONFIG_QMSI_BUILTIN) +=-I$(srctree)/ext/hal/qmsi/drivers/sensor/include
subdir-ccflags-$(CONFIG_QMSI_BUILTIN) +=-I$(srctree)/ext/hal/qmsi/soc/quark_se/include/

15
ext/hal/qmsi/README Normal file
View file

@ -0,0 +1,15 @@
The sources in this directory are imported from QMSI project
at https://github.com/01org/qmsi.
Intel® Quark™ Microcontroller Software Interface (QMSI) is a
Hardware Abstraction Layer (HAL) for Intel® Quark™
Microcontroller products. It currently support the following SoCs:
- Intel® Quark™ D2000 Microcontroller
- Intel® Quark™ SE Microcontroller
The current version supported in Zephyr is QMSI 1.1.0 See
https://github.com/01org/qmsi/releases/tag/v1.1.0
for more details.

View file

@ -0,0 +1,95 @@
#
# Copyright (c) 2016, Intel Corporation
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# 1. Redistributions of source code must retain the above copyright notice,
# this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright notice,
# this list of conditions and the following disclaimer in the documentation
# and/or other materials provided with the distribution.
# 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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.
#
SOC_ROOT_DIR = $(SOC)
SOC_MAKEFILE = $(SOC)
SUPPORTED_SOCS = quark_se \
quark_d2000
SOC ?= $(DEFAULT_SOC)
TARGET ?= $(DEFAULT_TARGET)
TARGETS_quark_d2000 = x86
TARGETS_quark_se = x86 \
sensor
ifeq ($(filter $(SOC),$(SUPPORTED_SOCS)),)
$(error SOC=$(SOC) is not supported. Run 'make help' for help)
endif
SUPPORTED_TARGETS = $(TARGETS_$(SOC))
ifeq ($(filter $(TARGET),$(SUPPORTED_TARGETS)),)
$(error TARGET=$(TARGET) is not supported for $(SOC). Run 'make help' for help)
endif
ifeq ($(TARGET), sensor)
SOC_ROOT_DIR = quark_se
SOC_MAKEFILE = sensor
endif
### Variables
BASE_DIR = ..
HEADERS = $(wildcard $(BASE_DIR)/include/*.h)
HEADERS += $(wildcard $(BASE_DIR)/soc/$(SOC_ROOT_DIR)/include/*.h)
HEADERS += $(wildcard $(BASE_DIR)/drivers/include/*.h)
ifeq ($(TARGET), sensor)
HEADERS += $(wildcard $(BASE_DIR)/drivers/sensor/include/*.h)
endif
EXPORTED_HEADERS += $(addprefix $(LIBQMSI_INCLUDE_DIR)/, $(notdir $(HEADERS)))
### Make includes
include $(BASE_DIR)/base.mk
include $(BASE_DIR)/drivers/drivers.mk
ifeq ($(TARGET), sensor)
include $(BASE_DIR)/drivers/sensor/sensor.mk
endif
include $(BASE_DIR)/soc/$(SOC_ROOT_DIR)/$(SOC_MAKEFILE).mk
include $(BASE_DIR)/soc/$(SOC_ROOT_DIR)/drivers/drivers.mk
SLINK_NAME := $(LIBQMSI_LIB_DIR)/libqmsi.a
$(LIBQMSI_LIB_DIR)/$(LIBQMSI_FILENAME): $(OBJECTS)
$(call mkdir, $(LIBQMSI_LIB_DIR))
$(AR) rcs $@ $?
ifeq ($(wildcard $(SLINK_NAME)),)
ifneq ($(OS),Windows_NT)
$(LN) -s $(LIBQMSI_FILENAME) $(SLINK_NAME)
endif
endif
$(LIBQMSI_INCLUDE_DIR)/%.h: $(HEADERS)
$(call mkdir, $(LIBQMSI_INCLUDE_DIR))
$(call copy, $(filter %/$(notdir $@), $(HEADERS)), $@)
.PHONY: all
all: $(LIBQMSI_LIB_DIR)/$(LIBQMSI_FILENAME) $(EXPORTED_HEADERS)

145
ext/hal/qmsi/drivers/apic.h Normal file
View file

@ -0,0 +1,145 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __APIC_H__
#define __APIC_H__
#include <stdint.h>
#include "qm_common.h"
#include "qm_soc_regs.h"
#define LAPIC_VECTOR_MASK (0xFF)
static void _ioapic_set_redtbl_entry(unsigned int irq, uint64_t value)
{
unsigned int offset = QM_IOAPIC_REG_REDTBL + (irq * 2);
QM_IOAPIC->ioregsel.reg = offset;
QM_IOAPIC->iowin.reg = value & 0x00000000FFFFFFFF;
QM_IOAPIC->ioregsel.reg = offset + 1;
QM_IOAPIC->iowin.reg = (value & 0xFFFFFFFF00000000) >> 32;
}
/* Get redirection table size */
static __inline__ int _ioapic_get_redtbl_size(void)
{
int max_entry_number;
QM_IOAPIC->ioregsel.reg = QM_IOAPIC_REG_VER;
max_entry_number = (QM_IOAPIC->iowin.reg & 0x00FF0000) >> 16;
return max_entry_number + 1;
}
static uint32_t _ioapic_get_redtbl_entry_lo(unsigned int irq)
{
QM_IOAPIC->ioregsel.reg = QM_IOAPIC_REG_REDTBL + (irq * 2);
return QM_IOAPIC->iowin.reg;
}
static void _ioapic_set_redtbl_entry_lo(unsigned int irq, uint32_t value)
{
QM_IOAPIC->ioregsel.reg = QM_IOAPIC_REG_REDTBL + (irq * 2);
QM_IOAPIC->iowin.reg = value;
}
/*
* Initialize Local and IOAPIC
*/
static __inline__ void apic_init(void)
{
int i;
int size;
/* Enable LAPIC */
QM_LAPIC->svr.reg |= BIT(8);
/* Set up LVT LINT0 to ExtINT and unmask it */
QM_LAPIC->lvtlint0.reg |= (BIT(8) | BIT(9) | BIT(10));
QM_LAPIC->lvtlint0.reg &= ~BIT(16);
/* Clear up any spurious LAPIC interrupts */
QM_LAPIC->eoi.reg = 0;
/* Setup IOAPIC Redirection Table */
size = _ioapic_get_redtbl_size();
for (i = 0; i < size; i++) {
_ioapic_set_redtbl_entry(i, BIT(16));
}
}
static __inline__ void ioapic_register_irq(unsigned int irq,
unsigned int vector)
{
uint32_t value;
value = _ioapic_get_redtbl_entry_lo(irq);
/* Assign vector and set polarity (positive). */
value &= ~LAPIC_VECTOR_MASK;
value |= (vector & LAPIC_VECTOR_MASK);
value &= ~BIT(13);
/* Set trigger mode. */
switch (irq) {
case QM_IRQ_RTC_0:
case QM_IRQ_AONPT_0:
case QM_IRQ_WDT_0:
/* Edge sensitive. */
value &= ~BIT(15);
break;
default:
/* Level sensitive. */
value |= BIT(15);
break;
}
_ioapic_set_redtbl_entry_lo(irq, value);
}
static __inline__ void ioapic_mask_irq(unsigned int irq)
{
uint32_t value = _ioapic_get_redtbl_entry_lo(irq);
value |= BIT(16);
_ioapic_set_redtbl_entry_lo(irq, value);
}
static __inline__ void ioapic_unmask_irq(unsigned int irq)
{
uint32_t value = _ioapic_get_redtbl_entry_lo(irq);
value &= ~BIT(16);
_ioapic_set_redtbl_entry_lo(irq, value);
}
#endif /* __APIC_H__ */

302
ext/hal/qmsi/drivers/clk.c Normal file
View file

@ -0,0 +1,302 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "clk.h"
#include "flash_layout.h"
#if (!QM_SENSOR) || (UNIT_TEST)
#include <x86intrin.h>
#endif
#if (QM_SENSOR) && (!UNIT_TEST)
/* Timestamp counter for Sensor Subsystem is 32bit. */
#define get_ticks() __builtin_arc_lr(QM_SS_TSC_BASE + QM_SS_TIMER_COUNT)
#elif(QM_SENSOR) && (UNIT_TEST)
#define get_ticks() _rdtsc() % ((uint32_t)-1)
#else
/* 64bit Timestamp counter */
#define get_ticks() _rdtsc()
#endif
/* NOTE: Currently user space data / bss section overwrites the ROM data / bss
* sections, so anything that is set in the ROM will be obliterated once we jump
* into the user app.
*/
static uint32_t ticks_per_us = SYS_TICKS_PER_US_32MHZ;
int clk_sys_set_mode(const clk_sys_mode_t mode, const clk_sys_div_t div)
{
QM_CHECK(div <= CLK_SYS_DIV_NUM, -EINVAL);
QM_CHECK(mode <= CLK_SYS_CRYSTAL_OSC, -EINVAL);
uint16_t trim = 0;
/* Store system ticks per us */
uint32_t sys_ticks_per_us = 1;
/*
* Get current settings, clear the clock divisor bits, and clock divider
* enable bit.
*/
uint32_t ccu_sys_clk_ctl =
QM_SCSS_CCU->ccu_sys_clk_ctl & CLK_SYS_CLK_DIV_DEF_MASK;
/*
* Steps:
* 1. Enable the new oscillator and wait for it to stabilise.
* 2. Switch to the new oscillator
* Note on registers:
* - QM_OSC0_MODE_SEL:
* - asserted: it switches to external crystal oscillator
* - not asserted: it switches to silicon oscillator
* - QM_CCU_SYS_CLK_SEL:
* - asserted: it switches to hybrid (silicon or external)
* oscillator
* - not asserted: it switches to RTC oscillator
* 3. Hybrid oscillator only: apply sysclk divisor
* 4. Disable mutually exclusive clock sources. For internal silicon
* oscillator is disables the external crystal oscillator and vice
* versa.
*/
switch (mode) {
case CLK_SYS_HYB_OSC_32MHZ:
case CLK_SYS_HYB_OSC_16MHZ:
case CLK_SYS_HYB_OSC_8MHZ:
case CLK_SYS_HYB_OSC_4MHZ:
/* Calculate the system clock ticks per microsecond
* and get the shadowed trim code from the Data Region of Flash.
*/
if (CLK_SYS_HYB_OSC_32MHZ == mode) {
sys_ticks_per_us = SYS_TICKS_PER_US_32MHZ / BIT(div);
trim = QM_FLASH_DATA_TRIM_CODE->osc_trim_32mhz;
} else if (CLK_SYS_HYB_OSC_16MHZ == mode) {
sys_ticks_per_us = SYS_TICKS_PER_US_16MHZ / BIT(div);
trim = QM_FLASH_DATA_TRIM_CODE->osc_trim_16mhz;
} else if (CLK_SYS_HYB_OSC_8MHZ == mode) {
sys_ticks_per_us = SYS_TICKS_PER_US_8MHZ / BIT(div);
trim = QM_FLASH_DATA_TRIM_CODE->osc_trim_8mhz;
} else {
sys_ticks_per_us = SYS_TICKS_PER_US_4MHZ / BIT(div);
trim = QM_FLASH_DATA_TRIM_CODE->osc_trim_4mhz;
}
/*
* Apply trim code for the selected mode if this has been
* written in the soc_data section.
* This is performed in rom on the first boot for each
* available frequency.
* If not present, something went wrong and trim code
* will not be applied.
*/
if ((trim & QM_FLASH_TRIM_PRESENT_MASK) ==
QM_FLASH_TRIM_PRESENT) {
clk_trim_apply(trim);
}
/* Select the silicon oscillator frequency */
QM_SCSS_CCU->osc0_cfg1 &= ~OSC0_CFG1_SI_FREQ_SEL_MASK;
QM_SCSS_CCU->osc0_cfg1 |= (mode << OSC0_CFG1_SI_FREQ_SEL_OFFS);
/* Enable the silicon oscillator */
QM_SCSS_CCU->osc0_cfg1 |= QM_OSC0_EN_SI_OSC;
/* Wait for the oscillator to lock */
while (!(QM_SCSS_CCU->osc0_stat1 & QM_OSC0_LOCK_SI)) {
};
/* Switch to silicon oscillator mode */
QM_SCSS_CCU->osc0_cfg1 &= ~QM_OSC0_MODE_SEL;
/* Set the system clock divider */
QM_SCSS_CCU->ccu_sys_clk_ctl =
ccu_sys_clk_ctl | QM_CCU_SYS_CLK_SEL |
(div << QM_CCU_SYS_CLK_DIV_OFFSET);
/* Disable the crystal oscillator */
QM_SCSS_CCU->osc0_cfg1 &= ~QM_OSC0_EN_CRYSTAL;
break;
case CLK_SYS_RTC_OSC:
/* The RTC oscillator is on by hardware default */
ccu_sys_clk_ctl |=
(QM_CCU_RTC_CLK_EN | (div << QM_CCU_SYS_CLK_DIV_OFFSET));
QM_SCSS_CCU->ccu_sys_clk_ctl =
(ccu_sys_clk_ctl & ~(QM_CCU_SYS_CLK_SEL));
break;
case CLK_SYS_CRYSTAL_OSC:
QM_SCSS_CCU->osc0_cfg1 |= QM_OSC0_EN_CRYSTAL;
sys_ticks_per_us = SYS_TICKS_PER_US_XTAL / BIT(div);
while (!(QM_SCSS_CCU->osc0_stat1 & QM_OSC0_LOCK_XTAL)) {
};
QM_SCSS_CCU->osc0_cfg1 |= QM_OSC0_MODE_SEL;
QM_SCSS_CCU->ccu_sys_clk_ctl =
ccu_sys_clk_ctl | QM_CCU_SYS_CLK_SEL |
(div << QM_CCU_SYS_CLK_DIV_OFFSET);
QM_SCSS_CCU->osc0_cfg1 &= ~QM_OSC0_EN_SI_OSC;
break;
}
QM_SCSS_CCU->ccu_sys_clk_ctl |= QM_CCU_SYS_CLK_DIV_EN;
ticks_per_us = (sys_ticks_per_us > 0 ? sys_ticks_per_us : 1);
return 0;
}
int clk_trim_read(uint32_t *const value)
{
QM_CHECK(NULL != value, -EINVAL);
*value = (QM_SCSS_CCU->osc0_cfg1 & OSC0_CFG1_FTRIMOTP_MASK) >>
OSC0_CFG1_FTRIMOTP_OFFS;
return 0;
}
int clk_trim_apply(const uint32_t value)
{
/* Apply trim code */
QM_SCSS_CCU->osc0_cfg1 &= ~OSC0_CFG1_FTRIMOTP_MASK;
QM_SCSS_CCU->osc0_cfg1 |=
(value << OSC0_CFG1_FTRIMOTP_OFFS) & OSC0_CFG1_FTRIMOTP_MASK;
return 0;
}
int clk_adc_set_div(const uint16_t div)
{
#if (QUARK_D2000)
/*
* The driver adds 1 to the value, so to avoid confusion for the user,
* subtract 1 from the input value.
*/
QM_CHECK((div - 1) <= QM_ADC_DIV_MAX, -EINVAL);
uint32_t reg = QM_SCSS_CCU->ccu_periph_clk_div_ctl0;
reg &= CLK_ADC_DIV_DEF_MASK;
reg |= ((div - 1) << QM_CCU_ADC_CLK_DIV_OFFSET);
QM_SCSS_CCU->ccu_periph_clk_div_ctl0 = reg;
#else
/* TODO this function should only be made available on D2000 */
(void)div;
#endif
return 0;
}
int clk_periph_set_div(const clk_periph_div_t div)
{
QM_CHECK(div <= CLK_PERIPH_DIV_8, -EINVAL);
#if (QUARK_D2000)
uint32_t reg =
QM_SCSS_CCU->ccu_periph_clk_div_ctl0 & CLK_PERIPH_DIV_DEF_MASK;
reg |= (div << QM_CCU_PERIPH_PCLK_DIV_OFFSET);
QM_SCSS_CCU->ccu_periph_clk_div_ctl0 = reg;
/* CLK Div en bit must be written from 0 -> 1 to apply new value */
QM_SCSS_CCU->ccu_periph_clk_div_ctl0 |= QM_CCU_PERIPH_PCLK_DIV_EN;
#elif(QUARK_SE)
QM_SCSS_CCU->ccu_periph_clk_div_ctl0 =
(div << QM_CCU_PERIPH_PCLK_DIV_OFFSET);
/* CLK Div en bit must be written from 0 -> 1 to apply new value */
QM_SCSS_CCU->ccu_periph_clk_div_ctl0 |= QM_CCU_PERIPH_PCLK_DIV_EN;
#endif
return 0;
}
int clk_gpio_db_set_div(const clk_gpio_db_div_t div)
{
QM_CHECK(div <= CLK_GPIO_DB_DIV_128, -EINVAL);
uint32_t reg =
QM_SCSS_CCU->ccu_gpio_db_clk_ctl & CLK_GPIO_DB_DIV_DEF_MASK;
reg |= (div << QM_CCU_GPIO_DB_DIV_OFFSET);
QM_SCSS_CCU->ccu_gpio_db_clk_ctl = reg;
/* CLK Div en bit must be written from 0 -> 1 to apply new value */
QM_SCSS_CCU->ccu_gpio_db_clk_ctl |= QM_CCU_GPIO_DB_CLK_DIV_EN;
return 0;
}
int clk_ext_set_div(const clk_ext_div_t div)
{
QM_CHECK(div <= CLK_EXT_DIV_8, -EINVAL);
uint32_t reg = QM_SCSS_CCU->ccu_ext_clock_ctl & CLK_EXTERN_DIV_DEF_MASK;
reg |= (div << QM_CCU_EXTERN_DIV_OFFSET);
QM_SCSS_CCU->ccu_ext_clock_ctl = reg;
/* CLK Div en bit must be written from 0 -> 1 to apply new value */
QM_SCSS_CCU->ccu_ext_clock_ctl |= QM_CCU_EXT_CLK_DIV_EN;
return 0;
}
int clk_rtc_set_div(const clk_rtc_div_t div)
{
QM_CHECK(div <= CLK_RTC_DIV_32768, -EINVAL);
uint32_t reg = QM_SCSS_CCU->ccu_sys_clk_ctl & CLK_RTC_DIV_DEF_MASK;
reg |= (div << QM_CCU_RTC_CLK_DIV_OFFSET);
QM_SCSS_CCU->ccu_sys_clk_ctl = reg;
/* CLK Div en bit must be written from 0 -> 1 to apply new value */
QM_SCSS_CCU->ccu_sys_clk_ctl |= QM_CCU_RTC_CLK_DIV_EN;
return 0;
}
int clk_periph_enable(const clk_periph_t clocks)
{
QM_CHECK(clocks <= CLK_PERIPH_ALL, -EINVAL);
QM_SCSS_CCU->ccu_periph_clk_gate_ctl |= clocks;
return 0;
}
int clk_periph_disable(const clk_periph_t clocks)
{
QM_CHECK(clocks <= CLK_PERIPH_ALL, -EINVAL);
QM_SCSS_CCU->ccu_periph_clk_gate_ctl &= ~clocks;
return 0;
}
uint32_t clk_sys_get_ticks_per_us(void)
{
return ticks_per_us;
}
void clk_sys_udelay(uint32_t microseconds)
{
uint32_t timeout = ticks_per_us * microseconds;
#if (QM_SENSOR)
uint32_t tsc_start;
#else
unsigned long long tsc_start;
#endif
tsc_start = get_ticks();
/* We need to wait until timeout system clock ticks has occurred. */
while (get_ticks() - tsc_start < timeout) {
}
}

397
ext/hal/qmsi/drivers/dma.h Normal file
View file

@ -0,0 +1,397 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __DMA_H_
#define __DMA_H_
#include <errno.h>
#include "clk.h"
#include "qm_dma.h"
/* Timeout definitions */
#define STANDARD_TIMEOUT_MICROSECOND (1000)
#define ONE_MICROSECOND (1)
/* Set specific register bits */
#define UPDATE_REG_BITS(reg, value, offset, mask) \
{ \
reg &= ~mask; \
reg |= (value << offset); \
} \
while (0)
/* Mask for all supported channels */
#define CHANNEL_MASK_ALL (BIT(QM_DMA_CHANNEL_NUM) - 1)
/*
* DMA Transfer Type
*/
typedef enum {
QM_DMA_TYPE_SINGLE = 0x0, /**< Single block mode. */
} dma_transfer_type_t;
/*
* DMA address increment type.
*/
typedef enum {
QM_DMA_ADDRESS_INCREMENT = 0x0, /**< Increment address. */
QM_DMA_ADDRESS_DECREMENT = 0x1, /**< Decrement address. */
QM_DMA_ADDRESS_NO_CHANGE = 0x2 /**< Don't modify address. */
} qm_dma_address_increment_t;
/*
* DMA channel private structure.
*/
typedef struct dma_cfg_prv_t {
/* DMA client context to be passed back with callbacks */
void *callback_context;
/* DMA channel transfer callback */
void (*client_callback)(void *callback_context, uint32_t len,
int error_code);
} dma_cfg_prv_t;
/*
* The length of the transfer at the time that this function is called is
* returned. The value returned is defined in bytes.
*/
static __inline__ uint32_t
get_transfer_length(const qm_dma_t dma, const qm_dma_channel_id_t channel_id)
{
uint32_t transfer_length;
uint32_t source_transfer_width;
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
/* Read the source transfer width register value. */
source_transfer_width =
((chan_reg->ctrl_low & QM_DMA_CTL_L_SRC_TR_WIDTH_MASK) >>
QM_DMA_CTL_L_SRC_TR_WIDTH_OFFSET);
/* Read the length from the block_ts field. The units of this field
* are dependent on the source transfer width. */
transfer_length = ((chan_reg->ctrl_high & QM_DMA_CTL_H_BLOCK_TS_MASK) >>
QM_DMA_CTL_H_BLOCK_TS_OFFSET);
/* To convert this to bytes the transfer length can be shifted using
* the source transfer width value. This value correspond to the
* shifts required and so this can be done as an optimization. */
return (transfer_length << source_transfer_width);
}
static __inline__ int dma_controller_disable(const qm_dma_t dma)
{
volatile qm_dma_misc_reg_t *misc_reg = &QM_DMA[dma]->misc_reg;
misc_reg->cfg_low = 0;
if (misc_reg->cfg_low) {
return -EIO;
}
return 0;
}
static __inline__ void dma_controller_enable(const qm_dma_t dma)
{
QM_DMA[dma]->misc_reg.cfg_low = QM_DMA_MISC_CFG_DMA_EN;
}
static int dma_channel_disable(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id)
{
uint8_t channel_mask = BIT(channel_id);
uint16_t timeout_us;
volatile qm_dma_misc_reg_t *misc_reg = &QM_DMA[dma]->misc_reg;
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
/* If the channel is already disabled return */
if (!(misc_reg->chan_en_low & channel_mask)) {
return 0;
}
/* Suspend the channel */
chan_reg->cfg_low |= QM_DMA_CFG_L_CH_SUSP_MASK;
/* Ensure that the channel has been suspended */
timeout_us = STANDARD_TIMEOUT_MICROSECOND;
while ((!(chan_reg->cfg_low & QM_DMA_CFG_L_CH_SUSP_MASK)) &&
timeout_us) {
clk_sys_udelay(ONE_MICROSECOND);
timeout_us--;
}
if (!(chan_reg->cfg_low & QM_DMA_CFG_L_CH_SUSP_MASK)) {
return -EIO;
}
/* Wait until the fifo is empty */
timeout_us = STANDARD_TIMEOUT_MICROSECOND;
while ((!(chan_reg->cfg_low & QM_DMA_CFG_L_FIFO_EMPTY_MASK)) &&
timeout_us) {
clk_sys_udelay(ONE_MICROSECOND);
timeout_us--;
}
if (!(chan_reg->cfg_low & QM_DMA_CFG_L_FIFO_EMPTY_MASK)) {
return -EIO;
}
/* Disable the channel and wait to confirm that it has been disabled. */
misc_reg->chan_en_low = (channel_mask << QM_DMA_MISC_CHAN_EN_WE_OFFSET);
timeout_us = STANDARD_TIMEOUT_MICROSECOND;
while ((misc_reg->chan_en_low & channel_mask) && timeout_us) {
clk_sys_udelay(ONE_MICROSECOND);
timeout_us--;
}
if (misc_reg->chan_en_low & channel_mask) {
return -EIO;
}
/* Set the channel to resume */
chan_reg->cfg_low &= ~QM_DMA_CFG_L_CH_SUSP_MASK;
return 0;
}
static __inline__ void dma_channel_enable(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id)
{
uint8_t channel_mask = BIT(channel_id);
QM_DMA[dma]->misc_reg.chan_en_low =
(channel_mask << QM_DMA_MISC_CHAN_EN_WE_OFFSET) | channel_mask;
}
static __inline__ void
dma_interrupt_disable(const qm_dma_t dma, const qm_dma_channel_id_t channel_id)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
chan_reg->ctrl_low &= ~QM_DMA_CTL_L_INT_EN_MASK;
}
static __inline__ void
dma_interrupt_enable(const qm_dma_t dma, const qm_dma_channel_id_t channel_id)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
chan_reg->ctrl_low |= QM_DMA_CTL_L_INT_EN_MASK;
}
static __inline__ int
dma_set_transfer_type(const qm_dma_t dma, const qm_dma_channel_id_t channel_id,
const dma_transfer_type_t transfer_type)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
/* Currently only single block is supported */
switch (transfer_type) {
case QM_DMA_TYPE_SINGLE:
chan_reg->llp_low = 0x0;
chan_reg->ctrl_low &= ~QM_DMA_CTL_L_LLP_SRC_EN_MASK;
chan_reg->ctrl_low &= ~QM_DMA_CTL_L_LLP_DST_EN_MASK;
chan_reg->cfg_low &= ~QM_DMA_CFG_L_RELOAD_SRC_MASK;
chan_reg->cfg_low &= ~QM_DMA_CFG_L_RELOAD_DST_MASK;
break;
default:
return -EINVAL;
}
return 0;
}
static __inline__ void
dma_set_source_transfer_width(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
const qm_dma_transfer_width_t transfer_width)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
UPDATE_REG_BITS(chan_reg->ctrl_low, transfer_width,
QM_DMA_CTL_L_SRC_TR_WIDTH_OFFSET,
QM_DMA_CTL_L_SRC_TR_WIDTH_MASK);
}
static __inline__ void
dma_set_destination_transfer_width(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
const qm_dma_transfer_width_t transfer_width)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
UPDATE_REG_BITS(chan_reg->ctrl_low, transfer_width,
QM_DMA_CTL_L_DST_TR_WIDTH_OFFSET,
QM_DMA_CTL_L_DST_TR_WIDTH_MASK);
}
static __inline__ void
dma_set_source_burst_length(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
const qm_dma_burst_length_t burst_length)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
UPDATE_REG_BITS(chan_reg->ctrl_low, burst_length,
QM_DMA_CTL_L_SRC_MSIZE_OFFSET,
QM_DMA_CTL_L_SRC_MSIZE_MASK);
}
static __inline__ void
dma_set_destination_burst_length(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
const qm_dma_burst_length_t burst_length)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
UPDATE_REG_BITS(chan_reg->ctrl_low, burst_length,
QM_DMA_CTL_L_DEST_MSIZE_OFFSET,
QM_DMA_CTL_L_DEST_MSIZE_MASK);
}
static __inline__ void
dma_set_transfer_direction(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
const qm_dma_channel_direction_t transfer_direction)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
UPDATE_REG_BITS(chan_reg->ctrl_low, transfer_direction,
QM_DMA_CTL_L_TT_FC_OFFSET, QM_DMA_CTL_L_TT_FC_MASK);
}
static __inline__ void
dma_set_source_increment(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
const qm_dma_address_increment_t address_increment)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
UPDATE_REG_BITS(chan_reg->ctrl_low, address_increment,
QM_DMA_CTL_L_SINC_OFFSET, QM_DMA_CTL_L_SINC_MASK);
}
static __inline__ void dma_set_destination_increment(
const qm_dma_t dma, const qm_dma_channel_id_t channel_id,
const qm_dma_address_increment_t address_increment)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
UPDATE_REG_BITS(chan_reg->ctrl_low, address_increment,
QM_DMA_CTL_L_DINC_OFFSET, QM_DMA_CTL_L_DINC_MASK);
}
static __inline__ void dma_set_handshake_interface(
const qm_dma_t dma, const qm_dma_channel_id_t channel_id,
const qm_dma_handshake_interface_t handshake_interface)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
UPDATE_REG_BITS(chan_reg->cfg_high, handshake_interface,
QM_DMA_CFG_H_SRC_PER_OFFSET, QM_DMA_CFG_H_SRC_PER_MASK);
UPDATE_REG_BITS(chan_reg->cfg_high, handshake_interface,
QM_DMA_CFG_H_DEST_PER_OFFSET,
QM_DMA_CFG_H_DEST_PER_MASK);
}
static __inline__ void
dma_set_handshake_type(const qm_dma_t dma, const qm_dma_channel_id_t channel_id,
const uint8_t handshake_type)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
UPDATE_REG_BITS(chan_reg->cfg_low, handshake_type,
QM_DMA_CFG_L_HS_SEL_SRC_OFFSET,
QM_DMA_CFG_L_HS_SEL_SRC_MASK);
UPDATE_REG_BITS(chan_reg->cfg_low, handshake_type,
QM_DMA_CFG_L_HS_SEL_DST_OFFSET,
QM_DMA_CFG_L_HS_SEL_DST_MASK);
}
static __inline__ void
dma_set_handshake_polarity(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
const qm_dma_handshake_polarity_t handshake_polarity)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
UPDATE_REG_BITS(chan_reg->cfg_low, handshake_polarity,
QM_DMA_CFG_L_SRC_HS_POL_OFFSET,
QM_DMA_CFG_L_SRC_HS_POL_MASK);
UPDATE_REG_BITS(chan_reg->cfg_low, handshake_polarity,
QM_DMA_CFG_L_DST_HS_POL_OFFSET,
QM_DMA_CFG_L_DST_HS_POL_MASK);
}
static __inline__ void
dma_set_source_address(const qm_dma_t dma, const qm_dma_channel_id_t channel_id,
const uint32_t source_address)
{
QM_DMA[dma]->chan_reg[channel_id].sar_low = source_address;
}
static __inline__ void
dma_set_destination_address(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
const uint32_t destination_address)
{
QM_DMA[dma]->chan_reg[channel_id].dar_low = destination_address;
}
static __inline__ void dma_set_block_size(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
const uint32_t block_size)
{
volatile qm_dma_chan_reg_t *chan_reg =
&QM_DMA[dma]->chan_reg[channel_id];
UPDATE_REG_BITS(chan_reg->ctrl_high, block_size,
QM_DMA_CTL_H_BLOCK_TS_OFFSET,
QM_DMA_CTL_H_BLOCK_TS_MASK);
}
#endif /* __DMA_H_ */

111
ext/hal/qmsi/drivers/idt.h Normal file
View file

@ -0,0 +1,111 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 <stdint.h>
#include <string.h>
#include "qm_common.h"
#include "qm_soc_regs.h"
#if (QUARK_SE)
#define IDT_NUM_GATES (68)
#elif(QUARK_D2000)
#define IDT_NUM_GATES (52)
#endif
#define IDT_SIZE (sizeof(intr_gate_desc_t) * IDT_NUM_GATES)
typedef struct idtr {
uint16_t limit;
uint32_t base;
} __attribute__((packed)) idtr_t;
typedef struct intr_gate_desc {
uint16_t isr_low;
uint16_t selector; /* Segment selector */
/* The format of conf is the following:
15 14 13 12 11 10 9 8 7 6 5 4 3 2 1 0
+--+--+--+--+--+--+--+--+--+--+--+--+--+--+--+--+
|p |dpl |ss|d |type | unused |
type: Gate type
d: size of Gate
ss: Storage Segment
dpl: Descriptor Privilege level
p: Segment present level
*/
uint16_t conf;
uint16_t isr_high;
} __attribute__((packed)) intr_gate_desc_t;
extern intr_gate_desc_t __idt_start[];
/*
* Setup IDT gate as an interrupt descriptor and assing the ISR entry point
*/
static __inline__ void idt_set_intr_gate_desc(uint32_t vector, uint32_t isr)
{
intr_gate_desc_t *desc;
desc = __idt_start + vector;
desc->isr_low = isr & 0xFFFF;
desc->selector = 0x08; /* Code segment offset in GDT */
desc->conf = 0x8E00; /* type: 0b11 (Interrupt)
d: 1 (32 bits)
ss: 0
dpl: 0
p: 1
*/
desc->isr_high = (isr >> 16) & 0xFFFF;
}
/*
* Initialize Interrupt Descriptor Table.
* The IDT is initialized with null descriptors: any interrupt at this stage
* will cause a triple fault.
*/
static __inline__ void idt_init(void)
{
idtr_t idtr;
memset(__idt_start, 0x00, IDT_SIZE);
/* Initialize idtr structure */
idtr.limit = IDT_SIZE - 1;
idtr.base = (uint32_t)__idt_start;
/* Load IDTR register */
__asm__ __volatile__("lidt %0\n\t" ::"m"(idtr));
}
#endif /* __IDT_H__ */

View file

@ -0,0 +1,307 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __CLK_H__
#define __CLK_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
#if (QM_SENSOR)
#include "qm_sensor_regs.h"
#endif
/**
* Clock Management.
*
* @defgroup groupCLK Clock Management
* @{
*/
/**
* When using an external crystal, this value must be set to the number of
* system ticks per micro second. The expected value is 32 ticks for a 32MHz
* crystal.
*/
#define SYS_TICKS_PER_US_XTAL (32)
/** System ticks per microseconds for a 32MHz oscillator. */
#define SYS_TICKS_PER_US_32MHZ (32)
/** System ticks per microseconds for a 16MHz oscillator. */
#define SYS_TICKS_PER_US_16MHZ (16)
/** System ticks per microseconds for a 8MHz oscillator. */
#define SYS_TICKS_PER_US_8MHZ (8)
/** System ticks per microseconds for a 4MHz oscillator. */
#define SYS_TICKS_PER_US_4MHZ (4)
/**
* System clock divider type.
*/
typedef enum {
CLK_SYS_DIV_1, /**< Clock Divider = 1. */
CLK_SYS_DIV_2, /**< Clock Divider = 2. */
CLK_SYS_DIV_4, /**< Clock Divider = 4. */
CLK_SYS_DIV_8, /**< Clock Divider = 8. */
#if (QUARK_D2000)
CLK_SYS_DIV_16, /**< Clock Divider = 16. */
CLK_SYS_DIV_32, /**< Clock Divider = 32. */
CLK_SYS_DIV_64, /**< Clock Divider = 64. */
CLK_SYS_DIV_128, /**< Clock Divider = 128. */
#endif
CLK_SYS_DIV_NUM
} clk_sys_div_t;
/**
* System clock mode type.
*/
typedef enum {
CLK_SYS_HYB_OSC_32MHZ, /**< 32MHz Hybrid Oscillator Clock. */
CLK_SYS_HYB_OSC_16MHZ, /**< 16MHz Hybrid Oscillator Clock. */
CLK_SYS_HYB_OSC_8MHZ, /**< 8MHz Hybrid Oscillator Clock. */
CLK_SYS_HYB_OSC_4MHZ, /**< 4MHz Hybrid Oscillator Clock. */
CLK_SYS_RTC_OSC, /**< Real Time Clock. */
CLK_SYS_CRYSTAL_OSC /**< Crystal Oscillator Clock. */
} clk_sys_mode_t;
/**
* Peripheral clock divider type.
*/
typedef enum {
CLK_PERIPH_DIV_1, /**< Peripheral Clock Divider = 1. */
CLK_PERIPH_DIV_2, /**< Peripheral Clock Divider = 2. */
CLK_PERIPH_DIV_4, /**< Peripheral Clock Divider = 4. */
CLK_PERIPH_DIV_8 /**< Peripheral Clock Divider = 8. */
} clk_periph_div_t;
/**
* GPIO clock debounce divider type.
*/
typedef enum {
CLK_GPIO_DB_DIV_1, /**< GPIO Clock Debounce Divider = 1. */
CLK_GPIO_DB_DIV_2, /**< GPIO Clock Debounce Divider = 2. */
CLK_GPIO_DB_DIV_4, /**< GPIO Clock Debounce Divider = 4. */
CLK_GPIO_DB_DIV_8, /**< GPIO Clock Debounce Divider = 8. */
CLK_GPIO_DB_DIV_16, /**< GPIO Clock Debounce Divider = 16. */
CLK_GPIO_DB_DIV_32, /**< GPIO Clock Debounce Divider = 32. */
CLK_GPIO_DB_DIV_64, /**< GPIO Clock Debounce Divider = 64. */
CLK_GPIO_DB_DIV_128 /**< GPIO Clock Debounce Divider = 128. */
} clk_gpio_db_div_t;
/**
* External crystal clock divider type.
*/
typedef enum {
CLK_EXT_DIV_1, /**< External Crystal Clock Divider = 1. */
CLK_EXT_DIV_2, /**< External Crystal Clock Divider = 2. */
CLK_EXT_DIV_4, /**< External Crystal Clock Divider = 4. */
CLK_EXT_DIV_8 /**< External Crystal Clock Divider = 8. */
} clk_ext_div_t;
/**
* RTC clock divider type.
*/
typedef enum {
CLK_RTC_DIV_1, /**< Real Time Clock Divider = 1. */
CLK_RTC_DIV_2, /**< Real Time Clock Divider = 2. */
CLK_RTC_DIV_4, /**< Real Time Clock Divider = 4. */
CLK_RTC_DIV_8, /**< Real Time Clock Divider = 8. */
CLK_RTC_DIV_16, /**< Real Time Clock Divider = 16. */
CLK_RTC_DIV_32, /**< Real Time Clock Divider = 32. */
CLK_RTC_DIV_64, /**< Real Time Clock Divider = 64. */
CLK_RTC_DIV_128, /**< Real Time Clock Divider = 128. */
CLK_RTC_DIV_256, /**< Real Time Clock Divider = 256. */
CLK_RTC_DIV_512, /**< Real Time Clock Divider = 512. */
CLK_RTC_DIV_1024, /**< Real Time Clock Divider = 1024. */
CLK_RTC_DIV_2048, /**< Real Time Clock Divider = 2048. */
CLK_RTC_DIV_4096, /**< Real Time Clock Divider = 4096. */
CLK_RTC_DIV_8192, /**< Real Time Clock Divider = 8192. */
CLK_RTC_DIV_16384, /**< Real Time Clock Divider = 16384. */
CLK_RTC_DIV_32768 /**< Real Time Clock Divider = 32768. */
} clk_rtc_div_t;
/**
* Set clock mode and divisor.
*
* Change the operating mode and clock divisor of the system
* clock source. Changing this clock speed affects all
* peripherals.
* This applies the correct trim code if available.
*
* If trim code is not available, it is not computed
* and previous trim code is not modified.
*
* @param[in] mode System clock source operating mode.
* @param[in] div System clock divisor.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int clk_sys_set_mode(const clk_sys_mode_t mode, const clk_sys_div_t div);
/**
* Read the silicon oscillator trim code for the current frequency.
*
* @param[out] value Pointer to store the trim code.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int clk_trim_read(uint32_t *const value);
/**
* Apply silicon oscillator trim code.
*
* @param[in] value Trim code to apply.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int clk_trim_apply(const uint32_t value);
/**
* Change divider value of ADC clock.
*
* Change ADC clock divider value. The new divider value is set to N, where N is
* the value set by the function and is between 1 and 1024.
* This function is only available on D2000.
*
* @param[in] div Divider value for the ADC clock.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int clk_adc_set_div(const uint16_t div);
/**
* Change divider value of peripheral clock.
*
* Change Peripheral clock divider value.
* The maximum divisor is /8.
* Refer to the list of supported peripherals for your SoC.
*
* @param[in] div Divider value for the peripheral clock.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int clk_periph_set_div(const clk_periph_div_t div);
/**
* Change divider value of GPIO debounce clock.
*
* Change GPIO debounce clock divider value.
* The maximum divisor is /128.
*
* @param[in] div Divider value for the GPIO debounce clock.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int clk_gpio_db_set_div(const clk_gpio_db_div_t div);
/**
* Change divider value of external clock.
*
* Change External clock divider value.
* The maximum divisor is /8.
*
* @param[in] div Divider value for the external clock.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int clk_ext_set_div(const clk_ext_div_t div);
/**
* Change divider value of RTC.
*
* Change RTC divider value.
* The maximum divisor is /32768.
*
* @param[in] div Divider value for the RTC.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int clk_rtc_set_div(const clk_rtc_div_t div);
/**
* Enable clocks for peripherals / registers.
*
* @param[in] clocks Which peripheral and register clocks to enable.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int clk_periph_enable(const clk_periph_t clocks);
/**
* Disable clocks for peripherals / registers.
*
* @param[in] clocks Which peripheral and register clocks to disable.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int clk_periph_disable(const clk_periph_t clocks);
/**
* Get number of system ticks per micro second.
*
* @return uint32_t Number of system ticks per micro second.
*/
uint32_t clk_sys_get_ticks_per_us(void);
/**
* Idle loop the processor for at least the value given in microseconds.
*
* This function will wait until at least the given number of microseconds has
* elapsed since calling this function.
*
* Note:
* It is dependent on the system clock speed.
* The delay parameter does not include, calling the function, returning
* from it, calculation setup and while loops.
*
* @param[in] microseconds Minimum number of micro seconds to delay for.
*/
void clk_sys_udelay(uint32_t microseconds);
/**
* @}
*/
#endif /* __CLK_H__ */

View file

@ -0,0 +1,297 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_ADC_H__
#define __QM_ADC_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
#if (QUARK_D2000)
/**
* Analog to Digital Converter (ADC).
*
* @defgroup groupADC Quark D2000 ADC
* @{
*/
/**
* ADC sample size type.
*/
typedef uint16_t qm_adc_sample_t;
/**
* ADC calibration type.
*/
typedef uint8_t qm_adc_calibration_t;
typedef enum {
QM_ADC_IDLE, /**< ADC idle. */
QM_ADC_COMPLETE, /**< ADC transfer complete. */
QM_ADC_OVERFLOW, /**< ADC FIFO overflow error. */
} qm_adc_status_t;
/**
* ADC resolution type.
*/
typedef enum {
QM_ADC_RES_6_BITS, /**< 6-bit mode. */
QM_ADC_RES_8_BITS, /**< 8-bit mode. */
QM_ADC_RES_10_BITS, /**< 10-bit mode. */
QM_ADC_RES_12_BITS /**< 12-bit mode. */
} qm_adc_resolution_t;
/**
* ADC operating mode type.
*/
typedef enum {
QM_ADC_MODE_DEEP_PWR_DOWN, /**< Deep power down mode. */
QM_ADC_MODE_PWR_DOWN, /**< Power down mode. */
QM_ADC_MODE_STDBY, /**< Standby mode. */
QM_ADC_MODE_NORM_CAL, /**< Normal mode, with calibration. */
QM_ADC_MODE_NORM_NO_CAL /**< Normal mode, no calibration. */
} qm_adc_mode_t;
/**
* ADC channels type.
*/
typedef enum {
QM_ADC_CH_0, /**< ADC Channel 0. */
QM_ADC_CH_1, /**< ADC Channel 1. */
QM_ADC_CH_2, /**< ADC Channel 2. */
QM_ADC_CH_3, /**< ADC Channel 3. */
QM_ADC_CH_4, /**< ADC Channel 4. */
QM_ADC_CH_5, /**< ADC Channel 5. */
QM_ADC_CH_6, /**< ADC Channel 6. */
QM_ADC_CH_7, /**< ADC Channel 7. */
QM_ADC_CH_8, /**< ADC Channel 8. */
QM_ADC_CH_9, /**< ADC Channel 9. */
QM_ADC_CH_10, /**< ADC Channel 10. */
QM_ADC_CH_11, /**< ADC Channel 11. */
QM_ADC_CH_12, /**< ADC Channel 12. */
QM_ADC_CH_13, /**< ADC Channel 13. */
QM_ADC_CH_14, /**< ADC Channel 14. */
QM_ADC_CH_15, /**< ADC Channel 15. */
QM_ADC_CH_16, /**< ADC Channel 16. */
QM_ADC_CH_17, /**< ADC Channel 17. */
QM_ADC_CH_18 /**< ADC Channel 18. */
} qm_adc_channel_t;
/**
* ADC interrupt callback source.
*/
typedef enum {
QM_ADC_TRANSFER, /**< Transfer complete or error callback. */
QM_ADC_MODE_CHANGED, /**< Mode change complete callback. */
QM_ADC_CAL_COMPLETE, /**< Calibration complete callback. */
} qm_adc_cb_source_t;
/**
* ADC configuration type.
*/
typedef struct {
/**
* Sample interval in ADC clock cycles, defines the period to wait
* between the start of each sample and can be in the range
* [(resolution+2) - 255].
*/
uint8_t window;
qm_adc_resolution_t resolution; /**< 12, 10, 8, 6-bit resolution. */
} qm_adc_config_t;
/**
* ADC transfer type.
*/
typedef struct {
qm_adc_channel_t *ch; /**< Channel sequence array (1-32 channels). */
uint8_t ch_len; /**< Number of channels in the above array. */
qm_adc_sample_t *samples; /**< Array to store samples. */
uint32_t samples_len; /**< Length of sample array. */
/**
* Transfer callback.
*
* Called when a conversion is performed or an error is detected.
*
* @param[in] data The callback user data.
* @param[in] error 0 on success.
* Negative @ref errno for possible error codes.
* @param[in] status ADC status.
* @param[in] source Interrupt callback source.
*/
void (*callback)(void *data, int error, qm_adc_status_t status,
qm_adc_cb_source_t source);
void *callback_data; /**< Callback user data. */
} qm_adc_xfer_t;
/**
* Switch operating mode of ADC.
*
* This call is blocking.
*
* @param[in] adc Which ADC to enable.
* @param[in] mode ADC operating mode.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_adc_set_mode(const qm_adc_t adc, const qm_adc_mode_t mode);
/**
* Switch operating mode of ADC.
*
* This call is non-blocking and will call the user callback on completion.
*
* @param[in] adc Which ADC to enable.
* @param[in] mode ADC operating mode.
* @param[in] callback Callback called on completion.
* @param[in] callback_data The callback user data.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_adc_irq_set_mode(const qm_adc_t adc, const qm_adc_mode_t mode,
void (*callback)(void *data, int error,
qm_adc_status_t status,
qm_adc_cb_source_t source),
void *callback_data);
/**
* Calibrate the ADC.
*
* It is necessary to calibrate if it is intended to use Normal Mode With
* Calibration. The calibration must be performed if the ADC is used for the
* first time or has been in deep power down mode. This call is blocking.
*
* @param[in] adc Which ADC to calibrate.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_adc_calibrate(const qm_adc_t adc);
/**
* Calibrate the ADC.
*
* It is necessary to calibrate if it is intended to use Normal Mode With
* Calibration. The calibration must be performed if the ADC is used for the
* first time or has been in deep power down mode. This call is non-blocking
* and will call the user callback on completion.
*
* @param[in] adc Which ADC to calibrate.
* @param[in] callback Callback called on completion.
* @param[in] callback_data The callback user data.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_adc_irq_calibrate(const qm_adc_t adc,
void (*callback)(void *data, int error,
qm_adc_status_t status,
qm_adc_cb_source_t source),
void *callback_data);
/**
* Set ADC calibration data.
*
* @param[in] adc Which ADC to set calibration for.
* @param[in] cal_data Calibration data.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_adc_set_calibration(const qm_adc_t adc, const qm_adc_calibration_t cal);
/**
* Get the current calibration data for an ADC.
*
* @param[in] adc Which ADC to get calibration for.
* @param[out] adc Calibration data. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_adc_get_calibration(const qm_adc_t adc, qm_adc_calibration_t *const cal);
/**
* Set ADC configuration.
*
* This sets the sample window and resolution.
*
* @param[in] adc Which ADC to configure.
* @param[in] cfg ADC configuration. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_adc_set_config(const qm_adc_t adc, const qm_adc_config_t *const cfg);
/**
* Synchronously read values from the ADC.
*
* This blocking call can read 1-32 ADC values into the array provided.
*
* @param[in] adc Which ADC to read.
* @param[in,out] xfer Channel and sample info. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_adc_convert(const qm_adc_t adc, qm_adc_xfer_t *const xfer);
/**
* Asynchronously read values from the ADC.
*
* This is a non-blocking call and will call the user provided callback after
* the requested number of samples have been converted.
*
* @param[in] adc Which ADC to read.
* @param[in,out] xfer Channel sample and callback info. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_adc_irq_convert(const qm_adc_t adc, qm_adc_xfer_t *const xfer);
/**
* @}
*/
#endif /* QUARK_D2000 */
#endif /* __QM_ADC_H__ */

View file

@ -0,0 +1,177 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_AON_COUNTERS_H__
#define __QM_AON_COUNTERS_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Always-on Counters.
*
* @defgroup groupAONC Always-on Counters
* @{
*/
/**
* Always-on Periodic Timer configuration type.
*/
typedef struct {
uint32_t count; /**< Time to count down from in clock cycles.*/
bool int_en; /**< Enable/disable the interrupts. */
/**
* User callback.
*
* @param[in] data User defined data.
*/
void (*callback)(void *data);
void *callback_data; /**< Callback data. */
} qm_aonpt_config_t;
/**
* Enable the Always-on Counter.
*
* @param[in] aonc Always-on counter to read.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_aonc_enable(const qm_scss_aon_t aonc);
/**
* Disable the Always-on Counter.
*
* @param[in] aonc Always-on counter to read.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_aonc_disable(const qm_scss_aon_t aonc);
/**
* Get the current value of the Always-on Counter.
*
* Returns a 32-bit value which represents the number of clock cycles
* since the counter was first enabled.
*
* @param[in] aonc Always-on counter to read.
* @param[out] val Value of the counter. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_aonc_get_value(const qm_scss_aon_t aonc, uint32_t *const val);
/**
* Set the Always-on Periodic Timer configuration.
*
* This includes the initial value of the Always-on Periodic Timer,
* the interrupt enable and the callback function that will be run
* when the timer expiers and an interrupt is triggered.
* The Periodic Timer is disabled if the counter is set to 0.
*
* @param[in] aonc Always-on counter to read.
* @param[in] cfg New configuration for the Always-on Periodic Timer.
* This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_aonpt_set_config(const qm_scss_aon_t aonc,
const qm_aonpt_config_t *const cfg);
/**
* Get the current value of the Always-on Periodic Timer.
*
* Returns a 32-bit value which represents the number of clock cycles
* remaining before the timer fires.
* This is the initial configured number minus the number of cycles that have
* passed.
*
* @param[in] aonc Always-on counter to read.
* @param[out] val Value of the Always-on Periodic Timer.
* This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_aonpt_get_value(const qm_scss_aon_t aonc, uint32_t *const val);
/**
* Get the current status of the Always-on Periodic Timer.
*
* Returns true if the timer has expired. This will continue to return true
* until it is cleared with qm_aonpt_clear().
*
* @param[in] aonc Always-on counter to read.
* @param[out] status Status of the Always-on Periodic Timer.
* This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_aonpt_get_status(const qm_scss_aon_t aonc, bool *const status);
/**
* Clear the status of the Always-on Periodic Timer.
*
* The status must be clear before the Always-on Periodic Timer can trigger
* another interrupt.
*
* @param[in] aonc Always-on counter to read.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_aonpt_clear(const qm_scss_aon_t aonc);
/**
* Reset the Always-on Periodic Timer back to the configured value.
*
* @param[in] aonc Always-on counter to read.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_aonpt_reset(const qm_scss_aon_t aonc);
/**
* @}
*/
#endif /* __QM_AON_COUNTERS_H__ */

View file

@ -0,0 +1,79 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_COMPARATOR_H__
#define __QM_COMPARATOR_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Analog Comparator.
*
* @defgroup groupAC Analog Comparator
* @{
*/
/**
* Analog Comparator configuration type.
*
* Each bit in the registers controls a single Analog Comparator pin.
*/
typedef struct {
uint32_t int_en; /**< Interrupt enable. */
uint32_t reference; /**< Reference voltage, 1b: VREF; 0b: AR_PIN. */
uint32_t polarity; /**< 0b: input>ref; 1b: input<ref */
uint32_t power; /**< 1b: Normal mode; 0b:Power-down/Shutdown mode */
/**
* Transfer callback.
*
* @param[in] data Callback user data.
* @param[in] status Comparator interrupt status.
*/
void (*callback)(void *data, uint32_t int_status);
void *callback_data; /**< Callback user data. */
} qm_ac_config_t;
/**
* Set Analog Comparator configuration.
*
* @param[in] config Analog Comparator configuration. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ac_set_config(const qm_ac_config_t *const config);
/**
* @}
*/
#endif /* __QM_COMPARATOR_H__ */

View file

@ -0,0 +1,262 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_DMA_H_
#define __QM_DMA_H_
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* DMA Driver for Quark Microcontrollers.
*
* @defgroup groupDMA DMA
* @{
*/
/**
* DMA Handshake Polarity
*/
typedef enum {
QM_DMA_HANDSHAKE_POLARITY_HIGH = 0x0, /**< Set HS polarity high. */
QM_DMA_HANDSHAKE_POLARITY_LOW = 0x1 /**< Set HS polarity low. */
} qm_dma_handshake_polarity_t;
/**
* DMA Burst Transfer Length
*/
typedef enum {
QM_DMA_BURST_TRANS_LENGTH_1 = 0x0, /**< Burst length 1 data item. */
QM_DMA_BURST_TRANS_LENGTH_4 = 0x1, /**< Burst length 4 data items. */
QM_DMA_BURST_TRANS_LENGTH_8 = 0x2, /**< Burst length 8 data items. */
QM_DMA_BURST_TRANS_LENGTH_16 = 0x3, /**< Burst length 16 data items. */
QM_DMA_BURST_TRANS_LENGTH_32 = 0x4, /**< Burst length 32 data items. */
QM_DMA_BURST_TRANS_LENGTH_64 = 0x5, /**< Burst length 64 data items. */
QM_DMA_BURST_TRANS_LENGTH_128 =
0x6, /**< Burst length 128 data items. */
QM_DMA_BURST_TRANS_LENGTH_256 = 0x7 /**< Burst length 256 data items. */
} qm_dma_burst_length_t;
/**
* DMA Transfer Width
*/
typedef enum {
QM_DMA_TRANS_WIDTH_8 = 0x0, /**< Transfer width of 8 bits. */
QM_DMA_TRANS_WIDTH_16 = 0x1, /**< Transfer width of 16 bits. */
QM_DMA_TRANS_WIDTH_32 = 0x2, /**< Transfer width of 32 bits. */
QM_DMA_TRANS_WIDTH_64 = 0x3, /**< Transfer width of 64 bits. */
QM_DMA_TRANS_WIDTH_128 = 0x4, /**< Transfer width of 128 bits. */
QM_DMA_TRANS_WIDTH_256 = 0x5 /**< Transfer width of 256 bits. */
} qm_dma_transfer_width_t;
/**
* DMA channel direction.
*/
typedef enum {
QM_DMA_MEMORY_TO_MEMORY = 0x0, /**< Memory to memory transfer. */
QM_DMA_MEMORY_TO_PERIPHERAL =
0x1, /**< Memory to peripheral transfer. */
QM_DMA_PERIPHERAL_TO_MEMORY = 0x2 /**< Peripheral to memory transfer. */
} qm_dma_channel_direction_t;
/**
* DMA channel configuration structure
*/
typedef struct {
/** DMA channel handshake interface ID */
qm_dma_handshake_interface_t handshake_interface;
/** DMA channel handshake polarity */
qm_dma_handshake_polarity_t handshake_polarity;
/** DMA channel direction */
qm_dma_channel_direction_t channel_direction;
/** DMA source transfer width */
qm_dma_transfer_width_t source_transfer_width;
/** DMA destination transfer width */
qm_dma_transfer_width_t destination_transfer_width;
/** DMA source burst length */
qm_dma_burst_length_t source_burst_length;
/** DMA destination burst length */
qm_dma_burst_length_t destination_burst_length;
/**
* Client callback for DMA transfer ISR
*
* @param[in] callback_context DMA client context.
* @param[in] len Data length transferred.
* @param[in] error Error code.
*/
void (*client_callback)(void *callback_context, uint32_t len,
int error_code);
/** DMA client context passed to the callbacks */
void *callback_context;
} qm_dma_channel_config_t;
/**
* DMA transfer configuration structure
*/
typedef struct {
uint32_t block_size; /**< DMA block size, Min = 1, Max = 4095. */
uint32_t *source_address; /**< DMA source transfer address. */
uint32_t *destination_address; /**< DMA destination transfer address. */
} qm_dma_transfer_t;
/**
* Initialise the DMA controller.
*
* The DMA controller and channels are first disabled.
* All DMA controller interrupts are masked
* using the controllers interrupt masking registers. The system
* DMA interrupts are then unmasked. Finally the DMA controller
* is enabled. This function must only be called once as it
* resets the DMA controller and interrupt masking.
*
* @param[in] dma DMA instance.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_dma_init(const qm_dma_t dma);
/**
* Setup a DMA channel configuration.
*
* Configures the channel source width, burst size, channel direction,
* handshaking interface and registers the client callback and callback
* context. qm_dma_init() must first be called before configuring
* a channel. This function only needs to be called once unless
* a channel is being repurposed.
*
* @param[in] dma DMA instance.
* @param[in] channel_id The channel to start.
* @param[in] channel_config The DMA channel configuration as
* defined by the DMA client. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_dma_channel_set_config(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
qm_dma_channel_config_t *const channel_config);
/**
* Setup a DMA channel transfer.
*
* Configure the source address,destination addresses and block size.
* qm_dma_channel_set_config() must first be called before
* configuring a transfer. qm_dma_transfer_set_config() must
* be called before starting every transfer, even if the
* addresses and block size remain unchanged.
*
* @param[in] dma DMA instance.
* @param[in] channel_id The channel to start.
* @param[in] transfer_config The transfer DMA configuration
* as defined by the dma client.
* This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_dma_transfer_set_config(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
qm_dma_transfer_t *const transfer_config);
/**
* Start a DMA transfer.
*
* qm_dma_transfer_set_config() mustfirst be called
* before starting a transfer.
*
* @param[in] dma DMA instance.
* @param[in] channel_id The channel to start.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_dma_transfer_start(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id);
/**
* Terminate a DMA transfer.
*
* This function is only called if a transfer needs to be terminated manually.
* This may be require if an expected transfer complete callback
* has not been received. Terminating the transfer will
* trigger the transfer complete callback. The length
* returned by the callback is the transfer length at the
* time that the transfer was terminated.
*
* @param[in] dma DMA instance.
* @param[in] channel_id The channel to stop.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_dma_transfer_terminate(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id);
/**
* Setup and start memory to memory transfer.
*
* This function will setup a memory to memory transfer by
* calling qm_dma_transfer_setup() and will then start the
* transfer by calling qm_dma_transfer_start(). This is
* done for consistency across user applications.
*
* @param[in] dma DMA instance.
* @param[in] channel_id The channel to start.
* @param[in] transfer_config The transfer DMA configuration
* as defined by the dma client.
* This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_dma_transfer_mem_to_mem(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
qm_dma_transfer_t *const transfer_config);
/**
* @}
*/
#endif /* __QM_DMA_H_ */

View file

@ -0,0 +1,245 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_FLASH_H__
#define __QM_FLASH_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Flash controller.
*
* @defgroup groupFlash Flash
* @{
*/
/** Flash mask to clear timing. */
#define QM_FLASH_TMG_DEF_MASK (0xFFFFFC00)
/** Flash mask to clear micro seconds. */
#define QM_FLASH_MICRO_SEC_COUNT_MASK (0x3F)
/** Flash mask to clear wait state. */
#define QM_FLASH_WAIT_STATE_MASK (0x3C0)
/** Flash wait state offset bit. */
#define QM_FLASH_WAIT_STATE_OFFSET (6)
/** Flash write disable offset bit. */
#define QM_FLASH_WRITE_DISABLE_OFFSET (4)
/** Flash write disable value. */
#define QM_FLASH_WRITE_DISABLE_VAL BIT(4)
/** Flash page size in dwords. */
#define QM_FLASH_PAGE_SIZE_DWORDS (0x200)
/** Flash page size in bytes. */
#define QM_FLASH_PAGE_SIZE_BYTES (0x800)
/** Flash page size in bits. */
#define QM_FLASH_PAGE_SIZE_BITS (11)
/** Flash page erase request. */
#define ER_REQ BIT(1)
/** Flash page erase done. */
#define ER_DONE (1)
/** Flash page write request. */
#define WR_REQ (1)
/** Flash page write done. */
#define WR_DONE BIT(1)
/** Flash write address offset. */
#define WR_ADDR_OFFSET (2)
/** Flash perform mass erase includes OTP region. */
#define MASS_ERASE_INFO BIT(6)
/** Flash perform mass erase. */
#define MASS_ERASE BIT(7)
#define QM_FLASH_ADDRESS_MASK (0x7FF)
/* Increment by 4 bytes each time, but there is an offset of 2, so 0x10. */
#define QM_FLASH_ADDR_INC (0x10)
/**
* Flash region enum.
*/
typedef enum {
QM_FLASH_REGION_OTP = 0, /**< Flash OTP region. */
QM_FLASH_REGION_SYS, /**< Flash System region. */
#if (QUARK_D2000)
QM_FLASH_REGION_DATA, /**< Flash Data region (Quark D2000 only). */
#endif
QM_FLASH_REGION_NUM /**< Total number of flash regions. */
} qm_flash_region_t;
/**
* Flash write disable / enable enum.
*/
typedef enum {
QM_FLASH_WRITE_ENABLE, /**< Flash write enable. */
QM_FLASH_WRITE_DISABLE /**< Flash write disable. */
} qm_flash_disable_t;
/**
* Flash configuration structure.
*/
typedef struct {
uint8_t wait_states; /**< Read wait state. */
uint8_t us_count; /**< Number of clocks in a microsecond. */
qm_flash_disable_t write_disable; /**< Write disable. */
} qm_flash_config_t;
/**
* Configure a Flash controller.
*
* The configuration includes timing and behavioral settings.
*
* Note: when switching SoC to a higher frequency, flash controllers must be
* reconfigured to reflect settings associated with higher frequency BEFORE SoC
* frequency is changed. On the other hand, when switching SoC to a lower
* frequency, flash controller must be reconfigured only 6 NOP instructions
* AFTER the SoC frequency has been updated. Otherwise, flash timings will be
* violated.
*
* @param[in] flash Flash controller index.
* @param[in] cfg Flash configuration. It must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_flash_set_config(const qm_flash_t flash,
const qm_flash_config_t *const cfg);
/**
* Write 4 bytes of data to Flash.
*
* Brownout check is performed before initiating the write.
*
* Note: this function performs a write operation only; page erase may be
* needed if the page is already programmed.
*
* @param[in] flash Flash controller index.
* @param[in] region Flash region to address.
* @param[in] f_addr Address within Flash physical address space.
* @param[in] data Data word to write.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_flash_word_write(const qm_flash_t flash, const qm_flash_region_t region,
uint32_t f_addr, const uint32_t data);
/**
* Write multiple of 4 bytes of data to Flash.
*
* Brownout check is performed before initiating the write. The page is erased,
* and then written to.
*
* NOTE: Since this operation may take some time to complete, the caller is
* responsible for ensuring that the watchdog timer does not elapse in the
* meantime (e.g., by restarting it before calling this function).
*
* @param[in] flash Flash controller index.
* @param[in] region Which Flash region to address.
* @param[in] f_addr Address within Flash physical address space.
* @param[in] page_buf Page buffer to store page during update. Must be at
* least QM_FLASH_PAGE_SIZE words big and must not be NULL.
* @param[in] data Data to write (array of words). This must not be NULL.
* @param[in] len Length of data to write (number of words).
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_flash_page_update(const qm_flash_t flash, const qm_flash_region_t reg,
uint32_t f_addr, uint32_t *const page_buf,
const uint32_t *const data, uint32_t len);
/**
* Write a 2KB flash page.
*
* Brownout check is performed before initiating the write. The page is erased,
* and then written to.
*
* NOTE: Since this operation may take some time to complete, the caller is
* responsible for ensuring that the watchdog timer does not elapse in the
* meantime (e.g., by restarting it before calling this function).
*
* @param[in] flash Flash controller index.
* @param[in] region Which Flash region to address.
* @param[in] page_num Which page of flash to overwrite.
* @param[in] data Data to write (array of words). This must not be NULL.
* @param[in] len Length of data to write (number of words).
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_flash_page_write(const qm_flash_t flash, const qm_flash_region_t region,
uint32_t page_num, const uint32_t *data, uint32_t len);
/**
* Erase one page of Flash.
*
* Brownout check is performed before initiating the write.
*
* @param[in] flash Flash controller index.
* @param[in] region Flash region to address.
* @param[in] page_num Page within the Flash controller to erase.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
/* Having page be 32-bits, saves 6 bytes over using 8 / 16-bits. */
int qm_flash_page_erase(const qm_flash_t flash, const qm_flash_region_t region,
uint32_t page_num);
/**
* Perform mass erase.
*
* Perform mass erase on the specified flash controller. Brownout check is
* performed before initiating the erase. The mass erase may include the ROM
* region, if present and unlocked. Note: it is not possible to mass-erase the
* ROM portion separately.
*
* NOTE: Since this operation may take some time to complete, the caller is
* responsible for ensuring that the watchdog timer does not elapse in the
* meantime (e.g., by restarting it before calling this function).
*
* @param[in] flash Flash controller index.
* @param[in] include_rom If set, it also erases the ROM region.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_flash_mass_erase(const qm_flash_t flash, const uint8_t include_rom);
/**
* @}
*/
#endif /* __QM_FLASH_H__ */

View file

@ -0,0 +1,169 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_FPR_H__
#define __QM_FPR_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Flash Protection Region control.
*
* @defgroup groupFPR FPR
* @{
*/
typedef void (*qm_fpr_callback_t)(void *data);
/**
* FPR register map.
*/
typedef enum {
QM_FPR_0, /**< FPR 0. */
QM_FPR_1, /**< FPR 1. */
QM_FPR_2, /**< FPR 2. */
QM_FPR_3, /**< FPR 3. */
QM_FPR_NUM
} qm_fpr_id_t;
/**
* FPR enable type.
*/
typedef enum {
QM_FPR_DISABLE, /**< Disable FPR. */
QM_FPR_ENABLE, /**< Enable FPR. */
QM_FPR_LOCK_DISABLE, /**< Disable FPR lock. */
QM_FPR_LOCK_ENABLE /**< Enable FPR lock. */
} qm_fpr_en_t;
/**
* FPR vilation mode type.
*/
typedef enum {
FPR_VIOL_MODE_INTERRUPT = 0, /**< Generate interrupt on violation. */
FPR_VIOL_MODE_RESET, /**< Reset SoC on violation. */
FPR_VIOL_MODE_PROBE /**< Enter probe mode on violation. */
} qm_fpr_viol_mode_t;
/**
* FPR region type.
*/
typedef enum {
QM_MAIN_FLASH_SYSTEM = 0, /**< System flash region. */
#if (QUARK_D2000)
QM_MAIN_FLASH_DATA, /**< Data flash region. */
#endif
QM_MAIN_FLASH_NUM, /**< Number of flash regions. */
} qm_flash_region_type_t;
/**
* FPR read allow type.
*/
typedef enum {
QM_FPR_HOST_PROCESSOR =
BIT(0), /**< Allow host processor to access flash region. */
#if (QUARK_SE)
QM_FPR_SENSOR_SUBSYSTEM =
BIT(1), /**< Allow sensor subsystem to access flash region. */
#endif
QM_FPR_DMA = BIT(2), /**< Allow DMA to access flash region. */
#if (QUARK_SE)
QM_FPR_OTHER_AGENTS =
BIT(3) /**< Allow other agents to access flash region. */
#endif
} qm_fpr_read_allow_t;
/**
* Flash Protection Region configuration structure.
*/
typedef struct {
qm_fpr_en_t en_mask; /**< Enable/lock bitmask. */
qm_fpr_read_allow_t allow_agents; /**< Per-agent read enable bitmask. */
uint8_t up_bound; /**< 1KB-aligned upper Flash phys addr. */
uint8_t low_bound; /**< 1KB-aligned lower Flash phys addr. */
} qm_fpr_config_t;
#define QM_FPR_FPR0_REG_OFFSET (7)
#define QM_FPR_WRITE_LOCK_OFFSET (31)
#define QM_FPR_ENABLE_OFFSET (30)
#define QM_FPR_ENABLE_MASK BIT(QM_FPR_ENABLE_OFFSET)
#define QM_FPR_RD_ALLOW_OFFSET (20)
#define QM_FPR_RD_ALLOW_MASK (0xF00000)
#define QM_FPR_UPPER_BOUND_OFFSET (10)
#define QM_FPR_UPPER_BOUND_MASK (0x3FC00)
#define QM_FPR_LOW_BOUND_MASK (0xFF)
#define QM_FPR_MPR_VSTS_VALID BIT(31)
#define QM_FPR_LOCK BIT(31)
#define QM_FPR_EN_MASK_ENABLE BIT(0)
#define QM_FPR_EN_MASK_LOCK BIT(1)
#define QM_FPR_AGENT_MASK_HOST BIT(0)
#define QM_FPR_AGENT_MASK_SS BIT(1)
#define QM_FPR_AGENT_MASK_DMA BIT(2)
#define QM_FPR_AGENT_MASK_OTHER BIT(3)
/**
* Configure a Flash controller's Flash Protection Region.
*
* @param[in] flash Which Flash controller to configure.
* @param[in] id FPR identifier.
* @param[in] cfg FPR configuration.
* @param[in] region The region of Flash to be configured.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_fpr_set_config(const qm_flash_t flash, const qm_fpr_id_t id,
const qm_fpr_config_t *const cfg,
const qm_flash_region_type_t region);
/**
* Configure FPR violation behaviour.
*
* @param[in] mode (generate interrupt, warm reset, enter probe mode).
* @param[in] flash controller.
* @param[in] fpr_cb for interrupt mode (only).
* @param[in] data user callback data for interrupt mode (only).
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_fpr_set_violation_policy(const qm_fpr_viol_mode_t mode,
const qm_flash_t flash,
qm_fpr_callback_t fpr_cb, void *data);
/**
* @}
*/
#endif /* __QM_FPR_H__ */

View file

@ -0,0 +1,180 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_GPIO_H__
#define __QM_GPIO_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* General Purpose IO.
*
* @defgroup groupGPIO GPIO
* @{
*/
/**
* GPIO pin states.
*/
typedef enum {
QM_GPIO_LOW, /**< GPIO low state. */
QM_GPIO_HIGH, /**< GPIO high state. */
QM_GPIO_STATE_NUM /**< Number of GPIO states. */
} qm_gpio_state_t;
/**
* GPIO port configuration type.
*
* Each bit in the registers control a GPIO pin.
*/
typedef struct {
uint32_t direction; /**< GPIO direction, 0b: input, 1b: output. */
uint32_t int_en; /**< Interrupt enable. */
uint32_t int_type; /**< Interrupt type, 0b: level; 1b: edge. */
uint32_t int_polarity; /**< Interrupt polarity, 0b: low, 1b: high. */
uint32_t int_debounce; /**< Interrupt debounce on/off. */
uint32_t int_bothedge; /**< Interrupt on rising and falling edges. */
/**
* Transfer callback.
*
* @param[in] data Callback user data.
* @param[in] int_status GPIO interrupt status.
*/
void (*callback)(void *data, uint32_t int_status);
void *callback_data; /**< Callback user data. */
} qm_gpio_port_config_t;
/**
* Set GPIO port configuration.
*
* This includes if interrupts are enabled or not, the level on which an
* interrupt is generated, the polarity of interrupts and if GPIO-debounce is
* enabled or not. If interrupts are enabled it also registers the user defined
* callback function.
*
* @param[in] gpio GPIO port index to configure.
* @param[in] cfg New configuration for GPIO port. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*
*/
int qm_gpio_set_config(const qm_gpio_t gpio,
const qm_gpio_port_config_t *const cfg);
/**
* Read the current state of a single pin on a given GPIO port.
*
* @param[in] gpio GPIO port index.
* @param[in] pin Pin of GPIO port to read.
* @param[out] state Current state of the pin. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_gpio_read_pin(const qm_gpio_t gpio, const uint8_t pin,
qm_gpio_state_t *const state);
/**
* Set a single pin on a given GPIO port.
*
* @param[in] gpio GPIO port index.
* @param[in] pin Pin of GPIO port to set.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_gpio_set_pin(const qm_gpio_t gpio, const uint8_t pin);
/**
* Clear a single pin on a given GPIO port.
*
* @param[in] gpio GPIO port index.
* @param[in] pin Pin of GPIO port to clear.
* @return int 0 on success, error code otherwise.
*
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_gpio_clear_pin(const qm_gpio_t gpio, const uint8_t pin);
/**
* Set or clear a single GPIO pin using a state variable.
*
* @param[in] gpio GPIO port index.
* @param[in] pin Pin of GPIO port to update.
* @param[in] state QM_GPIO_LOW for low or QM_GPIO_HIGH for high.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_gpio_set_pin_state(const qm_gpio_t gpio, const uint8_t pin,
const qm_gpio_state_t state);
/**
* Read the value of every pin on a GPIO port.
*
* Each bit of the val parameter is set to the current value of each pin on the
* port. Maximum 32 pins per port.
*
* @param[in] gpio GPIO port index.
* @param[out] port State of every pin in a GPIO port. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_gpio_read_port(const qm_gpio_t gpio, uint32_t *const port);
/**
* Write a value to every pin on a GPIO port.
*
* Each pin on the GPIO port is set to the corresponding value set in the val
* parameter. Maximum 32 pins per port.
*
* @param[in] gpio GPIO port index.
* @param[in] val Value of all pins on GPIO port.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_gpio_write_port(const qm_gpio_t gpio, const uint32_t val);
/**
* @}
*/
#endif /* __QM_GPIO_H__ */

View file

@ -0,0 +1,338 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_I2C_H__
#define __QM_I2C_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
#include "qm_dma.h"
/**
* I2C.
*
* @defgroup groupI2C I2C
* @{
*/
/* High/low period for 50% duty cycle bus clock (in nanoseconds). */
#define QM_I2C_SS_50_DC_NS (5000)
#define QM_I2C_FS_50_DC_NS (1250)
#define QM_I2C_FSP_50_DC_NS (500)
/* Minimum low period to meet timing requirements (in nanoseconds). */
#define QM_I2C_MIN_SS_NS (4700)
#define QM_I2C_MIN_FS_NS (1300)
#define QM_I2C_MIN_FSP_NS (500)
/* Data command register masks and values. */
#define DATA_COMMAND_READ_COMMAND_BYTE (QM_I2C_IC_DATA_CMD_READ >> 8)
#define DATA_COMMAND_STOP_BIT_BYTE (QM_I2C_IC_DATA_CMD_STOP_BIT_CTRL >> 8)
/**
* QM I2C addressing type.
*/
typedef enum{
QM_I2C_7_BIT = 0, /**< 7-bit mode. */
QM_I2C_10_BIT /**< 10-bit mode. */
} qm_i2c_addr_t;
/**
* QM I2C master / slave mode type.
*/
typedef enum {
QM_I2C_MASTER, /**< Master mode. */
QM_I2C_SLAVE /**< Slave mode. */
} qm_i2c_mode_t;
/**
* QM I2C Speed Type.
*/
typedef enum {
QM_I2C_SPEED_STD = 1, /**< Standard mode (100 Kbps). */
QM_I2C_SPEED_FAST = 2, /**< Fast mode (400 Kbps). */
QM_I2C_SPEED_FAST_PLUS = 3 /**< Fast plus mode (1 Mbps). */
} qm_i2c_speed_t;
/**
* I2C status type.
*/
typedef enum {
QM_I2C_IDLE = 0, /**< Controller idle. */
QM_I2C_TX_ABRT_7B_ADDR_NOACK = BIT(0), /**< 7-bit address noack. */
QM_I2C_TX_ABRT_10ADDR1_NOACK = BIT(1), /**< 10-bit address noack. */
QM_I2C_TX_ABRT_10ADDR2_NOACK = BIT(2), /**< 10-bit second address
byte address noack. */
QM_I2C_TX_ABRT_TXDATA_NOACK = BIT(3), /**< Tx data noack. */
QM_I2C_TX_ABRT_GCALL_NOACK = BIT(4), /**< General call noack. */
QM_I2C_TX_ABRT_GCALL_READ = BIT(5), /**< Read after general call. */
QM_I2C_TX_ABRT_HS_ACKDET = BIT(6), /**< High Speed master ID ACK. */
QM_I2C_TX_ABRT_SBYTE_ACKDET = BIT(7), /**< Start ACK. */
QM_I2C_TX_ABRT_HS_NORSTRT = BIT(8), /**< High Speed with restart
disabled. */
QM_I2C_TX_ABRT_10B_RD_NORSTRT = BIT(10), /**< 10-bit address read and
restart disabled. */
QM_I2C_TX_ABRT_MASTER_DIS = BIT(11), /**< Master disabled. */
QM_I2C_TX_ARB_LOST = BIT(12), /**< Master lost arbitration. */
QM_I2C_TX_ABRT_SLVFLUSH_TXFIFO = BIT(13), /**< Slave flush tx FIFO. */
QM_I2C_TX_ABRT_SLV_ARBLOST = BIT(14), /**< Slave lost bus. */
QM_I2C_TX_ABRT_SLVRD_INTX = BIT(15), /**< Slave read completion. */
QM_I2C_TX_ABRT_USER_ABRT = BIT(16), /**< User abort. */
QM_I2C_BUSY = BIT(17) /**< Controller busy. */
} qm_i2c_status_t;
/**
* I2C configuration type.
*/
typedef struct {
qm_i2c_speed_t speed; /**< Standard, Fast Mode. */
qm_i2c_addr_t address_mode; /**< 7 or 10 bit addressing. */
qm_i2c_mode_t mode; /**< Master or slave mode. */
uint16_t slave_addr; /**< I2C address when in slave mode. */
} qm_i2c_config_t;
/**
* I2C transfer type.
* Master mode:
* - If tx len is 0: perform receive-only transaction.
* - If rx len is 0: perform transmit-only transaction.
* - Both tx and Rx len not 0: perform a transmit-then-receive
* combined transaction.
* Slave mode:
* - If read or write exceed the buffer, then wrap around.
*/
typedef struct {
uint8_t *tx; /**< Write data. */
uint32_t tx_len; /**< Write data length. */
uint8_t *rx; /**< Read data. */
uint32_t rx_len; /**< Read buffer length. */
bool stop; /**< Generate master STOP. */
void (*callback)(void *data, int rc, qm_i2c_status_t status,
uint32_t len); /**< Callback. */
void *callback_data; /**< Callback identifier. */
} qm_i2c_transfer_t;
/**
* Set I2C configuration.
*
* @param[in] i2c Which I2C to set the configuration of.
* @param[out] cfg I2C configuration. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_i2c_set_config(const qm_i2c_t i2c, const qm_i2c_config_t *const cfg);
/**
* Set I2C speed.
*
* Fine tune I2C clock speed. This will set the SCL low count
* and the SCL hi count cycles. To achieve any required speed.
* @param[in] i2c I2C index.
* @param[in] speed Bus speed (Standard or Fast. Fast includes Fast+ mode).
* @param[in] lo_cnt SCL low count.
* @param[in] hi_cnt SCL high count.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_i2c_set_speed(const qm_i2c_t i2c, const qm_i2c_speed_t speed,
const uint16_t lo_cnt, const uint16_t hi_cnt);
/**
* Retrieve I2C status.
*
* @param[in] i2c Which I2C to read the status of.
* @param[out] status Get i2c status. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_i2c_get_status(const qm_i2c_t i2c, qm_i2c_status_t *const status);
/**
* Master write on I2C.
*
* Perform a master write on the I2C bus. This is a blocking synchronous call.
*
* @param[in] i2c Which I2C to write to.
* @param[in] slave_addr Address of slave to write to.
* @param[in] data Pre-allocated buffer of data to write. This must not be NULL.
* @param[in] len length of data to write.
* @param[in] stop Generate a STOP condition at the end of tx.
* @param[out] status Get i2c status.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_i2c_master_write(const qm_i2c_t i2c, const uint16_t slave_addr,
const uint8_t *const data, uint32_t len,
const bool stop, qm_i2c_status_t *const status);
/**
* Master read of I2C.
*
* Perform a single byte master read from the I2C. This is a blocking call.
*
* @param[in] i2c Which I2C to read from.
* @param[in] slave_addr Address of slave device to read from.
* @param[out] data Pre-allocated buffer to populate with data. This must not be
* NULL.
* @param[in] len length of data to read from slave.
* @param[in] stop Generate a STOP condition at the end of tx.
* @param[out] status Get i2c status.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_i2c_master_read(const qm_i2c_t i2c, const uint16_t slave_addr,
uint8_t *const data, uint32_t len,
const bool stop, qm_i2c_status_t *const status);
/**
* Interrupt based master transfer on I2C.
*
* Perform an interrupt based master transfer on the I2C bus. The function will
* replenish/empty TX/RX FIFOs on I2C empty/full interrupts.
*
* @param[in] i2c Which I2C to transfer from.
* @param[in] xfer Transfer structure includes write / read buffers, length,
* user callback function and the callback context. This must
* not be NULL.
* @param[in] slave_addr Address of slave to transfer data with.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_i2c_master_irq_transfer(const qm_i2c_t i2c,
const qm_i2c_transfer_t *const xfer,
const uint16_t slave_addr);
/**
* Terminate I2C IRQ transfer.
*
* Terminate the current IRQ or DMA transfer on the I2C bus.
* This will cause the user callback to be called with status
* QM_I2C_TX_ABRT_USER_ABRT.
*
* @param[in] i2c I2C register block pointer.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_i2c_irq_transfer_terminate(const qm_i2c_t i2c);
/**
* Configure a DMA channel with a specific transfer direction.
*
* Configure a DMA channel with a specific transfer direction. The user is
* responsible for managing the allocation of the pool of DMA channels provided
* by each DMA core to the different peripheral drivers that require them. Note
* that a I2C controller cannot use different DMA cores to manage transfers in
* different directions.
*
* This function configures DMA channel parameters that are unlikely to change
* between transfers, like transaction width, burst size, and handshake
* interface parameters. The user will likely only call this function once for
* the lifetime of an application unless the channel needs to be repurposed.
*
* Note that qm_dma_init() must first be called before configuring a channel.
*
* @param[in] i2c I2C controller identifier.
* @param[in] dma_ctrl_id DMA controller identifier.
* @param[in] dma_channel_id DMA channel identifier.
* @param[in] dma_channel_direction DMA channel direction, either
* QM_DMA_MEMORY_TO_PERIPHERAL (TX transfer) or QM_DMA_PERIPHERAL_TO_MEMORY
* (RX transfer).
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_i2c_dma_channel_config(const qm_i2c_t i2c,
const qm_dma_t dma_controller_id,
const qm_dma_channel_id_t channel_id,
const qm_dma_channel_direction_t direction);
/**
* Perform a DMA-based transfer on the I2C bus.
*
* Perform a DMA-based transfer on the I2C bus. If the transfer is TX only, it
* will enable DMA operation for the controller and start the transfer.
*
* If it's an RX only transfer, it will require 2 channels, one for writting the
* READ commands and another one for reading the bytes from the bus. Both DMA
* operations will start in parallel.
*
* If this is a combined transaction, both TX and RX operations will be set up,
* but only TX will be started. On TX finish (callback), the TX channel will be
* used for writing the READ commands and the RX operation will start.
*
* Note that qm_i2c_dma_channel_config() must first be called in order to
* configure all DMA channels needed for a transfer.
*
* @param[in] i2c I2C controller identifier.
* @param[in] xfer Structure containing pre-allocated write and read data
* buffers and callback functions. This pointer must be kept valid until the
* transfer is complete.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_i2c_master_dma_transfer(const qm_i2c_t i2c,
qm_i2c_transfer_t *const xfer,
const uint16_t slave_addr);
/**
* Terminate any DMA transfer going on on the controller.
*
* Calls the DMA driver to stop any ongoing DMA transfer and calls
* qm_i2c_irq_transfer_terminate.
*
* @param[in] i2c Which I2C to terminate transfers from.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_i2c_dma_transfer_terminate(const qm_i2c_t i2c);
/**
* @}
*/
#endif /* __QM_I2C_H__ */

View file

@ -0,0 +1,61 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_IDENTIFICATION_H__
#define __QM_IDENTIFICATION_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Identification functions for Quark Microcontrollers.
*
* @defgroup groupIdentification Identification
* @{
*/
/**
* Get Quark SoC identification number
*
* @return uint32_t SoC identifier number.
*/
uint32_t qm_soc_id(void);
/**
* Get Quark SoC version number
*
* @return uint32_t SoC version number.
*/
uint32_t qm_soc_version(void);
/**
* @}
*/
#endif /* __QM_IDENTIFICATION_H__ */

View file

@ -0,0 +1,64 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_INIT_H__
#define __QM_INIT_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Initialisation and reset.
*
* @defgroup groupInit Initialisation
* @{
*/
/**
* Reset Mode type.
*/
typedef enum {
QM_WARM_RESET = BIT(1), /**< Warm reset. */
QM_COLD_RESET = BIT(3), /**< Cold reset. */
} qm_soc_reset_t;
/**
* Reset the SoC.
*
* This can either be a cold reset or a warm reset.
*
* @param [in] reset_type Selects the type of reset to perform.
*/
void qm_soc_reset(qm_soc_reset_t reset_type);
/**
* @}
*/
#endif /* __QM_INIT_H__ */

View file

@ -0,0 +1,162 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_INTERRUPT_H__
#define __QM_INTERRUPT_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/*
* Linear mapping between IRQs and interrupt vectors
*/
#if (QUARK_SE)
#define QM_IRQ_TO_VECTOR(irq) (irq + 36) /**< Get the vector of and irq. */
#elif(QUARK_D2000)
#define QM_IRQ_TO_VECTOR(irq) (irq + 32) /**< Get the vector of and irq. */
#endif
/**
* Interrupt driver.
*
* @defgroup groupINT Interrupt
* @{
*/
/**
* Interrupt service routine type
*/
typedef void (*qm_isr_t)(struct interrupt_frame *frame);
/**
* Enable interrupt delivery for the SoC.
*/
void qm_irq_enable(void);
/**
* Disable interrupt delivery for the SoC.
*/
void qm_irq_disable(void);
/**
* Unmask a given interrupt line.
*
* @param[in] irq Which IRQ to unmask.
*/
void qm_irq_unmask(uint32_t irq);
/**
* Mask a given interrupt line.
*
* @param[in] irq Which IRQ to mask.
*/
void qm_irq_mask(uint32_t irq);
void _qm_register_isr(uint32_t vector, qm_isr_t isr);
void _qm_irq_setup(uint32_t irq, uint16_t register_offset);
/**
* Request a given IRQ and register Interrupt Service Routine to interrupt
* vector.
*
* @param[in] irq IRQ number. Must be of type QM_IRQ_XXX.
* @param[in] isr ISR to register to given IRQ.
*/
#if (UNIT_TEST)
#define qm_irq_request(irq, isr)
#elif(QM_SENSOR)
#define qm_irq_request(irq, isr) \
do { \
_qm_register_isr(irq##_VECTOR, isr); \
_qm_irq_setup(irq, irq##_MASK_OFFSET); \
} while (0);
#else
#define qm_irq_request(irq, isr) \
do { \
qm_int_vector_request(irq##_VECTOR, isr); \
\
_qm_irq_setup(irq, irq##_MASK_OFFSET); \
} while (0)
#endif /* UNIT_TEST */
/**
* Request an interrupt vector and register Interrupt Service Routine to it.
*
* @param[in] vector Vector number.
* @param[in] isr ISR to register to given IRQ.
*/
#if (UNIT_TEST)
#define qm_int_vector_request(vector, isr)
#else
#if (__iamcu__)
/*
* We assume that if the compiler supports the IAMCU ABI it also
* supports the 'interrupt' attribute.
*/
static __inline__ void qm_int_vector_request(uint32_t vector, qm_isr_t isr)
{
_qm_register_isr(vector, isr);
}
#else /* __iamcu__ */
/*
* Using the standard SysV calling convention. A dummy (NULL in this case)
* parameter is added to ISR handler, to maintain consistency with the API
* imposed by the __attribute__((interrupt)) usage.
*/
#define qm_int_vector_request(vector, isr) \
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" \
" push $0x00\n\t" \
" call %P2\n\t" \
" add $4, %%esp\n\t" \
" popal\n\t" \
" iret\n\t" \
"2:\n\t" ::"g"(vector), \
"i"(_qm_register_isr), "i"(isr) \
: "%eax", "%ecx", "%edx"); \
} while (0)
#endif /* __iamcu__ */
#endif /* UNIT_TEST */
/**
* @}
*/
#endif /* __QM_INTERRUPT_H__ */

View file

@ -0,0 +1,340 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_ISR_H__
#define __QM_ISR_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Interrupt Service Routines.
*
* @defgroup groupISR ISR
* @{
*/
#if (QUARK_D2000)
/**
* ISR for ADC 0 convert and calibration interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_ADC_0, qm_adc_0_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_adc_0_isr);
/**
* ISR for ADC 0 change mode interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_ADC_PWR_0, qm_adc_pwr_0_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_adc_pwr_0_isr);
#endif /* QUARK_D2000 */
#if (QUARK_SE)
/**
* ISR for SS ADC 0 calibration interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_SS_IRQ_ADC_CAL, qm_ss_adc_0_cal_isr);
* @endcode if IRQ based calibration is used.
*/
QM_ISR_DECLARE(qm_ss_adc_0_cal_isr);
/**
* ISR for SS ADC 0 mode change interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_SS_IRQ_ADC_PWR, qm_ss_adc_0_pwr_isr);
* @endcode if IRQ based mode change is used.
*/
QM_ISR_DECLARE(qm_ss_adc_0_pwr_isr);
#endif /* QUARK_SE */
/**
* ISR for Always-on Periodic Timer 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_AONPT_0, qm_aonpt_isr_0);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_aonpt_isr_0);
/**
* ISR for Analog Comparator 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_AC, qm_ac_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_ac_isr);
/**
* ISR for DMA error interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_DMA_ERR, qm_dma_0_isr_err);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_dma_0_isr_err);
/**
* ISR for DMA channel 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_DMA_0, qm_dma_0_isr_0);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_dma_0_isr_0);
/**
* ISR for DMA channel 1 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_DMA_1, qm_dma_0_isr_1);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_dma_0_isr_1);
#if (QUARK_SE)
/**
* ISR for DMA channel 2 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_DMA_2, qm_dma_0_isr_2);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_dma_0_isr_2);
/**
* ISR for DMA channel 3 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_DMA_3, qm_dma_0_isr_3);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_dma_0_isr_3);
/**
* ISR for DMA channel 4 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_DMA_4, qm_dma_0_isr_4);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_dma_0_isr_4);
/**
* ISR for DMA channel 5 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_DMA_5, qm_dma_0_isr_5);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_dma_0_isr_5);
/**
* ISR for DMA channel 6 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_DMA_6, qm_dma_0_isr_6);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_dma_0_isr_6);
/**
* ISR for DMA 0 channel 7 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_DMA_7, qm_dma_0_isr_7);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_dma_0_isr_7);
#endif /* QUARK_SE */
/**
* ISR for FPR 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_FLASH_0, qm_fpr_isr_0);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_fpr_isr_0);
/**
* ISR for FPR 1 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_FLASH_1, qm_fpr_isr_1);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_fpr_isr_1);
/**
* ISR for GPIO 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_GPIO_0, qm_gpio_isr_0);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_gpio_isr_0);
#if (HAS_AON_GPIO)
/**
* ISR for AON GPIO 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_AONGPIO_0, qm_aon_gpio_isr_0);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_aon_gpio_isr_0);
#endif /* HAS_AON_GPIO */
/**
* ISR for I2C 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_I2C_0, qm_i2c_0_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_i2c_0_isr);
/**
* ISR for I2C 1 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_I2C_1, qm_i2c_1_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_i2c_1_isr);
/**
* ISR for Mailbox interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_MBOX, qm_mbox_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_mbox_isr);
/**
* ISR for Memory Protection Region interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_SRAM, qm_mpr_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_mpr_isr);
/**
* ISR for PIC Timer interrupt.
*
* On Quark Microcontroller D2000 Development Platform,
* this function needs to be registered with:
* @code qm_int_vector_request(QM_INT_VECTOR_PIC_TIMER, qm_pic_timer_isr);
* @endcode if IRQ based transfers are used.
*
* On Quark SE, this function needs to be registered with:
* @code qm_irq_request(QM_IRQ_PIC_TIMER, qm_pic_timer_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_pic_timer_isr);
/**
* ISR for PWM 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_PWM_0, qm_pwm_isr_0);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_pwm_isr_0);
/**
* ISR for RTC 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_RTC_0, qm_rtc_isr_0);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_rtc_isr_0);
/**
* ISR for SPI Master 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_SPI_MASTER_0, qm_spi_master_0_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_spi_master_0_isr);
#if (QUARK_SE)
/**
* ISR for SPI Master 1 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_SPI_MASTER_1, qm_spi_master_1_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_spi_master_1_isr);
#endif /* QUARK_SE */
/**
* ISR for UART 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_UART_0, qm_uart_0_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_uart_0_isr);
/**
* ISR for UART 1 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_UART_1, qm_uart_1_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_uart_1_isr);
/**
* ISR for WDT 0 interrupt.
*
* This function needs to be registered with
* @code qm_irq_request(QM_IRQ_WDT_0, qm_wdt_isr_0);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_wdt_isr_0);
/**
* @}
*/
#endif /* __QM_ISR_H__ */

View file

@ -0,0 +1,170 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_MAILBOX_H__
#define __QM_MAILBOX_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
#if (HAS_MAILBOX)
/**
* Mailbox driver.
*
* @defgroup groupMailbox Mailbox
* @{
*/
/**
* Mailbox status. Those values are tied to HW bit setting and made up of
* the bit 0 and bit 1 of the mailbox channel status register.
*/
typedef enum {
/**< No interrupt pending nor any data to consume. */
QM_MBOX_CH_IDLE = 0,
QM_MBOX_CH_DATA = BIT(0), /**< Message has not been consumed. */
QM_MBOX_CH_INT = BIT(1), /**< Channel interrupt pending. */
QM_MBOX_CH_STATUS_MASK = BIT(1) | BIT(0) /**< Status mask. */
} qm_mbox_ch_status_t;
/**
* Mailbox channel.
*/
typedef enum {
QM_MBOX_CH_0 = 0, /**< Channel 0. */
QM_MBOX_CH_1, /**< Channel 1. */
QM_MBOX_CH_2, /**< Channel 2. */
QM_MBOX_CH_3, /**< Channel 3. */
QM_MBOX_CH_4, /**< Channel 4. */
QM_MBOX_CH_5, /**< Channel 5. */
QM_MBOX_CH_6, /**< Channel 6. */
QM_MBOX_CH_7, /**< Channel 7. */
QM_MBOX_CH_NUM /**< Mailbox number of channels. */
} qm_mbox_ch_t;
/**
* mailbox message pay-load index values.
*/
typedef enum {
QM_MBOX_PAYLOAD_0 = 0, /**< Payload index value 0. */
QM_MBOX_PAYLOAD_1, /**< Payload index value 1. */
QM_MBOX_PAYLOAD_2, /**< Payload index value 2. */
QM_MBOX_PAYLOAD_3, /**< Payload index value 3. */
QM_MBOX_PAYLOAD_NUM, /**< Numbers of payloads. */
} qm_mbox_payload_t;
/**
* Definition of the mailbox message.
*/
typedef struct {
uint32_t ctrl; /**< Mailbox control element. */
uint32_t data[QM_MBOX_PAYLOAD_NUM]; /**< Mailbox data buffer. */
} qm_mbox_msg_t;
/**
* Definition of the mailbox callback function prototype.
* @param[in] data The callback user data.
*/
typedef void (*qm_mbox_callback_t)(void *data);
/**
* Set the mailbox channel configuration.
*
* Configure a IRQ callback, enables or disables IRQ for the chosen mailbox
* channel.
*
* @param[in] mbox_ch Mailbox to enable.
* @param[in] mpr_cb Callback function to call on read mailbox, NULL for a
* write to Mailbox).
* @param[in] cb_data Callback function data to return via the callback.
* function. This must not be NULL.
* @param[in] irq_en Flag to enable/disable IRQ for this channel.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_mbox_ch_set_config(const qm_mbox_ch_t mbox_ch, qm_mbox_callback_t mpr_cb,
void *cb_data, const bool irq_en);
/**
* Write to a specified mailbox channel.
*
* @param[in] mbox_ch Mailbox channel identifier.
* @param[in] msg Pointer to the data to write to the mailbox channel. This
* must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_mbox_ch_write(const qm_mbox_ch_t mbox_ch,
const qm_mbox_msg_t *const msg);
/**
* Read specified mailbox channel.
*
* @param[in] mbox_ch mailbox channel identifier.
* @param[out] data pointer to the data to read from the mailbox channel. This
* must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_mbox_ch_read(const qm_mbox_ch_t mbox_ch, qm_mbox_msg_t *const msg);
/**
* Retrieve the specified mailbox channel status.
*
* @param[in] mbox_ch Mailbox identifier to retrieve the status from.
* @param[out] status Mailbox status. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_mbox_ch_get_status(const qm_mbox_ch_t mbox_ch,
qm_mbox_ch_status_t *const status);
/**
* Acknowledge the data arrival.
* @param[in] mbox_ch: Mailbox identifier to retrieve the status from.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_mbox_ch_data_ack(const qm_mbox_ch_t mbox_ch);
/**
* @}
*/
#endif /* HAS_MAILBOX */
#endif /* __QM_MAILBOX_H__ */

View file

@ -0,0 +1,106 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_MPR_H__
#define __QM_MPR_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Memory Protection Region control for Quark Microcontrollers.
*
* @defgroup groupMPR MPR
* @{
*/
/** MPR mask enable */
#define QM_SRAM_MPR_EN_MASK_ENABLE BIT(0)
/** MPR mask lock */
#define QM_SRAM_MPR_EN_MASK_LOCK BIT(1)
/** MPR mask host */
#define QM_SRAM_MPR_AGENT_MASK_HOST BIT(0)
/** MPR mask ss */
#if (QUARK_SE)
#define QM_SRAM_MPR_AGENT_MASK_SS BIT(1)
#endif
/** MPR mask dma */
#define QM_SRAM_MPR_AGENT_MASK_DMA BIT(2)
typedef void (*qm_mpr_callback_t)(void *);
/* MPR identifier */
typedef enum {
QM_MPR_0 = 0,
QM_MPR_1,
QM_MPR_2,
QM_MPR_3,
QM_MPR_NUM
} qm_mpr_id_t;
/** SRAM Memory Protection Region configuration type. */
typedef struct {
uint8_t en_lock_mask; /**< Enable/lock bitmask */
uint8_t agent_read_en_mask; /**< Per-agent read enable bitmask */
uint8_t agent_write_en_mask; /**< Per-agent write enable bitmask */
uint8_t up_bound; /**< 1KB-aligned upper addr */
uint8_t low_bound; /**< 1KB-aligned lower addr */
} qm_mpr_config_t;
typedef enum {
MPR_VIOL_MODE_INTERRUPT = 0,
MPR_VIOL_MODE_RESET,
MPR_VIOL_MODE_PROBE
} qm_mpr_viol_mode_t;
/**
* Configure SRAM controller's Memory Protection Region.
*
* @param [in] id Which MPR to configure.
* @param [in] cfg MPR configuration.
* @return int 0 on success, error code otherwise.
*/
int qm_mpr_set_config(const qm_mpr_id_t id, const qm_mpr_config_t *const cfg);
/**
* Configure MPR violation behaviour
*
* @param [in] mode (generate interrupt, warm reset, enter probe mode).
* @param [in] callback_fn for interrupt mode (only).
* @param [in] callback_data user data for interrupt mode (only).
* @return int 0 on success, error code otherwise.
* */
int qm_mpr_set_violation_policy(const qm_mpr_viol_mode_t mode,
qm_mpr_callback_t callback_fn, void *data);
/**
* @}
*/
#endif /* __QM_MPR_H__ */

View file

@ -0,0 +1,111 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_PIC_TIMER_H__
#define __QM_PIC_TIMER_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* PIC timer.
*
* @defgroup groupPICTimer PIC Timer
* @{
*/
/**
* PIC timer mode type.
*/
typedef enum {
QM_PIC_TIMER_MODE_ONE_SHOT, /**< One shot mode. */
QM_PIC_TIMER_MODE_PERIODIC /**< Periodic mode. */
} qm_pic_timer_mode_t;
/**
* PIC timer configuration type.
*/
typedef struct {
qm_pic_timer_mode_t mode; /**< Operation mode. */
bool int_en; /**< Interrupt enable. */
/**
* User callback.
*
* @param[in] data User defined data.
*/
void (*callback)(void *data);
void *callback_data; /**< Callback user data. */
} qm_pic_timer_config_t;
/**
* Set the PIC timer configuration.
*
* Set the PIC timer configuration.
* This includes timer mode and if interrupts are enabled. If interrupts are
* enabled, it will configure the callback function.
*
* @param[in] cfg PIC timer configuration. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_pic_timer_set_config(const qm_pic_timer_config_t *const cfg);
/**
* Set the current count value of the PIC timer.
*
* Set the current count value of the PIC timer.
* A value equal to 0 effectively stops the timer.
*
* @param[in] count Value to load the timer with.
*
* @return Standard errno return type for QMSI.
* @retval Always returns 0.
* @retval Negative @ref errno for possible error codes.
*/
int qm_pic_timer_set(const uint32_t count);
/**
* Get the current count value of the PIC timer.
*
* @param[out] count Pointer to the store the timer count.
* This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_pic_timer_get(uint32_t *const count);
/**
* @}
*/
#endif /* __QM_PIC_TIMER_H__ */

View file

@ -0,0 +1,197 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_PINMUX_H__
#define __QM_PINMUX_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Pin muxing configuration.
*
* @defgroup groupPinMux Pin Muxing setup
* @{
*/
/**
* Pin function type.
*/
typedef enum {
QM_PMUX_FN_0, /**< Gpio function 0. */
QM_PMUX_FN_1, /**< Gpio function 0. */
QM_PMUX_FN_2, /**< Gpio function 0. */
QM_PMUX_FN_3, /**< Gpio function 0. */
} qm_pmux_fn_t;
/**
* Pin slew rate setting.
*/
typedef enum {
#if (QUARK_SE)
QM_PMUX_SLEW_2MA, /**< Set gpio slew rate to 2MA. */
QM_PMUX_SLEW_4MA, /**< Set gpio slew rate to 4MA. */
#else
QM_PMUX_SLEW_12MA, /**< Set gpio slew rate to 12MA. */
QM_PMUX_SLEW_16MA, /**< Set gpio slew rate to 16MA. */
#endif
QM_PMUX_SLEW_NUM /**< Max number of slew rate options. */
} qm_pmux_slew_t;
/**
* External Pad pin identifiers
**/
typedef enum {
QM_PIN_ID_0, /**< Pin id 0. */
QM_PIN_ID_1, /**< Pin id 1. */
QM_PIN_ID_2, /**< Pin id 2. */
QM_PIN_ID_3, /**< Pin id 3. */
QM_PIN_ID_4, /**< Pin id 4. */
QM_PIN_ID_5, /**< Pin id 5. */
QM_PIN_ID_6, /**< Pin id 6. */
QM_PIN_ID_7, /**< Pin id 7. */
QM_PIN_ID_8, /**< Pin id 8. */
QM_PIN_ID_9, /**< Pin id 9. */
QM_PIN_ID_10, /**< Pin id 10. */
QM_PIN_ID_11, /**< Pin id 11. */
QM_PIN_ID_12, /**< Pin id 12. */
QM_PIN_ID_13, /**< Pin id 13. */
QM_PIN_ID_14, /**< Pin id 14. */
QM_PIN_ID_15, /**< Pin id 15. */
QM_PIN_ID_16, /**< Pin id 16. */
QM_PIN_ID_17, /**< Pin id 17. */
QM_PIN_ID_18, /**< Pin id 18. */
QM_PIN_ID_19, /**< Pin id 19. */
QM_PIN_ID_20, /**< Pin id 20. */
QM_PIN_ID_21, /**< Pin id 21. */
QM_PIN_ID_22, /**< Pin id 22. */
QM_PIN_ID_23, /**< Pin id 23. */
QM_PIN_ID_24, /**< Pin id 24. */
#if (QUARK_SE)
QM_PIN_ID_25, /**< Pin id 25. */
QM_PIN_ID_26, /**< Pin id 26. */
QM_PIN_ID_27, /**< Pin id 27. */
QM_PIN_ID_28, /**< Pin id 28. */
QM_PIN_ID_29, /**< Pin id 29. */
QM_PIN_ID_30, /**< Pin id 30. */
QM_PIN_ID_31, /**< Pin id 31. */
QM_PIN_ID_32, /**< Pin id 32. */
QM_PIN_ID_33, /**< Pin id 33. */
QM_PIN_ID_34, /**< Pin id 34. */
QM_PIN_ID_35, /**< Pin id 35. */
QM_PIN_ID_36, /**< Pin id 36. */
QM_PIN_ID_37, /**< Pin id 37. */
QM_PIN_ID_38, /**< Pin id 38. */
QM_PIN_ID_39, /**< Pin id 39. */
QM_PIN_ID_40, /**< Pin id 40. */
QM_PIN_ID_41, /**< Pin id 41. */
QM_PIN_ID_42, /**< Pin id 42. */
QM_PIN_ID_43, /**< Pin id 43. */
QM_PIN_ID_44, /**< Pin id 44. */
QM_PIN_ID_45, /**< Pin id 45. */
QM_PIN_ID_46, /**< Pin id 46. */
QM_PIN_ID_47, /**< Pin id 47. */
QM_PIN_ID_48, /**< Pin id 48. */
QM_PIN_ID_49, /**< Pin id 49. */
QM_PIN_ID_50, /**< Pin id 50. */
QM_PIN_ID_51, /**< Pin id 51. */
QM_PIN_ID_52, /**< Pin id 52. */
QM_PIN_ID_53, /**< Pin id 53. */
QM_PIN_ID_54, /**< Pin id 54. */
QM_PIN_ID_55, /**< Pin id 55. */
QM_PIN_ID_56, /**< Pin id 56. */
QM_PIN_ID_57, /**< Pin id 57. */
QM_PIN_ID_58, /**< Pin id 58. */
QM_PIN_ID_59, /**< Pin id 59. */
QM_PIN_ID_60, /**< Pin id 60. */
QM_PIN_ID_61, /**< Pin id 61. */
QM_PIN_ID_62, /**< Pin id 62. */
QM_PIN_ID_63, /**< Pin id 63. */
QM_PIN_ID_64, /**< Pin id 64. */
QM_PIN_ID_65, /**< Pin id 65. */
QM_PIN_ID_66, /**< Pin id 66. */
QM_PIN_ID_67, /**< Pin id 67. */
QM_PIN_ID_68, /**< Pin id 68. */
#endif
QM_PIN_ID_NUM
} qm_pin_id_t;
/**
* Set up pin muxing for a SoC pin. Select one of the pin functions.
*
* @param[in] pin which pin to configure.
* @param[in] fn the function to assign to the pin.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
* */
int qm_pmux_select(const qm_pin_id_t pin, const qm_pmux_fn_t fn);
/**
* Set up pin's slew rate in the pin mux controller.
*
* @param[in] pin which pin to configure.
* @param[in] slew the slew rate to assign to the pin.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_pmux_set_slew(const qm_pin_id_t pin, const qm_pmux_slew_t slew);
/**
* Enable input for a pin in the pin mux controller.
*
* @param[in] pin which pin to configure.
* @param[in] enable set to true to enable input.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_pmux_input_en(const qm_pin_id_t pin, const bool enable);
/**
* Enable pullup for a pin in the pin mux controller.
*
* @param[in] pin which pin to configure.
* @param[in] enable set to true to enable pullup.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_pmux_pullup_en(const qm_pin_id_t pin, const bool enable);
/**
* @}
*/
#endif /* __QM_PINMUX_H__ */

View file

@ -0,0 +1,165 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_PWM_H__
#define __QM_PWM_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Pulse width modulation and Timer driver.
*
* @defgroup groupPWM PWM / Timer
* @{
*/
#define PWM_START (1)
#define QM_PWM_CONF_MODE_MASK (10)
#define QM_PWM_CONF_INT_EN_MASK (4)
/**
* PWM operating mode type.
*/
typedef enum {
QM_PWM_MODE_TIMER_FREE_RUNNING = 0, /**< Timer: free runnig mode. */
QM_PWM_MODE_TIMER_COUNT = 2, /**< Timer: Counter mode. */
QM_PWM_MODE_PWM = 10 /**< Pwm mode. */
} qm_pwm_mode_t;
/**
* PWM / Timer configuration type.
*/
typedef struct {
uint32_t
lo_count; /**< Number of cycles the PWM output is driven low. In
timer mode, this is the timer load count. Must be
> 0. */
uint32_t hi_count; /**< Number of cycles the PWM output is driven high.
Not applicable in timer mode. Must be > 0.*/
bool mask_interrupt; /**< Mask interrupt. */
qm_pwm_mode_t mode; /**< Pwm mode. */
/**
* User callback.
*
* @param[in] data The callback user data.
* @param[in] int_status The timer status.
*/
void (*callback)(void *data, uint32_t int_status);
void *callback_data; /**< Callback user data. */
} qm_pwm_config_t;
/**
* Change the configuration of a PWM channel.
*
* This includes low period load value, high period load value, interrupt
* enable/disable. If interrupts are enabled, registers an ISR with the given
* user callback function. When operating in PWM mode, 0% and 100% duty cycle
* is not available on Quark SE or Quark D2000. When setting the mode to PWM
* mode, hi_count must be > 0. In timer mode, the value of high count is
* ignored.
*
* @brief Set PWM channel configuration.
* @param[in] pwm Which PWM module to configure.
* @param[in] id PWM channel id to configure.
* @param[in] cfg New configuration for PWM. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
* */
int qm_pwm_set_config(const qm_pwm_t pwm, const qm_pwm_id_t id,
const qm_pwm_config_t *const cfg);
/**
* Set the next period values of a PWM channel.
*
* This includes low period count and high period count. When operating in PWM
* mode, 0% and 100% duty cycle is not available on Quark SE or Quark D2000.
* When operating in PWM mode, hi_count must be > 0. In timer mode, the value of
* high count is ignored.
*
* @brief Set PWM period counts.
* @param[in] pwm Which PWM module to set the counts of.
* @param[in] id PWM channel id to set.
* @param[in] lo_count Num of cycles the output is driven low.
* @param[in] hi_count Num of cycles the output is driven high.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
* */
int qm_pwm_set(const qm_pwm_t pwm, const qm_pwm_id_t id,
const uint32_t lo_count, const uint32_t hi_count);
/**
* Get the current period values of a PWM channel.
*
* @param[in] pwm Which PWM module to get the count of.
* @param[in] id PWM channel id to read the values of.
* @param[out] lo_count Num of cycles the output is driven low. This must not be
* NULL.
* @param[out] hi_count Num of cycles the output is driven high. This must not
* be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
* */
int qm_pwm_get(const qm_pwm_t pwm, const qm_pwm_id_t id,
uint32_t *const lo_count, uint32_t *const hi_count);
/**
* Start a PWM/timer channel.
*
* @param[in] pwm Which PWM block the PWM is in.
* @param[in] id PWM channel id to start.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
* */
int qm_pwm_start(const qm_pwm_t pwm, const qm_pwm_id_t id);
/**
* Stop a PWM/timer channel.
*
* @param[in] pwm Which PWM block the PWM is in.
* @param[in] id PWM channel id to stop.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
* */
int qm_pwm_stop(const qm_pwm_t pwm, const qm_pwm_id_t id);
/**
* @}
*/
#endif /* __QM_PWM_H__ */

View file

@ -0,0 +1,106 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_RTC_H__
#define __QM_RTC_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
#include "clk.h"
/**
* Real Time clock.
*
* @defgroup groupRTC RTC
* @{
*/
#define QM_RTC_DIVIDER CLK_RTC_DIV_1
#define QM_RTC_CCR_INTERRUPT_ENABLE BIT(0)
#define QM_RTC_CCR_INTERRUPT_MASK BIT(1)
#define QM_RTC_CCR_ENABLE BIT(2)
#define QM_RTC_ALARM_SECOND (32768 / BIT(QM_RTC_DIVIDER))
#define QM_RTC_ALARM_MINUTE (QM_RTC_ALARM_SECOND * 60)
#define QM_RTC_ALARM_HOUR (QM_RTC_ALARM_MINUTE * 60)
#define QM_RTC_ALARM_DAY (QM_RTC_ALARM_HOUR * 24)
/**
* RTC configuration type.
*/
typedef struct {
uint32_t init_val; /**< Initial value in RTC clocks. */
bool alarm_en; /**< Alarm enable. */
uint32_t alarm_val; /**< Alarm value in RTC clocks. */
/**
* User callback.
*
* @param[in] data User defined data.
*/
void (*callback)(void *data);
void *callback_data; /**< Callback user data. */
} qm_rtc_config_t;
/**
* Set RTC configuration.
*
* This includes the initial value in RTC clock periods, and the alarm value if
* an alarm is required. If the alarm is enabled, register an ISR with the user
* defined callback function.
*
* @param[in] rtc RTC index.
* @param[in] cfg New RTC configuration. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_rtc_set_config(const qm_rtc_t rtc, const qm_rtc_config_t *const cfg);
/**
* Set Alarm value.
*
* Set a new RTC alarm value after an alarm, that has been set using the
* qm_rtc_set_config function, has expired and a new alarm value is required.
*
* @param[in] rtc RTC index.
* @param[in] alarm_val Value to set alarm to.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_rtc_set_alarm(const qm_rtc_t rtc, const uint32_t alarm_val);
/**
* @}
*/
#endif /* __QM_RTC_H__ */

View file

@ -0,0 +1,366 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_SPI_H__
#define __QM_SPI_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
#include "qm_dma.h"
/**
* SPI peripheral driver for Quark Microcontrollers.
*
* @defgroup groupSPI SPI
* @{
*/
/**
* QM SPI frame size type.
*/
typedef enum {
QM_SPI_FRAME_SIZE_4_BIT = 3, /**< 4 bit frame. */
QM_SPI_FRAME_SIZE_5_BIT, /**< 5 bit frame. */
QM_SPI_FRAME_SIZE_6_BIT, /**< 6 bit frame. */
QM_SPI_FRAME_SIZE_7_BIT, /**< 7 bit frame. */
QM_SPI_FRAME_SIZE_8_BIT, /**< 8 bit frame. */
QM_SPI_FRAME_SIZE_9_BIT, /**< 9 bit frame. */
QM_SPI_FRAME_SIZE_10_BIT, /**< 10 bit frame. */
QM_SPI_FRAME_SIZE_11_BIT, /**< 11 bit frame. */
QM_SPI_FRAME_SIZE_12_BIT, /**< 12 bit frame. */
QM_SPI_FRAME_SIZE_13_BIT, /**< 13 bit frame. */
QM_SPI_FRAME_SIZE_14_BIT, /**< 14 bit frame. */
QM_SPI_FRAME_SIZE_15_BIT, /**< 15 bit frame. */
QM_SPI_FRAME_SIZE_16_BIT, /**< 16 bit frame. */
QM_SPI_FRAME_SIZE_17_BIT, /**< 17 bit frame. */
QM_SPI_FRAME_SIZE_18_BIT, /**< 18 bit frame. */
QM_SPI_FRAME_SIZE_19_BIT, /**< 19 bit frame. */
QM_SPI_FRAME_SIZE_20_BIT, /**< 20 bit frame. */
QM_SPI_FRAME_SIZE_21_BIT, /**< 21 bit frame. */
QM_SPI_FRAME_SIZE_22_BIT, /**< 22 bit frame. */
QM_SPI_FRAME_SIZE_23_BIT, /**< 23 bit frame. */
QM_SPI_FRAME_SIZE_24_BIT, /**< 24 bit frame. */
QM_SPI_FRAME_SIZE_25_BIT, /**< 25 bit frame. */
QM_SPI_FRAME_SIZE_26_BIT, /**< 26 bit frame. */
QM_SPI_FRAME_SIZE_27_BIT, /**< 27 bit frame. */
QM_SPI_FRAME_SIZE_28_BIT, /**< 28 bit frame. */
QM_SPI_FRAME_SIZE_29_BIT, /**< 29 bit frame. */
QM_SPI_FRAME_SIZE_30_BIT, /**< 30 bit frame. */
QM_SPI_FRAME_SIZE_31_BIT, /**< 31 bit frame. */
QM_SPI_FRAME_SIZE_32_BIT /**< 32 bit frame. */
} qm_spi_frame_size_t;
/**
* SPI transfer mode type.
*/
typedef enum {
QM_SPI_TMOD_TX_RX, /**< Transmit & Receive. */
QM_SPI_TMOD_TX, /**< Transmit Only. */
QM_SPI_TMOD_RX, /**< Receive Only. */
QM_SPI_TMOD_EEPROM_READ /**< EEPROM Read. */
} qm_spi_tmode_t;
/**
* SPI bus mode type.
*/
typedef enum {
QM_SPI_BMODE_0, /**< Clock Polarity = 0, Clock Phase = 0. */
QM_SPI_BMODE_1, /**< Clock Polarity = 0, Clock Phase = 1. */
QM_SPI_BMODE_2, /**< Clock Polarity = 1, Clock Phase = 0. */
QM_SPI_BMODE_3 /**< Clock Polarity = 1, Clock Phase = 1. */
} qm_spi_bmode_t;
/**
* SPI slave select type.
*
* QM_SPI_SS_DISABLED prevents the controller from starting a transfer.
*/
typedef enum {
QM_SPI_SS_DISABLED = 0, /**< Slave select disable. */
QM_SPI_SS_0 = BIT(0), /**< Slave Select 0. */
QM_SPI_SS_1 = BIT(1), /**< Slave Select 1. */
QM_SPI_SS_2 = BIT(2), /**< Slave Select 2. */
QM_SPI_SS_3 = BIT(3), /**< Slave Select 3. */
} qm_spi_slave_select_t;
/**
* SPI status
*/
typedef enum {
QM_SPI_IDLE, /**< SPI device is not in use. */
QM_SPI_BUSY, /**< SPI device is busy. */
QM_SPI_RX_OVERFLOW /**< RX transfer has overflown. */
} qm_spi_status_t;
/**
* SPI configuration type.
*/
typedef struct {
qm_spi_frame_size_t frame_size; /**< Frame Size. */
qm_spi_tmode_t transfer_mode; /**< Transfer mode (enum). */
qm_spi_bmode_t bus_mode; /**< Bus mode (enum). */
/**
* SCK = SPI_clock/clk_divider.
*
* A value of 0 will disable SCK.
*/
uint16_t clk_divider;
} qm_spi_config_t;
/**
* SPI IRQ transfer type.
*/
typedef struct {
uint8_t *tx; /**< Write data. */
uint16_t tx_len; /**< Write data Length. */
uint8_t *rx; /**< Read data. */
uint16_t rx_len; /**< Read buffer length. */
/**
* Transfer callback.
*
* Called after all data is transmitted/received or if the driver
* detects an error during the SPI transfer.
*
* @param[in] data The callback user data.
* @param[in] error 0 on success.
* Negative @ref errno for possible error codes.
* @param[in] status SPI driver status.
* @param[in] len Length of the SPI transfer if successful, 0
* otherwise.
*/
void (*callback)(void *data, int error, qm_spi_status_t status,
uint16_t len);
void *callback_data; /**< Callback user data. */
} qm_spi_async_transfer_t;
/**
* SPI transfer type.
*/
typedef struct {
uint8_t *tx; /**< Write Data. */
uint16_t tx_len; /**< Write Data Length. */
uint8_t *rx; /**< Read Data. */
uint16_t rx_len; /**< Receive Data Length. */
} qm_spi_transfer_t;
/**
* Set SPI configuration.
*
* Change the configuration of a SPI module.
* This includes transfer mode, bus mode and clock divider.
*
* @param[in] spi Which SPI module to configure.
* @param[in] cfg New configuration for SPI. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_spi_set_config(const qm_spi_t spi, const qm_spi_config_t *const cfg);
/**
* Select which slave to perform SPI transmissions on.
*
* @param[in] spi Which SPI module to configure.
* @param[in] ss Which slave select line to enable when doing transmissions.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_spi_slave_select(const qm_spi_t spi, const qm_spi_slave_select_t ss);
/**
* Get SPI bus status.
*
* Retrieve SPI bus status. Return QM_SPI_BUSY if transmitting data or data Tx
* FIFO not empty.
*
* @param[in] spi Which SPI to read the status of.
* @param[out] status Get spi status. This must not be null.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_spi_get_status(const qm_spi_t spi, qm_spi_status_t *const status);
/**
* Multi-frame read / write on SPI.
*
* Perform a multi-frame read/write on the SPI bus. This is a blocking
* synchronous call. If the SPI is currently in use, the function will wait
* until the SPI is free before beginning the transfer. If transfer mode is
* full duplex (QM_SPI_TMOD_TX_RX), then tx_len and rx_len must be equal.
* Similarly, for transmit-only transfers (QM_SPI_TMOD_TX) rx_len must be 0,
* while for receive-only transfers (QM_SPI_TMOD_RX) tx_len must be 0.
*
* For starting a transfer, this controller demands at least one slave
* select line (SS) to be enabled. Thus, a call to qm_spi_slave_select()
* with one of the four SS valid lines is mandatory. This is true even if
* the native slave select line is not used (i.e. when a GPIO is used to
* drive the SS signal manually).
*
* @param[in] spi Which SPI to read/write on.
* @param[in] xfer Structure containing pre-allocated write and read data
* buffers. This must not be NULL.
* @param[out] status Get spi status.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_spi_transfer(const qm_spi_t spi, const qm_spi_transfer_t *const xfer,
qm_spi_status_t *const status);
/**
* Interrupt based transfer on SPI.
*
* Perform an interrupt based transfer on the SPI bus. The function will
* replenish/empty TX/RX FIFOs on SPI empty/full interrupts. If transfer
* mode is full duplex (QM_SPI_TMOD_TX_RX), then tx_len and rx_len must be
* equal. For transmit-only transfers (QM_SPI_TMOD_TX) rx_len must be 0
* while for receive-only transfers (QM_SPI_TMOD_RX) tx_len must be 0.
*
* For starting a transfer, this controller demands at least one slave
* select line (SS) to be enabled. Thus, a call to qm_spi_slave_select()
* with one of the four SS valid lines is mandatory. This is true even if
* the native slave select line is not used (i.e. when a GPIO is used to
* drive the SS signal manually).
*
* @param[in] spi Which SPI to transfer to / from.
* @param[in] xfer Transfer structure includes write / read buffers, length,
* user callback function and the callback context data.
* The structure must not be NULL and must be kept valid until
* the transfer is complete.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_spi_irq_transfer(const qm_spi_t spi,
const qm_spi_async_transfer_t *const xfer);
/**
* Configure a DMA channel with a specific transfer direction.
*
* The user is responsible for managing the allocation of the pool of DMA
* channels provided by each DMA core to the different peripheral drivers
* that require them.
*
* Note that a SPI controller cannot use different DMA cores to manage
* transfers in different directions.
*
* This function configures DMA channel parameters that are unlikely to change
* between transfers, like transaction width, burst size, and handshake
* interface parameters. The user will likely only call this function once for
* the lifetime of an application unless the channel needs to be repurposed.
*
* Note that qm_dma_init() must first be called before configuring a channel.
*
* @param[in] spi SPI controller identifier.
* @param[in] dma_ctrl_id DMA controller identifier.
* @param[in] dma_channel_id DMA channel identifier.
* @param[in] dma_channel_direction DMA channel direction, either
* QM_DMA_MEMORY_TO_PERIPHERAL (TX transfer) or QM_DMA_PERIPHERAL_TO_MEMORY
* (RX transfer).
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_spi_dma_channel_config(
const qm_spi_t spi, const qm_dma_t dma_ctrl_id,
const qm_dma_channel_id_t dma_channel_id,
const qm_dma_channel_direction_t dma_channel_direction);
/**
* Perform a DMA-based transfer on the SPI bus.
*
* If transfer mode is full duplex (QM_SPI_TMOD_TX_RX), then tx_len and
* rx_len must be equal and neither of both callbacks can be NULL.
* Similarly, for transmit-only transfers (QM_SPI_TMOD_TX) rx_len must be 0
* and tx_callback cannot be NULL, while for receive-only transfers
* (QM_SPI_TMOD_RX) tx_len must be 0 and rx_callback cannot be NULL.
* Transfer length is limited to 4KB.
*
* For starting a transfer, this controller demands at least one slave
* select line (SS) to be enabled. Thus, a call to qm_spi_slave_select()
* with one of the four SS valid lines is mandatory. This is true even if
* the native slave select line is not used (i.e. when a GPIO is used to
* drive the SS signal manually).
*
* Note that qm_spi_dma_channel_config() must first be called in order to
* configure all DMA channels needed for a transfer.
*
* @param[in] spi SPI controller identifier.
* @param[in] xfer Structure containing pre-allocated write and read data
* buffers and callback functions. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_spi_dma_transfer(const qm_spi_t spi,
const qm_spi_async_transfer_t *const xfer);
/**
* Terminate SPI IRQ transfer.
*
* Terminate the current IRQ transfer on the SPI bus.
* This will cause the user callback to be called with
* error code set to -ECANCELED.
*
* @param[in] spi Which SPI to cancel the current transfer.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_spi_irq_transfer_terminate(const qm_spi_t spi);
/**
* Terminate the current DMA transfer on the SPI bus.
*
* Terminate the current DMA transfer on the SPI bus.
* This will cause the relevant callbacks to be invoked.
*
* @param[in] spi SPI controller identifier.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_spi_dma_transfer_terminate(const qm_spi_t spi);
/**
* @}
*/
#endif /* __QM_SPI_H__ */

View file

@ -0,0 +1,491 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_UART_H__
#define __QM_UART_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
#include "qm_dma.h"
/**
* UART peripheral driver.
*
* @defgroup groupUART UART
* @{
*/
/** Divisor Latch Access Bit. */
#define QM_UART_LCR_DLAB BIT(7)
/** Auto Flow Control Enable Bit. */
#define QM_UART_MCR_AFCE BIT(5)
/** Request to Send Bit. */
#define QM_UART_MCR_RTS BIT(1)
/** FIFO Enable Bit. */
#define QM_UART_FCR_FIFOE BIT(0)
/** Reset Receive FIFO. */
#define QM_UART_FCR_RFIFOR BIT(1)
/** Reset Transmit FIFO. */
#define QM_UART_FCR_XFIFOR BIT(2)
/** FIFO half RX, half TX Threshold. */
#define QM_UART_FCR_DEFAULT_TX_RX_THRESHOLD (0xB0)
/** FIFO 1 byte RX, half TX Threshold. */
#define QM_UART_FCR_TX_1_2_RX_0_THRESHOLD (0x30)
/** FIFO half RX, empty TX Threshold. */
#define QM_UART_FCR_TX_0_RX_1_2_THRESHOLD (0x80)
/** Transmit Holding Register Empty. */
#define QM_UART_IIR_THR_EMPTY (0x02)
/** Received Data Available. */
#define QM_UART_IIR_RECV_DATA_AVAIL (0x04)
/** Receiver Line Status. */
#define QM_UART_IIR_RECV_LINE_STATUS (0x06)
/** Character Timeout. */
#define QM_UART_IIR_CHAR_TIMEOUT (0x0C)
/** Interrupt ID Mask. */
#define QM_UART_IIR_IID_MASK (0x0F)
/** Data Ready Bit. */
#define QM_UART_LSR_DR BIT(0)
/** Overflow Error Bit. */
#define QM_UART_LSR_OE BIT(1)
/** Parity Error Bit. */
#define QM_UART_LSR_PE BIT(2)
/** Framing Error Bit. */
#define QM_UART_LSR_FE BIT(3)
/** Break Interrupt Bit. */
#define QM_UART_LSR_BI BIT(4)
/** Transmit Holding Register Empty Bit. */
#define QM_UART_LSR_THRE BIT(5)
/** Transmitter Empty Bit. */
#define QM_UART_LSR_TEMT BIT(6)
/** Receiver FIFO Error Bit. */
#define QM_UART_LSR_RFE BIT(7)
/** Enable Received Data Available Interrupt. */
#define QM_UART_IER_ERBFI BIT(0)
/** Enable Transmit Holding Register Empty Interrupt. */
#define QM_UART_IER_ETBEI BIT(1)
/** Enable Receiver Line Status Interrupt. */
#define QM_UART_IER_ELSI BIT(2)
/** Programmable THRE Interrupt Mode. */
#define QM_UART_IER_PTIME BIT(7)
/** Line Status Errors. */
#define QM_UART_LSR_ERROR_BITS \
(QM_UART_LSR_OE | QM_UART_LSR_PE | QM_UART_LSR_FE | QM_UART_LSR_BI)
/** FIFO Depth. */
#define QM_UART_FIFO_DEPTH (16)
/** FIFO Half Depth. */
#define QM_UART_FIFO_HALF_DEPTH (QM_UART_FIFO_DEPTH / 2)
/** Divisor Latch High Offset. */
#define QM_UART_CFG_BAUD_DLH_OFFS 16
/** Divisor Latch Low Offset. */
#define QM_UART_CFG_BAUD_DLL_OFFS 8
/** Divisor Latch Fraction Offset. */
#define QM_UART_CFG_BAUD_DLF_OFFS 0
/** Divisor Latch High Mask. */
#define QM_UART_CFG_BAUD_DLH_MASK (0xFF << QM_UART_CFG_BAUD_DLH_OFFS)
/** Divisor Latch Low Mask. */
#define QM_UART_CFG_BAUD_DLL_MASK (0xFF << QM_UART_CFG_BAUD_DLL_OFFS)
/** Divisor Latch Fraction Mask. */
#define QM_UART_CFG_BAUD_DLF_MASK (0xFF << QM_UART_CFG_BAUD_DLF_OFFS)
/** Divisor Latch Packing Helper. */
#define QM_UART_CFG_BAUD_DL_PACK(dlh, dll, dlf) \
(dlh << QM_UART_CFG_BAUD_DLH_OFFS | dll << QM_UART_CFG_BAUD_DLL_OFFS | \
dlf << QM_UART_CFG_BAUD_DLF_OFFS)
/** Divisor Latch High Unpacking Helper. */
#define QM_UART_CFG_BAUD_DLH_UNPACK(packed) \
((packed & QM_UART_CFG_BAUD_DLH_MASK) >> QM_UART_CFG_BAUD_DLH_OFFS)
/** Divisor Latch Low Unpacking Helper. */
#define QM_UART_CFG_BAUD_DLL_UNPACK(packed) \
((packed & QM_UART_CFG_BAUD_DLL_MASK) >> QM_UART_CFG_BAUD_DLL_OFFS)
/** Divisor Latch Fraction Unpacking Helper. */
#define QM_UART_CFG_BAUD_DLF_UNPACK(packed) \
((packed & QM_UART_CFG_BAUD_DLF_MASK) >> QM_UART_CFG_BAUD_DLF_OFFS)
/**
* UART Line control.
*/
typedef enum {
QM_UART_LC_5N1 = 0x00, /**< 5 data bits, no parity, 1 stop bit. */
QM_UART_LC_5N1_5 = 0x04, /**< 5 data bits, no parity, 1.5 stop bits. */
QM_UART_LC_5E1 = 0x18, /**< 5 data bits, even parity, 1 stop bit. */
QM_UART_LC_5E1_5 = 0x1c, /**< 5 data bits, even par., 1.5 stop bits. */
QM_UART_LC_5O1 = 0x08, /**< 5 data bits, odd parity, 1 stop bit. */
QM_UART_LC_5O1_5 = 0x0c, /**< 5 data bits, odd parity, 1.5 stop bits. */
QM_UART_LC_6N1 = 0x01, /**< 6 data bits, no parity, 1 stop bit. */
QM_UART_LC_6N2 = 0x05, /**< 6 data bits, no parity, 2 stop bits. */
QM_UART_LC_6E1 = 0x19, /**< 6 data bits, even parity, 1 stop bit. */
QM_UART_LC_6E2 = 0x1d, /**< 6 data bits, even parity, 2 stop bits. */
QM_UART_LC_6O1 = 0x09, /**< 6 data bits, odd parity, 1 stop bit. */
QM_UART_LC_6O2 = 0x0d, /**< 6 data bits, odd parity, 2 stop bits. */
QM_UART_LC_7N1 = 0x02, /**< 7 data bits, no parity, 1 stop bit. */
QM_UART_LC_7N2 = 0x06, /**< 7 data bits, no parity, 2 stop bits. */
QM_UART_LC_7E1 = 0x1a, /**< 7 data bits, even parity, 1 stop bit. */
QM_UART_LC_7E2 = 0x1e, /**< 7 data bits, even parity, 2 stop bits. */
QM_UART_LC_7O1 = 0x0a, /**< 7 data bits, odd parity, 1 stop bit. */
QM_UART_LC_7O2 = 0x0e, /**< 7 data bits, odd parity, 2 stop bits. */
QM_UART_LC_8N1 = 0x03, /**< 8 data bits, no parity, 1 stop bit. */
QM_UART_LC_8N2 = 0x07, /**< 8 data bits, no parity, 2 stop bits. */
QM_UART_LC_8E1 = 0x1b, /**< 8 data bits, even parity, 1 stop bit. */
QM_UART_LC_8E2 = 0x1f, /**< 8 data bits, even parity, 2 stop bits. */
QM_UART_LC_8O1 = 0x0b, /**< 8 data bits, odd parity, 1 stop bit. */
QM_UART_LC_8O2 = 0x0f /**< 8 data bits, odd parity, 2 stop bits. */
} qm_uart_lc_t;
/**
* UART Status type.
*/
typedef enum {
QM_UART_IDLE = 0, /**< IDLE. */
QM_UART_RX_OE = BIT(1), /**< Receiver overrun. */
QM_UART_RX_PE = BIT(2), /**< Parity error. */
QM_UART_RX_FE = BIT(3), /**< Framing error. */
QM_UART_RX_BI = BIT(4), /**< Break interrupt. */
QM_UART_TX_BUSY = BIT(5), /**< TX Busy flag. */
QM_UART_RX_BUSY = BIT(6), /**< RX Busy flag. */
QM_UART_TX_NFULL = BIT(7), /**< TX FIFO not full. */
QM_UART_RX_NEMPTY = BIT(8), /**< RX FIFO not empty. */
} qm_uart_status_t;
/**
* UART configuration type.
*/
typedef struct {
qm_uart_lc_t line_control; /**< Line control (enum). */
uint32_t baud_divisor; /**< Baud Divisor. */
bool hw_fc; /**< Hardware Automatic Flow Control. */
bool int_en; /**< Interrupt enable. */
} qm_uart_config_t;
/**
* UART asynchronous transfer structure.
*/
typedef struct {
uint8_t *data; /**< Pre-allocated write or read buffer. */
uint32_t data_len; /**< Number of bytes to transfer. */
/** Transfer callback
*
* @param[in] data Callback user data.
* @param[in] error 0 on success.
* Negative @ref errno for possible error codes.
* @param[in] status UART module status
* @param[in] len Length of the UART transfer if successful, 0
* otherwise.
*/
void (*callback)(void *data, int error, qm_uart_status_t status,
uint32_t len);
void *callback_data; /**< Callback identifier. */
} qm_uart_transfer_t;
/**
* Set UART configuration.
*
* Change the configuration of a UART module. This includes line control,
* baud rate and hardware flow control.
*
* @param[in] uart Which UART module to configure.
* @param[in] cfg New configuration for UART. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_set_config(const qm_uart_t uart, const qm_uart_config_t *const cfg);
/**
* Get UART bus status.
*
* Retrieve UART interface status. Return QM_UART_BUSY if transmitting
* data; QM_UART_IDLE if available for transfer QM_UART_TX_ERROR if an
* error has occurred in transmission.
*
* @param[in] uart Which UART to read the status of.
* @param[out] status UART specific status. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_get_status(const qm_uart_t uart, qm_uart_status_t *const status);
/**
* UART character data write.
*
* Perform a single character write on the UART interface.
* This is a blocking synchronous call.
*
* @param[in] uart UART index.
* @param[in] data Data to write to UART.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_write(const qm_uart_t uart, const uint8_t data);
/**
* UART character data read.
*
* Perform a single character read from the UART interface.
* This is a blocking synchronous call.
*
* @param[in] uart UART index.
* @param[out] data Data to read from UART. This must not be NULL.
* @param[out] status UART specific status.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_read(const qm_uart_t uart, uint8_t *const data,
qm_uart_status_t *const status);
/**
* UART character data write.
*
* Perform a single character write on the UART interface.
* This is a non-blocking synchronous call.
*
* @param[in] uart UART index.
* @param[in] data Data to write to UART.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_write_non_block(const qm_uart_t uart, const uint8_t data);
/**
* UART character data read.
*
* Perform a single character read from the UART interface.
* This is a non-blocking synchronous call.
*
* @param[in] uart UART index.
* @param[out] data Character read. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_read_non_block(const qm_uart_t uart, uint8_t *const data);
/**
* UART multi-byte data write.
*
* Perform a write on the UART interface. This is a blocking
* synchronous call. The function will block until all data has
* been transferred.
*
* @param[in] uart UART index.
* @param[in] data Data to write to UART. This must not be NULL.
* @param[in] len Length of data to write to UART.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_write_buffer(const qm_uart_t uart, const uint8_t *const data,
uint32_t len);
/**
* Interrupt based TX on UART.
*
* Perform an interrupt based TX transfer on the UART bus. The function
* will replenish the TX FIFOs on UART empty interrupts.
*
* @param[in] uart UART index.
* @param[in] xfer Structure containing pre-allocated
* write buffer and callback functions.
* This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_irq_write(const qm_uart_t uart,
const qm_uart_transfer_t *const xfer);
/**
* Interrupt based RX on UART.
*
* Perform an interrupt based RX transfer on the UART bus. The function
* will read back the RX FIFOs on UART empty interrupts.
*
* @param[in] uart UART index.
* @param[in] xfer Structure containing pre-allocated read
* buffer and callback functions.
* This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_irq_read(const qm_uart_t uart,
const qm_uart_transfer_t *const xfer);
/**
* Terminate UART IRQ TX transfer.
*
* Terminate the current IRQ TX transfer on the UART bus.
* This will cause the relevant callbacks to be called.
*
* @param[in] uart UART index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_irq_write_terminate(const qm_uart_t uart);
/**
* Terminate UART IRQ RX transfer.
*
* Terminate the current IRQ RX transfer on the UART bus.
* This will cause the relevant callbacks to be called.
*
* @param[in] uart UART index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_irq_read_terminate(const qm_uart_t uart);
/**
* Configure a DMA channel with a specific transfer direction.
*
* The user is responsible for managing the allocation of the pool
* of DMA channels provided by each DMA core to the different
* peripheral drivers that require them.
*
* This function configures DMA channel parameters that are unlikely to change
* between transfers, like transaction width, burst size, and handshake
* interface parameters. The user will likely only call this function once for
* the lifetime of an application unless the channel needs to be repurposed.
*
* Note that qm_dma_init() must first be called before configuring a channel.
*
* @param[in] uart UART index.
* @param[in] dma_ctrl_id DMA controller identifier.
* @param[in] dma_channel_id DMA channel identifier.
* @param[in] dma_channel_direction DMA channel direction, either
* QM_DMA_MEMORY_TO_PERIPHERAL (write transfer) or QM_DMA_PERIPHERAL_TO_MEMORY
* (read transfer).
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_dma_channel_config(
const qm_uart_t uart, const qm_dma_t dma_ctrl_id,
const qm_dma_channel_id_t dma_channel_id,
const qm_dma_channel_direction_t dma_channel_direction);
/**
* Perform a DMA-based TX transfer on the UART bus.
*
* In order for this call to succeed, previously the user
* must have configured a DMA channel with direction
* QM_DMA_MEMORY_TO_PERIPHERAL to be used on this UART, calling
* qm_uart_dma_channel_config(). The transfer length is limited to 4KB.
*
* @param[in] uart UART index.
* @param[in] xfer Structure containing a pre-allocated write buffer
* and callback functions.
* This must not be NULL.
* Callback pointer must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_dma_write(const qm_uart_t uart,
const qm_uart_transfer_t *const xfer);
/**
* Perform a DMA-based RX transfer on the UART bus.
*
* In order for this call to succeed, previously the user
* must have configured a DMA channel with direction
* QM_DMA_PERIPHERAL_TO_MEMORY to be used on this UART, calling
* qm_uart_dma_channel_config(). The transfer length is limited to 4KB.
*
* @param[in] uart UART index.
* @param[in] xfer Structure containing a pre-allocated read buffer
* and callback functions.
* This must not be NULL.
* Callback pointer must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_dma_read(const qm_uart_t uart,
const qm_uart_transfer_t *const xfer);
/**
* Terminate the current DMA TX transfer on the UART bus.
*
* This will cause the relevant callbacks to be called.
*
* @param[in] uart UART index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_dma_write_terminate(const qm_uart_t uart);
/**
* Terminate the current DMA RX transfer on the UART bus.
*
* This will cause the relevant callbacks to be called.
*
* @param[in] uart UART index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_uart_dma_read_terminate(const qm_uart_t uart);
/**
* @}
*/
#endif /* __QM_UART_H__ */

View file

@ -0,0 +1,69 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_VERSION_H__
#define __QM_VERSION_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Version number functions for API.
*
* @defgroup groupVersion Version
* @{
*/
/**
* Create a single version number from the major, minor and patch numbers
*/
#define QM_VER_API_UINT \
((QM_VER_API_MAJOR * 10000) + (QM_VER_API_MINOR * 100) + \
QM_VER_API_PATCH)
/**
* Create a version number string from the major, minor and patch numbers
*/
#define QM_VER_API_STRING \
QM_VER_STRINGIFY(QM_VER_API_MAJOR, QM_VER_API_MINOR, QM_VER_API_PATCH)
/**
* Get the ROM version number.
*
* Reads the ROM version information from flash and returns it.
*
* @return uint32_t ROM version.
*/
uint32_t qm_ver_rom(void);
/**
* @}
*/
#endif /* __QM_VERSION_H__ */

View file

@ -0,0 +1,159 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_WDT_H__
#define __QM_WDT_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Watchdog timer.
*
* @defgroup groupWDT WDT
* @{
*/
/** Watchdog enable. */
#define QM_WDT_ENABLE (BIT(0))
/** Watchdog mode. */
#define QM_WDT_MODE (BIT(1))
/** Watchdog mode offset. */
#define QM_WDT_MODE_OFFSET (1)
/** Watchdog Timeout Mask. */
#define QM_WDT_TIMEOUT_MASK (0xF)
/**
* WDT Mode type.
*/
typedef enum {
/** Watchdog Reset Response Mode.
*
* The watchdog will request a SoC Warm Reset on a timeout.
*/
QM_WDT_MODE_RESET,
/** Watchdog Interrupt Reset Response Mode.
*
* The watchdog will generate an interrupt on first timeout.
* If interrupt has not been cleared by the second timeout
* the watchdog will then request a SoC Warm Reset.
*/
QM_WDT_MODE_INTERRUPT_RESET
} qm_wdt_mode_t;
/**
* WDT clock cycles for timeout type. This value is a power of 2.
*/
typedef enum {
QM_WDT_2_POW_16_CYCLES, /**< 16 clock cycles timeout. */
QM_WDT_2_POW_17_CYCLES, /**< 17 clock cycles timeout. */
QM_WDT_2_POW_18_CYCLES, /**< 18 clock cycles timeout. */
QM_WDT_2_POW_19_CYCLES, /**< 19 clock cycles timeout. */
QM_WDT_2_POW_20_CYCLES, /**< 20 clock cycles timeout. */
QM_WDT_2_POW_21_CYCLES, /**< 21 clock cycles timeout. */
QM_WDT_2_POW_22_CYCLES, /**< 22 clock cycles timeout. */
QM_WDT_2_POW_23_CYCLES, /**< 23 clock cycles timeout. */
QM_WDT_2_POW_24_CYCLES, /**< 24 clock cycles timeout. */
QM_WDT_2_POW_25_CYCLES, /**< 25 clock cycles timeout. */
QM_WDT_2_POW_26_CYCLES, /**< 26 clock cycles timeout. */
QM_WDT_2_POW_27_CYCLES, /**< 27 clock cycles timeout. */
QM_WDT_2_POW_28_CYCLES, /**< 28 clock cycles timeout. */
QM_WDT_2_POW_29_CYCLES, /**< 29 clock cycles timeout. */
QM_WDT_2_POW_30_CYCLES, /**< 30 clock cycles timeout. */
QM_WDT_2_POW_31_CYCLES, /**< 31 clock cycles timeout. */
QM_WDT_2_POW_CYCLES_NUM
} qm_wdt_clock_timeout_cycles_t;
/**
* QM WDT configuration type.
*/
typedef struct {
qm_wdt_clock_timeout_cycles_t timeout; /**< Timeout in cycles. */
qm_wdt_mode_t mode; /**< Watchdog response mode. */
/**
* User callback.
*
* param[in] data Callback user data.
*/
void (*callback)(void *data);
void *callback_data; /**< Callback user data. */
} qm_wdt_config_t;
/**
* Start WDT.
*
* Once started, WDT can only be stopped by a SoC reset.
*
* @param[in] wdt WDT index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_wdt_start(const qm_wdt_t wdt);
/**
* Set configuration of WDT module.
*
* This includes the timeout period in PCLK cycles, the WDT mode of operation.
* It also registers an ISR to the user defined callback.
*
* @param[in] wdt WDT index.
* @param[in] cfg New configuration for WDT.
* This must not be NULL.
* If QM_WDT_MODE_INTERRUPT_RESET mode is set,
* the 'callback' cannot be null.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_wdt_set_config(const qm_wdt_t wdt, const qm_wdt_config_t *const cfg);
/**
* Reload the WDT counter.
*
* Reload the WDT counter with safety value, i.e. service the watchdog.
*
* @param[in] wdt WDT index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_wdt_reload(const qm_wdt_t wdt);
/**
* @}
*/
#endif /* __QM_WDT_H__ */

View file

@ -0,0 +1,72 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __RAR_H__
#define __RAR_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
#if (HAS_RAR)
/**
* Retention alternator regulator for Quark D2000.
*
* @defgroup groupRAR RAR
* @{
*/
/**
* RAR modes type.
*/
typedef enum {
RAR_NORMAL, /**< Normal mode = 50 mA. */
RAR_RETENTION /**< Retention mode = 300 uA. */
} rar_state_t;
/**
* Change operating mode of RAR.
*
* Normal mode is able to source up to 50 mA.
* Retention mode is able to source up to 300 uA.
* Care must be taken when entering into retention mode
* to ensure the overall system draw is less than 300 uA.
*
* @param[in] mode Operating mode of the RAR.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int rar_set_mode(const rar_state_t mode);
/**
* @}
*/
#endif /* HAS_RAR */
#endif /* __RAR_H__ */

130
ext/hal/qmsi/drivers/mvic.h Normal file
View file

@ -0,0 +1,130 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __MVIC_H__
#define __MVIC_H__
#include <stdint.h>
#include "qm_common.h"
#include "qm_soc_regs.h"
#define NUM_IRQ_LINES (32)
static uint32_t _mvic_get_irq_val(unsigned int irq)
{
/* Register Select - select which IRQ line we are configuring
* Bits 0 and 4 are reserved
* So, for IRQ 15 ( 0x01111 ) write 0x101110
*/
QM_IOAPIC->ioregsel.reg = ((irq & 0x7) << 1) | ((irq & 0x18) << 2);
return QM_IOAPIC->iowin.reg;
}
static void _mvic_set_irq_val(unsigned int irq, uint32_t value)
{
/* Register Select - select which IRQ line we are configuring
* Bits 0 and 4 are reserved
* So, for IRQ 15 ( 0x01111 ) write 0x101110
*/
QM_IOAPIC->ioregsel.reg = ((irq & 0x7) << 1) | ((irq & 0x18) << 2);
QM_IOAPIC->iowin.reg = value;
}
/**
* Initialise MVIC.
*/
static __inline__ void mvic_init(void)
{
uint32_t i;
for (i = 0; i < NUM_IRQ_LINES; i++) {
/* Clear up any spurious LAPIC interrupts, each call only
* clears one bit.
*/
QM_MVIC->eoi.reg = 0;
/* Mask interrupt */
_mvic_set_irq_val(i, BIT(16));
}
}
/**
* Register IRQ with MVIC.
*
* @param irq IRQ to register.
*/
static __inline__ void mvic_register_irq(uint32_t irq)
{
/* Set IRQ triggering scheme and unmask the line. */
switch (irq) {
case QM_IRQ_RTC_0:
case QM_IRQ_AONPT_0:
case QM_IRQ_PIC_TIMER:
case QM_IRQ_WDT_0:
/* positive edge */
_mvic_set_irq_val(irq, 0);
break;
default:
/* high level */
_mvic_set_irq_val(irq, BIT(15));
break;
}
}
/**
* Unmask IRQ with MVIC.
*
* @param irq IRQ to unmask.
*/
static __inline__ void mvic_unmask_irq(uint32_t irq)
{
uint32_t value = _mvic_get_irq_val(irq);
value &= ~BIT(16);
_mvic_set_irq_val(irq, value);
}
/**
* Mask IRQ with MVIC.
*
* @param irq IRQ to mask.
*/
static __inline__ void mvic_mask_irq(uint32_t irq)
{
uint32_t value = _mvic_get_irq_val(irq);
value |= BIT(16);
_mvic_set_irq_val(irq, value);
}
#endif /* __MVIC_H__ */

View file

@ -0,0 +1,454 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_adc.h"
#include "clk.h"
#include <string.h>
#if (QUARK_D2000)
/* FIFO_INTERRUPT_THRESHOLD is used by qm_adc_irq_convert to set the threshold
* at which the FIFO will trigger an interrupt. */
#define FIFO_INTERRUPT_THRESHOLD (16)
#define QM_ADC_CHAN_SEQ_MAX (32)
/* ADC commands. */
#define QM_ADC_CMD_START_SINGLE (0)
#define QM_ADC_CMD_START_CONT (1)
#define QM_ADC_CMD_RESET_CAL (2)
#define QM_ADC_CMD_START_CAL (3)
#define QM_ADC_CMD_LOAD_CAL (4)
#define QM_ADC_CMD_STOP_CONT (5)
static uint8_t sample_window[QM_ADC_NUM];
static qm_adc_resolution_t resolution[QM_ADC_NUM];
static qm_adc_xfer_t irq_xfer[QM_ADC_NUM];
static uint32_t count[QM_ADC_NUM];
static bool dummy_conversion = false;
/* Callbacks for mode change and calibration. */
static void (*mode_callback[QM_ADC_NUM])(void *data, int error,
qm_adc_status_t status,
qm_adc_cb_source_t source);
static void (*cal_callback[QM_ADC_NUM])(void *data, int error,
qm_adc_status_t status,
qm_adc_cb_source_t source);
static void *mode_callback_data[QM_ADC_NUM];
static void *cal_callback_data[QM_ADC_NUM];
/* ISR handler for command/calibration complete. */
static void qm_adc_isr_handler(const qm_adc_t adc)
{
uint32_t int_status = 0;
uint32_t i, samples_to_read;
int_status = QM_ADC[adc].adc_intr_status;
/* FIFO overrun interrupt. */
if (int_status & QM_ADC_INTR_STATUS_FO) {
/* Stop the transfer. */
QM_ADC[adc].adc_cmd = QM_ADC_CMD_STOP_CONT;
/* Disable all interrupts. */
QM_ADC[adc].adc_intr_enable = 0;
/* Call the user callback. */
if (irq_xfer[adc].callback) {
irq_xfer[adc].callback(irq_xfer[adc].callback_data,
-EIO, QM_ADC_OVERFLOW,
QM_ADC_TRANSFER);
}
}
/* Continuous mode command complete interrupt. */
if (int_status & QM_ADC_INTR_STATUS_CONT_CC) {
/* Clear the interrupt. */
QM_ADC[adc].adc_intr_status &= QM_ADC_INTR_STATUS_CONT_CC;
/* Calculate the number of samples to read. */
samples_to_read = QM_ADC[adc].adc_fifo_count;
if (samples_to_read >
(irq_xfer[adc].samples_len - count[adc])) {
samples_to_read =
irq_xfer[adc].samples_len - count[adc];
}
/* Copy data out of FIFO. The sample must be shifted right by
* 2, 4 or 6 bits for 10, 8 and 6 bit resolution respectively
* to get the correct value. */
for (i = 0; i < samples_to_read; i++) {
irq_xfer[adc].samples[count[adc]] =
(QM_ADC[adc].adc_sample >>
(2 * (3 - resolution[adc])));
count[adc]++;
}
/* Check if we have the requested number of samples, stop the
* conversion and call the user callback function. */
if (count[adc] == irq_xfer[adc].samples_len) {
/* Stop the transfer. */
QM_ADC[adc].adc_cmd = QM_ADC_CMD_STOP_CONT;
/* Disable all interrupts. */
QM_ADC[adc].adc_intr_enable = 0;
/* Call the user callback. */
if (irq_xfer[adc].callback) {
irq_xfer[adc].callback(
irq_xfer[adc].callback_data, 0,
QM_ADC_COMPLETE, QM_ADC_TRANSFER);
}
}
}
/* The Command Complete interrupt is currently used to notify of the
* completion of a calibration command or a dummy conversion. */
if ((int_status & QM_ADC_INTR_STATUS_CC) && (!dummy_conversion)) {
/* Disable and clear the Command Complete interrupt */
QM_ADC[adc].adc_intr_enable &= ~QM_ADC_INTR_ENABLE_CC;
QM_ADC[adc].adc_intr_status = QM_ADC_INTR_STATUS_CC;
/* Call the user callback if it is set. */
if (cal_callback[adc]) {
cal_callback[adc](irq_xfer[adc].callback_data, 0,
QM_ADC_IDLE, QM_ADC_CAL_COMPLETE);
}
}
/* This dummy conversion is needed when switching to normal mode or
* normal mode with calibration. */
if ((int_status & QM_ADC_INTR_STATUS_CC) && (dummy_conversion)) {
/* Flush the FIFO to get rid of the dummy values. */
QM_ADC[adc].adc_sample = QM_ADC_FIFO_CLEAR;
/* Disable and clear the Command Complete interrupt. */
QM_ADC[adc].adc_intr_enable &= ~QM_ADC_INTR_ENABLE_CC;
QM_ADC[adc].adc_intr_status = QM_ADC_INTR_STATUS_CC;
dummy_conversion = false;
/* Call the user callback if it is set. */
if (mode_callback[adc]) {
mode_callback[adc](irq_xfer[adc].callback_data, 0,
QM_ADC_IDLE, QM_ADC_MODE_CHANGED);
}
}
}
/* ISR handler for mode change. */
static void qm_adc_pwr_0_isr_handler(const qm_adc_t adc)
{
/* Clear the interrupt. Note that this operates differently to the
* QM_ADC_INTR_STATUS regiseter because you have to write to the
* QM_ADC_OP_MODE register, Interrupt Enable bit to clear. */
QM_ADC[adc].adc_op_mode &= ~QM_ADC_OP_MODE_IE;
/* Perform a dummy conversion if we are transitioning to Normal Mode or
* Normal Mode With Calibration */
if ((QM_ADC[adc].adc_op_mode & QM_ADC_OP_MODE_OM_MASK) >=
QM_ADC_MODE_NORM_CAL) {
/* Set the first sequence register back to its default (ch 0) */
QM_ADC[adc].adc_seq0 = QM_ADC_CAL_SEQ_TABLE_DEFAULT;
/* Clear the command complete interrupt status field */
QM_ADC[adc].adc_intr_status = QM_ADC_INTR_STATUS_CC;
dummy_conversion = true;
/* Run a dummy conversion */
QM_ADC[adc].adc_cmd = (QM_ADC_CMD_IE | QM_ADC_CMD_START_SINGLE);
} else {
/* Call the user callback function */
if (mode_callback[adc]) {
mode_callback[adc](irq_xfer[adc].callback_data, 0,
QM_ADC_IDLE, QM_ADC_MODE_CHANGED);
}
}
}
/* ISR for ADC 0 Command/Calibration Complete. */
QM_ISR_DECLARE(qm_adc_0_isr)
{
qm_adc_isr_handler(QM_ADC_0);
QM_ISR_EOI(QM_IRQ_ADC_0_VECTOR);
}
/* ISR for ADC 0 Mode Change. */
QM_ISR_DECLARE(qm_adc_pwr_0_isr)
{
qm_adc_pwr_0_isr_handler(QM_ADC_0);
QM_ISR_EOI(QM_IRQ_ADC_PWR_0_VECTOR);
}
static void setup_seq_table(const qm_adc_t adc, qm_adc_xfer_t *xfer)
{
uint32_t i, offset = 0;
volatile uint32_t *reg_pointer = NULL;
/* Loop over all of the channels to be added. */
for (i = 0; i < xfer->ch_len; i++) {
/* Get a pointer to the correct address. */
reg_pointer = &QM_ADC[adc].adc_seq0 + (i / 4);
/* Get the offset within the register */
offset = ((i % 4) * 8);
/* Clear the Last bit from all entries we will use. */
*reg_pointer &= ~(1 << (offset + 7));
/* Place the channel numnber into the sequence table. */
*reg_pointer |= (xfer->ch[i] << offset);
}
if (reg_pointer) {
/* Set the correct Last bit. */
*reg_pointer |= (1 << (offset + 7));
}
}
int qm_adc_calibrate(const qm_adc_t adc)
{
QM_CHECK(adc < QM_ADC_NUM, -EINVAL);
/* Clear the command complete interrupt status field. */
QM_ADC[adc].adc_intr_status = QM_ADC_INTR_STATUS_CC;
/* Start the calibration and wait for it to complete. */
QM_ADC[adc].adc_cmd = (QM_ADC_CMD_IE | QM_ADC_CMD_START_CAL);
while (!(QM_ADC[adc].adc_intr_status & QM_ADC_INTR_STATUS_CC))
;
/* Clear the command complete interrupt status field again. */
QM_ADC[adc].adc_intr_status = QM_ADC_INTR_STATUS_CC;
return 0;
}
int qm_adc_irq_calibrate(const qm_adc_t adc,
void (*callback)(void *data, int error,
qm_adc_status_t status,
qm_adc_cb_source_t source),
void *callback_data)
{
QM_CHECK(adc < QM_ADC_NUM, -EINVAL);
/* Set the callback. */
cal_callback[adc] = callback;
cal_callback_data[adc] = callback_data;
/* Clear and enable the command complete interupt. */
QM_ADC[adc].adc_intr_status = QM_ADC_INTR_STATUS_CC;
QM_ADC[adc].adc_intr_enable |= QM_ADC_INTR_ENABLE_CC;
/* Start the calibration */
QM_ADC[adc].adc_cmd = (QM_ADC_CMD_IE | QM_ADC_CMD_START_CAL);
return 0;
}
int qm_adc_set_calibration(const qm_adc_t adc, const qm_adc_calibration_t cal)
{
QM_CHECK(adc < QM_ADC_NUM, -EINVAL);
QM_CHECK(cal < 0x3F, -EINVAL);
/* Clear the command complete interrupt status field. */
QM_ADC[adc].adc_intr_status = QM_ADC_INTR_STATUS_CC;
/* Set the calibration data and wait for it to complete. */
QM_ADC[adc].adc_cmd = ((cal << QM_ADC_CMD_CAL_DATA_OFFSET) |
QM_ADC_CMD_IE | QM_ADC_CMD_LOAD_CAL);
while (!(QM_ADC[adc].adc_intr_status & QM_ADC_INTR_STATUS_CC))
;
/* Clear the command complete interrupt status field again. */
QM_ADC[adc].adc_intr_status = QM_ADC_INTR_STATUS_CC;
return 0;
}
int qm_adc_get_calibration(const qm_adc_t adc, qm_adc_calibration_t *const cal)
{
QM_CHECK(adc < QM_ADC_NUM, -EINVAL);
QM_CHECK(NULL != cal, -EINVAL);
*cal = QM_ADC[adc].adc_calibration;
return 0;
}
int qm_adc_set_mode(const qm_adc_t adc, const qm_adc_mode_t mode)
{
QM_CHECK(adc < QM_ADC_NUM, -EINVAL);
QM_CHECK(mode <= QM_ADC_MODE_NORM_NO_CAL, -EINVAL);
/* Issue mode change command and wait for it to complete. */
QM_ADC[adc].adc_op_mode = mode;
while ((QM_ADC[adc].adc_op_mode & QM_ADC_OP_MODE_OM_MASK) != mode)
;
/* Perform a dummy conversion if we are transitioning to Normal Mode. */
if ((mode >= QM_ADC_MODE_NORM_CAL)) {
/* Set the first sequence register back to its default. */
QM_ADC[adc].adc_seq0 = QM_ADC_CAL_SEQ_TABLE_DEFAULT;
/* Clear the command complete interrupt status field. */
QM_ADC[adc].adc_intr_status = QM_ADC_INTR_STATUS_CC;
/* Run a dummy convert and wait for it to complete. */
QM_ADC[adc].adc_cmd = (QM_ADC_CMD_IE | QM_ADC_CMD_START_SINGLE);
while (!(QM_ADC[adc].adc_intr_status & QM_ADC_INTR_STATUS_CC))
;
/* Flush the FIFO to get rid of the dummy values. */
QM_ADC[adc].adc_sample = QM_ADC_FIFO_CLEAR;
/* Clear the command complete interrupt status field. */
QM_ADC[adc].adc_intr_status = QM_ADC_INTR_STATUS_CC;
}
return 0;
}
int qm_adc_irq_set_mode(const qm_adc_t adc, const qm_adc_mode_t mode,
void (*callback)(void *data, int error,
qm_adc_status_t status,
qm_adc_cb_source_t source),
void *callback_data)
{
QM_CHECK(adc < QM_ADC_NUM, -EINVAL);
QM_CHECK(mode <= QM_ADC_MODE_NORM_NO_CAL, -EINVAL);
/* Set the callback. */
mode_callback[adc] = callback;
mode_callback_data[adc] = callback_data;
/* When transitioning to Normal Mode or Normal Mode With Calibration,
* enable command complete interrupt to perform a dummy conversion. */
if ((mode >= QM_ADC_MODE_NORM_CAL)) {
QM_ADC[adc].adc_intr_enable |= QM_ADC_INTR_ENABLE_CC;
}
/* Issue mode change command. Completion if this command is notified via
* the ADC Power interrupt source, which is serviced separately to the
* Command/Calibration Complete interrupt. */
QM_ADC[adc].adc_op_mode = (QM_ADC_OP_MODE_IE | mode);
return 0;
}
int qm_adc_set_config(const qm_adc_t adc, const qm_adc_config_t *const cfg)
{
QM_CHECK(adc < QM_ADC_NUM, -EINVAL);
QM_CHECK(NULL != cfg, -EINVAL);
QM_CHECK(cfg->resolution <= QM_ADC_RES_12_BITS, -EINVAL);
/* Convert cfg->resolution to actual resolution (2x+6) and add 2 to get
* minimum value for window size. */
QM_CHECK(cfg->window >= ((cfg->resolution * 2) + 8), -EINVAL);
/* Set the sample window and resolution. */
sample_window[adc] = cfg->window;
resolution[adc] = cfg->resolution;
return 0;
}
int qm_adc_convert(const qm_adc_t adc, qm_adc_xfer_t *xfer)
{
uint32_t i;
QM_CHECK(adc < QM_ADC_NUM, -EINVAL);
QM_CHECK(NULL != xfer, -EINVAL);
QM_CHECK(NULL != xfer->ch, -EINVAL);
QM_CHECK(NULL != xfer->samples, -EINVAL);
QM_CHECK(xfer->ch_len > 0, -EINVAL);
QM_CHECK(xfer->ch_len <= QM_ADC_CHAN_SEQ_MAX, -EINVAL);
QM_CHECK(xfer->samples_len > 0, -EINVAL);
QM_CHECK(xfer->samples_len <= QM_ADC_FIFO_LEN, -EINVAL);
/* Flush the FIFO. */
QM_ADC[adc].adc_sample = QM_ADC_FIFO_CLEAR;
/* Populate the sample sequence table. */
setup_seq_table(adc, xfer);
/* Issue cmd: window & resolution, number of samples, command. */
QM_ADC[adc].adc_cmd =
(sample_window[adc] << QM_ADC_CMD_SW_OFFSET |
resolution[adc] << QM_ADC_CMD_RESOLUTION_OFFSET |
((xfer->samples_len - 1) << QM_ADC_CMD_NS_OFFSET) |
QM_ADC_CMD_START_SINGLE);
/* Wait for fifo count to reach number of samples. */
while (QM_ADC[adc].adc_fifo_count != xfer->samples_len)
;
/* Read the value into the data structure. The sample must be shifted
* right by 2, 4 or 6 bits for 10, 8 and 6 bit resolution respectively
* to get the correct value. */
for (i = 0; i < xfer->samples_len; i++) {
xfer->samples[i] =
(QM_ADC[adc].adc_sample >> (2 * (3 - resolution[adc])));
}
return 0;
}
int qm_adc_irq_convert(const qm_adc_t adc, qm_adc_xfer_t *xfer)
{
QM_CHECK(adc < QM_ADC_NUM, -EINVAL);
QM_CHECK(NULL != xfer, -EINVAL);
QM_CHECK(NULL != xfer->ch, -EINVAL);
QM_CHECK(NULL != xfer->samples, -EINVAL);
QM_CHECK(xfer->ch_len > 0, -EINVAL);
QM_CHECK(xfer->ch_len <= QM_ADC_CHAN_SEQ_MAX, -EINVAL);
QM_CHECK(xfer->samples_len > 0, -EINVAL);
/* Reset the count and flush the FIFO. */
count[adc] = 0;
QM_ADC[adc].adc_sample = QM_ADC_FIFO_CLEAR;
/* Populate the sample sequence table. */
setup_seq_table(adc, xfer);
/* Copy the xfer struct so we can get access from the ISR. */
memcpy(&irq_xfer[adc], xfer, sizeof(qm_adc_xfer_t));
/* Clear all pending interrupts. */
QM_ADC[adc].adc_intr_status = QM_ADC_INTR_STATUS_CC |
QM_ADC_INTR_STATUS_FO |
QM_ADC_INTR_STATUS_CONT_CC;
/* Enable the continuous command and fifo overrun interupts. */
QM_ADC[adc].adc_intr_enable =
QM_ADC_INTR_ENABLE_FO | QM_ADC_INTR_ENABLE_CONT_CC;
/* Issue cmd: window & resolution, number of samples, interrupt enable
* and start continuous coversion command. If xfer->samples_len is less
* than FIFO_INTERRUPT_THRESHOLD extra samples will be discarded in the
* ISR. */
QM_ADC[adc].adc_cmd =
(sample_window[adc] << QM_ADC_CMD_SW_OFFSET |
resolution[adc] << QM_ADC_CMD_RESOLUTION_OFFSET |
((FIFO_INTERRUPT_THRESHOLD - 1) << QM_ADC_CMD_NS_OFFSET) |
QM_ADC_CMD_IE | QM_ADC_CMD_START_CONT);
return 0;
}
#endif /* QUARK_D2000 */

View file

@ -0,0 +1,150 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_aon_counters.h"
static void (*callback)(void *) = NULL;
static void *callback_data;
static void pt_reset(const qm_scss_aon_t aonc)
{
static bool first_run = true;
uint32_t aonc_cfg;
/* After POR, it is required to wait for one RTC clock cycle before
* asserting QM_AONPT_CTRL_RST. Note the AON counter is enabled with an
* initial value of 0 at POR.
*/
if (first_run) {
first_run = false;
/* Ensure the AON counter is enabled */
aonc_cfg = QM_SCSS_AON[aonc].aonc_cfg;
QM_SCSS_AON[aonc].aonc_cfg = BIT(0);
while (0 == QM_SCSS_AON[aonc].aonc_cnt) {
}
QM_SCSS_AON[aonc].aonc_cfg = aonc_cfg;
}
QM_SCSS_AON[aonc].aonpt_ctrl |= BIT(1);
}
QM_ISR_DECLARE(qm_aonpt_isr_0)
{
if (callback) {
(*callback)(callback_data);
}
QM_SCSS_AON[0].aonpt_ctrl |= BIT(0); /* Clear pending interrupts */
QM_ISR_EOI(QM_IRQ_AONPT_0_VECTOR);
}
int qm_aonc_enable(const qm_scss_aon_t aonc)
{
QM_CHECK(aonc < QM_SCSS_AON_NUM, -EINVAL);
QM_SCSS_AON[aonc].aonc_cfg = 0x1;
return 0;
}
int qm_aonc_disable(const qm_scss_aon_t aonc)
{
QM_CHECK(aonc < QM_SCSS_AON_NUM, -EINVAL);
QM_SCSS_AON[aonc].aonc_cfg = 0x0;
return 0;
}
int qm_aonc_get_value(const qm_scss_aon_t aonc, uint32_t * const val)
{
QM_CHECK(aonc < QM_SCSS_AON_NUM, -EINVAL);
QM_CHECK(val != NULL, -EINVAL);
*val = QM_SCSS_AON[aonc].aonc_cnt;
return 0;
}
int qm_aonpt_set_config(const qm_scss_aon_t aonc,
const qm_aonpt_config_t *const cfg)
{
QM_CHECK(aonc < QM_SCSS_AON_NUM, -EINVAL);
QM_CHECK(cfg != NULL, -EINVAL);
QM_SCSS_AON[aonc].aonpt_ctrl |= BIT(0); /* Clear pending interrupts */
QM_SCSS_AON[aonc].aonpt_cfg = cfg->count;
if (cfg->int_en) {
callback = cfg->callback;
callback_data = cfg->callback_data;
} else {
callback = NULL;
}
pt_reset(aonc);
return 0;
}
int qm_aonpt_get_value(const qm_scss_aon_t aonc, uint32_t *const val)
{
QM_CHECK(aonc < QM_SCSS_AON_NUM, -EINVAL);
QM_CHECK(val != NULL, -EINVAL);
*val = QM_SCSS_AON[aonc].aonpt_cnt;
return 0;
}
int qm_aonpt_get_status(const qm_scss_aon_t aonc, bool *const status)
{
QM_CHECK(aonc < QM_SCSS_AON_NUM, -EINVAL);
QM_CHECK(status != NULL, -EINVAL);
*status = QM_SCSS_AON[aonc].aonpt_stat & BIT(0);
return 0;
}
int qm_aonpt_clear(const qm_scss_aon_t aonc)
{
QM_CHECK(aonc < QM_SCSS_AON_NUM, -EINVAL);
QM_SCSS_AON[aonc].aonpt_ctrl |= BIT(0);
return 0;
}
int qm_aonpt_reset(const qm_scss_aon_t aonc)
{
QM_CHECK(aonc < QM_SCSS_AON_NUM, -EINVAL);
pt_reset(aonc);
return 0;
}

View file

@ -0,0 +1,82 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_comparator.h"
static void (*callback)(void *, uint32_t) = NULL;
static void *callback_data;
QM_ISR_DECLARE(qm_ac_isr)
{
uint32_t int_status = QM_SCSS_CMP->cmp_stat_clr;
#if (QUARK_D2000)
/*
* If the SoC is in deep sleep mode, all the clocks are gated, if the
* interrupt source is cleared before the oscillators are ungated, the
* oscillators return to a powered down state and the SoC will not
* return to an active state then.
*/
if ((QM_SCSS_GP->gps1 & QM_SCSS_GP_POWER_STATES_MASK) ==
QM_SCSS_GP_POWER_STATE_DEEP_SLEEP) {
/* Return the oscillators to an active state. */
QM_SCSS_CCU->osc0_cfg1 &= ~QM_OSC0_PD;
QM_SCSS_CCU->osc1_cfg0 &= ~QM_OSC1_PD;
/* HYB_OSC_PD_LATCH_EN = 1, RTC_OSC_PD_LATCH_EN=1 */
QM_SCSS_CCU->ccu_lp_clk_ctl |=
(QM_HYB_OSC_PD_LATCH_EN | QM_RTC_OSC_PD_LATCH_EN);
}
#endif
if (callback) {
(*callback)(callback_data, int_status);
}
/* Clear all pending interrupts */
QM_SCSS_CMP->cmp_stat_clr = int_status;
QM_ISR_EOI(QM_IRQ_AC_VECTOR);
}
int qm_ac_set_config(const qm_ac_config_t *const config)
{
QM_CHECK(config != NULL, -EINVAL);
callback = config->callback;
callback_data = config->callback_data;
QM_SCSS_CMP->cmp_ref_sel = config->reference;
QM_SCSS_CMP->cmp_ref_pol = config->polarity;
QM_SCSS_CMP->cmp_pwr = config->power;
/* Clear all pending interrupts before we enable */
QM_SCSS_CMP->cmp_stat_clr = 0x7FFFF;
QM_SCSS_CMP->cmp_en = config->int_en;
return 0;
}

View file

@ -0,0 +1,393 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "dma.h"
#ifndef UNIT_TEST
qm_dma_reg_t *qm_dma[QM_DMA_NUM] = {(qm_dma_reg_t *)QM_DMA_BASE};
#endif
/* DMA driver private data structures */
dma_cfg_prv_t dma_channel_config[QM_DMA_NUM][QM_DMA_CHANNEL_NUM] = {{{0}}};
/*
* Transfer interrupt handler.
*/
static void qm_dma_isr_handler(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id)
{
uint32_t transfer_length;
dma_cfg_prv_t *chan_cfg;
volatile qm_dma_int_reg_t *int_reg = &QM_DMA[dma]->int_reg;
QM_ASSERT(int_reg->status_int_low & QM_DMA_INT_STATUS_TFR);
QM_ASSERT(int_reg->status_tfr_low & BIT(channel_id));
/* Clear interrupt */
int_reg->clear_tfr_low = BIT(channel_id);
/* Mask interrupts for this channel */
int_reg->mask_tfr_low = BIT(channel_id) << 8;
int_reg->mask_err_low = BIT(channel_id) << 8;
/* Call the callback if registered and pass the
* transfer length */
chan_cfg = &dma_channel_config[dma][channel_id];
if (chan_cfg->client_callback) {
transfer_length = get_transfer_length(dma, channel_id);
chan_cfg->client_callback(chan_cfg->callback_context,
transfer_length, 0);
}
}
/*
* Error interrupt handler.
*/
static void qm_dma_isr_err_handler(const qm_dma_t dma)
{
uint32_t interrupt_channel_mask;
dma_cfg_prv_t *chan_cfg;
qm_dma_channel_id_t channel_id = 0;
volatile qm_dma_int_reg_t *int_reg = &QM_DMA[dma]->int_reg;
QM_ASSERT(int_reg->status_int_low & QM_DMA_INT_STATUS_ERR);
QM_ASSERT(int_reg->status_err_low);
interrupt_channel_mask = int_reg->status_err_low;
while (interrupt_channel_mask) {
/* Find the channel that the interrupt is for */
if (!(interrupt_channel_mask & 0x1)) {
interrupt_channel_mask >>= 1;
channel_id++;
continue;
}
/* Clear the error interrupt for this channel */
int_reg->clear_err_low = BIT(channel_id);
/* Mask interrupts for this channel */
int_reg->mask_tfr_low = BIT(channel_id) << 8;
int_reg->mask_err_low = BIT(channel_id) << 8;
/* Call the callback if registered and pass the
* transfer error code */
chan_cfg = &dma_channel_config[dma][channel_id];
if (chan_cfg->client_callback) {
chan_cfg->client_callback(chan_cfg->callback_context, 0,
-EIO);
}
interrupt_channel_mask >>= 1;
channel_id++;
}
}
QM_ISR_DECLARE(qm_dma_0_isr_err)
{
qm_dma_isr_err_handler(QM_DMA_0);
QM_ISR_EOI(QM_IRQ_DMA_ERR_VECTOR);
}
QM_ISR_DECLARE(qm_dma_0_isr_0)
{
qm_dma_isr_handler(QM_DMA_0, QM_DMA_CHANNEL_0);
QM_ISR_EOI(QM_IRQ_DMA_0_VECTOR);
}
QM_ISR_DECLARE(qm_dma_0_isr_1)
{
qm_dma_isr_handler(QM_DMA_0, QM_DMA_CHANNEL_1);
QM_ISR_EOI(QM_IRQ_DMA_1_VECTOR);
}
#if (QUARK_SE)
QM_ISR_DECLARE(qm_dma_0_isr_2)
{
qm_dma_isr_handler(QM_DMA_0, QM_DMA_CHANNEL_2);
QM_ISR_EOI(QM_IRQ_DMA_2_VECTOR);
}
QM_ISR_DECLARE(qm_dma_0_isr_3)
{
qm_dma_isr_handler(QM_DMA_0, QM_DMA_CHANNEL_3);
QM_ISR_EOI(QM_IRQ_DMA_3_VECTOR);
}
QM_ISR_DECLARE(qm_dma_0_isr_4)
{
qm_dma_isr_handler(QM_DMA_0, QM_DMA_CHANNEL_4);
QM_ISR_EOI(QM_IRQ_DMA_4_VECTOR);
}
QM_ISR_DECLARE(qm_dma_0_isr_5)
{
qm_dma_isr_handler(QM_DMA_0, QM_DMA_CHANNEL_5);
QM_ISR_EOI(QM_IRQ_DMA_5_VECTOR);
}
QM_ISR_DECLARE(qm_dma_0_isr_6)
{
qm_dma_isr_handler(QM_DMA_0, QM_DMA_CHANNEL_6);
QM_ISR_EOI(QM_IRQ_DMA_6_VECTOR);
}
QM_ISR_DECLARE(qm_dma_0_isr_7)
{
qm_dma_isr_handler(QM_DMA_0, QM_DMA_CHANNEL_7);
QM_ISR_EOI(QM_IRQ_DMA_7_VECTOR);
}
#endif /* QUARK_SE */
int qm_dma_init(const qm_dma_t dma)
{
QM_CHECK(dma < QM_DMA_NUM, -EINVAL);
qm_dma_channel_id_t channel_id;
volatile qm_dma_int_reg_t *int_reg = &QM_DMA[dma]->int_reg;
int return_code;
/* Enable the DMA Clock */
QM_SCSS_CCU->ccu_mlayer_ahb_ctl |= QM_CCU_DMA_CLK_EN;
/* Disable the controller */
return_code = dma_controller_disable(dma);
if (return_code) {
return return_code;
}
/* Disable the channels and interrupts */
for (channel_id = 0; channel_id < QM_DMA_CHANNEL_NUM; channel_id++) {
return_code = dma_channel_disable(dma, channel_id);
if (return_code) {
return return_code;
}
dma_interrupt_disable(dma, channel_id);
}
/* Mask all interrupts */
int_reg->mask_tfr_low = CHANNEL_MASK_ALL << 8;
int_reg->mask_block_low = CHANNEL_MASK_ALL << 8;
int_reg->mask_src_trans_low = CHANNEL_MASK_ALL << 8;
int_reg->mask_dst_trans_low = CHANNEL_MASK_ALL << 8;
int_reg->mask_err_low = CHANNEL_MASK_ALL << 8;
/* Clear all interrupts */
int_reg->clear_tfr_low = CHANNEL_MASK_ALL;
int_reg->clear_block_low = CHANNEL_MASK_ALL;
int_reg->clear_src_trans_low = CHANNEL_MASK_ALL;
int_reg->clear_dst_trans_low = CHANNEL_MASK_ALL;
int_reg->clear_err_low = CHANNEL_MASK_ALL;
/* Enable the controller */
dma_controller_enable(dma);
return 0;
}
int qm_dma_channel_set_config(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
qm_dma_channel_config_t *const channel_config)
{
QM_CHECK(dma < QM_DMA_NUM, -EINVAL);
QM_CHECK(channel_id < QM_DMA_CHANNEL_NUM, -EINVAL);
QM_CHECK(channel_config != NULL, -EINVAL);
dma_cfg_prv_t *chan_cfg = &dma_channel_config[dma][channel_id];
int return_code;
/* Set the transfer type. Only one currently supported */
return_code =
dma_set_transfer_type(dma, channel_id, QM_DMA_TYPE_SINGLE);
if (return_code) {
return return_code;
}
/* Set the source and destination transfer width. */
dma_set_source_transfer_width(dma, channel_id,
channel_config->source_transfer_width);
dma_set_destination_transfer_width(
dma, channel_id, channel_config->destination_transfer_width);
/* Set the source and destination burst transfer length. */
dma_set_source_burst_length(dma, channel_id,
channel_config->source_burst_length);
dma_set_destination_burst_length(
dma, channel_id, channel_config->destination_burst_length);
/* Set channel direction */
dma_set_transfer_direction(dma, channel_id,
channel_config->channel_direction);
/* Set the increment type depending on direction */
switch (channel_config->channel_direction) {
case QM_DMA_PERIPHERAL_TO_MEMORY:
dma_set_source_increment(dma, channel_id,
QM_DMA_ADDRESS_NO_CHANGE);
dma_set_destination_increment(dma, channel_id,
QM_DMA_ADDRESS_INCREMENT);
break;
case QM_DMA_MEMORY_TO_PERIPHERAL:
dma_set_source_increment(dma, channel_id,
QM_DMA_ADDRESS_INCREMENT);
dma_set_destination_increment(dma, channel_id,
QM_DMA_ADDRESS_NO_CHANGE);
break;
case QM_DMA_MEMORY_TO_MEMORY:
dma_set_source_increment(dma, channel_id,
QM_DMA_ADDRESS_INCREMENT);
dma_set_destination_increment(dma, channel_id,
QM_DMA_ADDRESS_INCREMENT);
break;
}
if (channel_config->channel_direction != QM_DMA_MEMORY_TO_MEMORY) {
/* Set the handshake interface. */
dma_set_handshake_interface(
dma, channel_id, channel_config->handshake_interface);
/* Set the handshake type. This is hardcoded to hardware */
dma_set_handshake_type(dma, channel_id, 0);
/* Set the handshake polarity. */
dma_set_handshake_polarity(dma, channel_id,
channel_config->handshake_polarity);
}
/* Save the client ID */
chan_cfg->callback_context = channel_config->callback_context;
/* Save the callback provided by DMA client */
chan_cfg->client_callback = channel_config->client_callback;
return 0;
}
int qm_dma_transfer_set_config(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
qm_dma_transfer_t *const transfer_config)
{
QM_CHECK(dma < QM_DMA_NUM, -EINVAL);
QM_CHECK(channel_id < QM_DMA_CHANNEL_NUM, -EINVAL);
QM_CHECK(transfer_config != NULL, -EINVAL);
QM_CHECK(transfer_config->source_address != NULL, -EINVAL);
QM_CHECK(transfer_config->destination_address != NULL, -EINVAL);
QM_CHECK(transfer_config->block_size >= QM_DMA_CTL_H_BLOCK_TS_MIN,
-EINVAL);
QM_CHECK(transfer_config->block_size <= QM_DMA_CTL_H_BLOCK_TS_MAX,
-EINVAL);
/* Set the source and destination addresses. */
dma_set_source_address(dma, channel_id,
(uint32_t)transfer_config->source_address);
dma_set_destination_address(
dma, channel_id, (uint32_t)transfer_config->destination_address);
/* Set the block size for the transfer. */
dma_set_block_size(dma, channel_id, transfer_config->block_size);
return 0;
}
int qm_dma_transfer_start(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id)
{
QM_CHECK(dma < QM_DMA_NUM, -EINVAL);
QM_CHECK(channel_id < QM_DMA_CHANNEL_NUM, -EINVAL);
volatile qm_dma_int_reg_t *int_reg = &QM_DMA[dma]->int_reg;
/* Unmask Interrupts */
int_reg->mask_tfr_low = ((BIT(channel_id) << 8) | BIT(channel_id));
int_reg->mask_err_low = ((BIT(channel_id) << 8) | BIT(channel_id));
/* Enable interrupts and the channel */
dma_interrupt_enable(dma, channel_id);
dma_channel_enable(dma, channel_id);
return 0;
}
int qm_dma_transfer_terminate(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id)
{
QM_CHECK(dma < QM_DMA_NUM, -EINVAL);
QM_CHECK(channel_id < QM_DMA_CHANNEL_NUM, -EINVAL);
dma_cfg_prv_t *chan_cfg;
int return_code;
uint32_t transfer_length;
volatile qm_dma_int_reg_t *int_reg = &QM_DMA[dma]->int_reg;
/* Disable interrupts for the channel */
dma_interrupt_disable(dma, channel_id);
/* Mask Interrupts */
int_reg->mask_tfr_low = (BIT(channel_id) << 8);
int_reg->mask_err_low = (BIT(channel_id) << 8);
/* The channel is disabled and the transfer complete callback is
* triggered. This callback provides the client with the data length
* transfered before the transfer was stopped. */
return_code = dma_channel_disable(dma, channel_id);
if (!return_code) {
chan_cfg = &dma_channel_config[dma][channel_id];
if (chan_cfg->client_callback) {
transfer_length = get_transfer_length(dma, channel_id);
chan_cfg->client_callback(chan_cfg->callback_context,
transfer_length, 0);
}
}
return return_code;
}
int qm_dma_transfer_mem_to_mem(const qm_dma_t dma,
const qm_dma_channel_id_t channel_id,
qm_dma_transfer_t *const transfer_config)
{
QM_CHECK(dma < QM_DMA_NUM, -EINVAL);
QM_CHECK(channel_id < QM_DMA_CHANNEL_NUM, -EINVAL);
QM_CHECK(transfer_config != NULL, -EINVAL);
QM_CHECK(transfer_config->source_address != NULL, -EINVAL);
QM_CHECK(transfer_config->destination_address != NULL, -EINVAL);
QM_CHECK(transfer_config->block_size <= QM_DMA_CTL_H_BLOCK_TS_MAX,
-EINVAL);
int return_code;
/* Set the transfer configuration and start the transfer */
return_code =
qm_dma_transfer_set_config(dma, channel_id, transfer_config);
if (!return_code) {
return_code = qm_dma_transfer_start(dma, channel_id);
}
return return_code;
}

View file

@ -0,0 +1,326 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_flash.h"
#ifndef UNIT_TEST
#if (QUARK_SE)
qm_flash_reg_t *qm_flash[QM_FLASH_NUM] = {(qm_flash_reg_t *)QM_FLASH_BASE_0,
(qm_flash_reg_t *)QM_FLASH_BASE_1};
#elif(QUARK_D2000)
qm_flash_reg_t *qm_flash[QM_FLASH_NUM] = {(qm_flash_reg_t *)QM_FLASH_BASE_0};
#endif
#endif
int qm_flash_set_config(const qm_flash_t flash, const qm_flash_config_t *cfg)
{
QM_CHECK(flash < QM_FLASH_NUM, -EINVAL);
QM_CHECK(cfg != NULL, -EINVAL);
QM_CHECK(cfg->wait_states <= QM_FLASH_MAX_WAIT_STATES, -EINVAL);
QM_CHECK(cfg->us_count <= QM_FLASH_MAX_US_COUNT, -EINVAL);
QM_CHECK(cfg->write_disable <= QM_FLASH_WRITE_DISABLE, -EINVAL);
qm_flash_reg_t *const controller = QM_FLASH[flash];
controller->tmg_ctrl =
(controller->tmg_ctrl & QM_FLASH_TMG_DEF_MASK) |
(cfg->us_count | (cfg->wait_states << QM_FLASH_WAIT_STATE_OFFSET));
if (QM_FLASH_WRITE_DISABLE == cfg->write_disable) {
controller->ctrl |= QM_FLASH_WRITE_DISABLE_VAL;
} else {
controller->ctrl &= ~QM_FLASH_WRITE_DISABLE_VAL;
}
return 0;
}
int qm_flash_word_write(const qm_flash_t flash, const qm_flash_region_t region,
uint32_t f_addr, const uint32_t data)
{
QM_CHECK(flash < QM_FLASH_NUM, -EINVAL);
QM_CHECK(region <= QM_FLASH_REGION_NUM, -EINVAL);
QM_CHECK(f_addr < QM_FLASH_MAX_ADDR, -EINVAL);
volatile uint32_t *p_wr_data, *p_wr_ctrl;
qm_flash_reg_t *const controller = QM_FLASH[flash];
/* Rom and flash write registers are laid out the same, but different */
/* locations in memory, so point to those to have the same function to*/
/* update page section based on main or rom. */
switch (region) {
case QM_FLASH_REGION_SYS:
p_wr_data = &controller->flash_wr_data;
p_wr_ctrl = &controller->flash_wr_ctrl;
#if (QUARK_D2000)
/* Main flash memory starts after flash data section. */
f_addr += QM_FLASH_REGION_DATA_0_SIZE;
#endif
break;
#if (QUARK_D2000)
case QM_FLASH_REGION_DATA:
p_wr_data = &controller->flash_wr_data;
p_wr_ctrl = &controller->flash_wr_ctrl;
break;
#endif
case QM_FLASH_REGION_OTP:
p_wr_data = &controller->rom_wr_data;
p_wr_ctrl = &controller->rom_wr_ctrl;
break;
default:
return -EINVAL;
break;
}
/* Update address to include the write_address offset. */
f_addr <<= WR_ADDR_OFFSET;
*p_wr_data = data;
*p_wr_ctrl = f_addr |= WR_REQ;
/* Wait for write to finish. */
while (!(controller->flash_stts & WR_DONE))
;
return 0;
}
int qm_flash_page_write(const qm_flash_t flash, const qm_flash_region_t region,
uint32_t page_num, const uint32_t *const data,
uint32_t len)
{
QM_CHECK(flash < QM_FLASH_NUM, -EINVAL);
QM_CHECK(region <= QM_FLASH_REGION_NUM, -EINVAL);
QM_CHECK(page_num <= QM_FLASH_MAX_PAGE_NUM, -EINVAL);
QM_CHECK(data != NULL, -EINVAL);
QM_CHECK(len <= QM_FLASH_PAGE_SIZE_DWORDS, -EINVAL);
uint32_t i;
volatile uint32_t *p_wr_data, *p_wr_ctrl;
qm_flash_reg_t *const controller = QM_FLASH[flash];
/* Rom and flash write registers are laid out the same, but different */
/* locations in memory, so point to those to have the same function to*/
/* update page section based on main or rom. */
switch (region) {
case QM_FLASH_REGION_SYS:
#if (QUARK_D2000)
page_num += QM_FLASH_REGION_DATA_0_PAGES;
case QM_FLASH_REGION_DATA:
#endif
p_wr_data = &controller->flash_wr_data;
p_wr_ctrl = &controller->flash_wr_ctrl;
break;
case QM_FLASH_REGION_OTP:
p_wr_data = &controller->rom_wr_data;
p_wr_ctrl = &controller->rom_wr_ctrl;
break;
default:
return -EINVAL;
break;
}
/* Update address to include the write_address offset. */
page_num <<= (QM_FLASH_PAGE_SIZE_BITS + WR_ADDR_OFFSET);
/* Erase the Flash page. */
*p_wr_ctrl = page_num | ER_REQ;
/* Wait for the erase to complete. */
while (!(controller->flash_stts & ER_DONE))
;
/* Write bytes into Flash. */
for (i = 0; i < len; i++) {
*p_wr_data = data[i];
*p_wr_ctrl = page_num;
*p_wr_ctrl |= WR_REQ;
page_num += QM_FLASH_ADDR_INC;
/* Wait for write to finish. */
while (!(controller->flash_stts & WR_DONE))
;
}
return 0;
}
int qm_flash_page_update(const qm_flash_t flash, const qm_flash_region_t region,
uint32_t f_addr, uint32_t *const page_buffer,
const uint32_t *const data_buffer, uint32_t len)
{
QM_CHECK(flash < QM_FLASH_NUM, -EINVAL);
QM_CHECK(region <= QM_FLASH_REGION_NUM, -EINVAL);
QM_CHECK(f_addr < QM_FLASH_MAX_ADDR, -EINVAL);
QM_CHECK(page_buffer != NULL, -EINVAL);
QM_CHECK(data_buffer != NULL, -EINVAL);
QM_CHECK(len <= QM_FLASH_PAGE_SIZE_DWORDS, -EINVAL);
uint32_t i, j;
volatile uint32_t *p_flash = NULL, *p_wr_data, *p_wr_ctrl;
qm_flash_reg_t *const controller = QM_FLASH[flash];
/* Rom and flash write registers are laid out the same, but different */
/* locations in memory, so point to those to have the same function to*/
/* update page section based on main or rom. */
switch (region) {
case QM_FLASH_REGION_SYS:
p_wr_data = &controller->flash_wr_data;
p_wr_ctrl = &controller->flash_wr_ctrl;
#if (QUARK_D2000)
p_flash = (uint32_t *)(QM_FLASH_REGION_SYS_0_BASE +
(f_addr & QM_FLASH_PAGE_MASK));
/* Main flash memory starts after flash data section. */
f_addr += QM_FLASH_REGION_DATA_0_SIZE;
#elif(QUARK_SE)
if (flash == QM_FLASH_0) {
p_flash = (uint32_t *)(QM_FLASH_REGION_SYS_0_BASE +
(f_addr & QM_FLASH_PAGE_MASK));
} else {
p_flash = (uint32_t *)(QM_FLASH_REGION_SYS_1_BASE +
(f_addr & QM_FLASH_PAGE_MASK));
}
#else
#error("Unsupported / unspecified processor type")
#endif
break;
#if (QUARK_D2000)
case QM_FLASH_REGION_DATA:
p_wr_data = &controller->flash_wr_data;
p_wr_ctrl = &controller->flash_wr_ctrl;
p_flash = (uint32_t *)(QM_FLASH_REGION_DATA_0_BASE +
(f_addr & QM_FLASH_PAGE_MASK));
break;
#endif
case QM_FLASH_REGION_OTP:
p_wr_data = &controller->rom_wr_data;
p_wr_ctrl = &controller->rom_wr_ctrl;
p_flash = (uint32_t *)(QM_FLASH_REGION_OTP_0_BASE +
(f_addr & QM_FLASH_PAGE_MASK));
break;
default:
return -EINVAL;
break;
}
/* Copy Flash Page, with location to be modified, to SRAM */
for (i = 0; i < QM_FLASH_PAGE_SIZE_DWORDS; i++) {
page_buffer[i] = *p_flash;
p_flash++;
}
/* Erase the Flash page */
*p_wr_ctrl = ((f_addr & QM_FLASH_PAGE_MASK) << WR_ADDR_OFFSET) | ER_REQ;
/* Update sram data with new data */
j = (f_addr & QM_FLASH_ADDRESS_MASK) >> 2;
for (i = 0; i < len; i++, j++) {
page_buffer[j] = data_buffer[i];
}
/* Wait for the erase to complete */
while (!(controller->flash_stts & ER_DONE))
;
/* Update address to include the write_address offset. */
f_addr &= QM_FLASH_PAGE_MASK;
f_addr <<= WR_ADDR_OFFSET;
/* Copy the modified page in SRAM into Flash. */
for (i = 0; i < QM_FLASH_PAGE_SIZE_DWORDS; i++) {
*p_wr_data = page_buffer[i];
*p_wr_ctrl = f_addr |= WR_REQ;
f_addr += QM_FLASH_ADDR_INC;
/* Wait for write to finish. */
while (!(controller->flash_stts & WR_DONE))
;
}
return 0;
}
int qm_flash_page_erase(const qm_flash_t flash, const qm_flash_region_t region,
uint32_t page_num)
{
QM_CHECK(flash < QM_FLASH_NUM, -EINVAL);
QM_CHECK(region <= QM_FLASH_REGION_NUM, -EINVAL);
QM_CHECK(page_num <= QM_FLASH_MAX_PAGE_NUM, -EINVAL);
qm_flash_reg_t *const controller = QM_FLASH[flash];
switch (region) {
case QM_FLASH_REGION_SYS:
#if (QUARK_D2000)
page_num += QM_FLASH_REGION_DATA_0_PAGES;
case QM_FLASH_REGION_DATA:
#endif
controller->flash_wr_ctrl =
(page_num << (QM_FLASH_PAGE_SIZE_BITS + WR_ADDR_OFFSET)) |
ER_REQ;
break;
case QM_FLASH_REGION_OTP:
controller->rom_wr_ctrl =
(page_num << (QM_FLASH_PAGE_SIZE_BITS + WR_ADDR_OFFSET)) |
ER_REQ;
break;
default:
return -EINVAL;
}
while (!(controller->flash_stts & ER_DONE))
;
return 0;
}
int qm_flash_mass_erase(const qm_flash_t flash, const uint8_t include_rom)
{
QM_CHECK(flash < QM_FLASH_NUM, -EINVAL);
qm_flash_reg_t *const controller = QM_FLASH[flash];
/* Erase all the Flash pages */
if (include_rom) {
controller->ctrl |= MASS_ERASE_INFO;
}
controller->ctrl |= MASS_ERASE;
while (!(controller->flash_stts & ER_DONE))
;
return 0;
}

View file

@ -0,0 +1,158 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_fpr.h"
#include "qm_interrupt.h"
static void (*callback[QM_FLASH_NUM])(void *);
static void *callback_data[QM_FLASH_NUM];
QM_ISR_DECLARE(qm_fpr_isr_0)
{
(*callback[QM_FLASH_0])(callback_data[QM_FLASH_0]);
QM_FLASH[QM_FLASH_0]->mpr_vsts = QM_FPR_MPR_VSTS_VALID;
QM_ISR_EOI(QM_IRQ_FLASH_0_VECTOR);
}
#if (QUARK_SE)
QM_ISR_DECLARE(qm_fpr_isr_1)
{
(*callback[QM_FLASH_1])(callback_data[QM_FLASH_1]);
QM_FLASH[QM_FLASH_1]->mpr_vsts = QM_FPR_MPR_VSTS_VALID;
QM_ISR_EOI(QM_IRQ_FLASH_1_VECTOR);
}
#endif
int qm_fpr_set_config(const qm_flash_t flash, const qm_fpr_id_t id,
const qm_fpr_config_t *const cfg,
const qm_flash_region_type_t region)
{
QM_CHECK(flash < QM_FLASH_NUM, -EINVAL);
QM_CHECK(id < QM_FPR_NUM, -EINVAL);
QM_CHECK(region < QM_MAIN_FLASH_NUM, -EINVAL);
QM_CHECK(cfg != NULL, -EINVAL);
QM_CHECK(cfg->low_bound <= cfg->up_bound, -EINVAL);
qm_flash_reg_t *const controller = QM_FLASH[flash];
controller->fpr_rd_cfg[id] &= ~QM_FPR_LOCK;
if (region == QM_MAIN_FLASH_SYSTEM) {
controller->fpr_rd_cfg[id] =
(cfg->allow_agents << QM_FPR_RD_ALLOW_OFFSET) |
((cfg->up_bound + QM_FLASH_REGION_DATA_BASE_OFFSET)
<< QM_FPR_UPPER_BOUND_OFFSET) |
(cfg->low_bound + QM_FLASH_REGION_DATA_BASE_OFFSET);
}
#if (QUARK_D2000)
else if (region == QM_MAIN_FLASH_DATA) {
controller->fpr_rd_cfg[id] =
(cfg->allow_agents << QM_FPR_RD_ALLOW_OFFSET) |
(cfg->up_bound << QM_FPR_UPPER_BOUND_OFFSET) |
cfg->low_bound;
}
#endif
/* qm_fpr_id_t enable/lock */
controller->fpr_rd_cfg[id] |= (cfg->en_mask << QM_FPR_ENABLE_OFFSET);
return 0;
}
int qm_fpr_set_violation_policy(const qm_fpr_viol_mode_t mode,
const qm_flash_t flash,
qm_fpr_callback_t callback_fn, void *data)
{
QM_CHECK(mode <= FPR_VIOL_MODE_PROBE, -EINVAL);
QM_CHECK(flash < QM_FLASH_NUM, -EINVAL);
volatile uint32_t *int_flash_controller_mask =
&QM_SCSS_INT->int_flash_controller_0_mask;
/* interrupt mode */
if (FPR_VIOL_MODE_INTERRUPT == mode) {
callback[flash] = callback_fn;
callback_data[flash] = data;
/* unmask interrupt */
if (flash == QM_FLASH_0) {
qm_irq_unmask(QM_IRQ_FLASH_0);
#if (QUARK_SE)
} else {
qm_irq_unmask(QM_IRQ_FLASH_1);
#endif
}
#if defined(QM_SENSOR)
int_flash_controller_mask[flash] |=
QM_INT_FLASH_CONTROLLER_SS_HALT_MASK;
#else /* QM_SENSOR */
int_flash_controller_mask[flash] |=
QM_INT_FLASH_CONTROLLER_HOST_HALT_MASK;
#endif /* QM_SENSOR */
QM_SCSS_PMU->p_sts &= ~QM_P_STS_HALT_INTERRUPT_REDIRECTION;
}
/* probe or reset mode */
else {
/* mask interrupt */
if (flash == QM_FLASH_0) {
qm_irq_mask(QM_IRQ_FLASH_0);
#if (QUARK_SE)
} else {
qm_irq_mask(QM_IRQ_FLASH_1);
#endif
}
#if defined(QM_SENSOR)
int_flash_controller_mask[flash] &=
~QM_INT_FLASH_CONTROLLER_SS_HALT_MASK;
#else /* QM_SENSOR */
int_flash_controller_mask[flash] &=
~QM_INT_FLASH_CONTROLLER_HOST_HALT_MASK;
#endif /* QM_SENSOR */
if (FPR_VIOL_MODE_PROBE == mode) {
/* When an enabled host halt interrupt occurs, this bit
* determines if the interrupt event triggers a warm
* reset
* or an entry into Probe Mode.
* 0b : Warm Reset
* 1b : Probe Mode Entry
*/
QM_SCSS_PMU->p_sts |=
QM_P_STS_HALT_INTERRUPT_REDIRECTION;
} else {
QM_SCSS_PMU->p_sts &=
~QM_P_STS_HALT_INTERRUPT_REDIRECTION;
}
}
return 0;
}

View file

@ -0,0 +1,161 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_gpio.h"
#ifndef UNIT_TEST
#if (QUARK_SE)
qm_gpio_reg_t *qm_gpio[QM_GPIO_NUM] = {(qm_gpio_reg_t *)QM_GPIO_BASE,
(qm_gpio_reg_t *)QM_AON_GPIO_BASE};
#elif(QUARK_D2000)
qm_gpio_reg_t *qm_gpio[QM_GPIO_NUM] = {(qm_gpio_reg_t *)QM_GPIO_BASE};
#endif
#endif
static void (*callback[QM_GPIO_NUM])(void *, uint32_t);
static void *callback_data[QM_GPIO_NUM];
static void gpio_isr(const qm_gpio_t gpio)
{
const uint32_t int_status = QM_GPIO[gpio]->gpio_intstatus;
if (callback[gpio]) {
(*callback[gpio])(callback_data[gpio], int_status);
}
/* This will clear all pending interrupts flags in status */
QM_GPIO[gpio]->gpio_porta_eoi = int_status;
/* Read back EOI register to avoid a spurious interrupt due to EOI
* propagation delay */
QM_GPIO[gpio]->gpio_porta_eoi;
}
QM_ISR_DECLARE(qm_gpio_isr_0)
{
gpio_isr(QM_GPIO_0);
QM_ISR_EOI(QM_IRQ_GPIO_0_VECTOR);
}
#if (HAS_AON_GPIO)
QM_ISR_DECLARE(qm_aon_gpio_isr_0)
{
gpio_isr(QM_AON_GPIO_0);
QM_ISR_EOI(QM_IRQ_AONGPIO_0_VECTOR);
}
#endif
int qm_gpio_set_config(const qm_gpio_t gpio,
const qm_gpio_port_config_t *const cfg)
{
QM_CHECK(gpio < QM_GPIO_NUM, -EINVAL);
QM_CHECK(cfg != NULL, -EINVAL);
qm_gpio_reg_t *const controller = QM_GPIO[gpio];
uint32_t mask = controller->gpio_intmask;
controller->gpio_intmask = 0xffffffff;
controller->gpio_swporta_ddr = cfg->direction;
controller->gpio_inten = cfg->int_en;
controller->gpio_inttype_level = cfg->int_type;
controller->gpio_int_polarity = cfg->int_polarity;
controller->gpio_debounce = cfg->int_debounce;
controller->gpio_int_bothedge = cfg->int_bothedge;
callback[gpio] = cfg->callback;
callback_data[gpio] = cfg->callback_data;
controller->gpio_intmask = mask;
return 0;
}
int qm_gpio_read_pin(const qm_gpio_t gpio, const uint8_t pin,
qm_gpio_state_t *const state)
{
QM_CHECK(gpio < QM_GPIO_NUM, -EINVAL);
QM_CHECK(pin <= QM_NUM_GPIO_PINS, -EINVAL);
QM_CHECK(state != NULL, -EINVAL);
*state = ((QM_GPIO[gpio]->gpio_ext_porta) >> pin) & 1;
return 0;
}
int qm_gpio_set_pin(const qm_gpio_t gpio, const uint8_t pin)
{
QM_CHECK(gpio < QM_GPIO_NUM, -EINVAL);
QM_CHECK(pin <= QM_NUM_GPIO_PINS, -EINVAL);
QM_GPIO[gpio]->gpio_swporta_dr |= (1 << pin);
return 0;
}
int qm_gpio_clear_pin(const qm_gpio_t gpio, const uint8_t pin)
{
QM_CHECK(gpio < QM_GPIO_NUM, -EINVAL);
QM_CHECK(pin <= QM_NUM_GPIO_PINS, -EINVAL);
QM_GPIO[gpio]->gpio_swporta_dr &= ~(1 << pin);
return 0;
}
int qm_gpio_set_pin_state(const qm_gpio_t gpio, const uint8_t pin,
const qm_gpio_state_t state)
{
QM_CHECK(gpio < QM_GPIO_NUM, -EINVAL);
QM_CHECK(pin <= QM_NUM_GPIO_PINS, -EINVAL);
QM_CHECK(state < QM_GPIO_STATE_NUM, -EINVAL);
uint32_t reg = QM_GPIO[gpio]->gpio_swporta_dr;
reg ^= (-state ^ reg) & (1 << pin);
QM_GPIO[gpio]->gpio_swporta_dr = reg;
return 0;
}
int qm_gpio_read_port(const qm_gpio_t gpio, uint32_t *const port)
{
QM_CHECK(gpio < QM_GPIO_NUM, -EINVAL);
QM_CHECK(port != NULL, -EINVAL);
*port = QM_GPIO[gpio]->gpio_ext_porta;
return 0;
}
int qm_gpio_write_port(const qm_gpio_t gpio, const uint32_t val)
{
QM_CHECK(gpio < QM_GPIO_NUM, -EINVAL);
QM_GPIO[gpio]->gpio_swporta_dr = val;
return 0;
}

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,53 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_identification.h"
/* Quark D2000 ID is 1.1 */
#define QUARK_D2000_SOC_ID (0x11)
uint32_t qm_soc_id(void)
{
#if (QUARK_D2000)
return QUARK_D2000_SOC_ID;
#elif(QUARK_SE)
return QM_SCSS_GP->id;
#else
#error "Unsupported / unspecified processor detected."
#endif
}
uint32_t qm_soc_version(void)
{
#if (QUARK_D2000)
return (QUARK_D2000_SOC_ID << 8) | QM_SCSS_INFO->rev;
#elif(QUARK_SE)
return (QM_SCSS_GP->id << 8) | QM_SCSS_GP->rev;
#endif
}

View file

@ -0,0 +1,35 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_init.h"
void qm_soc_reset(qm_soc_reset_t reset_type)
{
QM_SCSS_PMU->rstc |= reset_type;
}

View file

@ -0,0 +1,186 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_common.h"
#include "qm_interrupt.h"
#include "idt.h"
#if (HAS_APIC)
#include "apic.h"
#elif(HAS_MVIC)
#include "mvic.h"
#elif(QM_SENSOR)
#include "qm_ss_interrupt.h"
#include "qm_sensor_regs.h"
extern qm_ss_isr_t __ivt_vect_table[];
#else
#error "Unsupported / unspecified processor detected."
#endif
/* SCSS base addr for LMT interrupt routing, for linear IRQ mapping */
#define SCSS_LMT_INT_MASK_BASE (&QM_SCSS_INT->int_i2c_mst_0_mask)
#if (QM_SENSOR)
#define SCSS_INT_MASK BIT(8) /* Sensor Subsystem interrupt masking */
static void ss_register_irq(unsigned int vector);
#else
#define SCSS_INT_MASK BIT(0) /* Lakemont interrupt masking */
#endif
void qm_irq_disable(void)
{
#if (QM_SENSOR)
qm_ss_irq_disable();
#else
__asm__ __volatile__("cli");
#endif
}
void qm_irq_enable(void)
{
#if (QM_SENSOR)
qm_ss_irq_enable();
#else
__asm__ __volatile__("sti");
#endif
}
void qm_irq_mask(uint32_t irq)
{
#if (HAS_APIC)
ioapic_mask_irq(irq);
#elif(HAS_MVIC)
mvic_mask_irq(irq);
#elif(QM_SENSOR)
qm_ss_irq_mask(irq);
#endif
}
void qm_irq_unmask(uint32_t irq)
{
#if (HAS_APIC)
ioapic_unmask_irq(irq);
#elif(HAS_MVIC)
mvic_unmask_irq(irq);
#elif(QM_SENSOR)
qm_ss_irq_unmask(irq);
#endif
}
void _qm_irq_setup(uint32_t irq, uint16_t register_offset)
{
uint32_t *scss_intmask;
#if (HAS_APIC)
/*
* Quark SE SOC has an APIC. Other SoCs uses a simple, fixed-vector
* non-8259 PIC that requires no configuration.
*/
ioapic_register_irq(irq, QM_IRQ_TO_VECTOR(irq));
#elif(HAS_MVIC)
mvic_register_irq(irq);
#elif(QM_SENSOR)
ss_register_irq(QM_IRQ_TO_VECTOR(irq));
#endif
/* Route peripheral interrupt to Lakemont/Sensor Subsystem */
scss_intmask = (uint32_t *)SCSS_LMT_INT_MASK_BASE + register_offset;
#if (QUARK_SE || QUARK_D2000 || QM_SENSOR)
/* On Quark D2000 and Quark SE the register for the analog comparator
* host mask has a different bit field than the other host mask
* registers. */
if (QM_IRQ_AC_MASK_OFFSET == register_offset) {
*scss_intmask &= ~0x0007ffff;
#if !defined(QUARK_D2000)
} else if (QM_IRQ_MBOX_MASK_OFFSET == register_offset) {
/* Masking MAILBOX irq id done inside mbox driver */
#endif
} else {
*scss_intmask &= ~SCSS_INT_MASK;
}
#else
*scss_intmask &= ~SCSS_INT_MASK;
#endif
#if (HAS_APIC)
ioapic_unmask_irq(irq);
#elif(HAS_MVIC)
mvic_unmask_irq(irq);
#elif(QM_SENSOR)
qm_ss_irq_unmask(QM_IRQ_TO_VECTOR(irq));
#endif
}
/*
* Register an Interrupt Service Routine to a given interrupt vector.
*
* @param[in] vector Interrupt Vector number.
* @param[in] isr ISR to register to given vector. Must be a valid x86 ISR.
* If this can't be provided, qm_irq_request() or
* qm_int_vector_request() should be used instead.
*/
void _qm_register_isr(uint32_t vector, qm_isr_t isr)
{
#if (QM_SENSOR)
__ivt_vect_table[vector] = isr;
#else
idt_set_intr_gate_desc(vector, (uint32_t)isr);
#endif
}
#if (QM_SENSOR)
static void ss_register_irq(unsigned int vector)
{
/*
* By hardware power-on default, SS interrupts are level triggered.
* The following switch statement sets some of the peripherals to edge
* triggered.
*/
switch (vector) {
case QM_SS_IRQ_ADC_PWR_VECTOR:
case QM_IRQ_RTC_0_VECTOR:
case QM_IRQ_AONPT_0_VECTOR:
case QM_IRQ_WDT_0_VECTOR:
/* Edge sensitive. */
__builtin_arc_sr(vector, QM_SS_AUX_IRQ_SELECT);
__builtin_arc_sr(QM_SS_IRQ_EDGE_SENSITIVE,
QM_SS_AUX_IRQ_TRIGER);
}
}
#endif

View file

@ -0,0 +1,190 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_common.h"
#include "qm_mailbox.h"
#include "qm_interrupt.h"
/* Register offsets from a base register for a particular mailbox channel. */
#define QM_MBOX_CTRL_OFFSET (0x00)
#define QM_MBOX_DATA0_OFFSET (0x04)
#define QM_MBOX_DATA1_OFFSET (0x08)
#define QM_MBOX_DATA2_OFFSET (0x0C)
#define QM_MBOX_DATA3_OFFSET (0x10)
#define QM_MBOX_STATUS_OFFSET (0x14)
#define QM_MBOX_SS_MASK_OFFSET (0x8)
/* Private data structure maintained by the driver */
typedef struct qm_mailbox_info_t {
/*!< Callback function registered with the application. */
qm_mbox_callback_t mpr_cb;
/*!< Callback function data return via the callback function. */
void *cb_data;
} qm_mailbox_info_t;
/* Mailbox channels private data structures */
static qm_mailbox_info_t mailbox_devs[QM_MBOX_CH_NUM];
QM_ISR_DECLARE(qm_mbox_isr)
{
qm_mailbox_t *const mbox_reg = (qm_mailbox_t *)QM_SCSS_MAILBOX;
uint8_t i = 0;
uint8_t mask;
uint16_t chall_sts = QM_SCSS_MAILBOX->mbox_chall_sts;
/*
* Interrupt masking register is has a bit assigned per MBOX channel.
* QM_SCSS_INT 0-7 bits are MBOX interrupt gates to APIC, 8-15 are
* gating interrupts to Sensors PIC.
*/
#if (QM_SENSOR)
mask = 0xff & (QM_SCSS_INT->int_mailbox_mask >> QM_MBOX_SS_MASK_OFFSET);
#else
mask = 0xff & QM_SCSS_INT->int_mailbox_mask;
#endif
for (i = 0; chall_sts; i++, chall_sts >>= 2) {
if ((chall_sts & QM_MBOX_CH_INT) == 0) {
continue;
}
if (mask & BIT(i)) {
continue;
}
if (mbox_reg[i].ch_sts & QM_MBOX_CH_INT) {
if (NULL != mailbox_devs[i].mpr_cb) {
/* Callback */
mailbox_devs[i].mpr_cb(mailbox_devs[i].cb_data);
}
/* Clear the interrupt */
mbox_reg[i].ch_sts = QM_MBOX_CH_INT;
}
}
QM_ISR_EOI(QM_IRQ_MBOX_VECTOR);
}
int qm_mbox_ch_set_config(const qm_mbox_ch_t mbox_ch, qm_mbox_callback_t mpr_cb,
void *cb_data, const bool irq_en)
{
uint32_t mask;
QM_CHECK(mbox_ch < QM_MBOX_CH_NUM, -EINVAL);
/* Block interrupts while configuring MBOX */
qm_irq_mask(QM_IRQ_MBOX);
#if (QM_SENSOR)
/* MBOX Interrupt Routing gate to SS core. */
mask = BIT((mbox_ch + QM_MBOX_SS_MASK_OFFSET));
#else
/* MBOX Interrupt Routing gate to LMT core. */
mask = BIT(mbox_ch);
#endif
/* Register callback function */
mailbox_devs[mbox_ch].mpr_cb = mpr_cb;
mailbox_devs[mbox_ch].cb_data = cb_data;
if (irq_en == true) {
/* Note: Routing is done now, cannot be done in irq_request! */
QM_SCSS_INT->int_mailbox_mask &= ~mask;
/* Clear the interrupt */
((qm_mailbox_t *)QM_SCSS_MAILBOX + mbox_ch)->ch_sts =
QM_MBOX_CH_INT;
} else {
/* Note: Routing is done now, cannot be done in irq_request! */
QM_SCSS_INT->int_mailbox_mask |= mask;
}
/* UnBlock MBOX interrupts. */
qm_irq_unmask(QM_IRQ_MBOX);
return 0;
}
int qm_mbox_ch_write(const qm_mbox_ch_t mbox_ch,
const qm_mbox_msg_t *const data)
{
qm_mailbox_t *const mbox_reg = (qm_mailbox_t *)QM_SCSS_MAILBOX +
mbox_ch;
/* Check if the previous message has been consumed. */
if (!(mbox_reg->ch_ctrl & QM_MBOX_TRIGGER_CH_INT)) {
/* Write the payload data to the mailbox channel. */
mbox_reg->ch_data[0] = data->data[QM_MBOX_PAYLOAD_0];
mbox_reg->ch_data[1] = data->data[QM_MBOX_PAYLOAD_1];
mbox_reg->ch_data[2] = data->data[QM_MBOX_PAYLOAD_2];
mbox_reg->ch_data[3] = data->data[QM_MBOX_PAYLOAD_3];
/* Write the control word and trigger the channel interrupt. */
mbox_reg->ch_ctrl = data->ctrl | QM_MBOX_TRIGGER_CH_INT;
return 0;
}
/* Previous message has not been consumed. */
return -EIO;
}
int qm_mbox_ch_read(const qm_mbox_ch_t mbox_ch, qm_mbox_msg_t *const data)
{
qm_mailbox_t *const mbox_reg = (qm_mailbox_t *)QM_SCSS_MAILBOX + mbox_ch;
/* Read data from the mailbox channel and clear bit 31 of the
* control word. */
data->ctrl = mbox_reg->ch_ctrl & ~QM_MBOX_TRIGGER_CH_INT;
data->data[QM_MBOX_PAYLOAD_0] = mbox_reg->ch_data[0];
data->data[QM_MBOX_PAYLOAD_1] = mbox_reg->ch_data[1];
data->data[QM_MBOX_PAYLOAD_2] = mbox_reg->ch_data[2];
data->data[QM_MBOX_PAYLOAD_3] = mbox_reg->ch_data[3];
/* Check if the message has arrived. */
if (mbox_reg->ch_sts & QM_MBOX_CH_DATA) {
/* Clear data status bit */
mbox_reg->ch_sts = QM_MBOX_CH_DATA;
return 0;
}
/* there is no new data in mailbox */
return -EIO;
}
int qm_mbox_ch_get_status(const qm_mbox_ch_t mbox_ch,
qm_mbox_ch_status_t *const status)
{
QM_CHECK(mbox_ch < QM_MBOX_CH_NUM, -EINVAL);
qm_mailbox_t *const mbox_reg = (qm_mailbox_t *)QM_SCSS_MAILBOX +
mbox_ch;
*status = mbox_reg->ch_sts &QM_MBOX_CH_STATUS_MASK;
return 0;
}
int qm_mbox_ch_data_ack(const qm_mbox_ch_t mbox_ch)
{
QM_CHECK(mbox_ch < QM_MBOX_CH_NUM, -EINVAL);
((qm_mailbox_t *)QM_SCSS_MAILBOX + mbox_ch)->ch_sts = QM_MBOX_CH_DATA;
return 0;
}

View file

@ -0,0 +1,121 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_mpr.h"
#include "qm_interrupt.h"
#define ADDRESS_MASK_7_BIT (0x7F)
static void (*callback)(void *data);
static void *callback_data;
QM_ISR_DECLARE(qm_mpr_isr)
{
if (callback) {
(*callback)(callback_data);
}
QM_MPR->mpr_vsts = QM_MPR_VSTS_VALID;
QM_ISR_EOI(QM_IRQ_SRAM_VECTOR);
}
int qm_mpr_set_config(const qm_mpr_id_t id, const qm_mpr_config_t *const cfg)
{
QM_CHECK(id < QM_MPR_NUM, -EINVAL);
QM_CHECK(cfg != NULL, -EINVAL);
QM_MPR->mpr_cfg[id] &= ~QM_MPR_EN_LOCK_MASK;
QM_MPR->mpr_cfg[id] =
(cfg->agent_write_en_mask << QM_MPR_WR_EN_OFFSET) |
(cfg->agent_read_en_mask << QM_MPR_RD_EN_OFFSET) |
/* MPR Upper bound 16:10 */
((cfg->up_bound & ADDRESS_MASK_7_BIT) << QM_MPR_UP_BOUND_OFFSET)
/* MPR Lower bound 6:0 */
|
cfg->low_bound;
/* enable/lock */
QM_MPR->mpr_cfg[id] |= (cfg->en_lock_mask << QM_MPR_EN_LOCK_OFFSET);
return 0;
}
int qm_mpr_set_violation_policy(const qm_mpr_viol_mode_t mode,
qm_mpr_callback_t callback_fn,
void *callback_data)
{
QM_CHECK(mode <= MPR_VIOL_MODE_PROBE, -EINVAL);
/* interrupt mode */
if (MPR_VIOL_MODE_INTERRUPT == mode) {
callback = callback_fn;
callback_data = callback_data;
/* unmask interrupt */
qm_irq_unmask(QM_IRQ_SRAM);
#if defined(QM_SENSOR)
QM_SCSS_INT->int_sram_controller_mask |=
QM_INT_SRAM_CONTROLLER_SS_HALT_MASK;
#else /* QM_SENSOR */
QM_SCSS_INT->int_sram_controller_mask |=
QM_INT_SRAM_CONTROLLER_HOST_HALT_MASK;
#endif /* QM_SENSOR */
}
/* probe or reset mode */
else {
/* mask interrupt */
qm_irq_mask(QM_IRQ_SRAM);
#if defined(QM_SENSOR)
QM_SCSS_INT->int_sram_controller_mask &=
~QM_INT_SRAM_CONTROLLER_SS_HALT_MASK;
#else /* QM_SENSOR */
QM_SCSS_INT->int_sram_controller_mask &=
~QM_INT_SRAM_CONTROLLER_HOST_HALT_MASK;
#endif /* QM_SENSOR */
if (MPR_VIOL_MODE_PROBE == mode) {
/* When an enabled host halt interrupt occurs, this bit
* determines if the interrupt event triggers a warm
* reset
* or an entry into Probe Mode.
* 0b : Warm Reset
* 1b : Probe Mode Entry
*/
QM_SCSS_PMU->p_sts |=
QM_P_STS_HALT_INTERRUPT_REDIRECTION;
}
else {
QM_SCSS_PMU->p_sts &=
~QM_P_STS_HALT_INTERRUPT_REDIRECTION;
}
}
return 0;
}

View file

@ -0,0 +1,108 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_pic_timer.h"
/*
* PIC timer access layer. Supports both Local APIC timer and MVIC timer.
*
* The MVIC timer differs from the LAPIC specs in that:
* - it does not support TSC deadline mode
* - vector table lvttimer[3:0] holds the IRQ (not the vector) of the timer
*/
#define LVTTIMER_MODE_PERIODIC_OFFS (17)
#define LVTTIMER_INT_MASK_OFFS (16)
static void (*callback)(void *data);
static void *callback_data;
#if (HAS_APIC)
#define PIC_TIMER (QM_LAPIC)
#else
#define PIC_TIMER (QM_PIC_TIMER)
#endif
QM_ISR_DECLARE(qm_pic_timer_isr)
{
if (callback) {
callback(callback_data);
}
#if (HAS_APIC)
/* Use an invalid vector to avoid acknowledging a valid IRQ */
QM_ISR_EOI(0);
#else
QM_ISR_EOI(QM_IRQ_PIC_TIMER_VECTOR);
#endif
}
int qm_pic_timer_set_config(const qm_pic_timer_config_t *const cfg)
{
QM_CHECK(cfg != NULL, -EINVAL);
QM_CHECK(cfg->mode <= QM_PIC_TIMER_MODE_PERIODIC, -EINVAL);
/* Stop timer, mask interrupt and program interrupt vector */
PIC_TIMER->timer_icr.reg = 0;
PIC_TIMER->lvttimer.reg = BIT(LVTTIMER_INT_MASK_OFFS) |
#if (HAS_APIC)
QM_INT_VECTOR_PIC_TIMER;
#else
QM_IRQ_PIC_TIMER;
#endif
#if (HAS_APIC)
/* LAPIC has a timer clock divisor, POR default: 2. Set it to 1. */
QM_LAPIC->timer_dcr.reg = 0xB;
#endif
PIC_TIMER->lvttimer.reg |= cfg->mode << LVTTIMER_MODE_PERIODIC_OFFS;
callback = cfg->callback;
callback_data = cfg->callback_data;
if (cfg->int_en) {
PIC_TIMER->lvttimer.reg &= ~BIT(LVTTIMER_INT_MASK_OFFS);
}
return 0;
}
int qm_pic_timer_set(const uint32_t count)
{
PIC_TIMER->timer_icr.reg = count;
return 0;
}
int qm_pic_timer_get(uint32_t *const count)
{
QM_CHECK(count != NULL, -EINVAL);
*count = PIC_TIMER->timer_ccr.reg;
return 0;
}

View file

@ -0,0 +1,120 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_pinmux.h"
#include "qm_common.h"
#define MASK_1BIT (0x1)
#define MASK_2BIT (0x3)
/**
* Calculate the register index for a specific pin.
*
* @param[in] pin The pin to be used.
* @param[in] width The width in bits for each pin in the register.
*
* @return The register index of the given pin.
*/
static uint32_t pin_to_register(uint32_t pin, uint32_t width)
{
return (pin / (32 / width));
}
/**
* Calculate the offset for a pin within a register.
*
* @param[in] pin The pin to be used.
* @param[in] width The width in bits for each pin in the register.
*
* @return The offset for the pin within the register.
*/
static uint32_t pin_to_offset(uint32_t pin, uint32_t width)
{
return ((pin % (32 / width)) * width);
}
int qm_pmux_select(const qm_pin_id_t pin, const qm_pmux_fn_t fn)
{
QM_CHECK(pin < QM_PIN_ID_NUM, -EINVAL);
QM_CHECK(fn <= QM_PMUX_FN_3, -EINVAL);
uint32_t reg = pin_to_register(pin, 2);
uint32_t offs = pin_to_offset(pin, 2);
QM_SCSS_PMUX->pmux_sel[reg] &= ~(MASK_2BIT << offs);
QM_SCSS_PMUX->pmux_sel[reg] |= (fn << offs);
return 0;
}
int qm_pmux_set_slew(const qm_pin_id_t pin, const qm_pmux_slew_t slew)
{
QM_CHECK(pin < QM_PIN_ID_NUM, -EINVAL);
QM_CHECK(slew < QM_PMUX_SLEW_NUM, -EINVAL);
uint32_t reg = pin_to_register(pin, 1);
uint32_t mask = MASK_1BIT << pin_to_offset(pin, 1);
if (slew == 0) {
QM_SCSS_PMUX->pmux_slew[reg] &= ~mask;
} else {
QM_SCSS_PMUX->pmux_slew[reg] |= mask;
}
return 0;
}
int qm_pmux_input_en(const qm_pin_id_t pin, const bool enable)
{
QM_CHECK(pin < QM_PIN_ID_NUM, -EINVAL);
uint32_t reg = pin_to_register(pin, 1);
uint32_t mask = MASK_1BIT << pin_to_offset(pin, 1);
if (enable == false) {
QM_SCSS_PMUX->pmux_in_en[reg] &= ~mask;
} else {
QM_SCSS_PMUX->pmux_in_en[reg] |= mask;
}
return 0;
}
int qm_pmux_pullup_en(const qm_pin_id_t pin, const bool enable)
{
QM_CHECK(pin < QM_PIN_ID_NUM, -EINVAL);
uint32_t reg = pin_to_register(pin, 1);
uint32_t mask = MASK_1BIT << pin_to_offset(pin, 1);
if (enable == false) {
QM_SCSS_PMUX->pmux_pullup[reg] &= ~mask;
} else {
QM_SCSS_PMUX->pmux_pullup[reg] |= mask;
}
return 0;
}

View file

@ -0,0 +1,124 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_pwm.h"
static void (*callback[QM_PWM_NUM])(void *data, uint32_t int_status);
static void *callback_data[QM_PWM_NUM];
QM_ISR_DECLARE(qm_pwm_isr_0)
{
/* Which timers fired. */
uint32_t int_status = QM_PWM[QM_PWM_0].timersintstatus;
/* Clear timers interrupt flag. */
QM_PWM[QM_PWM_0].timerseoi;
if (callback[QM_PWM_0]) {
(*callback[QM_PWM_0])(callback_data[QM_PWM_0], int_status);
}
QM_ISR_EOI(QM_IRQ_PWM_0_VECTOR);
}
int qm_pwm_start(const qm_pwm_t pwm, const qm_pwm_id_t id)
{
QM_CHECK(pwm < QM_PWM_NUM, -EINVAL);
QM_CHECK(id < QM_PWM_ID_NUM, -EINVAL);
QM_PWM[pwm].timer[id].controlreg |= PWM_START;
return 0;
}
int qm_pwm_stop(const qm_pwm_t pwm, const qm_pwm_id_t id)
{
QM_CHECK(pwm < QM_PWM_NUM, -EINVAL);
QM_CHECK(id < QM_PWM_ID_NUM, -EINVAL);
QM_PWM[pwm].timer[id].controlreg &= ~PWM_START;
return 0;
}
int qm_pwm_set_config(const qm_pwm_t pwm, const qm_pwm_id_t id,
const qm_pwm_config_t *const cfg)
{
QM_CHECK(pwm < QM_PWM_NUM, -EINVAL);
QM_CHECK(id < QM_PWM_ID_NUM, -EINVAL);
QM_CHECK(cfg != NULL, -EINVAL);
QM_CHECK(cfg->mode <= QM_PWM_MODE_PWM, -EINVAL);
QM_CHECK(0 < cfg->lo_count, -EINVAL);
/* If mode is PWM, hi_count must be > 0, otherwise don't care. */
QM_CHECK(cfg->mode == QM_PWM_MODE_PWM ? 0 != cfg->hi_count : 1,
-EINVAL);
QM_PWM[pwm].timer[id].loadcount = cfg->lo_count - 1;
QM_PWM[pwm].timer[id].controlreg =
(cfg->mode | (cfg->mask_interrupt << QM_PWM_INTERRUPT_MASK_OFFSET));
QM_PWM[pwm].timer_loadcount2[id] = cfg->hi_count - 1;
/* Assign user callback function. */
callback[pwm] = cfg->callback;
callback_data[pwm] = cfg->callback_data;
return 0;
}
int qm_pwm_set(const qm_pwm_t pwm, const qm_pwm_id_t id,
const uint32_t lo_count, const uint32_t hi_count)
{
QM_CHECK(pwm < QM_PWM_NUM, -EINVAL);
QM_CHECK(id < QM_PWM_ID_NUM, -EINVAL);
QM_CHECK(0 < lo_count, -EINVAL);
/* If mode is PWM, hi_count must be > 0, otherwise don't care. */
QM_CHECK(((QM_PWM[pwm].timer[id].controlreg & QM_PWM_CONF_MODE_MASK) ==
QM_PWM_MODE_PWM
? 0 < hi_count
: 1),
-EINVAL);
QM_PWM[pwm].timer[id].loadcount = lo_count - 1;
QM_PWM[pwm].timer_loadcount2[id] = hi_count - 1;
return 0;
}
int qm_pwm_get(const qm_pwm_t pwm, const qm_pwm_id_t id,
uint32_t *const lo_count, uint32_t *const hi_count)
{
QM_CHECK(pwm < QM_PWM_NUM, -EINVAL);
QM_CHECK(id < QM_PWM_ID_NUM, -EINVAL);
QM_CHECK(lo_count != NULL, -EINVAL);
QM_CHECK(hi_count != NULL, -EINVAL);
*lo_count = QM_PWM[pwm].timer[id].loadcount;
*hi_count = QM_PWM[pwm].timer_loadcount2[id];
return 0;
}

View file

@ -0,0 +1,86 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_rtc.h"
static void (*callback[QM_RTC_NUM])(void *data);
static void *callback_data[QM_RTC_NUM];
QM_ISR_DECLARE(qm_rtc_isr_0)
{
/* Disable RTC interrupt */
QM_RTC[QM_RTC_0].rtc_ccr &= ~QM_RTC_CCR_INTERRUPT_ENABLE;
if (callback[QM_RTC_0]) {
(callback[QM_RTC_0])(callback_data[QM_RTC_0]);
}
/* clear interrupt */
QM_RTC[QM_RTC_0].rtc_eoi;
QM_ISR_EOI(QM_IRQ_RTC_0_VECTOR);
}
int qm_rtc_set_config(const qm_rtc_t rtc, const qm_rtc_config_t *const cfg)
{
QM_CHECK(rtc < QM_RTC_NUM, -EINVAL);
QM_CHECK(cfg != NULL, -EINVAL);
/* set rtc divider */
clk_rtc_set_div(QM_RTC_DIVIDER);
QM_RTC[rtc].rtc_clr = cfg->init_val;
/* clear any pending interrupts */
QM_RTC[rtc].rtc_eoi;
callback[rtc] = cfg->callback;
callback_data[rtc] = cfg->callback_data;
if (cfg->alarm_en) {
qm_rtc_set_alarm(rtc, cfg->alarm_val);
} else {
/* Disable RTC interrupt */
QM_RTC[rtc].rtc_ccr &= ~QM_RTC_CCR_INTERRUPT_ENABLE;
}
return 0;
}
int qm_rtc_set_alarm(const qm_rtc_t rtc, const uint32_t alarm_val)
{
QM_CHECK(rtc < QM_RTC_NUM, -EINVAL);
/* Enable RTC interrupt */
QM_RTC[rtc].rtc_ccr |= QM_RTC_CCR_INTERRUPT_ENABLE;
/* set alarm val */
QM_RTC[rtc].rtc_cmr = alarm_val;
return 0;
}

View file

@ -0,0 +1,876 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_spi.h"
/* SPI FIFO size defaults */
#define SPI_DEFAULT_TX_THRESHOLD (0x05)
#define SPI_DEFAULT_RX_THRESHOLD (0x05)
#define SPI_FIFOS_DEPTH (8)
/* SPI DMA transmit watermark level. When the number of valid data entries in
* the transmit FIFO is equal to or below this field value, dma_tx_req is
* generated. The burst length has to fit in the remaining space of the transmit
* FIFO, i.e. the burst length cannot be bigger than (16 - watermark level). */
#define SPI_DMATDLR_DMATDL (0x03)
#define SPI_DMA_WRITE_BURST_LENGTH QM_DMA_BURST_TRANS_LENGTH_4
/* SPI DMA receive watermark level. When the number of valid data entries in the
* receive FIFO is equal to or above this field value + 1, dma_rx_req is
* generated. The burst length has to match the watermark level so that the
* exact number of data entries fit one burst, and therefore only some values
* are allowed:
* DMARDL DMA read burst length
* 0 1
* 3 4
* 7 (highest) 8
*/
#define SPI_DMARDLR_DMARDL (0x03)
#define SPI_DMA_READ_BURST_LENGTH QM_DMA_BURST_TRANS_LENGTH_4
/* Arbitrary byte sent in RX-only mode. */
#define SPI_RX_ONLY_DUMMY_BYTE (0xf0)
/* DMA transfer information, relevant on callback invocations from the DMA
* driver. */
typedef struct {
qm_spi_t spi_id; /**< SPI controller identifier. */
qm_dma_channel_id_t dma_channel_id; /**< Used DMA channel. */
volatile bool cb_pending; /**< True if waiting for DMA calllback. */
} dma_context_t;
/**
* Extern qm_spi_reg_t* array declared at qm_soc_regs.h .
*/
#ifndef UNIT_TEST
#if (QUARK_SE)
qm_spi_reg_t *qm_spi_controllers[QM_SPI_NUM] = {
(qm_spi_reg_t *)QM_SPI_MST_0_BASE, (qm_spi_reg_t *)QM_SPI_MST_1_BASE};
#elif(QUARK_D2000)
qm_spi_reg_t *qm_spi_controllers[QM_SPI_NUM] = {
(qm_spi_reg_t *)QM_SPI_MST_0_BASE};
#endif
#endif
static const qm_spi_async_transfer_t *spi_async_transfer[QM_SPI_NUM];
static volatile uint16_t tx_counter[QM_SPI_NUM], rx_counter[QM_SPI_NUM];
static uint8_t dfs[QM_SPI_NUM];
static const uint32_t tx_dummy_frame = SPI_RX_ONLY_DUMMY_BYTE;
static qm_spi_tmode_t tmode[QM_SPI_NUM];
/* DMA (memory to SPI controller) callback information. */
static dma_context_t dma_context_tx[QM_SPI_NUM];
/* DMA (SPI controller to memory) callback information. */
static dma_context_t dma_context_rx[QM_SPI_NUM];
/* DMA core being used by each SPI controller. */
static qm_dma_t dma_core[QM_SPI_NUM];
static void read_frame(const qm_spi_t spi, uint8_t *const rx_buffer)
{
const qm_spi_reg_t *const controller = QM_SPI[spi];
const uint8_t frame_size = dfs[spi];
if (frame_size == 1) {
*(uint8_t *)rx_buffer = controller->dr[0];
} else if (frame_size == 2) {
*(uint16_t *)rx_buffer = controller->dr[0];
} else {
*(uint32_t *)rx_buffer = controller->dr[0];
}
}
static void write_frame(const qm_spi_t spi, const uint8_t *const tx_buffer)
{
qm_spi_reg_t *const controller = QM_SPI[spi];
const uint8_t frame_size = dfs[spi];
if (frame_size == 1) {
controller->dr[0] = *(uint8_t *)tx_buffer;
} else if (frame_size == 2) {
controller->dr[0] = *(uint16_t *)tx_buffer;
} else {
controller->dr[0] = *(uint32_t *)tx_buffer;
}
}
static void wait_for_controller(const qm_spi_reg_t *const controller)
{
/* Page 42 of databook says you must poll TFE status waiting for 1
* before checking QM_SPI_SR_BUSY.
*/
while (!(controller->sr & QM_SPI_SR_TFE))
;
while (controller->sr & QM_SPI_SR_BUSY)
;
}
/**
* Service an RX FIFO Full interrupt
*
* @brief Interrupt based transfer on SPI.
* @param [in] spi Which SPI to transfer from.
*/
static __inline__ void handle_rx_interrupt(const qm_spi_t spi)
{
qm_spi_reg_t *const controller = QM_SPI[spi];
const qm_spi_async_transfer_t *const transfer = spi_async_transfer[spi];
/* Jump to the right position of RX buffer.
* If no bytes were received before, we start from the beginning,
* otherwise we jump to the next available frame position.
*/
uint8_t *rx_buffer = transfer->rx + (rx_counter[spi] * dfs[spi]);
while (controller->rxflr) {
read_frame(spi, rx_buffer);
rx_buffer += dfs[spi];
rx_counter[spi]++;
/* Check that there's not more data in the FIFO than we had
* requested.
*/
if (transfer->rx_len == rx_counter[spi]) {
controller->imr &=
~(QM_SPI_IMR_RXUIM | QM_SPI_IMR_RXOIM |
QM_SPI_IMR_RXFIM);
if (transfer->callback &&
tmode[spi] == QM_SPI_TMOD_RX) {
transfer->callback(transfer->callback_data, 0,
QM_SPI_IDLE,
transfer->rx_len);
}
break;
}
}
/* Check if enough data will arrive to trigger an interrupt and adjust
* rxftlr accordingly.
*/
const uint32_t frames_left = transfer->rx_len - rx_counter[spi];
if (frames_left <= controller->rxftlr) {
controller->rxftlr = frames_left - 1;
}
}
/**
* Service an Tx FIFO Empty interrupt
*
* @brief Interrupt based transfer on SPI.
* @param [in] spi Which SPI to transfer to.
*/
static __inline__ void handle_tx_interrupt(const qm_spi_t spi)
{
qm_spi_reg_t *const controller = QM_SPI[spi];
const qm_spi_async_transfer_t *const transfer = spi_async_transfer[spi];
/* Jump to the right position of TX buffer.
* If no bytes were transmitted before, we start from the beginning,
* otherwise we jump to the next frame to be sent.
*/
const uint8_t *tx_buffer = transfer->tx + (tx_counter[spi] * dfs[spi]);
int frames =
SPI_FIFOS_DEPTH - controller->txflr - controller->rxflr - 1;
while (frames > 0) {
write_frame(spi, tx_buffer);
tx_buffer += dfs[spi];
tx_counter[spi]++;
frames--;
if (transfer->tx_len == tx_counter[spi]) {
controller->txftlr = 0;
break;
}
}
}
static void handle_spi_interrupt(const qm_spi_t spi)
{
qm_spi_reg_t *const controller = QM_SPI[spi];
const qm_spi_async_transfer_t *transfer = spi_async_transfer[spi];
const uint32_t int_status = controller->isr;
QM_ASSERT((int_status & (QM_SPI_ISR_TXOIS | QM_SPI_ISR_RXUIS)) == 0);
if (int_status & QM_SPI_ISR_RXOIS) {
if (transfer->callback) {
transfer->callback(transfer->callback_data, -EIO,
QM_SPI_RX_OVERFLOW,
rx_counter[spi]);
}
controller->rxoicr;
controller->imr = QM_SPI_IMR_MASK_ALL;
controller->ssienr = 0;
return;
}
if (int_status & QM_SPI_ISR_RXFIS) {
handle_rx_interrupt(spi);
}
if (transfer->rx_len == rx_counter[spi] &&
transfer->tx_len == tx_counter[spi] &&
(controller->sr & QM_SPI_SR_TFE) &&
!(controller->sr & QM_SPI_SR_BUSY)) {
controller->imr = QM_SPI_IMR_MASK_ALL;
controller->ssienr = 0;
if (transfer->callback && tmode[spi] != QM_SPI_TMOD_RX) {
transfer->callback(transfer->callback_data, 0,
QM_SPI_IDLE, transfer->tx_len);
}
return;
}
if (int_status & QM_SPI_ISR_TXEIS &&
transfer->tx_len > tx_counter[spi]) {
handle_tx_interrupt(spi);
}
}
int qm_spi_set_config(const qm_spi_t spi, const qm_spi_config_t *cfg)
{
QM_CHECK(spi < QM_SPI_NUM, -EINVAL);
QM_CHECK(cfg, -EINVAL);
QM_ASSERT(QM_SPI[spi]->ssienr == 0);
qm_spi_reg_t *const controller = QM_SPI[spi];
/* Apply the selected cfg options */
controller->ctrlr0 = (cfg->frame_size << QM_SPI_CTRLR0_DFS_32_OFFSET) |
(cfg->transfer_mode << QM_SPI_CTRLR0_TMOD_OFFSET) |
(cfg->bus_mode << QM_SPI_CTRLR0_SCPOL_SCPH_OFFSET);
controller->baudr = cfg->clk_divider;
/* Keep the current data frame size in bytes, being:
* - 1 byte for DFS set from 4 to 8 bits;
* - 2 bytes for DFS set from 9 to 16 bits;
* - 3 bytes for DFS set from 17 to 24 bits;
* - 4 bytes for DFS set from 25 to 32 bits.
*/
dfs[spi] = (cfg->frame_size / 8) + 1;
tmode[spi] = cfg->transfer_mode;
return 0;
}
int qm_spi_slave_select(const qm_spi_t spi, const qm_spi_slave_select_t ss)
{
QM_CHECK(spi < QM_SPI_NUM, -EINVAL);
/* Check if the device reports as busy. */
QM_ASSERT(!(QM_SPI[spi]->sr & QM_SPI_SR_BUSY));
QM_SPI[spi]->ser = ss;
return 0;
}
int qm_spi_get_status(const qm_spi_t spi, qm_spi_status_t *const status)
{
QM_CHECK(spi < QM_SPI_NUM, -EINVAL);
QM_CHECK(status, -EINVAL);
qm_spi_reg_t *const controller = QM_SPI[spi];
if (controller->sr & QM_SPI_SR_BUSY) {
*status = QM_SPI_BUSY;
} else {
*status = QM_SPI_IDLE;
}
if (controller->risr & QM_SPI_RISR_RXOIR) {
*status = QM_SPI_RX_OVERFLOW;
}
return 0;
}
int qm_spi_transfer(const qm_spi_t spi, const qm_spi_transfer_t *const xfer,
qm_spi_status_t *const status)
{
QM_CHECK(spi < QM_SPI_NUM, -EINVAL);
QM_CHECK(xfer, -EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_TX_RX
? (xfer->tx_len == xfer->rx_len)
: 1,
-EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_TX ? (xfer->rx_len == 0) : 1,
-EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_RX ? (xfer->tx_len == 0) : 1,
-EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_EEPROM_READ
? (xfer->tx_len && xfer->rx_len)
: 1,
-EINVAL);
uint32_t i_tx = xfer->tx_len;
uint32_t i_rx = xfer->rx_len;
int rc = 0;
qm_spi_reg_t *const controller = QM_SPI[spi];
/* Wait for the SPI device to become available. */
wait_for_controller(controller);
/* Mask all interrupts, this is a blocking function. */
controller->imr = QM_SPI_IMR_MASK_ALL;
/* If we are in RX only or EEPROM Read mode, the ctrlr1 reg holds how
* many bytes the controller solicits, minus 1. */
if (xfer->rx_len) {
controller->ctrlr1 = xfer->rx_len - 1;
}
/* Enable SPI device */
controller->ssienr = QM_SPI_SSIENR_SSIENR;
/* Transfer is only complete when all the tx data is sent and all
* expected rx data has been received.
*/
uint8_t *rx_buffer = xfer->rx;
const uint8_t *tx_buffer = xfer->tx;
int frames;
/* RX Only transfers need a dummy byte to be sent for starting.
* This is covered by the databook on page 42.
*/
if (tmode[spi] == QM_SPI_TMOD_RX) {
tx_buffer = (uint8_t *)&tx_dummy_frame;
i_tx = 1;
}
while (i_tx || i_rx) {
if (controller->risr & QM_SPI_RISR_RXOIR) {
rc = -EIO;
if (status) {
*status |= QM_SPI_RX_OVERFLOW;
}
controller->rxoicr;
break;
}
while (i_rx && controller->rxflr) {
read_frame(spi, rx_buffer);
rx_buffer += dfs[spi];
i_rx--;
}
frames =
SPI_FIFOS_DEPTH - controller->txflr - controller->rxflr - 1;
while (i_tx && frames) {
write_frame(spi, tx_buffer);
tx_buffer += dfs[spi];
i_tx--;
frames--;
}
/* Databook page 43 says we always need to busy-wait until the
* controller is ready again after writing frames to the TX
* FIFO.
*
* That is only needed for TX or TX_RX transfer modes.
*/
if (tmode[spi] == QM_SPI_TMOD_TX_RX ||
tmode[spi] == QM_SPI_TMOD_TX) {
wait_for_controller(controller);
}
}
controller->ssienr = 0; /** Disable SPI Device */
return rc;
}
int qm_spi_irq_transfer(const qm_spi_t spi,
const qm_spi_async_transfer_t *const xfer)
{
QM_CHECK(spi < QM_SPI_NUM, -EINVAL);
QM_CHECK(xfer, -EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_TX_RX
? (xfer->tx_len == xfer->rx_len)
: 1,
-EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_TX ? (xfer->rx_len == 0) : 1,
-EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_RX ? (xfer->tx_len == 0) : 1,
-EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_EEPROM_READ
? (xfer->tx_len && xfer->rx_len)
: 1,
-EINVAL);
qm_spi_reg_t *const controller = QM_SPI[spi];
/* If we are in RX only or EEPROM Read mode, the ctrlr1 reg holds how
* many bytes the controller solicits, minus 1. We also set the same
* into rxftlr, so the controller only triggers a RX_FIFO_FULL
* interrupt when all frames are available at the FIFO for consumption.
*/
if (xfer->rx_len) {
controller->ctrlr1 = xfer->rx_len - 1;
controller->rxftlr = (xfer->rx_len < SPI_FIFOS_DEPTH)
? xfer->rx_len - 1
: SPI_DEFAULT_RX_THRESHOLD;
}
controller->txftlr = SPI_DEFAULT_TX_THRESHOLD;
spi_async_transfer[spi] = xfer;
tx_counter[spi] = 0;
rx_counter[spi] = 0;
/* Unmask interrupts */
if (tmode[spi] == QM_SPI_TMOD_TX) {
controller->imr = QM_SPI_IMR_TXEIM | QM_SPI_IMR_TXOIM;
} else if (tmode[spi] == QM_SPI_TMOD_RX) {
controller->imr =
QM_SPI_IMR_RXUIM | QM_SPI_IMR_RXOIM | QM_SPI_IMR_RXFIM;
controller->ssienr = QM_SPI_SSIENR_SSIENR;
write_frame(spi, (uint8_t *)&tx_dummy_frame);
} else {
controller->imr = QM_SPI_IMR_TXEIM | QM_SPI_IMR_TXOIM |
QM_SPI_IMR_RXUIM | QM_SPI_IMR_RXOIM |
QM_SPI_IMR_RXFIM;
}
controller->ssienr = QM_SPI_SSIENR_SSIENR; /** Enable SPI Device */
return 0;
}
QM_ISR_DECLARE(qm_spi_master_0_isr)
{
handle_spi_interrupt(QM_SPI_MST_0);
QM_ISR_EOI(QM_IRQ_SPI_MASTER_0_VECTOR);
}
#if (QUARK_SE)
QM_ISR_DECLARE(qm_spi_master_1_isr)
{
handle_spi_interrupt(QM_SPI_MST_1);
QM_ISR_EOI(QM_IRQ_SPI_MASTER_1_VECTOR);
}
#endif
int qm_spi_irq_transfer_terminate(const qm_spi_t spi)
{
QM_CHECK(spi < QM_SPI_NUM, -EINVAL);
qm_spi_reg_t *const controller = QM_SPI[spi];
const qm_spi_async_transfer_t *const transfer = spi_async_transfer[spi];
/* Mask the interrupts */
controller->imr = QM_SPI_IMR_MASK_ALL;
controller->ssienr = 0; /** Disable SPI device */
if (transfer->callback) {
uint16_t len = 0;
if (tmode[spi] == QM_SPI_TMOD_TX ||
tmode[spi] == QM_SPI_TMOD_TX_RX) {
len = tx_counter[spi];
} else {
len = rx_counter[spi];
}
/*
* NOTE: change this to return controller-specific code
* 'user aborted'.
*/
transfer->callback(transfer->callback_data, -ECANCELED,
QM_SPI_IDLE, len);
}
tx_counter[spi] = 0;
rx_counter[spi] = 0;
return 0;
}
/* DMA driver invoked callback. */
static void spi_dma_callback(void *callback_context, uint32_t len,
int error_code)
{
QM_ASSERT(callback_context);
int client_error = 0;
uint32_t frames_expected;
volatile bool *cb_pending_alternate_p;
/* The DMA driver returns a pointer to a dma_context struct from which
* we find out the corresponding SPI device and transfer direction. */
dma_context_t *const dma_context_p = callback_context;
const qm_spi_t spi = dma_context_p->spi_id;
QM_ASSERT(spi < QM_SPI_NUM);
qm_spi_reg_t *const controller = QM_SPI[spi];
const qm_spi_async_transfer_t *const transfer = spi_async_transfer[spi];
QM_ASSERT(transfer);
const uint8_t frame_size = dfs[spi];
QM_ASSERT((frame_size == 1) || (frame_size == 2) || (frame_size == 4));
/* DMA driver returns length in bytes but user expects number of frames.
*/
const uint32_t frames_transfered = len / frame_size;
QM_ASSERT((dma_context_p == &dma_context_tx[spi]) ||
(dma_context_p == &dma_context_rx[spi]));
if (dma_context_p == &dma_context_tx[spi]) {
/* TX transfer. */
frames_expected = transfer->tx_len;
cb_pending_alternate_p = &dma_context_rx[spi].cb_pending;
} else if (dma_context_p == &dma_context_rx[spi]) {
/* RX tranfer. */
frames_expected = transfer->rx_len;
cb_pending_alternate_p = &dma_context_tx[spi].cb_pending;
} else {
return;
}
QM_ASSERT(cb_pending_alternate_p);
QM_ASSERT(dma_context_p->cb_pending);
dma_context_p->cb_pending = false;
if (error_code) {
/* Transfer failed, pass to client the error code returned by
* the DMA driver. */
client_error = error_code;
} else if (false == *cb_pending_alternate_p) {
/* TX transfers invoke the callback before the TX data has been
* transmitted, we need to wait here. */
wait_for_controller(controller);
if (frames_transfered != frames_expected) {
QM_ASSERT(frames_transfered < frames_expected);
/* Callback triggered through a transfer terminate. */
client_error = -ECANCELED;
}
} else {
/* Controller busy due to alternate DMA channel active. */
return;
}
/* Disable DMA setting and SPI controller. */
controller->dmacr = 0;
controller->ssienr = 0;
if (transfer->callback) {
transfer->callback(transfer->callback_data, client_error,
QM_SPI_IDLE, frames_transfered);
}
}
int qm_spi_dma_channel_config(
const qm_spi_t spi, const qm_dma_t dma_ctrl_id,
const qm_dma_channel_id_t dma_channel_id,
const qm_dma_channel_direction_t dma_channel_direction)
{
QM_CHECK(spi < QM_SPI_NUM, -EINVAL);
QM_CHECK(dma_ctrl_id < QM_DMA_NUM, -EINVAL);
QM_CHECK(dma_channel_id < QM_DMA_CHANNEL_NUM, -EINVAL);
int ret = -EINVAL;
dma_context_t *dma_context_p = NULL;
qm_dma_channel_config_t dma_chan_cfg = {0};
dma_chan_cfg.handshake_polarity = QM_DMA_HANDSHAKE_POLARITY_HIGH;
dma_chan_cfg.channel_direction = dma_channel_direction;
dma_chan_cfg.client_callback = spi_dma_callback;
/* Every data transfer performed by the DMA core corresponds to an SPI
* data frame, the SPI uses the number of bits determined by a previous
* qm_spi_set_config call where the frame size was specified. */
switch (dfs[spi]) {
case 1:
dma_chan_cfg.source_transfer_width = QM_DMA_TRANS_WIDTH_8;
break;
case 2:
dma_chan_cfg.source_transfer_width = QM_DMA_TRANS_WIDTH_16;
break;
case 4:
dma_chan_cfg.source_transfer_width = QM_DMA_TRANS_WIDTH_32;
break;
default:
/* The DMA core cannot handle 3 byte frame sizes. */
return -EINVAL;
}
dma_chan_cfg.destination_transfer_width =
dma_chan_cfg.source_transfer_width;
switch (dma_channel_direction) {
case QM_DMA_MEMORY_TO_PERIPHERAL:
switch (spi) {
case QM_SPI_MST_0:
dma_chan_cfg.handshake_interface =
DMA_HW_IF_SPI_MASTER_0_TX;
break;
#if (QUARK_SE)
case QM_SPI_MST_1:
dma_chan_cfg.handshake_interface =
DMA_HW_IF_SPI_MASTER_1_TX;
break;
#endif
default:
/* Slave SPI is not supported. */
return -EINVAL;
}
/* The DMA burst length has to fit in the space remaining in the
* TX FIFO after the watermark level, DMATDLR. */
dma_chan_cfg.source_burst_length = SPI_DMA_WRITE_BURST_LENGTH;
dma_chan_cfg.destination_burst_length =
SPI_DMA_WRITE_BURST_LENGTH;
dma_context_p = &dma_context_tx[spi];
break;
case QM_DMA_PERIPHERAL_TO_MEMORY:
switch (spi) {
case QM_SPI_MST_0:
dma_chan_cfg.handshake_interface =
DMA_HW_IF_SPI_MASTER_0_RX;
break;
#if (QUARK_SE)
case QM_SPI_MST_1:
dma_chan_cfg.handshake_interface =
DMA_HW_IF_SPI_MASTER_1_RX;
break;
#endif
default:
/* Slave SPI is not supported. */
return -EINVAL;
}
/* The DMA burst length has to match the value of the receive
* watermark level, DMARDLR + 1. */
dma_chan_cfg.source_burst_length = SPI_DMA_READ_BURST_LENGTH;
dma_chan_cfg.destination_burst_length =
SPI_DMA_READ_BURST_LENGTH;
dma_context_p = &dma_context_rx[spi];
break;
default:
/* Memory to memory not allowed on SPI transfers. */
return -EINVAL;
}
/* The DMA driver needs a pointer to the client callback function so
* that later we can identify to which SPI controller the DMA callback
* corresponds to as well as whether we are dealing with a TX or RX
* dma_context struct. */
QM_ASSERT(dma_context_p);
dma_chan_cfg.callback_context = dma_context_p;
ret = qm_dma_channel_set_config(dma_ctrl_id, dma_channel_id,
&dma_chan_cfg);
if (ret) {
return ret;
}
/* To be used on received DMA callback. */
dma_context_p->spi_id = spi;
dma_context_p->dma_channel_id = dma_channel_id;
/* To be used on transfer setup. */
dma_core[spi] = dma_ctrl_id;
return 0;
}
int qm_spi_dma_transfer(const qm_spi_t spi,
const qm_spi_async_transfer_t *const xfer)
{
QM_CHECK(spi < QM_SPI_NUM, -EINVAL);
QM_CHECK(xfer, -EINVAL);
QM_CHECK(xfer->tx_len
? (xfer->tx &&
dma_context_tx[spi].dma_channel_id < QM_DMA_CHANNEL_NUM)
: 1,
-EINVAL);
QM_CHECK(xfer->rx_len
? (xfer->rx &&
dma_context_rx[spi].dma_channel_id < QM_DMA_CHANNEL_NUM)
: 1,
-EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_TX_RX ? (xfer->tx && xfer->rx) : 1,
-EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_TX_RX
? (xfer->tx_len == xfer->rx_len)
: 1,
-EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_TX ? (xfer->tx_len && !xfer->rx_len)
: 1,
-EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_RX ? (xfer->rx_len && !xfer->tx_len)
: 1,
-EINVAL);
QM_CHECK(tmode[spi] == QM_SPI_TMOD_EEPROM_READ
? (xfer->tx_len && xfer->rx_len)
: 1,
-EINVAL);
QM_CHECK(dma_core[spi] < QM_DMA_NUM, -EINVAL);
int ret;
qm_dma_transfer_t dma_trans = {0};
qm_spi_reg_t *const controller = QM_SPI[spi];
QM_ASSERT(0 == controller->ssienr);
/* Mask interrupts. */
controller->imr = QM_SPI_IMR_MASK_ALL;
if (xfer->rx_len) {
dma_trans.block_size = xfer->rx_len;
dma_trans.source_address = (uint32_t *)&controller->dr[0];
dma_trans.destination_address = (uint32_t *)xfer->rx;
ret = qm_dma_transfer_set_config(
dma_core[spi], dma_context_rx[spi].dma_channel_id,
&dma_trans);
if (ret) {
return ret;
}
/* In RX-only or EEPROM mode, the ctrlr1 register holds how
* many data frames the controller solicits, minus 1. */
controller->ctrlr1 = xfer->rx_len - 1;
}
if (xfer->tx_len) {
dma_trans.block_size = xfer->tx_len;
dma_trans.source_address = (uint32_t *)xfer->tx;
dma_trans.destination_address = (uint32_t *)&controller->dr[0];
ret = qm_dma_transfer_set_config(
dma_core[spi], dma_context_tx[spi].dma_channel_id,
&dma_trans);
if (ret) {
return ret;
}
}
/* Transfer pointer kept to extract user callback address and transfer
* client id when DMA completes. */
spi_async_transfer[spi] = xfer;
/* Enable the SPI device. */
controller->ssienr = QM_SPI_SSIENR_SSIENR;
if (xfer->rx_len) {
/* Enable receive DMA. */
controller->dmacr |= QM_SPI_DMACR_RDMAE;
/* Set the DMA receive threshold. */
controller->dmardlr = SPI_DMARDLR_DMARDL;
dma_context_rx[spi].cb_pending = true;
ret = qm_dma_transfer_start(dma_core[spi],
dma_context_rx[spi].dma_channel_id);
if (ret) {
dma_context_rx[spi].cb_pending = false;
/* Disable DMA setting and SPI controller. */
controller->dmacr = 0;
controller->ssienr = 0;
return ret;
}
if (!xfer->tx_len) {
/* In RX-only mode we need to transfer an initial dummy
* byte. */
write_frame(spi, (uint8_t *)&tx_dummy_frame);
}
}
if (xfer->tx_len) {
/* Enable transmit DMA. */
controller->dmacr |= QM_SPI_DMACR_TDMAE;
/* Set the DMA transmit threshold. */
controller->dmatdlr = SPI_DMATDLR_DMATDL;
dma_context_tx[spi].cb_pending = true;
ret = qm_dma_transfer_start(dma_core[spi],
dma_context_tx[spi].dma_channel_id);
if (ret) {
dma_context_tx[spi].cb_pending = false;
if (xfer->rx_len) {
/* If a RX transfer was previously started, we
* need to stop it - the SPI device will be
* disabled when handling the DMA callback. */
qm_spi_dma_transfer_terminate(spi);
} else {
/* Disable DMA setting and SPI controller. */
controller->dmacr = 0;
controller->ssienr = 0;
}
return ret;
}
}
return 0;
}
int qm_spi_dma_transfer_terminate(qm_spi_t spi)
{
QM_CHECK(spi < QM_SPI_NUM, -EINVAL);
QM_CHECK(dma_context_tx[spi].cb_pending
? (dma_context_tx[spi].dma_channel_id < QM_DMA_CHANNEL_NUM)
: 1,
-EINVAL);
QM_CHECK(dma_context_rx[spi].cb_pending
? (dma_context_rx[spi].dma_channel_id < QM_DMA_CHANNEL_NUM)
: 1,
-EINVAL);
int ret = 0;
if (dma_context_tx[spi].cb_pending) {
if (0 !=
qm_dma_transfer_terminate(
dma_core[spi], dma_context_tx[spi].dma_channel_id)) {
ret = -EIO;
}
}
if (dma_context_rx[spi].cb_pending) {
if (0 !=
qm_dma_transfer_terminate(
dma_core[spi], dma_context_rx[spi].dma_channel_id)) {
ret = -EIO;
}
}
return ret;
}

View file

@ -0,0 +1,635 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 <errno.h>
#include "qm_uart.h"
#ifndef UNIT_TEST
qm_uart_reg_t *qm_uart[QM_UART_NUM] = {(qm_uart_reg_t *)QM_UART_0_BASE,
(qm_uart_reg_t *)QM_UART_1_BASE};
#endif
typedef void (*uart_client_callback_t)(void *data, int error,
qm_uart_status_t status, uint32_t len);
/**
* DMA transfer information, relevant on callback invocations from the DMA
* driver.
*/
typedef struct {
qm_dma_channel_id_t dma_channel_id; /**< DMA channel. */
const qm_uart_transfer_t *xfer; /**< User transfer structure. */
} dma_context_t;
/* UART Callback pointers. */
static uart_client_callback_t write_callback[QM_UART_NUM];
static uart_client_callback_t read_callback[QM_UART_NUM];
/* User callback data. */
static void *write_data[QM_UART_NUM], *read_data[QM_UART_NUM];
/* Buffer pointers to store transmit / receive data for UART */
static uint8_t *write_buffer[QM_UART_NUM], *read_buffer[QM_UART_NUM];
static uint32_t write_pos[QM_UART_NUM], write_len[QM_UART_NUM];
static uint32_t read_pos[QM_UART_NUM], read_len[QM_UART_NUM];
/* DMA (memory to UART) callback information. */
static dma_context_t dma_context_tx[QM_UART_NUM];
/* DMA (UART to memory) callback information. */
static dma_context_t dma_context_rx[QM_UART_NUM];
/* DMA core being used by each UART. */
static qm_dma_t dma_core[QM_UART_NUM];
static bool is_read_xfer_complete(const qm_uart_t uart)
{
return read_pos[uart] >= read_len[uart];
}
static bool is_write_xfer_complete(const qm_uart_t uart)
{
return write_pos[uart] >= write_len[uart];
}
static void qm_uart_isr_handler(const qm_uart_t uart)
{
qm_uart_reg_t *const regs = QM_UART[uart];
uint8_t interrupt_id = regs->iir_fcr & QM_UART_IIR_IID_MASK;
/*
* Interrupt ID priority levels (from highest to lowest):
* 1: QM_UART_IIR_RECV_LINE_STATUS
* 2: QM_UART_IIR_RECV_DATA_AVAIL and QM_UART_IIR_CHAR_TIMEOUT
* 3: QM_UART_IIR_THR_EMPTY
*/
switch (interrupt_id) {
case QM_UART_IIR_THR_EMPTY:
if (is_write_xfer_complete(uart)) {
regs->ier_dlh &= ~QM_UART_IER_ETBEI;
/*
* At this point the FIFOs are empty, but the shift
* register still is transmitting the last 8 bits. So if
* we were to read LSR, it would say the device is still
* busy. Use the SCR Bit 0 to indicate an irq tx is
* complete.
*/
regs->scr |= BIT(0);
if (write_callback[uart]) {
write_callback[uart](write_data[uart], 0,
QM_UART_IDLE,
write_pos[uart]);
}
return;
}
/*
* If we are starting the transfer then the TX FIFO is empty.
* In that case we set 'count' variable to QM_UART_FIFO_DEPTH
* in order to take advantage of the whole FIFO capacity.
*/
int count = (write_pos[uart] == 0) ? QM_UART_FIFO_DEPTH
: QM_UART_FIFO_HALF_DEPTH;
while (count-- && !is_write_xfer_complete(uart)) {
regs->rbr_thr_dll =
write_buffer[uart][write_pos[uart]++];
}
/*
* Change the threshold level to trigger an interrupt when the
* TX buffer is empty.
*/
if (is_write_xfer_complete(uart)) {
regs->iir_fcr = QM_UART_FCR_TX_0_RX_1_2_THRESHOLD |
QM_UART_FCR_FIFOE;
}
break;
case QM_UART_IIR_CHAR_TIMEOUT:
case QM_UART_IIR_RECV_DATA_AVAIL:
/*
* Copy data from RX FIFO to xfer buffer as long as the xfer
* has not completed and we have data in the RX FIFO.
*/
while (!is_read_xfer_complete(uart)) {
uint32_t lsr = regs->lsr;
/*
* A break condition may cause a line status interrupt
* to follow very closely after a char timeout
* interrupt, but reading the lsr effectively clears the
* pending interrupts so we issue here the callback
* instead, otherwise we would miss it.
* NOTE: Returned len is 0 for now, this might change
* in the future.
*/
if (lsr & QM_UART_LSR_ERROR_BITS) {
if (read_callback[uart]) {
read_callback[uart](
read_data[uart], -EIO,
lsr & QM_UART_LSR_ERROR_BITS, 0);
}
}
if (lsr & QM_UART_LSR_DR) {
read_buffer[uart][read_pos[uart]++] =
regs->rbr_thr_dll;
} else {
/* No more data in the RX FIFO */
break;
}
}
if (is_read_xfer_complete(uart)) {
/*
* Disable both 'Receiver Data Available' and
* 'Receiver Line Status' interrupts.
*/
regs->ier_dlh &=
~(QM_UART_IER_ERBFI | QM_UART_IER_ELSI);
if (read_callback[uart]) {
read_callback[uart](read_data[uart], 0,
QM_UART_IDLE,
read_pos[uart]);
}
}
break;
case QM_UART_IIR_RECV_LINE_STATUS:
if (read_callback[uart]) {
/*
* NOTE: Returned len is 0 for now, this might change
* in the future.
*/
read_callback[uart](read_data[uart], -EIO,
regs->lsr & QM_UART_LSR_ERROR_BITS,
0);
}
break;
}
}
QM_ISR_DECLARE(qm_uart_0_isr)
{
qm_uart_isr_handler(QM_UART_0);
QM_ISR_EOI(QM_IRQ_UART_0_VECTOR);
}
QM_ISR_DECLARE(qm_uart_1_isr)
{
qm_uart_isr_handler(QM_UART_1);
QM_ISR_EOI(QM_IRQ_UART_1_VECTOR);
}
int qm_uart_set_config(const qm_uart_t uart, const qm_uart_config_t *cfg)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
QM_CHECK(cfg != NULL, -EINVAL);
qm_uart_reg_t *const regs = QM_UART[uart];
/* Clear DLAB by unsetting line parameters */
regs->lcr = 0;
/* Set divisor latch registers (integer + fractional part) */
regs->lcr = QM_UART_LCR_DLAB;
regs->ier_dlh = QM_UART_CFG_BAUD_DLH_UNPACK(cfg->baud_divisor);
regs->rbr_thr_dll = QM_UART_CFG_BAUD_DLL_UNPACK(cfg->baud_divisor);
regs->dlf = QM_UART_CFG_BAUD_DLF_UNPACK(cfg->baud_divisor);
/* Set line parameters. This also unsets the DLAB */
regs->lcr = cfg->line_control;
/* Hardware automatic flow control */
regs->mcr = 0;
if (true == cfg->hw_fc) {
regs->mcr |= QM_UART_MCR_AFCE | QM_UART_MCR_RTS;
}
/* FIFO's enable and reset, set interrupt threshold */
regs->iir_fcr =
(QM_UART_FCR_FIFOE | QM_UART_FCR_RFIFOR | QM_UART_FCR_XFIFOR |
QM_UART_FCR_DEFAULT_TX_RX_THRESHOLD);
regs->ier_dlh |= QM_UART_IER_PTIME;
return 0;
}
int qm_uart_get_status(const qm_uart_t uart, qm_uart_status_t *const status)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
QM_CHECK(status != NULL, -EINVAL);
qm_uart_reg_t *const regs = QM_UART[uart];
uint32_t lsr = regs->lsr;
*status = (lsr & (QM_UART_LSR_OE | QM_UART_LSR_PE | QM_UART_LSR_FE |
QM_UART_LSR_BI));
/*
* Check as an IRQ TX completed, if so, the Shift register may still be
* busy.
*/
if (regs->scr & BIT(0)) {
regs->scr &= ~BIT(0);
} else if (!(lsr & (QM_UART_LSR_TEMT))) {
*status |= QM_UART_TX_BUSY;
}
if (lsr & QM_UART_LSR_DR) {
*status |= QM_UART_RX_BUSY;
}
return 0;
}
int qm_uart_write(const qm_uart_t uart, const uint8_t data)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
qm_uart_reg_t *const regs = QM_UART[uart];
while (regs->lsr & QM_UART_LSR_THRE) {
}
regs->rbr_thr_dll = data;
/* Wait for transaction to complete. */
while (!(regs->lsr & QM_UART_LSR_TEMT)) {
}
return 0;
}
int qm_uart_read(const qm_uart_t uart, uint8_t *const data,
qm_uart_status_t *status)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
QM_CHECK(data != NULL, -EINVAL);
qm_uart_reg_t *const regs = QM_UART[uart];
uint32_t lsr = regs->lsr;
while (!(lsr & QM_UART_LSR_DR)) {
lsr = regs->lsr;
}
/* Check if there are any errors on the line. */
if (lsr & QM_UART_LSR_ERROR_BITS) {
if (status) {
*status = (lsr & QM_UART_LSR_ERROR_BITS);
}
return -EIO;
}
*data = regs->rbr_thr_dll;
return 0;
}
int qm_uart_write_non_block(const qm_uart_t uart, const uint8_t data)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
qm_uart_reg_t *const regs = QM_UART[uart];
regs->rbr_thr_dll = data;
return 0;
}
int qm_uart_read_non_block(const qm_uart_t uart, uint8_t *const data)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
QM_CHECK(data != NULL, -EINVAL);
qm_uart_reg_t *const regs = QM_UART[uart];
*data = regs->rbr_thr_dll;
return 0;
}
int qm_uart_write_buffer(const qm_uart_t uart, const uint8_t *const data,
uint32_t len)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
QM_CHECK(data != NULL, -EINVAL);
qm_uart_reg_t *const regs = QM_UART[uart];
uint8_t *d = (uint8_t *)data;
while (len--) {
/*
* Because FCR_FIFOE and IER_PTIME are enabled, LSR_THRE
* behaves as a TX FIFO full indicator.
*/
while (regs->lsr & QM_UART_LSR_THRE) {
}
regs->rbr_thr_dll = *d;
d++;
}
/* Wait for transaction to complete. */
while (!(regs->lsr & QM_UART_LSR_TEMT)) {
}
return 0;
}
int qm_uart_irq_write(const qm_uart_t uart,
const qm_uart_transfer_t *const xfer)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
QM_CHECK(xfer != NULL, -EINVAL);
qm_uart_reg_t *const regs = QM_UART[uart];
write_pos[uart] = 0;
write_len[uart] = xfer->data_len;
write_buffer[uart] = xfer->data;
write_callback[uart] = xfer->callback;
write_data[uart] = xfer->callback_data;
/* Set threshold */
regs->iir_fcr =
(QM_UART_FCR_FIFOE | QM_UART_FCR_DEFAULT_TX_RX_THRESHOLD);
/* Enable TX holding reg empty interrupt. */
regs->ier_dlh |= QM_UART_IER_ETBEI;
return 0;
}
int qm_uart_irq_read(const qm_uart_t uart, const qm_uart_transfer_t *const xfer)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
QM_CHECK(xfer != NULL, -EINVAL);
qm_uart_reg_t *const regs = QM_UART[uart];
read_pos[uart] = 0;
read_len[uart] = xfer->data_len;
read_buffer[uart] = xfer->data;
read_callback[uart] = xfer->callback;
read_data[uart] = xfer->callback_data;
/* Set threshold */
regs->iir_fcr =
(QM_UART_FCR_FIFOE | QM_UART_FCR_DEFAULT_TX_RX_THRESHOLD);
/*
* Enable both 'Receiver Data Available' and 'Receiver
* Line Status' interrupts.
*/
regs->ier_dlh |= QM_UART_IER_ERBFI | QM_UART_IER_ELSI;
return 0;
}
int qm_uart_irq_write_terminate(const qm_uart_t uart)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
qm_uart_reg_t *const regs = QM_UART[uart];
/* Disable TX holding reg empty interrupt. */
regs->ier_dlh &= ~QM_UART_IER_ETBEI;
if (write_callback[uart]) {
write_callback[uart](write_data[uart], -ECANCELED, QM_UART_IDLE,
write_pos[uart]);
}
write_len[uart] = 0;
return 0;
}
int qm_uart_irq_read_terminate(const qm_uart_t uart)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
qm_uart_reg_t *const regs = QM_UART[uart];
/*
* Disable both 'Receiver Data Available' and 'Receiver Line Status'
* interrupts.
*/
regs->ier_dlh &= ~(QM_UART_IER_ERBFI | QM_UART_IER_ELSI);
if (read_callback[uart]) {
read_callback[uart](read_data[uart], -ECANCELED, QM_UART_IDLE,
read_pos[uart]);
}
read_len[uart] = 0;
return 0;
}
/* DMA driver invoked callback. */
static void uart_dma_callback(void *callback_context, uint32_t len,
int error_code)
{
QM_ASSERT(callback_context);
const qm_uart_transfer_t *const xfer =
((dma_context_t *)callback_context)->xfer;
QM_ASSERT(xfer);
const uart_client_callback_t client_callback = xfer->callback;
void *const client_data = xfer->callback_data;
const uint32_t client_expected_len = xfer->data_len;
if (!client_callback) {
return;
}
if (error_code) {
/*
* Transfer failed, pass to client the error code returned by
* the DMA driver.
*/
client_callback(client_data, error_code, QM_UART_IDLE, 0);
} else if (len == client_expected_len) {
/* Transfer completed successfully. */
client_callback(client_data, 0, QM_UART_IDLE, len);
} else {
QM_ASSERT(len < client_expected_len);
/* Transfer cancelled. */
client_callback(client_data, -ECANCELED, QM_UART_IDLE, len);
}
}
int qm_uart_dma_channel_config(
const qm_uart_t uart, const qm_dma_t dma_ctrl_id,
const qm_dma_channel_id_t dma_channel_id,
const qm_dma_channel_direction_t dma_channel_direction)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
QM_CHECK(dma_ctrl_id < QM_DMA_NUM, -EINVAL);
QM_CHECK(dma_channel_id < QM_DMA_CHANNEL_NUM, -EINVAL);
int ret = -EINVAL;
qm_dma_channel_config_t dma_chan_cfg = {0};
/* UART has inverted handshake polarity. */
dma_chan_cfg.handshake_polarity = QM_DMA_HANDSHAKE_POLARITY_LOW;
dma_chan_cfg.channel_direction = dma_channel_direction;
dma_chan_cfg.source_transfer_width = QM_DMA_TRANS_WIDTH_8;
dma_chan_cfg.destination_transfer_width = QM_DMA_TRANS_WIDTH_8;
/* Default FIFO threshold is 1/2 full (8 bytes). */
dma_chan_cfg.source_burst_length = QM_DMA_BURST_TRANS_LENGTH_8;
dma_chan_cfg.destination_burst_length = QM_DMA_BURST_TRANS_LENGTH_8;
dma_chan_cfg.client_callback = uart_dma_callback;
switch (dma_channel_direction) {
case QM_DMA_MEMORY_TO_PERIPHERAL:
switch (uart) {
case QM_UART_0:
dma_chan_cfg.handshake_interface = DMA_HW_IF_UART_A_TX;
break;
case QM_UART_1:
dma_chan_cfg.handshake_interface = DMA_HW_IF_UART_B_TX;
break;
default:
return -EINVAL;
}
/*
* The DMA driver needs a pointer to the DMA context structure
* used on DMA callback invocation.
*/
dma_context_tx[uart].dma_channel_id = dma_channel_id;
dma_chan_cfg.callback_context = &dma_context_tx[uart];
break;
case QM_DMA_PERIPHERAL_TO_MEMORY:
switch (uart) {
case QM_UART_0:
dma_chan_cfg.handshake_interface = DMA_HW_IF_UART_A_RX;
break;
case QM_UART_1:
dma_chan_cfg.handshake_interface = DMA_HW_IF_UART_B_RX;
break;
default:
return -EINVAL;
}
/*
* The DMA driver needs a pointer to the DMA context structure
* used on DMA callback invocation.
*/
dma_context_rx[uart].dma_channel_id = dma_channel_id;
dma_chan_cfg.callback_context = &dma_context_rx[uart];
break;
default:
/* Direction not allowed on UART transfers. */
return -EINVAL;
}
dma_core[uart] = dma_ctrl_id;
ret = qm_dma_channel_set_config(dma_ctrl_id, dma_channel_id,
&dma_chan_cfg);
return ret;
}
int qm_uart_dma_write(const qm_uart_t uart,
const qm_uart_transfer_t *const xfer)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
QM_CHECK(xfer, -EINVAL);
QM_CHECK(xfer->data, -EINVAL);
QM_CHECK(xfer->data_len, -EINVAL);
int ret = -EINVAL;
qm_uart_reg_t *regs = QM_UART[uart];
qm_dma_transfer_t dma_trans = {0};
dma_trans.block_size = xfer->data_len;
dma_trans.source_address = (uint32_t *)xfer->data;
dma_trans.destination_address = (uint32_t *)&regs->rbr_thr_dll;
ret = qm_dma_transfer_set_config(
dma_core[uart], dma_context_tx[uart].dma_channel_id, &dma_trans);
if (ret) {
return ret;
}
/* Store the user transfer pointer that we will need on DMA callback. */
dma_context_tx[uart].xfer = xfer;
/* Set the FCR register FIFO thresholds. */
regs->iir_fcr =
(QM_UART_FCR_FIFOE | QM_UART_FCR_DEFAULT_TX_RX_THRESHOLD);
ret = qm_dma_transfer_start(dma_core[uart],
dma_context_tx[uart].dma_channel_id);
return ret;
}
int qm_uart_dma_read(const qm_uart_t uart, const qm_uart_transfer_t *const xfer)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
QM_CHECK(xfer, -EINVAL);
QM_CHECK(xfer->data, -EINVAL);
QM_CHECK(xfer->data_len, -EINVAL);
int ret = -EINVAL;
qm_uart_reg_t *regs = QM_UART[uart];
qm_dma_transfer_t dma_trans = {0};
dma_trans.block_size = xfer->data_len;
dma_trans.source_address = (uint32_t *)&regs->rbr_thr_dll;
dma_trans.destination_address = (uint32_t *)xfer->data;
ret = qm_dma_transfer_set_config(
dma_core[uart], dma_context_rx[uart].dma_channel_id, &dma_trans);
if (ret) {
return ret;
}
/* Store the user transfer pointer that we will need on DMA callback. */
dma_context_rx[uart].xfer = xfer;
/* Set the FCR register FIFO thresholds. */
regs->iir_fcr =
(QM_UART_FCR_FIFOE | QM_UART_FCR_DEFAULT_TX_RX_THRESHOLD);
ret = qm_dma_transfer_start(dma_core[uart],
dma_context_rx[uart].dma_channel_id);
return ret;
}
int qm_uart_dma_write_terminate(const qm_uart_t uart)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
int ret = qm_dma_transfer_terminate(
dma_core[uart], dma_context_tx[uart].dma_channel_id);
return ret;
}
int qm_uart_dma_read_terminate(const qm_uart_t uart)
{
QM_CHECK(uart < QM_UART_NUM, -EINVAL);
int ret = qm_dma_transfer_terminate(
dma_core[uart], dma_context_rx[uart].dma_channel_id);
return ret;
}

View file

@ -0,0 +1,39 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_version.h"
uint32_t qm_ver_rom(void)
{
volatile uint32_t *ver_pointer;
ver_pointer = (uint32_t*)ROM_VERSION_ADDRESS;
return *ver_pointer;
}

View file

@ -0,0 +1,93 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_wdt.h"
#define QM_WDT_RELOAD_VALUE (0x76)
static void (*callback[QM_WDT_NUM])(void *data);
static void *callback_data[QM_WDT_NUM];
QM_ISR_DECLARE(qm_wdt_isr_0)
{
if (callback[QM_WDT_0]) {
callback[QM_WDT_0](callback_data);
}
QM_ISR_EOI(QM_IRQ_WDT_0_VECTOR);
}
int qm_wdt_start(const qm_wdt_t wdt)
{
QM_CHECK(wdt < QM_WDT_NUM, -EINVAL);
QM_WDT[wdt].wdt_cr |= QM_WDT_ENABLE;
#if (QUARK_SE)
/* Enable the peripheral clock. */
QM_SCSS_CCU->ccu_periph_clk_gate_ctl |= BIT(1);
#elif(QUARK_D2000)
QM_SCSS_CCU->ccu_periph_clk_gate_ctl |= BIT(10);
#else
#error("Unsupported / unspecified processor detected.");
#endif
QM_SCSS_PERIPHERAL->periph_cfg0 |= BIT(1);
return 0;
}
int qm_wdt_set_config(const qm_wdt_t wdt, const qm_wdt_config_t *const cfg)
{
QM_CHECK(wdt < QM_WDT_NUM, -EINVAL);
QM_CHECK(cfg != NULL, -EINVAL);
if (cfg->mode == QM_WDT_MODE_INTERRUPT_RESET) {
callback[wdt] = cfg->callback;
callback_data[wdt] = cfg->callback_data;
}
QM_WDT[wdt].wdt_cr &= ~QM_WDT_MODE;
QM_WDT[wdt].wdt_cr |= cfg->mode << QM_WDT_MODE_OFFSET;
QM_WDT[wdt].wdt_torr = cfg->timeout;
/* kick the WDT to load the Timeout Period(TOP) value */
qm_wdt_reload(wdt);
return 0;
}
int qm_wdt_reload(const qm_wdt_t wdt)
{
QM_CHECK(wdt < QM_WDT_NUM, -EINVAL);
QM_WDT[wdt].wdt_crr = QM_WDT_RELOAD_VALUE;
return 0;
}

View file

@ -0,0 +1,60 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "rar.h"
#if (HAS_RAR)
int rar_set_mode(const rar_state_t mode)
{
QM_CHECK(mode <= RAR_RETENTION, -EINVAL);
volatile uint32_t i = 32;
volatile uint32_t reg;
switch (mode) {
case RAR_RETENTION:
QM_SCSS_PMU->aon_vr |=
(QM_AON_VR_PASS_CODE | QM_AON_VR_ROK_BUF_VREG_MASK);
QM_SCSS_PMU->aon_vr |=
(QM_AON_VR_PASS_CODE | QM_AON_VR_VREG_SEL);
break;
case RAR_NORMAL:
reg = QM_SCSS_PMU->aon_vr & ~QM_AON_VR_VREG_SEL;
QM_SCSS_PMU->aon_vr = QM_AON_VR_PASS_CODE | reg;
/* Wait for >= 2usec, at most 64 clock cycles. */
while (i--) {
__asm__ __volatile__("nop");
}
reg = QM_SCSS_PMU->aon_vr & ~QM_AON_VR_ROK_BUF_VREG_MASK;
QM_SCSS_PMU->aon_vr = QM_AON_VR_PASS_CODE | reg;
break;
}
return 0;
}
#endif

View file

@ -0,0 +1,301 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_SS_ADC_H__
#define __QM_SS_ADC_H__
#include "qm_common.h"
#include "qm_sensor_regs.h"
/**
* Analog to Digital Converter (ADC) for the Sensor Subsystem.
*
* @defgroup groupSSADC SS ADC
* @{
*/
/**
* SS ADC sample size type.
*/
typedef uint16_t qm_ss_adc_sample_t;
/**
* SS ADC calibration type.
*/
typedef uint8_t qm_ss_adc_calibration_t;
/**
* SS ADC status.
*/
typedef enum {
QM_SS_ADC_IDLE = 0x0, /**< ADC idle. */
QM_SS_ADC_COMPLETE = 0x1, /**< ADC data available. */
QM_SS_ADC_OVERFLOW = 0x2, /**< ADC overflow error. */
QM_SS_ADC_UNDERFLOW = 0x4, /**< ADC underflow error. */
QM_SS_ADC_SEQERROR = 0x8 /**< ADC sequencer error. */
} qm_ss_adc_status_t;
/**
* SS ADC resolution type.
*/
typedef enum {
QM_SS_ADC_RES_6_BITS = 0x5, /**< 6-bit mode. */
QM_SS_ADC_RES_8_BITS = 0x7, /**< 8-bit mode. */
QM_SS_ADC_RES_10_BITS = 0x9, /**< 10-bit mode. */
QM_SS_ADC_RES_12_BITS = 0xB /**< 12-bit mode. */
} qm_ss_adc_resolution_t;
/**
* SS ADC operating mode type.
*/
typedef enum {
QM_SS_ADC_MODE_DEEP_PWR_DOWN, /**< Deep power down mode. */
QM_SS_ADC_MODE_PWR_DOWN, /**< Power down mode. */
QM_SS_ADC_MODE_STDBY, /**< Standby mode. */
QM_SS_ADC_MODE_NORM_CAL, /**< Normal mode, with calibration. */
QM_SS_ADC_MODE_NORM_NO_CAL /**< Normal mode, no calibration. */
} qm_ss_adc_mode_t;
/**
* SS ADC channels type.
*/
typedef enum {
QM_SS_ADC_CH_0, /**< ADC Channel 0. */
QM_SS_ADC_CH_1, /**< ADC Channel 1. */
QM_SS_ADC_CH_2, /**< ADC Channel 2. */
QM_SS_ADC_CH_3, /**< ADC Channel 3. */
QM_SS_ADC_CH_4, /**< ADC Channel 4. */
QM_SS_ADC_CH_5, /**< ADC Channel 5. */
QM_SS_ADC_CH_6, /**< ADC Channel 6. */
QM_SS_ADC_CH_7, /**< ADC Channel 7. */
QM_SS_ADC_CH_8, /**< ADC Channel 8. */
QM_SS_ADC_CH_9, /**< ADC Channel 9. */
QM_SS_ADC_CH_10, /**< ADC Channel 10. */
QM_SS_ADC_CH_11, /**< ADC Channel 11. */
QM_SS_ADC_CH_12, /**< ADC Channel 12. */
QM_SS_ADC_CH_13, /**< ADC Channel 13. */
QM_SS_ADC_CH_14, /**< ADC Channel 14. */
QM_SS_ADC_CH_15, /**< ADC Channel 15. */
QM_SS_ADC_CH_16, /**< ADC Channel 16. */
QM_SS_ADC_CH_17, /**< ADC Channel 17. */
QM_SS_ADC_CH_18 /**< ADC Channel 18. */
} qm_ss_adc_channel_t;
/**
* SS ADC interrupt callback source.
*/
typedef enum {
QM_SS_ADC_TRANSFER, /**< Transfer complete or error callback. */
QM_SS_ADC_MODE_CHANGED, /**< Mode change complete callback. */
QM_SS_ADC_CAL_COMPLETE, /**< Calibration complete callback. */
} qm_ss_adc_cb_source_t;
/**
* SS ADC configuration type.
*/
typedef struct {
/**
* Sample interval in ADC clock cycles, defines the period to wait
* between the start of each sample and can be in the range
* [(resolution+2) - 255].
*/
uint8_t window;
qm_ss_adc_resolution_t resolution; /**< 12, 10, 8, 6-bit resolution. */
} qm_ss_adc_config_t;
/**
* SS ADC transfer type.
*/
typedef struct {
qm_ss_adc_channel_t *ch; /**< Channel sequence array (1-32 channels). */
uint8_t ch_len; /**< Number of channels in the above array. */
qm_ss_adc_sample_t *samples; /**< Array to store samples. */
uint32_t samples_len; /**< Length of sample array. */
/**
* Transfer callback.
*
* Called when a conversion is performed or an error is detected.
*
* @param[in] data The callback user data.
* @param[in] error 0 on success.
* Negative @ref errno for possible error codes.
* @param[in] status ADC status.
* @param[in] source Interrupt callback source.
*/
void (*callback)(void *data, int error, qm_ss_adc_status_t status,
qm_ss_adc_cb_source_t source);
void *callback_data; /**< Callback user data. */
} qm_ss_adc_xfer_t;
/**
* Switch operating mode of SS ADC.
*
* This call is blocking.
*
* @param[in] adc Which ADC to enable.
* @param[in] mode ADC operating mode.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_adc_set_mode(const qm_ss_adc_t adc, const qm_ss_adc_mode_t mode);
/**
* Switch operating mode of SS ADC.
*
* This call is non-blocking and will call the user callback on completion.
*
* @param[in] adc Which ADC to enable.
* @param[in] mode ADC operating mode.
* @param[in] callback Callback called on completion.
* @param[in] callback_data The callback user data.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_adc_irq_set_mode(const qm_ss_adc_t adc, const qm_ss_adc_mode_t mode,
void (*callback)(void *data, int error,
qm_ss_adc_status_t status,
qm_ss_adc_cb_source_t source),
void *callback_data);
/**
* Calibrate the SS ADC.
*
* It is necessary to calibrate if it is intended to use Normal Mode With
* Calibration. The calibration must be performed if the ADC is used for the
* first time or has been in deep power down mode. This call is blocking.
*
* @param[in] adc Which ADC to calibrate.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_adc_calibrate(const qm_ss_adc_t adc);
/**
* Calibrate the SS ADC.
*
* It is necessary to calibrate if it is intended to use Normal Mode With
* Calibration. The calibration must be performed if the ADC is used for the
* first time or has been in deep power down mode. This call is non-blocking
* and will call the user callback on completion.
*
* @param[in] adc Which ADC to calibrate.
* @param[in] callback Callback called on completion.
* @param[in] callback_data The callback user data.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_adc_irq_calibrate(const qm_ss_adc_t adc,
void (*callback)(void *data, int error,
qm_ss_adc_status_t status,
qm_ss_adc_cb_source_t source),
void *callback_data);
/**
* Set SS ADC calibration data.
*
* @param[in] adc Which ADC to set calibration for.
* @param[in] cal Calibration data.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_adc_set_calibration(const qm_ss_adc_t adc,
const qm_ss_adc_calibration_t cal);
/**
* Get the current calibration data for an SS ADC.
*
* @param[in] adc Which ADC to get calibration for.
* @param[out] adc Calibration data. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_adc_get_calibration(const qm_ss_adc_t adc,
qm_ss_adc_calibration_t *const cal);
/**
* Set SS ADC configuration.
*
* This sets the sample window and resolution.
*
* @param[in] adc Which ADC to configure.
* @param[in] cfg ADC configuration. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_adc_set_config(const qm_ss_adc_t adc,
const qm_ss_adc_config_t *const cfg);
/**
* Synchronously read values from the ADC.
*
* This blocking call can read 1-32 ADC values into the array provided.
*
* @param[in] adc Which ADC to read.
* @param[in,out] xfer Channel and sample info. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_adc_convert(const qm_ss_adc_t adc, qm_ss_adc_xfer_t *const xfer);
/**
* Asynchronously read values from the SS ADC.
*
* This is a non-blocking call and will call the user provided callback after
* the requested number of samples have been converted.
*
* @param[in] adc Which ADC to read.
* @param[in,out] xfer Channel sample and callback info. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_adc_irq_convert(const qm_ss_adc_t adc, qm_ss_adc_xfer_t *const xfer);
/**
* @}
*/
#endif /* __QM_ADC_H__ */

View file

@ -0,0 +1,179 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_SS_GPIO_H__
#define __QM_SS_GPIO_H__
#include "qm_common.h"
#include "qm_sensor_regs.h"
/**
* General Purpose IO for Sensor Subsystem.
*
* @defgroup groupSSGPIO SS GPIO
* @{
*/
/**
* GPIO SS pin states.
*/
typedef enum {
QM_SS_GPIO_LOW, /**< Pin level high. */
QM_SS_GPIO_HIGH, /**< Pin level low. */
QM_SS_GPIO_STATE_NUM
} qm_ss_gpio_state_t;
/**
* GPIO port configuration type.
*
* Each bit in the registers control a GPIO pin.
*/
typedef struct {
uint32_t direction; /**< SS GPIO direction, 0b: input, 1b: output. */
uint32_t int_en; /**< Interrupt enable. */
uint32_t int_type; /**< Interrupt type, 0b: level; 1b: edge. */
uint32_t int_polarity; /**< Interrupt polarity, 0b: low, 1b: high. */
uint32_t int_debounce; /**< Debounce on/off. */
/**
* User callback.
*
* Called for any interrupt on the Sensor Subsystem GPIO.
*
* @param[in] data The callback user data.
* @param[in] int_status Bitfield of triggered pins.
*/
void (*callback)(void *data, uint32_t int_status);
void *callback_data; /**< Callback user data. */
} qm_ss_gpio_port_config_t;
/**
* Set SS GPIO port configuration.
*
* This includes the direction of the pins, if interrupts are enabled or not,
* the level on which an interrupt is generated, the polarity of interrupts
* and if GPIO-debounce is enabled or not. If interrupts are enabled it also
* registers the user defined callback function.
*
* @param[in] gpio SS GPIO port index to configure.
* @param[in] cfg New configuration for SS GPIO port. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_gpio_set_config(const qm_ss_gpio_t gpio,
const qm_ss_gpio_port_config_t *const cfg);
/**
* Read the current value of a single pin on a given SS GPIO port.
*
* @param[in] gpio SS GPIO port index.
* @param[in] pin Pin of SS GPIO port to read.
* @param[out] state QM_GPIO_LOW for low or QM_GPIO_HIGH for high. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_gpio_read_pin(const qm_ss_gpio_t gpio, const uint8_t pin,
qm_ss_gpio_state_t *const state);
/**
* Set a single pin on a given SS GPIO port.
*
* @param[in] gpio SS GPIO port index.
* @param[in] pin Pin of SS GPIO port to set.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_gpio_set_pin(const qm_ss_gpio_t gpio, const uint8_t pin);
/**
* Clear a single pin on a given SS GPIO port.
*
* @param[in] gpio SS GPIO port index.
* @param[in] pin Pin of SS GPIO port to clear.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_gpio_clear_pin(const qm_ss_gpio_t gpio, const uint8_t pin);
/**
* Set or clear a single SS GPIO pin using a state variable.
*
* @param[in] gpio GPIO port index.
* @param[in] pin Pin of GPIO port to update.
* @param[in] state QM_GPIO_LOW for low or QM_GPIO_HIGH for high.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_gpio_set_pin_state(const qm_ss_gpio_t gpio, const uint8_t pin,
const qm_ss_gpio_state_t state);
/**
* Get SS GPIO port values.
*
* Read entire SS GPIO port. Each bit of the val parameter is set to the current
* value of each pin on the port. Maximum 32 pins per port.
*
* @param[in] gpio SS GPIO port index.
* @param[out] port Value of all pins on GPIO port. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_gpio_read_port(const qm_ss_gpio_t gpio, uint32_t *const port);
/**
* Get SS GPIO port values.
*
* Write entire SS GPIO port. Each pin on the SS GPIO port is set to the
* corresponding value set in the val parameter. Maximum 32 pins per port.
*
* @param[in] gpio SS GPIO port index.
* @param[in] val Value of all pins on SS GPIO port.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_gpio_write_port(const qm_ss_gpio_t gpio, const uint32_t val);
/**
* @}
*/
#endif /* __QM_SS_GPIO_H__ */

View file

@ -0,0 +1,264 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_SS_I2C_H__
#define __QM_SS_I2C_H__
#include "qm_common.h"
#include "qm_sensor_regs.h"
/**
* I2C driver for Sensor Subsystem.
*
* @defgroup groupSSI2C SS I2C
* @{
*/
/**
* Standard speed High/low period for 50% duty cycle bus clock (in nanosecs).
*/
#define QM_I2C_SS_50_DC_NS (5000)
/**
* Fast Speed High/low period for 50% duty cycle bus clock (in nanosecs).
*/
#define QM_I2C_FS_50_DC_NS (1250)
/**
* High Speed High/low period for 50% duty cycle bus clock (in nanosecs).
*/
#define QM_I2C_FSP_50_DC_NS (500)
/**
* Standard speed minimum low period to meet timing requirements (in nanosecs).
*/
#define QM_I2C_MIN_SS_NS (4700)
/**
* Fast speed minimum low period to meet timing requirements (in nanosecs).
*/
#define QM_I2C_MIN_FS_NS (1300)
/**
* High speed minimum low period to meet timing requirements (in nanosecs).
*/
#define QM_I2C_MIN_FSP_NS (500)
/**
* QM SS I2C addressing type.
*/
typedef enum {
QM_SS_I2C_7_BIT = 0, /**< 7-bit mode. */
QM_SS_I2C_10_BIT /**< 10-bit mode. */
} qm_ss_i2c_addr_t;
/**
* QM SS I2C Speed Type.
*/
typedef enum {
QM_SS_I2C_SPEED_STD = 1, /**< Standard mode (100 Kbps). */
QM_SS_I2C_SPEED_FAST = 2 /**< Fast mode (400 Kbps). */
} qm_ss_i2c_speed_t;
/**
* QM SS I2C status type.
*/
typedef enum {
QM_I2C_IDLE = 0, /**< Controller idle. */
QM_I2C_TX_ABRT_7B_ADDR_NOACK = BIT(0), /**< 7-bit address noack. */
QM_I2C_TX_ABRT_TXDATA_NOACK = BIT(3), /**< Tx data noack. */
QM_I2C_TX_ABRT_SBYTE_ACKDET = BIT(7), /**< Start ACK. */
QM_I2C_TX_ABRT_MASTER_DIS = BIT(11), /**< Master disabled. */
QM_I2C_TX_ARB_LOST = BIT(12), /**< Master lost arbitration. */
QM_I2C_TX_ABRT_SLVFLUSH_TXFIFO = BIT(13), /**< Slave flush tx FIFO. */
QM_I2C_TX_ABRT_SLV_ARBLOST = BIT(14), /**< Slave lost bus. */
QM_I2C_TX_ABRT_SLVRD_INTX = BIT(15), /**< Slave read completion. */
QM_I2C_TX_ABRT_USER_ABRT = BIT(16), /**< User abort. */
QM_I2C_BUSY = BIT(17) /**< Controller busy. */
} qm_ss_i2c_status_t;
/**
* QM SS I2C configuration type.
*/
typedef struct {
qm_ss_i2c_speed_t speed; /**< Standard, Fast Mode. */
qm_ss_i2c_addr_t address_mode; /**< 7 or 10 bit addressing. */
} qm_ss_i2c_config_t;
/**
* QM SS I2C transfer type.
* - if tx len is 0: perform receive-only transaction.
* - if rx len is 0: perform transmit-only transaction.
* - both tx and rx len not 0: perform a transmit-then-receive
* combined transaction.
*/
typedef struct {
uint8_t *tx; /**< Write data. */
uint32_t tx_len; /**< Write data length. */
uint8_t *rx; /**< Read data. */
uint32_t rx_len; /**< Read buffer length. */
bool stop; /**< Generate master STOP. */
/**
* User callback.
*
* @param[in] data User defined data.
* @param[in] rc 0 on success.
* Negative @ref errno for possible error codes.
* @param[in] status I2C status.
* @param[in] len Length of the transfer if succesfull, 0 otherwise.
*/
void (*callback)(void *data, int rc, qm_ss_i2c_status_t status,
uint32_t len);
void *callback_data; /**< User callback data. */
} qm_ss_i2c_transfer_t;
/**
* Set SS I2C configuration.
*
* @param[in] i2c Which I2C to set the configuration of.
* @param[in] cfg I2C configuration. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_i2c_set_config(const qm_ss_i2c_t i2c,
const qm_ss_i2c_config_t *const cfg);
/**
* Set I2C speed.
*
* Fine tune SS I2C clock speed.
* This will set the SCL low count and the SCL hi count cycles
* to achieve any required speed.
*
* @param[in] i2c I2C index.
* @param[in] speed Bus speed (Standard or Fast.Fast includes Fast + mode).
* @param[in] lo_cnt SCL low count.
* @param[in] hi_cnt SCL high count.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_i2c_set_speed(const qm_ss_i2c_t i2c, const qm_ss_i2c_speed_t speed,
const uint16_t lo_cnt, const uint16_t hi_cnt);
/**
* Retrieve SS I2C status.
*
* @param[in] i2c Which I2C to read the status of.
* @param[out] status Get i2c status. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_i2c_get_status(const qm_ss_i2c_t i2c,
qm_ss_i2c_status_t *const status);
/**
* Master write on I2C.
*
* Perform a master write on the SS I2C bus.
* This is a blocking synchronous call.
*
* @param[in] i2c Which I2C to write to.
* @param[in] slave_addr Address of slave to write to.
* @param[in] data Pre-allocated buffer of data to write.
* This must not be NULL.
* @param[in] len length of data to write.
* @param[in] stop Generate a STOP condition at the end of tx.
* @param[out] status Get i2c status.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_i2c_master_write(const qm_ss_i2c_t i2c, const uint16_t slave_addr,
const uint8_t *const data, uint32_t len,
const bool stop, qm_ss_i2c_status_t *const status);
/**
* Master read of I2C.
*
* Perform a single byte master read from the SS I2C. This is a blocking call.
*
* @param[in] i2c Which I2C to read from.
* @param[in] slave_addr Address of slave device to read from.
* @param[out] data Pre-allocated buffer to populate with data.
* This must not be NULL.
* @param[in] len length of data to read from slave.
* @param[in] stop Generate a STOP condition at the end of tx.
* @param[out] status Get i2c status.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_i2c_master_read(const qm_ss_i2c_t i2c, const uint16_t slave_addr,
uint8_t *const data, uint32_t len, const bool stop,
qm_ss_i2c_status_t *const status);
/**
* Interrupt based master transfer on I2C.
*
* Perform an interrupt based master transfer on the SS I2C bus. The function
* will replenish/empty TX/RX FIFOs on I2C empty/full interrupts.
*
* @param[in] i2c Which I2C to transfer from.
* @param[in] xfer Transfer structure includes write / read data and length,
* user callback function and the callback context.
* This must not be NULL.
* @param[in] slave_addr Address of slave to transfer data with.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_i2c_master_irq_transfer(const qm_ss_i2c_t i2c,
const qm_ss_i2c_transfer_t *const xfer,
const uint16_t slave_addr);
/**
* Terminate I2C IRQ/DMA transfer.
*
* Terminate the current IRQ transfer on the SS I2C bus.
* This will cause the user callback to be called with status
* QM_I2C_TX_ABRT_USER_ABRT.
*
* @param[in] i2c I2C register block pointer.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_i2c_irq_transfer_terminate(const qm_ss_i2c_t i2c);
/**
* @}
*/
#endif /* __QM_SS_I2C_H__ */

View file

@ -0,0 +1,92 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_SS_INTERRUPT_H__
#define __QM_SS_INTERRUPT_H__
#include "qm_common.h"
#include "qm_sensor_regs.h"
/**
* Interrupt driver for Sensor Subsystem.
*
* @defgroup groupSSINT SS Interrupt
* @{
*/
/**
* Interrupt service routine type.
*/
typedef void (*qm_ss_isr_t)(struct interrupt_frame *frame);
/**
* Enable interrupt delivery for the Sensor Subsystem.
*/
void qm_ss_irq_enable(void);
/**
* Disable interrupt delivery for the Sensor Subsystem.
*/
void qm_ss_irq_disable(void);
/**
* Unmask a given interrupt line.
*
* @param [in] irq Which IRQ to unmask.
*/
void qm_ss_irq_unmask(uint32_t irq);
/**
* Mask a given interrupt line.
*
* @param [in] irq Which IRQ to mask.
*/
void qm_ss_irq_mask(uint32_t irq);
/**
* Request a given IRQ and register ISR to interrupt vector.
*
* @param [in] irq IRQ number.
* @param [in] isr ISR to register to given IRQ.
*/
void qm_ss_irq_request(uint32_t irq, qm_ss_isr_t isr);
/**
* Register an Interrupt Service Routine to a given interrupt vector.
*
* @param [in] vector Interrupt Vector number.
* @param [in] isr ISR to register to given vector. Must be a valid Sensor
* Subsystem ISR.
*/
void qm_ss_int_vector_request(uint32_t vector, qm_ss_isr_t isr);
/**
* @}
*/
#endif /* __QM_SS_INTERRUPT_H__ */

View file

@ -0,0 +1,169 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_SS_ISR_H__
#define __QM_SS_ISR_H__
#include "qm_common.h"
/**
* Sensor Subsystem Interrupt Service Routines.
*
* @defgroup groupSSISR SS ISR
* @{
*/
/**
* ISR for ADC interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_ADC_IRQ, qm_ss_adc_0_isr);
* @endcode if IRQ based conversions are used.
*/
QM_ISR_DECLARE(qm_ss_adc_0_isr);
/**
* ISR for ADC error interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_ADC_ERR, qm_ss_adc_0_err_isr);
* @endcode if IRQ based conversions are used.
*/
QM_ISR_DECLARE(qm_ss_adc_0_err_isr);
/**
* ISR for GPIO 0 error interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_GPIO_INTR_0, qm_ss_gpio_isr_0);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_ss_gpio_isr_0);
/**
* ISR for GPIO 1 error interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_GPIO_INTR_1, qm_ss_gpio_isr_1);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_ss_gpio_isr_1);
/**
* ISR for I2C 0 error interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_I2C_0_ERR, qm_ss_i2c_isr_0);
* @code qm_ss_irq_request(QM_SS_IRQ_I2C_0_RX_AVAIL, qm_ss_i2c_isr_0);
* @code qm_ss_irq_request(QM_SS_IRQ_I2C_0_TX_REQ, qm_ss_i2c_isr_0);
* @code qm_ss_irq_request(QM_SS_IRQ_I2C_0_STOP_DET, qm_ss_i2c_isr_0);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_ss_i2c_isr_0);
/**
* ISR for I2C 1 error interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_I2C_1_ERR, qm_ss_i2c_isr_1);
* @code qm_ss_irq_request(QM_SS_IRQ_I2C_1_RX_AVAIL, qm_ss_i2c_isr_1);
* @code qm_ss_irq_request(QM_SS_IRQ_I2C_1_TX_REQ, qm_ss_i2c_isr_1);
* @code qm_ss_irq_request(QM_SS_IRQ_I2C_1_STOP_DET, qm_ss_i2c_isr_1);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_ss_i2c_isr_1);
/**
* ISR for SPI 0 error interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_SPI_0_ERR_INT, qm_ss_spi_0_err_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_ss_spi_0_err_isr);
/**
* ISR for SPI 1 error interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_SPI_1_ERR_INT, qm_ss_spi_1_err_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_ss_spi_1_err_isr);
/**
* ISR for SPI 0 TX data requested interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_SPI_0_TX_REQ, qm_ss_spi_0_tx_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_ss_spi_0_tx_isr);
/**
* ISR for SPI 1 TX data requested interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_SPI_1_TX_REQ, qm_ss_spi_1_tx_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_ss_spi_1_tx_isr);
/**
* ISR for SPI 0 RX data available interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_SPI_0_RX_AVAIL, qm_ss_spi_0_rx_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_ss_spi_0_rx_isr);
/**
* ISR for SPI 1 data available interrupt.
*
* This function needs to be registered with
* @code qm_ss_irq_request(QM_SS_IRQ_SPI_1_RX_AVAIL, qm_ss_spi_1_rx_isr);
* @endcode if IRQ based transfers are used.
*/
QM_ISR_DECLARE(qm_ss_spi_1_rx_isr);
/**
* ISR for SS Timer 0 interrupt.
*
* This function needs to be registered with
* @code qm_ss_int_vector_request(QM_SS_INT_TIMER_0, qm_ss_timer_isr_0);
* @endcode
*/
QM_ISR_DECLARE(qm_ss_timer_isr_0);
/**
* @}
*/
#endif /* __QM_SS_ISR_H__ */

View file

@ -0,0 +1,299 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_SS_SPI_H__
#define __QM_SS_SPI_H__
#include "qm_common.h"
#include "qm_sensor_regs.h"
/**
* SPI peripheral driver for Sensor Subsystem.
*
* @defgroup groupSSSPI SS SPI
* @{
*/
/**
* QM SPI frame size type.
*/
typedef enum {
QM_SS_SPI_FRAME_SIZE_4_BIT = 3, /**< 4 bit frame. */
QM_SS_SPI_FRAME_SIZE_5_BIT, /**< 5 bit frame. */
QM_SS_SPI_FRAME_SIZE_6_BIT, /**< 6 bit frame. */
QM_SS_SPI_FRAME_SIZE_7_BIT, /**< 7 bit frame. */
QM_SS_SPI_FRAME_SIZE_8_BIT, /**< 8 bit frame. */
QM_SS_SPI_FRAME_SIZE_9_BIT, /**< 9 bit frame. */
QM_SS_SPI_FRAME_SIZE_10_BIT, /**< 10 bit frame. */
QM_SS_SPI_FRAME_SIZE_11_BIT, /**< 11 bit frame. */
QM_SS_SPI_FRAME_SIZE_12_BIT, /**< 12 bit frame. */
QM_SS_SPI_FRAME_SIZE_13_BIT, /**< 13 bit frame. */
QM_SS_SPI_FRAME_SIZE_14_BIT, /**< 14 bit frame. */
QM_SS_SPI_FRAME_SIZE_15_BIT, /**< 15 bit frame. */
QM_SS_SPI_FRAME_SIZE_16_BIT /**< 16 bit frame. */
} qm_ss_spi_frame_size_t;
/**
* SPI transfer mode type.
*/
typedef enum {
/**
* Transmit & Receive mode.
*
* This mode synchronously receives and transmits data during the
* transfer. rx_len and tx_len buffer need to be the same length.
*/
QM_SS_SPI_TMOD_TX_RX,
/**
* Transmit-Only mode.
*
* This mode only transmits data. The rx buffer is not accessed and
* rx_len need to be set to 0.
*/
QM_SS_SPI_TMOD_TX,
/**
* Receive-Only mode.
*
* This mode only receives data. The tx buffer is not accessed and
* tx_len need to be set to 0.
*/
QM_SS_SPI_TMOD_RX,
/**
* EEPROM-Read Mode.
*
* This mode transmits the data stored in the tx buffer (EEPROM
* address). After the transmit is completed it populates the rx buffer
* (EEPROM data) with received data.
*/
QM_SS_SPI_TMOD_EEPROM_READ
} qm_ss_spi_tmode_t;
/**
* SPI bus mode type.
*/
typedef enum {
QM_SS_SPI_BMODE_0, /**< Clock Polarity = 0, Clock Phase = 0. */
QM_SS_SPI_BMODE_1, /**< Clock Polarity = 0, Clock Phase = 1. */
QM_SS_SPI_BMODE_2, /**< Clock Polarity = 1, Clock Phase = 0. */
QM_SS_SPI_BMODE_3 /**< Clock Polarity = 1, Clock Phase = 1. */
} qm_ss_spi_bmode_t;
/**
* SPI slave select type.
*
* Slave selects can be combined by logical OR.
*/
typedef enum {
QM_SS_SPI_SS_NONE = 0, /**< No slave select. */
QM_SS_SPI_SS_0 = BIT(0), /**< Slave select 0. */
QM_SS_SPI_SS_1 = BIT(1), /**< Slave select 1. */
QM_SS_SPI_SS_2 = BIT(2), /**< Slave select 2. */
QM_SS_SPI_SS_3 = BIT(3), /**< Slave select 3. */
} qm_ss_spi_slave_select_t;
/**
* SPI status.
*/
typedef enum {
QM_SS_SPI_IDLE, /**< SPI device is not in use. */
QM_SS_SPI_BUSY, /**< SPI device is busy. */
QM_SS_SPI_RX_OVERFLOW /**< RX transfer has overflown. */
} qm_ss_spi_status_t;
/**
* SPI configuration type.
*/
typedef struct {
qm_ss_spi_frame_size_t frame_size; /**< Frame Size. */
qm_ss_spi_tmode_t transfer_mode; /**< Transfer mode (enum). */
qm_ss_spi_bmode_t bus_mode; /**< Bus mode (enum). */
/**
* Clock divider.
*
* The clock divider sets the SPI speed on the interface.
* A value of 0 will disable SCK. The LSB of this value is ignored.
*/
uint16_t clk_divider;
} qm_ss_spi_config_t;
/**
* SPI IRQ transfer type.
*/
typedef struct {
uint8_t *tx; /**< Write data buffer pointer. */
uint16_t tx_len; /**< Write data length. */
uint8_t *rx; /**< Read data buffer pointer. */
uint16_t rx_len; /**< Read buffer length. */
/**
* Transfer callback.
*
* Called after all data is transmitted/received or if the driver
* detects an error during the SPI transfer.
*
* @param[in] data The callback user data.
* @param[in] error 0 on success.
* Negative @ref errno for possible error codes.
* @param[in] status The SPI module status.
* @param[in] len The amount of frames transmitted.
*/
void (*callback)(void *data, int error, qm_ss_spi_status_t status,
uint16_t len);
void *data; /**< Callback user data. */
} qm_ss_spi_async_transfer_t;
/**
* SPI transfer type.
*/
typedef struct {
uint8_t *tx; /**< Write data buffer pointer. */
uint16_t tx_len; /**< Write data length. */
uint8_t *rx; /**< Read data buffer pointer. */
uint16_t rx_len; /**< Read buffer length. */
} qm_ss_spi_transfer_t;
/**
* Set SPI configuration.
*
* Change the configuration of a SPI module.
* This includes transfer mode, bus mode and clock divider.
*
* This operation is permitted only when the SPI module is disabled.
*
* @param[in] spi SPI module identifier.
* @param[in] cfg New configuration for SPI. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_spi_set_config(const qm_ss_spi_t spi,
const qm_ss_spi_config_t *const cfg);
/**
* Set Slave Select lines.
*
* Select which slaves to perform SPI transmissions on. Select lines can be
* combined using the | operator. It is only suggested to use this functionality
* in TX only mode. This operation is permitted only when a SPI transfer is not
* already in progress; the caller should check that by retrieving the device
* status.
*
* @param[in] spi SPI module identifier.
* @param[in] ss Select lines to enable when performing transfers.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_spi_slave_select(const qm_ss_spi_t spi,
const qm_ss_spi_slave_select_t ss);
/**
* Get SPI bus status.
*
* @param[in] spi SPI module identifier.
* @param[out] status Reference to the variable where to store the current SPI
* bus status (QM_SS_SPI_BUSY if a transfer is in progress
* or QM_SS_SPI_IDLE if SPI device is IDLE).
* This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_spi_get_status(const qm_ss_spi_t spi,
qm_ss_spi_status_t *const status);
/**
* Perform a blocking SPI transfer.
*
* This is a blocking synchronous call. If transfer mode is full duplex
* (QM_SS_SPI_TMOD_TX_RX) tx_len and rx_len must be equal. Similarly, for
* transmit-only transfers (QM_SS_SPI_TMOD_TX) rx_len must be 0, while for
* receive-only transfers (QM_SS_SPI_TMOD_RX) tx_len must be 0.
*
* @param[in] spi SPI module identifier.
* @param[in] xfer Structure containing transfer information.
* This must not be NULL.
* @param[out] status Reference to the variable where to store the SPI status
* at the end of the transfer.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_spi_transfer(const qm_ss_spi_t spi,
const qm_ss_spi_transfer_t *const xfer,
qm_ss_spi_status_t *const status);
/**
* Initiate a interrupt based SPI transfer.
*
* Perform an interrupt based SPI transfer. If transfer mode is full duplex
* (QM_SS_SPI_TMOD_TX_RX), then tx_len and rx_len must be equal. Similarly, for
* transmit-only transfers (QM_SS_SPI_TMOD_TX) rx_len must be 0, while for
* receive-only transfers (QM_SS_SPI_TMOD_RX) tx_len must be 0. This function is
* non blocking.
*
* @param[in] spi SPI module identifier.
* @param[in] xfer Structure containing transfer information.
* The structure must not be NULL and must be kept valid until
* the transfer is complete.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_spi_irq_transfer(const qm_ss_spi_t spi,
const qm_ss_spi_async_transfer_t *const xfer);
/**
* Terminate SPI IRQ transfer.
*
* Terminate the current IRQ SPI transfer.
* This function will trigger complete callbacks even
* if the transfer is not completed.
*
* @param[in] spi SPI module identifier.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_spi_transfer_terminate(const qm_ss_spi_t spi);
/**
* @}
*/
#endif /* __QM_SS_SPI_H__ */

View file

@ -0,0 +1,119 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_SS_TIMER_H__
#define __QM_SS_TIMER_H__
#include "qm_common.h"
#include "qm_sensor_regs.h"
/**
* Timer driver for Sensor Subsystem.
*
* @defgroup groupSSTimer SS Timer
* @{
*/
/**
* Sensor Subsystem Timer Configuration Type.
*/
typedef struct {
bool watchdog_mode; /**< Watchdog mode. */
/**
* Increments in run state only.
*
* If this field is set to 0, the timer will count
* in both halt state and running state.
* When set to 1, this will only increment in
* running state.
*/
bool inc_run_only;
bool int_en; /**< Interrupt enable. */
uint32_t count; /**< Final count value. */
/**
* User callback.
*
* Called for any interrupt on the Sensor Subsystem Timer.
*
* @param[in] data The callback user data.
*/
void (*callback)(void *data);
void *callback_data; /**< Callback user data. */
} qm_ss_timer_config_t;
/**
* Set the SS timer configuration.
*
* This includes final count value, timer mode and if interrupts are enabled.
* If interrupts are enabled, it will configure the callback function.
*
* @param[in] timer Which SS timer to configure.
* @param[in] cfg SS timer configuration. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_timer_set_config(const qm_ss_timer_t timer,
const qm_ss_timer_config_t *const cfg);
/**
* Set SS timer count value.
*
* Set the current count value of the SS timer.
*
* @param[in] timer Which SS timer to set the count of.
* @param[in] count Value to load the timer with.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_timer_set(const qm_ss_timer_t timer, const uint32_t count);
/**
* Get SS timer count value.
*
* Get the current count value of the SS timer.
*
* @param[in] timer Which SS timer to get the count of.
* @param[out] count Current value of timer. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int qm_ss_timer_get(const qm_ss_timer_t timer, uint32_t *const count);
/**
* @}
*/
#endif /* __QM_SS_TIMER_H__ */

View file

@ -0,0 +1,182 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __SS_CLK_H__
#define __SS_CLK_H__
#include "qm_common.h"
#include "qm_sensor_regs.h"
#include "clk.h"
/**
* Clock Management for Sensor Subsystem.
*
* The clock distribution has three level of gating:
* 1. SE SoC gating through register CCU_PERIPH_CLK_GATE_CTL
* 2. SS Soc gating through register IO_CREG_MST0_CTRL (IO_CREG_MST0_CTRL)
* 3. SS peripheral clk gating
* Note: the first two are ungated by hardware power-on default (clock gating is
* done at peripheral level). Thus the only one level of control is enough (and
* implemented in ss_clk driver) to gate clock on or off to the particular
* peripheral.
*
* @defgroup groupSSClock SS Clock
* @{
*/
/**
* Peripheral clocks selection type.
*/
typedef enum {
SS_CLK_PERIPH_ADC = BIT(31), /**< ADC clock selector. */
SS_CLK_PERIPH_I2C_1 = BIT(30), /**< I2C 1 clock selector. */
SS_CLK_PERIPH_I2C_0 = BIT(29), /**< I2C 0 clock selector. */
SS_CLK_PERIPH_SPI_1 = BIT(28), /**< SPI 1 clock selector. */
SS_CLK_PERIPH_SPI_0 = BIT(27), /**< SPI 0 clock selector. */
/**
* GPIO 1 clock selector.
*
* Special domain peripherals - these do not map onto the standard
* register.
*/
SS_CLK_PERIPH_GPIO_1 = BIT(1),
/**
* GPIO 0 clock selector.
*
* Special domain peripherals - these do not map onto the standard
* register.
*/
SS_CLK_PERIPH_GPIO_0 = BIT(0)
} ss_clk_periph_t;
/**
* Enable clocking for SS GPIO peripheral.
*
* @param [in] gpio GPIO port index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int ss_clk_gpio_enable(const qm_ss_gpio_t gpio);
/**
* Disable clocking for SS GPIO peripheral.
*
* @param [in] gpio GPIO port index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int ss_clk_gpio_disable(const qm_ss_gpio_t gpio);
/**
* Enable clocking for SS SPI peripheral.
*
* @param [in] spi SPI port index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int ss_clk_spi_enable(const qm_ss_spi_t spi);
/**
* Disable clocking for SS SPI peripheral.
*
* @param [in] spi SPI port index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int ss_clk_spi_disable(const qm_ss_spi_t spi);
/**
* Enable clocking for SS I2C peripheral.
*
* @param [in] i2c I2C port index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int ss_clk_i2c_enable(const qm_ss_i2c_t i2c);
/**
* Disable clocking for SS I2C peripheral.
*
* @param [in] i2c I2C port index.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int ss_clk_i2c_disable(const qm_ss_i2c_t i2c);
/**
* Enable the SS ADC clock.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
*/
int ss_clk_adc_enable(void);
/**
* Disable the SS ADC clock.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
*/
int ss_clk_adc_disable(void);
/**
* Set clock divisor for SS ADC.
*
* Note: If the system clock speed is changed, the divisor must be recalculated.
* The minimum supported speed for the SS ADC is 0.14 MHz. So for a system clock
* speed of 1 MHz, the max value of div is 7, and for 32 MHz, the max value is
* 224. System clock speeds of less than 1 MHz are not supported by this
* function.
*
* @param [in] div ADC clock divider value.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int ss_clk_adc_set_div(const uint32_t div);
/**
* @}
*/
#endif /* __SS_CLK_H__ */

View file

@ -0,0 +1,94 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_SS_POWER_STATES_H__
#define __QM_SS_POWER_STATES_H__
#include "qm_common.h"
#include "qm_sensor_regs.h"
/**
* SS Power mode control for Quark SE Microcontrollers.
*
* @defgroup groupSSPower SS Power states
* @{
*/
/**
* Sensor Subsystem SS1 Timers mode type.
*/
typedef enum {
SS_POWER_CPU_SS1_TIMER_OFF = 0, /**< Disable SS Timers in SS1. */
SS_POWER_CPU_SS1_TIMER_ON /**< Keep SS Timers enabled in SS1. */
} ss_power_cpu_ss1_mode_t;
/**
* Enter Sensor SS1 state.
*
* Put the Sensor Subsystem into SS1.<BR>
* Processor Clock is gated in this state.
*
* A wake event causes the Sensor Subsystem to transition to SS0.<BR>
* A wake event is a sensor subsystem interrupt.
*
* According to the mode selected, Sensor Subsystem Timers can be disabled.
*
* @param[in] mode Mode selection for SS1 state.
*/
void ss_power_cpu_ss1(const ss_power_cpu_ss1_mode_t mode);
/**
* Enter Sensor SS2 state or SoC LPSS state.
*
* Put the Sensor Subsystem into SS2.<BR>
* Sensor Complex Clock is gated in this state.<BR>
* Sensor Peripherals are gated in this state.<BR>
*
* This enables entry in LPSS if:
* - Sensor Subsystem is in SS2
* - Lakemont is in C2 or C2LP
* - LPSS entry is enabled
*
* A wake event causes the Sensor Subsystem to transition to SS0.<BR>
* There are two kinds of wake event depending on the Sensor Subsystem
* and SoC state:
* - SS2: a wake event is a Sensor Subsystem interrupt
* - LPSS: a wake event is a Sensor Subsystem interrupt or a Lakemont interrupt
*
* LPSS wake events apply if LPSS is entered.
* If Host wakes the SoC from LPSS,
* Sensor also transitions back to SS0.
*/
void ss_power_cpu_ss2(void);
/**
* @}
*/
#endif /* __QM_SS_POWER_STATES_H__ */

View file

@ -0,0 +1,652 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_ss_adc.h"
#include <string.h>
#include "clk.h"
/* FIFO_INTERRUPT_THRESHOLD is used by qm_ss_adc_irq_convert to set the
* threshold at which the FIFO will trigger an interrupt. It is also used the
* ISR handler to determine the number of samples to read from the FIFO. */
#define FIFO_INTERRUPT_THRESHOLD (16)
#define QM_SS_ADC_CHAN_SEQ_MAX (32)
#define ADC_SAMPLE_SHIFT (11)
/* SS ADC commands. */
#define QM_SS_ADC_CMD_START_CAL (3)
#define QM_SS_ADC_CMD_LOAD_CAL (4)
/* Mode change delay is clock speed * 5. */
#define CALCULATE_DELAY() (clk_sys_get_ticks_per_us() * 5)
static uint32_t adc_base[QM_SS_ADC_NUM] = {QM_SS_ADC_BASE};
static qm_ss_adc_xfer_t irq_xfer[QM_SS_ADC_NUM];
static uint8_t sample_window[QM_SS_ADC_NUM];
static qm_ss_adc_resolution_t resolution[QM_SS_ADC_NUM];
static uint32_t count[QM_SS_ADC_NUM];
static void (*mode_callback[QM_SS_ADC_NUM])(void *data, int error,
qm_ss_adc_status_t status,
qm_ss_adc_cb_source_t source);
static void (*cal_callback[QM_SS_ADC_NUM])(void *data, int error,
qm_ss_adc_status_t status,
qm_ss_adc_cb_source_t source);
static void *mode_callback_data[QM_SS_ADC_NUM];
static void *cal_callback_data[QM_SS_ADC_NUM];
static void dummy_conversion(uint32_t controller);
static bool first_mode_callback_ignored[QM_SS_ADC_NUM] = {false};
static qm_ss_adc_mode_t requested_mode[QM_SS_ADC_NUM];
static void enable_adc(void)
{
QM_SS_REG_AUX_OR(QM_SS_ADC_BASE + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_ADC_ENA);
}
static void disable_adc(void)
{
QM_SS_REG_AUX_NAND(QM_SS_ADC_BASE + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_ADC_ENA);
}
static void qm_ss_adc_isr_handler(const qm_ss_adc_t adc)
{
uint32_t i, samples_to_read;
uint32_t controller = adc_base[adc];
/* Calculate the number of samples to read. */
samples_to_read = FIFO_INTERRUPT_THRESHOLD;
if (samples_to_read > (irq_xfer[adc].samples_len - count[adc])) {
samples_to_read = irq_xfer[adc].samples_len - count[adc];
}
/* Read the samples into the array. */
for (i = 0; i < samples_to_read; i++) {
/* Pop one sample into the sample register. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_SET,
QM_SS_ADC_SET_POP_RX);
/* Read the sample in the array. */
irq_xfer[adc].samples[count[adc]] =
(__builtin_arc_lr(controller + QM_SS_ADC_SAMPLE) >>
(ADC_SAMPLE_SHIFT - resolution[adc]));
count[adc]++;
}
/* Clear the data available status register. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_CLR_DATA_A);
if (count[adc] == irq_xfer[adc].samples_len) {
/* Stop the sequencer. */
QM_SS_REG_AUX_NAND(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_SEQ_START);
/* Mask all interrupts. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_MSK_ALL_INT);
/* Call the user callback. */
if (irq_xfer[adc].callback) {
irq_xfer[adc].callback(irq_xfer[adc].callback_data, 0,
QM_SS_ADC_COMPLETE,
QM_SS_ADC_TRANSFER);
}
/* Disable the ADC. */
disable_adc();
return;
}
}
static void qm_ss_adc_isr_err_handler(const qm_ss_adc_t adc)
{
uint32_t controller = adc_base[adc];
uint32_t intstat = __builtin_arc_lr(controller + QM_SS_ADC_INTSTAT);
/* Stop the sequencer. */
QM_SS_REG_AUX_NAND(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_SEQ_START);
/* Mask all interrupts. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_MSK_ALL_INT);
/* Call the user callback and pass it the status code. */
if (intstat & QM_SS_ADC_INTSTAT_OVERFLOW) {
if (irq_xfer[adc].callback) {
irq_xfer[adc].callback(irq_xfer[adc].callback_data,
-EIO, QM_SS_ADC_OVERFLOW,
QM_SS_ADC_TRANSFER);
}
}
if (intstat & QM_SS_ADC_INTSTAT_UNDERFLOW) {
if (irq_xfer[adc].callback) {
irq_xfer[adc].callback(irq_xfer[adc].callback_data,
-EIO, QM_SS_ADC_UNDERFLOW,
QM_SS_ADC_TRANSFER);
}
}
if (intstat & QM_SS_ADC_INTSTAT_SEQERROR) {
if (irq_xfer[adc].callback) {
irq_xfer[adc].callback(irq_xfer[adc].callback_data,
-EIO, QM_SS_ADC_SEQERROR,
QM_SS_ADC_TRANSFER);
}
}
/* Clear all error interrupts. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
(QM_SS_ADC_CTRL_CLR_SEQERROR |
QM_SS_ADC_CTRL_CLR_OVERFLOW |
QM_SS_ADC_CTRL_CLR_UNDERFLOW));
/* Disable the ADC. */
disable_adc();
}
static void qm_ss_adc_isr_pwr_handler(const qm_ss_adc_t adc)
{
uint32_t controller = adc_base[adc];
/* The IRQ associated with the mode change fires an interrupt as soon
* as it is enabled so it is necessary to ignore it the first time the
* ISR runs. */
if (!first_mode_callback_ignored[adc]) {
first_mode_callback_ignored[adc] = true;
return;
}
/* Perform a dummy conversion if we are transitioning to Normal Mode. */
if ((requested_mode[adc] >= QM_SS_ADC_MODE_NORM_CAL)) {
dummy_conversion(controller);
}
/* Call the user callback if it is set. */
if (mode_callback[adc]) {
mode_callback[adc](mode_callback_data[adc], 0, QM_SS_ADC_IDLE,
QM_SS_ADC_MODE_CHANGED);
}
}
static void qm_ss_adc_isr_cal_handler(const qm_ss_adc_t adc)
{
/* Clear the calibration request reg. */
QM_SS_REG_AUX_NAND(QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL,
QM_SS_ADC_CAL_REQ);
/* Call the user callback if it is set. */
if (cal_callback[adc]) {
cal_callback[adc](cal_callback_data[adc], 0, QM_SS_ADC_IDLE,
QM_SS_ADC_CAL_COMPLETE);
}
/* Disable the ADC. */
disable_adc();
}
/* ISR for SS ADC 0 Data avaliable. */
QM_ISR_DECLARE(qm_ss_adc_0_isr)
{
qm_ss_adc_isr_handler(QM_SS_ADC_0);
}
/* ISR for SS ADC 0 Error. */
QM_ISR_DECLARE(qm_ss_adc_0_err_isr)
{
qm_ss_adc_isr_err_handler(QM_SS_ADC_0);
}
/* ISR for SS ADC 0 Mode change. */
QM_ISR_DECLARE(qm_ss_adc_0_pwr_isr)
{
qm_ss_adc_isr_pwr_handler(QM_SS_ADC_0);
}
/* ISR for SS ADC 0 Calibration. */
QM_ISR_DECLARE(qm_ss_adc_0_cal_isr)
{
qm_ss_adc_isr_cal_handler(QM_SS_ADC_0);
}
static void setup_seq_table(const qm_ss_adc_t adc, qm_ss_adc_xfer_t *xfer,
bool single_run)
{
uint32_t i, reg, ch_odd, ch_even, seq_entry = 0;
uint32_t num_channels, controller = adc_base[adc];
/* The sample window is the time in cycles between the start of one
* sample and the start of the next. Resolution is indexed from 0 so we
* need to add 1 and a further 2 for the time it takes to process. */
uint16_t delay = (sample_window[adc] - (resolution[adc] + 3));
/* Reset the sequence table and sequence pointer. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_SEQ_TABLE_RST);
/* If a single run is requested and the number of channels in ch is less
* than the number of samples requested we need to insert multiple
* channels into the sequence table. */
num_channels = single_run ? xfer->samples_len : xfer->ch_len;
/* The sequence table has to be populated with pairs of entries so there
* are sample_len/2 pairs of entries. These entries are read from the
* ch array in pairs. The same delay is used between all entries. */
for (i = 0; i < (num_channels - 1); i += 2) {
ch_odd = xfer->ch[(i + 1) % xfer->ch_len];
ch_even = xfer->ch[i % xfer->ch_len];
seq_entry =
((delay << QM_SS_ADC_SEQ_DELAYODD_OFFSET) |
(ch_odd << QM_SS_ADC_SEQ_MUXODD_OFFSET) |
(delay << QM_SS_ADC_SEQ_DELAYEVEN_OFFSET) | ch_even);
__builtin_arc_sr(seq_entry, controller + QM_SS_ADC_SEQ);
}
/* If there is an uneven number of entries we need to create a final
* pair with a singly entry. */
if (num_channels % 2) {
ch_even = xfer->ch[i % xfer->ch_len];
seq_entry =
((delay << QM_SS_ADC_SEQ_DELAYEVEN_OFFSET) | (ch_even));
__builtin_arc_sr(seq_entry, controller + QM_SS_ADC_SEQ);
}
/* Reset the sequence pointer back to 0. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_SEQ_PTR_RST);
/* Set the number of entries in the sequencer. */
reg = __builtin_arc_lr(controller + QM_SS_ADC_SET);
reg &= ~QM_SS_ADC_SET_SEQ_ENTRIES_MASK;
reg |= ((num_channels - 1) << QM_SS_ADC_SET_SEQ_ENTRIES_OFFSET);
__builtin_arc_sr(reg, controller + QM_SS_ADC_SET);
}
static void dummy_conversion(uint32_t controller)
{
uint32_t reg;
int res;
/* Flush the FIFO. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_SET, QM_SS_ADC_SET_FLUSH_RX);
/* Set up sequence table. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_SEQ_TABLE_RST);
/* Populate the seq table. */
__builtin_arc_sr(QM_SS_ADC_SEQ_DUMMY, controller + QM_SS_ADC_SEQ);
/* Reset the sequence pointer back to 0. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_SEQ_PTR_RST);
/* Set the number of entries in the sequencer. */
reg = __builtin_arc_lr(controller + QM_SS_ADC_SET);
reg &= ~QM_SS_ADC_SET_SEQ_ENTRIES_MASK;
reg |= (0 << QM_SS_ADC_SET_SEQ_ENTRIES_OFFSET);
__builtin_arc_sr(reg, controller + QM_SS_ADC_SET);
/* Set the threshold. */
reg = __builtin_arc_lr(controller + QM_SS_ADC_SET);
reg &= ~QM_SS_ADC_SET_THRESHOLD_MASK;
reg |= (0 << QM_SS_ADC_SET_THRESHOLD_OFFSET);
__builtin_arc_sr(reg, controller + QM_SS_ADC_SET);
/* Set the sequence mode to single run. */
QM_SS_REG_AUX_NAND(controller + QM_SS_ADC_SET, QM_SS_ADC_SET_SEQ_MODE);
/* Clear all interrupts. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_CLR_ALL_INT);
/* Mask all interrupts. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_MSK_ALL_INT);
/* Enable the ADC. */
enable_adc();
/* Start the sequencer. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL, QM_SS_ADC_CTRL_SEQ_START);
/* Wait for the sequence to finish. */
while (!(res = __builtin_arc_lr(controller + QM_SS_ADC_INTSTAT))) {
}
/* Flush the FIFO. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_SET, QM_SS_ADC_SET_FLUSH_RX);
/* Clear the data available status register. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_CLR_DATA_A);
/* Unmask all interrupts. */
QM_SS_REG_AUX_NAND(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_MSK_ALL_INT);
/* Disable the ADC. */
disable_adc();
}
int qm_ss_adc_set_config(const qm_ss_adc_t adc,
const qm_ss_adc_config_t *const cfg)
{
uint32_t reg;
uint32_t controller = adc_base[adc];
QM_CHECK(adc < QM_SS_ADC_NUM, -EINVAL);
QM_CHECK(NULL != cfg, -EINVAL);
QM_CHECK(cfg->resolution <= QM_SS_ADC_RES_12_BITS, -EINVAL);
/* The window must be 2 greater than the resolution but since this is
* indexed from 0 we need to add a further 1. */
QM_CHECK(cfg->window >= (cfg->resolution + 3), -EINVAL);
/* Set the sample window and resolution. */
sample_window[adc] = cfg->window;
resolution[adc] = cfg->resolution;
/* Set the resolution. */
reg = __builtin_arc_lr(controller + QM_SS_ADC_SET);
reg &= ~QM_SS_ADC_SET_SAMPLE_WIDTH_MASK;
reg |= resolution[adc];
__builtin_arc_sr(reg, controller + QM_SS_ADC_SET);
return 0;
}
int qm_ss_adc_set_mode(const qm_ss_adc_t adc, const qm_ss_adc_mode_t mode)
{
uint32_t creg, delay;
uint32_t controller = adc_base[adc];
QM_CHECK(adc < QM_SS_ADC_NUM, -EINVAL);
QM_CHECK(mode <= QM_SS_ADC_MODE_NORM_NO_CAL, -EINVAL);
/* Calculate the delay. */
delay = CALCULATE_DELAY();
/* Issue mode change command and wait for it to complete. */
creg = __builtin_arc_lr(QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL);
creg &= ~((QM_SS_ADC_DELAY_MASK << QM_SS_ADC_DELAY_OFFSET) |
QM_SS_ADC_PWR_MODE_MASK);
creg |= ((delay << QM_SS_ADC_DELAY_OFFSET) | mode);
__builtin_arc_sr(creg, QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL);
/* Wait for the mode change to complete. */
while (!(__builtin_arc_lr(QM_SS_CREG_BASE + QM_SS_IO_CREG_SLV0_OBSR) &
QM_SS_ADC_PWR_MODE_STS)) {
}
/* Perform a dummy conversion if transitioning to Normal Mode. */
if ((mode >= QM_SS_ADC_MODE_NORM_CAL)) {
dummy_conversion(controller);
}
return 0;
}
int qm_ss_adc_irq_set_mode(const qm_ss_adc_t adc, const qm_ss_adc_mode_t mode,
void (*callback)(void *data, int error,
qm_ss_adc_status_t status,
qm_ss_adc_cb_source_t source),
void *callback_data)
{
uint32_t creg, delay;
QM_CHECK(adc < QM_SS_ADC_NUM, -EINVAL);
QM_CHECK(mode <= QM_SS_ADC_MODE_NORM_NO_CAL, -EINVAL);
mode_callback[adc] = callback;
mode_callback_data[adc] = callback_data;
requested_mode[adc] = mode;
/* Calculate the delay. */
delay = CALCULATE_DELAY();
/* Issue mode change command and wait for it to complete. */
creg = __builtin_arc_lr(QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL);
creg &= ~((QM_SS_ADC_DELAY_MASK << QM_SS_ADC_DELAY_OFFSET) |
QM_SS_ADC_PWR_MODE_MASK);
creg |= ((delay << QM_SS_ADC_DELAY_OFFSET) | mode);
__builtin_arc_sr(creg, QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL);
return 0;
}
int qm_ss_adc_calibrate(const qm_ss_adc_t adc __attribute__((unused)))
{
uint32_t creg;
QM_CHECK(adc < QM_SS_ADC_NUM, -EINVAL);
/* Enable the ADC. */
enable_adc();
/* Issue the start calibrate command. */
creg = __builtin_arc_lr(QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL);
creg &= ~(QM_SS_ADC_CAL_CMD_MASK | QM_SS_ADC_CAL_REQ);
creg |= ((QM_SS_ADC_CMD_START_CAL << QM_SS_ADC_CAL_CMD_OFFSET) |
QM_SS_ADC_CAL_REQ);
__builtin_arc_sr(creg, QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL);
/* Wait for the calibrate command to complete. */
while (!(__builtin_arc_lr(QM_SS_CREG_BASE + QM_SS_IO_CREG_SLV0_OBSR) &
QM_SS_ADC_CAL_ACK)) {
}
/* Clear the calibration request reg. */
QM_SS_REG_AUX_NAND(QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL,
QM_SS_ADC_CAL_REQ);
/* Disable the ADC. */
disable_adc();
return 0;
}
int qm_ss_adc_irq_calibrate(const qm_ss_adc_t adc,
void (*callback)(void *data, int error,
qm_ss_adc_status_t status,
qm_ss_adc_cb_source_t source),
void *callback_data)
{
uint32_t creg;
QM_CHECK(adc < QM_SS_ADC_NUM, -EINVAL);
cal_callback[adc] = callback;
cal_callback_data[adc] = callback_data;
/* Enable the ADC. */
enable_adc();
/* Issue the start calibrate command. */
creg = __builtin_arc_lr(QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL);
creg &= ~(QM_SS_ADC_CAL_CMD_MASK | QM_SS_ADC_CAL_REQ);
creg |= ((QM_SS_ADC_CMD_START_CAL << QM_SS_ADC_CAL_CMD_OFFSET) |
QM_SS_ADC_CAL_REQ);
__builtin_arc_sr(creg, QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL);
return 0;
}
int qm_ss_adc_set_calibration(const qm_ss_adc_t adc __attribute__((unused)),
const qm_ss_adc_calibration_t cal_data)
{
uint32_t creg;
QM_CHECK(adc < QM_SS_ADC_NUM, -EINVAL);
QM_CHECK(cal_data <= QM_SS_ADC_CAL_MAX, -EINVAL);
/* Issue the load calibrate command. */
creg = __builtin_arc_lr(QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL);
creg &= ~(QM_SS_ADC_CAL_VAL_SET_MASK | QM_SS_ADC_CAL_CMD_MASK |
QM_SS_ADC_CAL_REQ);
creg |= ((cal_data << QM_SS_ADC_CAL_VAL_SET_OFFSET) |
(QM_SS_ADC_CMD_LOAD_CAL << QM_SS_ADC_CAL_CMD_OFFSET) |
QM_SS_ADC_CAL_REQ);
__builtin_arc_sr(creg, QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL);
/* Wait for the calibrate command to complete. */
while (!(__builtin_arc_lr(QM_SS_CREG_BASE + QM_SS_IO_CREG_SLV0_OBSR) &
QM_SS_ADC_CAL_ACK)) {
}
/* Clear the calibration request reg. */
QM_SS_REG_AUX_NAND(QM_SS_CREG_BASE + QM_SS_IO_CREG_MST0_CTRL,
QM_SS_ADC_CAL_REQ);
return 0;
}
int qm_ss_adc_get_calibration(const qm_ss_adc_t adc __attribute__((unused)),
qm_ss_adc_calibration_t *const cal)
{
QM_CHECK(adc < QM_SS_ADC_NUM, -EINVAL);
QM_CHECK(NULL != cal, -EINVAL);
*cal = ((__builtin_arc_lr(QM_SS_CREG_BASE + QM_SS_IO_CREG_SLV0_OBSR) &
QM_SS_ADC_CAL_VAL_GET_MASK) >>
QM_SS_ADC_CAL_VAL_GET_OFFSET);
return 0;
}
int qm_ss_adc_convert(const qm_ss_adc_t adc, qm_ss_adc_xfer_t *xfer)
{
uint32_t reg, i;
uint32_t controller = adc_base[adc];
int res;
QM_CHECK(adc < QM_SS_ADC_NUM, -EINVAL);
QM_CHECK(NULL != xfer, -EINVAL);
QM_CHECK(NULL != xfer->ch, -EINVAL);
QM_CHECK(NULL != xfer->samples, -EINVAL);
QM_CHECK(xfer->ch_len > 0, -EINVAL);
QM_CHECK(xfer->ch_len <= QM_SS_ADC_CHAN_SEQ_MAX, -EINVAL);
QM_CHECK(xfer->samples_len > 0, -EINVAL);
QM_CHECK(xfer->samples_len <= QM_SS_ADC_FIFO_LEN, -EINVAL);
/* Flush the FIFO. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_SET, QM_SS_ADC_SET_FLUSH_RX);
/* Populate the sequence table. */
setup_seq_table(adc, xfer, true);
/* Set the threshold. */
reg = __builtin_arc_lr(controller + QM_SS_ADC_SET);
reg &= ~QM_SS_ADC_SET_THRESHOLD_MASK;
reg |= ((xfer->samples_len - 1) << QM_SS_ADC_SET_THRESHOLD_OFFSET);
__builtin_arc_sr(reg, controller + QM_SS_ADC_SET);
/* Set the sequence mode to single run. */
QM_SS_REG_AUX_NAND(controller + QM_SS_ADC_SET, QM_SS_ADC_SET_SEQ_MODE);
/* Mask all interrupts. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_MSK_ALL_INT);
/* Enable the ADC. */
enable_adc();
/* Start the sequencer. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL, QM_SS_ADC_CTRL_SEQ_START);
/* Wait for the sequence to finish. */
while (!(res = __builtin_arc_lr(controller + QM_SS_ADC_INTSTAT))) {
}
/* Return if we get an error (UNDERFLOW, OVERFLOW, SEQ_ERROR). */
if (res > 1) {
return -EIO;
}
/* Read the samples into the array. */
for (i = 0; i < xfer->samples_len; i++) {
/* Pop one sample into the sample register. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_SET,
QM_SS_ADC_SET_POP_RX);
/* Read the sample in the array. */
xfer->samples[i] =
(__builtin_arc_lr(controller + QM_SS_ADC_SAMPLE) >>
(ADC_SAMPLE_SHIFT - resolution[adc]));
}
/* Clear the data available status register. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_CLR_DATA_A);
/* Disable the ADC. */
disable_adc();
return 0;
}
int qm_ss_adc_irq_convert(const qm_ss_adc_t adc, qm_ss_adc_xfer_t *xfer)
{
uint32_t reg;
uint32_t controller = adc_base[adc];
QM_CHECK(adc < QM_SS_ADC_NUM, -EINVAL);
QM_CHECK(NULL != xfer, -EINVAL);
QM_CHECK(NULL != xfer->ch, -EINVAL);
QM_CHECK(NULL != xfer->samples, -EINVAL);
QM_CHECK(xfer->ch_len > 0, -EINVAL);
QM_CHECK(xfer->samples_len > 0, -EINVAL);
QM_CHECK(xfer->ch_len <= QM_SS_ADC_CHAN_SEQ_MAX, -EINVAL);
/* Flush the FIFO. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_SET, QM_SS_ADC_SET_FLUSH_RX);
/* Populate the sequence table. */
setup_seq_table(adc, xfer, false);
/* Copy the xfer struct so we can get access from the ISR. */
memcpy(&irq_xfer[adc], xfer, sizeof(qm_ss_adc_xfer_t));
/* Set count back to 0. */
count[adc] = 0;
/* Set the threshold. */
reg = __builtin_arc_lr(controller + QM_SS_ADC_SET);
reg &= ~QM_SS_ADC_SET_THRESHOLD_MASK;
reg |= (FIFO_INTERRUPT_THRESHOLD - 1) << QM_SS_ADC_SET_THRESHOLD_OFFSET;
__builtin_arc_sr(reg, controller + QM_SS_ADC_SET);
/* Set the sequence mode to repetitive. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_SET, QM_SS_ADC_SET_SEQ_MODE);
/* Enable all interrupts. */
QM_SS_REG_AUX_NAND(controller + QM_SS_ADC_CTRL, 0x1F00);
/* Enable the ADC. */
enable_adc();
/* Start the sequencer. */
QM_SS_REG_AUX_OR(controller + QM_SS_ADC_CTRL, QM_SS_ADC_CTRL_SEQ_START);
return 0;
}

View file

@ -0,0 +1,158 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_ss_gpio.h"
static void (*callback[QM_SS_GPIO_NUM])(void *data, uint32_t int_status);
static void *callback_data[QM_SS_GPIO_NUM];
static uint32_t gpio_base[QM_SS_GPIO_NUM] = {QM_SS_GPIO_0_BASE,
QM_SS_GPIO_1_BASE};
static void ss_gpio_isr_handler(qm_ss_gpio_t gpio)
{
uint32_t int_status = 0;
uint32_t controller = gpio_base[gpio];
int_status = __builtin_arc_lr(controller + QM_SS_GPIO_INTSTATUS);
if (callback[gpio]) {
callback[gpio](callback_data, int_status);
}
__builtin_arc_sr(int_status, controller + QM_SS_GPIO_PORTA_EOI);
}
QM_ISR_DECLARE(qm_ss_gpio_isr_0)
{
ss_gpio_isr_handler(QM_SS_GPIO_0);
}
QM_ISR_DECLARE(qm_ss_gpio_isr_1)
{
ss_gpio_isr_handler(QM_SS_GPIO_1);
}
int qm_ss_gpio_set_config(const qm_ss_gpio_t gpio,
const qm_ss_gpio_port_config_t *const cfg)
{
uint32_t controller;
QM_CHECK(gpio < QM_SS_GPIO_NUM, -EINVAL);
QM_CHECK(cfg != NULL, -EINVAL);
controller = gpio_base[gpio];
__builtin_arc_sr(0xFFFFFFFF, controller + QM_SS_GPIO_INTMASK);
__builtin_arc_sr(cfg->direction, controller + QM_SS_GPIO_SWPORTA_DDR);
__builtin_arc_sr(cfg->int_type, controller + QM_SS_GPIO_INTTYPE_LEVEL);
__builtin_arc_sr(cfg->int_polarity,
controller + QM_SS_GPIO_INT_POLARITY);
__builtin_arc_sr(cfg->int_debounce, controller + QM_SS_GPIO_DEBOUNCE);
callback[gpio] = cfg->callback;
callback_data[gpio] = cfg->callback_data;
__builtin_arc_sr(cfg->int_en, controller + QM_SS_GPIO_INTEN);
__builtin_arc_sr(~cfg->int_en, controller + QM_SS_GPIO_INTMASK);
return 0;
}
int qm_ss_gpio_read_pin(const qm_ss_gpio_t gpio, const uint8_t pin,
qm_ss_gpio_state_t *const state)
{
QM_CHECK(gpio < QM_SS_GPIO_NUM, -EINVAL);
QM_CHECK(pin <= QM_SS_GPIO_NUM_PINS, -EINVAL);
QM_CHECK(state != NULL, -EINVAL);
*state =
((__builtin_arc_lr(gpio_base[gpio] + QM_SS_GPIO_EXT_PORTA) >> pin) &
1);
return 0;
}
int qm_ss_gpio_set_pin(const qm_ss_gpio_t gpio, const uint8_t pin)
{
uint32_t val;
QM_CHECK(gpio < QM_SS_GPIO_NUM, -EINVAL);
QM_CHECK(pin <= QM_SS_GPIO_NUM_PINS, -EINVAL);
val = __builtin_arc_lr(gpio_base[gpio] + QM_SS_GPIO_SWPORTA_DR) |
BIT(pin);
__builtin_arc_sr(val, gpio_base[gpio] + QM_SS_GPIO_SWPORTA_DR);
return 0;
}
int qm_ss_gpio_clear_pin(const qm_ss_gpio_t gpio, const uint8_t pin)
{
uint32_t val;
QM_CHECK(gpio < QM_SS_GPIO_NUM, -EINVAL);
QM_CHECK(pin <= QM_SS_GPIO_NUM_PINS, -EINVAL);
val = __builtin_arc_lr(gpio_base[gpio] + QM_SS_GPIO_SWPORTA_DR);
val &= ~BIT(pin);
__builtin_arc_sr(val, gpio_base[gpio] + QM_SS_GPIO_SWPORTA_DR);
return 0;
}
int qm_ss_gpio_set_pin_state(const qm_ss_gpio_t gpio, const uint8_t pin,
const qm_ss_gpio_state_t state)
{
uint32_t val;
QM_CHECK(gpio < QM_SS_GPIO_NUM, -EINVAL);
QM_CHECK(state < QM_SS_GPIO_STATE_NUM, -EINVAL);
val = __builtin_arc_lr(gpio_base[gpio] + QM_SS_GPIO_SWPORTA_DR);
val ^= (-state ^ val) & (1 << pin);
__builtin_arc_sr(val, gpio_base[gpio] + QM_SS_GPIO_SWPORTA_DR);
return 0;
}
int qm_ss_gpio_read_port(const qm_ss_gpio_t gpio, uint32_t *const port)
{
QM_CHECK(gpio < QM_SS_GPIO_NUM, -EINVAL);
QM_CHECK(port != NULL, -EINVAL);
*port = (__builtin_arc_lr(gpio_base[gpio] + QM_SS_GPIO_EXT_PORTA));
return 0;
}
int qm_ss_gpio_write_port(const qm_ss_gpio_t gpio, const uint32_t val)
{
QM_CHECK(gpio < QM_SS_GPIO_NUM, -EINVAL);
__builtin_arc_sr(val, gpio_base[gpio] + QM_SS_GPIO_SWPORTA_DR);
return 0;
}

View file

@ -0,0 +1,681 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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.
*/
#define SPK_LEN_SS (1)
#define SPK_LEN_FS (2)
#define TX_TL (2)
#define RX_TL (5)
#include <string.h>
#include "qm_ss_i2c.h"
#include "clk.h"
/*
* NOTE: There are a number of differences between this Sensor Subsystem I2C
* driver and the Lakemont version. The IP is not the same, the
* functionality is a subset of the features contained on the Lakemont
* version:
* 1. Fast Mode Plus is not supported
* 2. Slave mode is not supported
*
* The registers are different and the register set is compressed.
* Some noteworthy differences are:
* 1. Clock enable is contained in the QM_SS_I2C_CON register
* 2. SPKLEN is contained in the QM_SS_I2C_CON register
* 3. The high and low count values are contained within a single
* register
* 4. There is no raw interrupt status register, QM_SS_I2C_INT_STAT
* takes its place and is non-maskable
* 5. There is a reduced number of TX abrt source status bits
* 6. The QM_SS_I2C_DATA_CMD register is different and requires the
* strobe bit to be written to indicate a QM_SS_I2C_DATA_CMD
* register update. There is a push and pop mechanism for using
* the FIFO.
*/
static uint32_t i2c_base[QM_SS_I2C_NUM] = {QM_SS_I2C_0_BASE, QM_SS_I2C_1_BASE};
static qm_ss_i2c_transfer_t i2c_transfer[QM_SS_I2C_NUM];
static uint32_t i2c_write_pos[QM_SS_I2C_NUM], i2c_read_pos[QM_SS_I2C_NUM],
i2c_read_buffer_remaining[QM_SS_I2C_NUM];
static void controller_enable(const qm_ss_i2c_t i2c);
static void controller_disable(const qm_ss_i2c_t i2c);
static void qm_ss_i2c_isr_handler(const qm_ss_i2c_t i2c)
{
uint32_t controller = i2c_base[i2c], data_cmd = 0,
count_tx = (QM_SS_I2C_FIFO_SIZE - TX_TL);
qm_ss_i2c_status_t status = 0;
int rc = 0;
/* Check for errors */
QM_ASSERT(!(__builtin_arc_lr(controller + QM_SS_I2C_INTR_STAT) &
QM_SS_I2C_INTR_STAT_TX_OVER));
QM_ASSERT(!(__builtin_arc_lr(controller + QM_SS_I2C_INTR_STAT) &
QM_SS_I2C_INTR_STAT_RX_UNDER));
QM_ASSERT(!(__builtin_arc_lr(controller + QM_SS_I2C_INTR_STAT) &
QM_SS_I2C_INTR_STAT_RX_OVER));
if ((__builtin_arc_lr(controller + QM_SS_I2C_INTR_STAT) &
QM_SS_I2C_INTR_STAT_TX_ABRT)) {
QM_ASSERT(
!(__builtin_arc_lr(controller + QM_SS_I2C_TX_ABRT_SOURCE) &
QM_SS_I2C_TX_ABRT_SBYTE_NORSTRT));
status =
(__builtin_arc_lr(controller + QM_SS_I2C_TX_ABRT_SOURCE) &
QM_SS_I2C_TX_ABRT_SOURCE_ALL_MASK);
/* clear intr */
__builtin_arc_sr(QM_SS_I2C_INTR_CLR_TX_ABRT,
controller + QM_SS_I2C_INTR_CLR);
/* mask interrupts */
__builtin_arc_sr(QM_SS_I2C_INTR_MASK_ALL,
controller + QM_SS_I2C_INTR_MASK);
rc = (status & QM_I2C_TX_ABRT_USER_ABRT) ? -ECANCELED : -EIO;
if (i2c_transfer[i2c].callback) {
i2c_transfer[i2c].callback(
i2c_transfer[i2c].callback_data, rc, status, 0);
}
}
/* RX read from buffer */
if ((__builtin_arc_lr(controller + QM_SS_I2C_INTR_STAT) &
QM_SS_I2C_INTR_STAT_RX_FULL)) {
while (i2c_read_buffer_remaining[i2c] &&
(__builtin_arc_lr(controller + QM_SS_I2C_RXFLR))) {
__builtin_arc_sr(QM_SS_I2C_DATA_CMD_POP,
controller + QM_SS_I2C_DATA_CMD);
/* IC_DATA_CMD[7:0] contains received data */
i2c_transfer[i2c].rx[i2c_read_pos[i2c]] =
__builtin_arc_lr(controller + QM_SS_I2C_DATA_CMD);
i2c_read_buffer_remaining[i2c]--;
i2c_read_pos[i2c]++;
if (i2c_read_buffer_remaining[i2c] == 0) {
/* mask rx full interrupt if transfer
* complete
*/
QM_SS_REG_AUX_NAND(
(controller + QM_SS_I2C_INTR_MASK),
QM_SS_I2C_INTR_MASK_RX_FULL);
if (i2c_transfer[i2c].stop) {
controller_disable(i2c);
}
if (i2c_transfer[i2c].callback) {
i2c_transfer[i2c].callback(
i2c_transfer[i2c].callback_data, 0,
QM_I2C_IDLE, i2c_read_pos[i2c]);
}
}
}
if (i2c_read_buffer_remaining[i2c] > 0 &&
i2c_read_buffer_remaining[i2c] < (RX_TL + 1)) {
/* Adjust the RX threshold so the next 'RX_FULL'
* interrupt is generated when all the remaining
* data are received.
*/
QM_SS_REG_AUX_NAND((controller + QM_SS_I2C_TL),
QM_SS_I2C_TL_RX_TL_MASK);
QM_SS_REG_AUX_OR((controller + QM_SS_I2C_TL),
(i2c_read_buffer_remaining[i2c] - 1));
}
/* RX_FULL INTR is autocleared when the buffer
* levels goes below the threshold
*/
}
if ((__builtin_arc_lr(controller + QM_SS_I2C_INTR_STAT) &
QM_SS_I2C_INTR_STAT_TX_EMPTY)) {
if ((__builtin_arc_lr(controller + QM_SS_I2C_STATUS) &
QM_SS_I2C_STATUS_TFE) &&
(i2c_transfer[i2c].tx != NULL) &&
(i2c_transfer[i2c].tx_len == 0) &&
(i2c_transfer[i2c].rx_len == 0)) {
QM_SS_REG_AUX_NAND((controller + QM_SS_I2C_INTR_MASK),
QM_SS_I2C_INTR_MASK_TX_EMPTY);
/* if this is not a combined
* transaction, disable the controller now
*/
if ((i2c_read_buffer_remaining[i2c] == 0) &&
i2c_transfer[i2c].stop) {
controller_disable(i2c);
/* callback */
if (i2c_transfer[i2c].callback) {
i2c_transfer[i2c].callback(
i2c_transfer[i2c].callback_data, 0,
QM_I2C_IDLE, i2c_write_pos[i2c]);
}
}
}
while ((count_tx) && i2c_transfer[i2c].tx_len) {
count_tx--;
/* write command -IC_DATA_CMD[8] = 0 */
/* fill IC_DATA_CMD[7:0] with the data */
data_cmd = QM_SS_I2C_DATA_CMD_PUSH |
i2c_transfer[i2c].tx[i2c_write_pos[i2c]];
i2c_transfer[i2c].tx_len--;
/* if transfer is a combined transfer, only
* send stop at
* end of the transfer sequence */
if (i2c_transfer[i2c].stop &&
(i2c_transfer[i2c].tx_len == 0) &&
(i2c_transfer[i2c].rx_len == 0)) {
data_cmd |= QM_SS_I2C_DATA_CMD_STOP;
}
/* write data */
__builtin_arc_sr(data_cmd,
controller + QM_SS_I2C_DATA_CMD);
i2c_write_pos[i2c]++;
/* TX_EMPTY INTR is autocleared when the buffer
* levels goes above the threshold
*/
}
/* TX read command */
count_tx =
QM_SS_I2C_FIFO_SIZE -
(__builtin_arc_lr(controller + QM_SS_I2C_TXFLR) +
(__builtin_arc_lr(controller + QM_SS_I2C_RXFLR) + 1));
while (i2c_transfer[i2c].rx_len &&
(i2c_transfer[i2c].tx_len == 0) && count_tx) {
count_tx--;
i2c_transfer[i2c].rx_len--;
/* if transfer is a combined transfer, only
* send stop at
* end of
* the transfer sequence */
if (i2c_transfer[i2c].stop &&
(i2c_transfer[i2c].rx_len == 0) &&
(i2c_transfer[i2c].tx_len == 0)) {
__builtin_arc_sr((QM_SS_I2C_DATA_CMD_CMD |
QM_SS_I2C_DATA_CMD_PUSH |
QM_SS_I2C_DATA_CMD_STOP),
controller +
QM_SS_I2C_DATA_CMD);
} else {
__builtin_arc_sr((QM_SS_I2C_DATA_CMD_CMD |
QM_SS_I2C_DATA_CMD_PUSH),
controller +
QM_SS_I2C_DATA_CMD);
}
}
/* generate a tx_empty interrupt when tx fifo is fully
* empty */
if ((i2c_transfer[i2c].tx_len == 0) &&
(i2c_transfer[i2c].rx_len == 0)) {
QM_SS_REG_AUX_NAND((controller + QM_SS_I2C_TL),
QM_SS_I2C_TL_TX_TL_MASK);
}
}
}
QM_ISR_DECLARE(qm_ss_i2c_isr_0)
{
qm_ss_i2c_isr_handler(QM_SS_I2C_0);
}
QM_ISR_DECLARE(qm_ss_i2c_isr_1)
{
qm_ss_i2c_isr_handler(QM_SS_I2C_1);
}
static uint32_t get_lo_cnt(uint32_t lo_time_ns)
{
return (((clk_sys_get_ticks_per_us() * lo_time_ns) / 1000) - 1);
}
static uint32_t get_hi_cnt(qm_ss_i2c_t i2c, uint32_t hi_time_ns)
{
uint32_t controller = i2c_base[i2c];
return (((clk_sys_get_ticks_per_us() * hi_time_ns) / 1000) - 7 -
((__builtin_arc_lr(controller + QM_SS_I2C_CON) &
QM_SS_I2C_CON_SPKLEN_MASK) >>
QM_SS_I2C_CON_SPKLEN_OFFSET));
}
int qm_ss_i2c_set_config(const qm_ss_i2c_t i2c,
const qm_ss_i2c_config_t *const cfg)
{
uint32_t controller = i2c_base[i2c], lcnt = 0, hcnt = 0, full_cnt = 0,
min_lcnt = 0, lcnt_diff = 0,
con = (__builtin_arc_lr(controller + QM_SS_I2C_CON) &
QM_SS_I2C_CON_CLK_ENA);
QM_CHECK(i2c < QM_SS_I2C_NUM, -EINVAL);
QM_CHECK(cfg != NULL, -EINVAL);
/* mask all interrupts */
__builtin_arc_sr(QM_SS_I2C_INTR_MASK_ALL,
controller + QM_SS_I2C_INTR_MASK);
/* disable controller */
controller_disable(i2c);
/* set mode */
con |= QM_SS_I2C_CON_RESTART_EN |
/* set 7/10 bit address mode */
(cfg->address_mode << QM_SS_I2C_CON_IC_10BITADDR_OFFSET);
/*
* Timing generation algorithm:
* 1. compute hi/lo count so as to achieve the desired bus
* speed at 50% duty cycle
* 2. adjust the hi/lo count to ensure that minimum hi/lo
* timings are guaranteed as per spec.
*/
switch (cfg->speed) {
case QM_SS_I2C_SPEED_STD:
con |= QM_SS_I2C_CON_SPEED_SS |
SPK_LEN_SS << QM_SS_I2C_CON_SPKLEN_OFFSET;
__builtin_arc_sr(con, controller + QM_SS_I2C_CON);
min_lcnt = get_lo_cnt(QM_I2C_MIN_SS_NS);
lcnt = get_lo_cnt(QM_I2C_SS_50_DC_NS);
hcnt = get_hi_cnt(i2c, QM_I2C_SS_50_DC_NS);
break;
case QM_SS_I2C_SPEED_FAST:
con |= QM_SS_I2C_CON_SPEED_FS |
SPK_LEN_FS << QM_SS_I2C_CON_SPKLEN_OFFSET;
__builtin_arc_sr(con, controller + QM_SS_I2C_CON);
min_lcnt = get_lo_cnt(QM_I2C_MIN_FS_NS);
lcnt = get_lo_cnt(QM_I2C_FS_50_DC_NS);
hcnt = get_hi_cnt(i2c, QM_I2C_FS_50_DC_NS);
break;
}
if (hcnt > QM_SS_I2C_IC_HCNT_MAX || hcnt < QM_SS_I2C_IC_HCNT_MIN) {
return -EINVAL;
}
if (lcnt > QM_SS_I2C_IC_LCNT_MAX || lcnt < QM_SS_I2C_IC_LCNT_MIN) {
return -EINVAL;
}
/* Increment minimum low count to account for rounding down */
min_lcnt++;
if (lcnt < min_lcnt) {
lcnt_diff = (min_lcnt - lcnt);
lcnt += (lcnt_diff);
hcnt -= (lcnt_diff);
}
full_cnt = (lcnt & 0xFFFF) |
(hcnt & 0xFFFF) << QM_SS_I2C_SS_FS_SCL_CNT_HCNT_OFFSET;
if (QM_SS_I2C_SPEED_STD == cfg->speed) {
__builtin_arc_sr(full_cnt, controller + QM_SS_I2C_SS_SCL_CNT);
} else {
__builtin_arc_sr(full_cnt, controller + QM_SS_I2C_FS_SCL_CNT);
}
return 0;
}
int qm_ss_i2c_set_speed(const qm_ss_i2c_t i2c, const qm_ss_i2c_speed_t speed,
const uint16_t lo_cnt, const uint16_t hi_cnt)
{
uint32_t full_cnt = 0, controller = i2c_base[i2c],
con = __builtin_arc_lr(controller + QM_SS_I2C_CON);
QM_CHECK(i2c < QM_SS_I2C_NUM, -EINVAL);
QM_CHECK(hi_cnt < QM_SS_I2C_IC_HCNT_MAX &&
lo_cnt > QM_SS_I2C_IC_HCNT_MIN,
-EINVAL);
QM_CHECK(lo_cnt < QM_SS_I2C_IC_LCNT_MAX &&
lo_cnt > QM_SS_I2C_IC_LCNT_MIN,
-EINVAL);
con &= ~QM_SS_I2C_CON_SPEED_MASK;
full_cnt = (lo_cnt & QM_SS_I2C_SS_FS_SCL_CNT_16BIT_MASK) |
(hi_cnt & QM_SS_I2C_SS_FS_SCL_CNT_16BIT_MASK)
<< QM_SS_I2C_SS_FS_SCL_CNT_HCNT_OFFSET;
switch (speed) {
case QM_SS_I2C_SPEED_STD:
con |= QM_SS_I2C_CON_SPEED_SS;
__builtin_arc_sr(full_cnt, controller + QM_SS_I2C_SS_SCL_CNT);
break;
case QM_SS_I2C_SPEED_FAST:
con |= QM_SS_I2C_CON_SPEED_FS;
__builtin_arc_sr(full_cnt, controller + QM_SS_I2C_FS_SCL_CNT);
break;
}
__builtin_arc_sr(con, controller + QM_SS_I2C_CON);
return 0;
}
int qm_ss_i2c_get_status(const qm_ss_i2c_t i2c,
qm_ss_i2c_status_t *const status)
{
uint32_t controller = i2c_base[i2c];
QM_CHECK(status != NULL, -EINVAL);
*status = 0;
/* check if slave or master are active */
if (__builtin_arc_lr(controller + QM_SS_I2C_STATUS) &
QM_SS_I2C_STATUS_BUSY_MASK) {
*status |= QM_I2C_BUSY;
}
/* check for abort status */
*status |= (__builtin_arc_lr(controller + QM_SS_I2C_TX_ABRT_SOURCE) &
QM_SS_I2C_TX_ABRT_SOURCE_ALL_MASK);
return 0;
}
int qm_ss_i2c_master_write(const qm_ss_i2c_t i2c, const uint16_t slave_addr,
const uint8_t *const data, uint32_t len,
const bool stop, qm_ss_i2c_status_t *const status)
{
uint8_t *d = (uint8_t *)data;
uint32_t controller = i2c_base[i2c],
con = __builtin_arc_lr(controller + QM_SS_I2C_CON),
data_cmd = 0;
int ret = 0;
QM_CHECK(i2c < QM_SS_I2C_NUM, -EINVAL);
QM_CHECK(data != NULL, -EINVAL);
QM_CHECK(len > 0, -EINVAL);
/* write slave address to TAR */
con &= ~QM_SS_I2C_CON_TAR_SAR_MASK;
con |= (slave_addr & QM_SS_I2C_CON_TAR_SAR_10_BIT_MASK)
<< QM_SS_I2C_CON_TAR_SAR_OFFSET;
__builtin_arc_sr(con, controller + QM_SS_I2C_CON);
/* enable controller */
controller_enable(i2c);
while (len--) {
/* wait if FIFO is full */
while (!((__builtin_arc_lr(controller + QM_SS_I2C_STATUS)) &
QM_SS_I2C_STATUS_TFNF))
;
/* write command -IC_DATA_CMD[8] = 0 */
/* fill IC_DATA_CMD[7:0] with the data */
data_cmd = *d;
data_cmd |= QM_SS_I2C_DATA_CMD_PUSH;
/* send stop after last byte */
if (len == 0 && stop) {
data_cmd |= QM_SS_I2C_DATA_CMD_STOP;
}
__builtin_arc_sr(data_cmd, controller + QM_SS_I2C_DATA_CMD);
d++;
}
/* this is a blocking call, wait until FIFO is empty or tx abrt
* error */
while (!(__builtin_arc_lr(controller + QM_SS_I2C_STATUS) &
QM_SS_I2C_STATUS_TFE))
;
if ((__builtin_arc_lr(controller + QM_SS_I2C_INTR_STAT) &
QM_SS_I2C_INTR_STAT_TX_ABRT)) {
ret = -EIO;
}
/* disable controller */
if (true == stop) {
controller_disable(i2c);
}
if (status != NULL) {
qm_ss_i2c_get_status(i2c, status);
}
/* Clear abort status
* The controller flushes/resets/empties
* the TX FIFO whenever this bit is set. The TX
* FIFO remains in this flushed state until the
* register IC_CLR_TX_ABRT is read.
*/
__builtin_arc_sr(QM_SS_I2C_INTR_CLR_TX_ABRT,
controller + QM_SS_I2C_INTR_CLR);
return ret;
}
int qm_ss_i2c_master_read(const qm_ss_i2c_t i2c, const uint16_t slave_addr,
uint8_t *const data, uint32_t len, const bool stop,
qm_ss_i2c_status_t *const status)
{
uint32_t controller = i2c_base[i2c],
con = __builtin_arc_lr(controller + QM_SS_I2C_CON),
data_cmd = QM_SS_I2C_DATA_CMD_CMD | QM_SS_I2C_DATA_CMD_PUSH;
uint8_t *d = (uint8_t *)data;
int ret = 0;
QM_CHECK(i2c < QM_SS_I2C_NUM, -EINVAL);
QM_CHECK(data != NULL, -EINVAL);
QM_CHECK(len > 0, -EINVAL);
/* write slave address to TAR */
con &= ~QM_SS_I2C_CON_TAR_SAR_MASK;
con |= (slave_addr & QM_SS_I2C_CON_TAR_SAR_10_BIT_MASK)
<< QM_SS_I2C_CON_TAR_SAR_OFFSET;
__builtin_arc_sr(con, controller + QM_SS_I2C_CON);
/* enable controller */
controller_enable(i2c);
while (len--) {
if (len == 0 && stop) {
data_cmd |= QM_SS_I2C_DATA_CMD_STOP;
}
__builtin_arc_sr(data_cmd, controller + QM_SS_I2C_DATA_CMD);
/* wait if rx fifo is empty, break if tx empty and
* error*/
while (!(__builtin_arc_lr(controller + QM_SS_I2C_STATUS) &
QM_SS_I2C_STATUS_RFNE)) {
if (__builtin_arc_lr(controller + QM_SS_I2C_INTR_STAT) &
QM_SS_I2C_INTR_STAT_TX_ABRT) {
break;
}
}
if ((__builtin_arc_lr(controller + QM_SS_I2C_INTR_STAT) &
QM_SS_I2C_INTR_STAT_TX_ABRT)) {
ret = -EIO;
break;
}
__builtin_arc_sr(QM_SS_I2C_DATA_CMD_POP,
controller + QM_SS_I2C_DATA_CMD);
/* wait until rx fifo is empty, indicating pop is complete*/
while ((__builtin_arc_lr(controller + QM_SS_I2C_STATUS) &
QM_SS_I2C_STATUS_RFNE));
/* IC_DATA_CMD[7:0] contains received data */
*d = __builtin_arc_lr(controller + QM_SS_I2C_DATA_CMD);
d++;
}
/* disable controller */
if (true == stop) {
controller_disable(i2c);
}
if (status != NULL) {
qm_ss_i2c_get_status(i2c, status);
}
/* Clear abort status
* The controller flushes/resets/empties
* the TX FIFO whenever this bit is set. The TX
* FIFO remains in this flushed state until the
* register IC_CLR_TX_ABRT is read.
*/
__builtin_arc_sr(QM_SS_I2C_INTR_CLR_TX_ABRT,
controller + QM_SS_I2C_INTR_CLR);
return ret;
}
int qm_ss_i2c_master_irq_transfer(const qm_ss_i2c_t i2c,
const qm_ss_i2c_transfer_t *const xfer,
const uint16_t slave_addr)
{
uint32_t controller = i2c_base[i2c],
con = __builtin_arc_lr(controller + QM_SS_I2C_CON);
QM_CHECK(i2c < QM_SS_I2C_NUM, -EINVAL);
QM_CHECK(NULL != xfer, -EINVAL);
/* write slave address to TAR */
con &= ~QM_SS_I2C_CON_TAR_SAR_MASK;
con |= (slave_addr & QM_SS_I2C_CON_TAR_SAR_10_BIT_MASK)
<< QM_SS_I2C_CON_TAR_SAR_OFFSET;
__builtin_arc_sr(con, controller + QM_SS_I2C_CON);
i2c_write_pos[i2c] = 0;
i2c_read_pos[i2c] = 0;
i2c_read_buffer_remaining[i2c] = xfer->rx_len;
memcpy(&i2c_transfer[i2c], xfer, sizeof(i2c_transfer[i2c]));
/* set threshold */
if (xfer->rx_len > 0 && xfer->rx_len < (RX_TL + 1)) {
/* If 'rx_len' is less than the default threshold, we have to
* change the threshold value so the 'RX FULL' interrupt is
* generated once all data from the transfer is received.
*/
__builtin_arc_sr(
((TX_TL << QM_SS_I2C_TL_TX_TL_OFFSET) | (xfer->rx_len - 1)),
controller + QM_SS_I2C_TL);
} else {
__builtin_arc_sr(((TX_TL << QM_SS_I2C_TL_TX_TL_OFFSET) | RX_TL),
controller + QM_SS_I2C_TL);
}
/* mask interrupts */
__builtin_arc_sr(QM_SS_I2C_INTR_MASK_ALL,
controller + QM_SS_I2C_INTR_MASK);
/* enable controller */
controller_enable(i2c);
/* unmask interrupts */
__builtin_arc_sr(
(QM_SS_I2C_INTR_MASK_TX_ABRT | QM_SS_I2C_INTR_MASK_TX_EMPTY |
QM_SS_I2C_INTR_MASK_TX_OVER | QM_SS_I2C_INTR_MASK_RX_FULL |
QM_SS_I2C_INTR_MASK_RX_OVER | QM_SS_I2C_INTR_MASK_RX_UNDER),
controller + QM_SS_I2C_INTR_MASK);
return 0;
}
static void controller_enable(const qm_ss_i2c_t i2c)
{
uint32_t controller = i2c_base[i2c];
if (!(__builtin_arc_lr(controller + QM_SS_I2C_ENABLE_STATUS) &
QM_SS_I2C_ENABLE_STATUS_IC_EN)) {
/* enable controller */
QM_SS_REG_AUX_OR((controller + QM_SS_I2C_CON),
QM_SS_I2C_CON_ENABLE);
/* wait until controller is enabled */
while (
!(__builtin_arc_lr(controller + QM_SS_I2C_ENABLE_STATUS) &
QM_SS_I2C_ENABLE_STATUS_IC_EN))
;
}
}
static void controller_disable(const qm_ss_i2c_t i2c)
{
uint32_t controller = i2c_base[i2c];
if (__builtin_arc_lr(controller + QM_SS_I2C_ENABLE_STATUS) &
QM_SS_I2C_ENABLE_STATUS_IC_EN) {
/* disable controller */
QM_SS_REG_AUX_NAND((controller + QM_SS_I2C_CON),
QM_SS_I2C_CON_ENABLE);
/* wait until controller is disabled */
while ((__builtin_arc_lr(controller + QM_SS_I2C_ENABLE_STATUS) &
QM_SS_I2C_ENABLE_STATUS_IC_EN))
;
}
}
int qm_ss_i2c_irq_transfer_terminate(const qm_ss_i2c_t i2c)
{
uint32_t controller = i2c_base[i2c];
QM_CHECK(i2c < QM_SS_I2C_NUM, -EINVAL);
/* Abort:
* In response to an ABORT, the controller issues a STOP and
* flushes
* the Tx FIFO after completing the current transfer, then sets
* the
* TX_ABORT interrupt after the abort operation. The ABORT bit
* is
* cleared automatically by hardware after the abort operation.
*/
QM_SS_REG_AUX_OR((controller + QM_SS_I2C_CON), QM_SS_I2C_CON_ABORT);
return 0;
}

View file

@ -0,0 +1,97 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_ss_interrupt.h"
#include "qm_soc_regs.h"
#include "qm_sensor_regs.h"
/* SCSS base addr for Sensor Subsystem interrupt routing, for linear IRQ
* mapping */
#define SCSS_SS_INT_MASK_BASE (&QM_SCSS_INT->int_ss_adc_err_mask)
#define SCSS_SS_INT_MASK BIT(8) /* Sensor Subsystem interrupt masking */
#if (UNIT_TEST)
qm_ss_isr_t __ivt_vect_table[QM_SS_INT_VECTOR_NUM];
#else
extern qm_ss_isr_t __ivt_vect_table[];
#endif
void qm_ss_irq_disable(void)
{
__builtin_arc_clri();
}
void qm_ss_irq_enable(void)
{
__builtin_arc_seti(0);
}
void qm_ss_irq_mask(uint32_t irq)
{
__builtin_arc_sr(irq, QM_SS_AUX_IRQ_SELECT);
__builtin_arc_sr(QM_SS_INT_DISABLE, QM_SS_AUX_IRQ_ENABLE);
}
void qm_ss_irq_unmask(uint32_t irq)
{
__builtin_arc_sr(irq, QM_SS_AUX_IRQ_SELECT);
__builtin_arc_sr(QM_SS_INT_ENABLE, QM_SS_AUX_IRQ_ENABLE);
}
void qm_ss_int_vector_request(uint32_t vector, qm_ss_isr_t isr)
{
/* Invalidate the I-cache line which contains the irq vector. This
* will bypass I-Cach and set vector with the good isr. */
__builtin_arc_sr((uint32_t)&__ivt_vect_table[0] + (vector * 4),
QM_SS_AUX_IC_IVIL);
/* All SR accesses to the IC_IVIL register must be followed by three
* NOP instructions, see chapter 3.3.59 in the datasheet
* "ARC_V2_ProgrammersReference.pdf" */
__builtin_arc_nop();
__builtin_arc_nop();
__builtin_arc_nop();
__ivt_vect_table[vector] = isr;
}
void qm_ss_irq_request(uint32_t irq, qm_ss_isr_t isr)
{
uint32_t *scss_intmask;
uint32_t vector = irq + (QM_SS_EXCEPTION_NUM + QM_SS_INT_TIMER_NUM);
/* Guarding the IRQ set-up */
qm_ss_irq_mask(vector);
qm_ss_int_vector_request(vector, isr);
/* Route peripheral interrupt to Sensor Subsystem */
scss_intmask = (uint32_t *)SCSS_SS_INT_MASK_BASE + irq;
*scss_intmask &= ~SCSS_SS_INT_MASK;
qm_ss_irq_unmask(vector);
}

View file

@ -0,0 +1,400 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_ss_spi.h"
#define FIFO_SIZE (8) /* Maximum size of RX or TX FIFO */
#define FIFO_RX_W_MARK (6) /* Interrupt mark to read RX FIFO */
#define FIFO_TX_W_MARK (3) /* Interrupt mark to write TX FIFO */
#define BYTES_PER_FRAME(reg_data) \
(((reg_data & QM_SS_SPI_CTRL_DFS_MASK) >> 3) + 1)
static uint32_t base[QM_SS_SPI_NUM] = {QM_SS_SPI_0_BASE, QM_SS_SPI_1_BASE};
static const qm_ss_spi_async_transfer_t *transfer[QM_SS_SPI_NUM];
static uint32_t rx_c[QM_SS_SPI_NUM];
static uint32_t tx_c[QM_SS_SPI_NUM];
static uint8_t *rx_p[QM_SS_SPI_NUM];
static uint8_t *tx_p[QM_SS_SPI_NUM];
static uint16_t dummy_frame;
/* Private Functions */
static void spi_disable(const qm_ss_spi_t spi)
{
/* Disable SPI device */
QM_SS_REG_AUX_NAND(base[spi] + QM_SS_SPI_SPIEN, QM_SS_SPI_SPIEN_EN);
/* MASK all interrupts. */
__builtin_arc_sr(0, base[spi] + QM_SS_SPI_INTR_MASK);
/* Clear all interrupts */
__builtin_arc_sr(QM_SS_SPI_INTR_ALL, base[spi] + QM_SS_SPI_CLR_INTR);
}
static __inline__ void fifo_write(const qm_ss_spi_t spi, void *data,
uint8_t size)
{
uint32_t dr;
if (size == 1) {
dr = *(uint8_t *)data;
} else {
dr = *(uint16_t *)data;
}
dr |= QM_SS_SPI_DR_W_MASK;
__builtin_arc_sr(dr, base[spi] + QM_SS_SPI_DR);
}
static __inline__ void fifo_read(const qm_ss_spi_t spi, void *data,
uint8_t size)
{
__builtin_arc_sr(QM_SS_SPI_DR_R_MASK, base[spi] + QM_SS_SPI_DR);
if (size == 1) {
*(uint8_t *)data = __builtin_arc_lr(base[spi] + QM_SS_SPI_DR);
} else {
*(uint16_t *)data = __builtin_arc_lr(base[spi] + QM_SS_SPI_DR);
}
}
/* Public Functions */
int qm_ss_spi_set_config(const qm_ss_spi_t spi,
const qm_ss_spi_config_t *const cfg)
{
QM_CHECK(spi < QM_SS_SPI_NUM, -EINVAL);
QM_CHECK(cfg, -EINVAL);
/* Configuration can be changed only when SPI is disabled */
/* NOTE: check if QM_ASSERT is the right thing to do here */
QM_ASSERT((__builtin_arc_lr(base[spi] + QM_SS_SPI_SPIEN) &
QM_SS_SPI_SPIEN_EN) == 0);
uint32_t ctrl = __builtin_arc_lr(QM_SS_SPI_0_BASE + QM_SS_SPI_CTRL);
ctrl &= QM_SS_SPI_CTRL_CLK_ENA;
ctrl |= cfg->frame_size << QM_SS_SPI_CTRL_DFS_OFFS;
ctrl |= cfg->transfer_mode << QM_SS_SPI_CTRL_TMOD_OFFS;
ctrl |= cfg->bus_mode << QM_SS_SPI_CTRL_BMOD_OFFS;
__builtin_arc_sr(ctrl, base[spi] + QM_SS_SPI_CTRL);
__builtin_arc_sr(cfg->clk_divider, base[spi] + QM_SS_SPI_TIMING);
return 0;
}
int qm_ss_spi_slave_select(const qm_ss_spi_t spi,
const qm_ss_spi_slave_select_t ss)
{
QM_CHECK(spi < QM_SS_SPI_NUM, -EINVAL);
/* Check if the device reports as busy. */
/* NOTE: check if QM_ASSERT is the right thing to do here */
QM_ASSERT(
!(__builtin_arc_lr(base[spi] + QM_SS_SPI_SR) & QM_SS_SPI_SR_BUSY));
uint32_t spien = __builtin_arc_lr(base[spi] + QM_SS_SPI_SPIEN);
spien &= ~QM_SS_SPI_SPIEN_SER_MASK;
spien |= (ss << QM_SS_SPI_SPIEN_SER_OFFS);
__builtin_arc_sr(spien, base[spi] + QM_SS_SPI_SPIEN);
return 0;
}
int qm_ss_spi_get_status(const qm_ss_spi_t spi,
qm_ss_spi_status_t *const status)
{
QM_CHECK(spi < QM_SS_SPI_NUM, -EINVAL);
QM_CHECK(status, -EINVAL);
if (__builtin_arc_lr(base[spi] + QM_SS_SPI_SR) & QM_SS_SPI_SR_BUSY) {
*status = QM_SS_SPI_BUSY;
} else {
*status = QM_SS_SPI_IDLE;
}
return 0;
}
int qm_ss_spi_transfer(const qm_ss_spi_t spi,
const qm_ss_spi_transfer_t *const xfer,
qm_ss_spi_status_t *const status)
{
QM_CHECK(spi < QM_SS_SPI_NUM, -EINVAL);
QM_CHECK(xfer, -EINVAL);
uint32_t ctrl = __builtin_arc_lr(base[spi] + QM_SS_SPI_CTRL);
uint8_t tmode = (uint8_t)((ctrl & QM_SS_SPI_CTRL_TMOD_MASK) >>
QM_SS_SPI_CTRL_TMOD_OFFS);
QM_CHECK(tmode == QM_SS_SPI_TMOD_TX_RX ? (xfer->tx_len == xfer->rx_len)
: 1,
-EINVAL);
QM_CHECK(tmode == QM_SS_SPI_TMOD_TX ? (xfer->rx_len == 0) : 1, -EINVAL);
QM_CHECK(tmode == QM_SS_SPI_TMOD_EEPROM_READ ? (xfer->rx_len > 0) : 1,
-EINVAL);
QM_CHECK(tmode == QM_SS_SPI_TMOD_RX ? (xfer->rx_len > 0) : 1, -EINVAL);
QM_CHECK(tmode == QM_SS_SPI_TMOD_RX ? (xfer->tx_len == 0) : 1, -EINVAL);
uint32_t tx_cnt = xfer->tx_len;
uint32_t rx_cnt = xfer->rx_len;
uint8_t *rx_buffer = xfer->rx;
uint8_t *tx_buffer = xfer->tx;
int ret = 0;
/* Disable all SPI interrupts */
__builtin_arc_sr(0, base[spi] + QM_SS_SPI_INTR_MASK);
/* Set NDF (Number of Data Frames) in RX or EEPROM Read mode. (-1) */
if (tmode == QM_SS_SPI_TMOD_RX || tmode == QM_SS_SPI_TMOD_EEPROM_READ) {
ctrl &= ~QM_SS_SPI_CTRL_NDF_MASK;
ctrl |= ((xfer->rx_len - 1) << QM_SS_SPI_CTRL_NDF_OFFS) &
QM_SS_SPI_CTRL_NDF_MASK;
__builtin_arc_sr(ctrl, base[spi] + QM_SS_SPI_CTRL);
}
/* RX only transfers need a dummy frame to be sent. */
if (tmode == QM_SS_SPI_TMOD_RX) {
tx_buffer = (uint8_t *)&dummy_frame;
tx_cnt = 1;
}
/* Calculate number of bytes per frame (1 or 2)*/
uint8_t bytes = BYTES_PER_FRAME(ctrl);
/* Enable SPI device */
QM_SS_REG_AUX_OR(base[spi] + QM_SS_SPI_SPIEN, QM_SS_SPI_SPIEN_EN);
while (tx_cnt || rx_cnt) {
uint32_t sr = __builtin_arc_lr(base[spi] + QM_SS_SPI_SR);
/* Break and report error if RX FIFO has overflown */
if (__builtin_arc_lr(base[spi] + QM_SS_SPI_INTR_STAT) &
QM_SS_SPI_INTR_RXOI) {
ret = -EIO;
if (status) {
*status |= QM_SS_SPI_RX_OVERFLOW;
}
break;
}
/* Copy data to buffer as long RX-FIFO is not empty */
if (sr & QM_SS_SPI_SR_RFNE && rx_cnt) {
fifo_read(spi, rx_buffer, bytes);
rx_buffer += bytes;
rx_cnt--;
}
/* Copy data from buffer as long TX-FIFO is not full. */
if (sr & QM_SS_SPI_SR_TFNF && tx_cnt) {
fifo_write(spi, tx_buffer, bytes);
tx_buffer += bytes;
tx_cnt--;
}
}
/* Wait for last byte transfered */
while (__builtin_arc_lr(base[spi] + QM_SS_SPI_SR) & QM_SS_SPI_SR_BUSY)
;
spi_disable(spi);
return ret;
}
/* Interrupt related functions. */
int qm_ss_spi_irq_transfer(const qm_ss_spi_t spi,
const qm_ss_spi_async_transfer_t *const xfer)
{
QM_CHECK(spi < QM_SS_SPI_NUM, -EINVAL);
QM_CHECK(xfer, -EINVAL);
/* Load and save initial control register */
uint32_t ctrl = __builtin_arc_lr(base[spi] + QM_SS_SPI_CTRL);
uint8_t tmode = (uint8_t)((ctrl & QM_SS_SPI_CTRL_TMOD_MASK) >>
QM_SS_SPI_CTRL_TMOD_OFFS);
QM_CHECK(tmode == QM_SS_SPI_TMOD_TX_RX ? (xfer->tx_len == xfer->rx_len)
: 1,
-EINVAL);
transfer[spi] = xfer;
tx_c[spi] = xfer->tx_len;
rx_c[spi] = xfer->rx_len;
tx_p[spi] = xfer->tx;
rx_p[spi] = xfer->rx;
/* RX only transfers need a dummy frame byte to be sent. */
if (tmode == QM_SS_SPI_TMOD_RX) {
tx_p[spi] = (uint8_t *)&dummy_frame;
tx_c[spi] = 1;
}
uint32_t ftlr =
(((FIFO_RX_W_MARK < xfer->rx_len ? FIFO_RX_W_MARK : xfer->rx_len) -
1)
<< QM_SS_SPI_FTLR_RFT_OFFS) &
QM_SS_SPI_FTLR_RFT_MASK;
__builtin_arc_sr(ftlr, base[spi] + QM_SS_SPI_FTLR);
/* Unmask all interrupts */
__builtin_arc_sr(QM_SS_SPI_INTR_ALL, base[spi] + QM_SS_SPI_INTR_MASK);
/* Enable SPI device */
QM_SS_REG_AUX_OR(base[spi] + QM_SS_SPI_SPIEN, QM_SS_SPI_SPIEN_EN);
return 0;
}
int qm_ss_spi_transfer_terminate(const qm_ss_spi_t spi)
{
QM_CHECK(spi < QM_SS_SPI_NUM, -EINVAL);
spi_disable(spi);
if (transfer[spi]->callback) {
uint32_t len = 0;
uint32_t ctrl = __builtin_arc_lr(base[spi] + QM_SS_SPI_CTRL);
uint8_t tmode = (uint8_t)((ctrl & QM_SS_SPI_CTRL_TMOD_MASK) >>
QM_SS_SPI_CTRL_TMOD_OFFS);
if (tmode == QM_SS_SPI_TMOD_TX ||
tmode == QM_SS_SPI_TMOD_TX_RX) {
len = transfer[spi]->tx_len - tx_c[spi];
} else {
len = transfer[spi]->rx_len - rx_c[spi];
}
/*
* NOTE: change this to return controller-specific code
* 'user aborted'.
*/
transfer[spi]->callback(transfer[spi]->data, -ECANCELED,
QM_SS_SPI_IDLE, (uint16_t)len);
}
return 0;
}
static void handle_spi_err_interrupt(const qm_ss_spi_t spi)
{
uint32_t intr_stat = __builtin_arc_lr(base[spi] + QM_SS_SPI_INTR_STAT);
spi_disable(spi);
QM_ASSERT((intr_stat &
(QM_SS_SPI_INTR_STAT_TXOI | QM_SS_SPI_INTR_STAT_RXFI)) == 0);
if ((intr_stat & QM_SS_SPI_INTR_RXOI) && transfer[spi]->callback) {
transfer[spi]->callback(transfer[spi]->data, -EIO,
QM_SS_SPI_RX_OVERFLOW,
transfer[spi]->rx_len - rx_c[spi]);
}
}
static void handle_spi_tx_interrupt(const qm_ss_spi_t spi)
{
/* Clear Transmit Fifo Emtpy interrupt */
__builtin_arc_sr(QM_SS_SPI_INTR_TXEI, base[spi] + QM_SS_SPI_CLR_INTR);
uint32_t ctrl = __builtin_arc_lr(base[spi] + QM_SS_SPI_CTRL);
/* Calculate number of bytes per frame (1 or 2)*/
uint8_t bytes = BYTES_PER_FRAME(ctrl);
uint8_t tmode = (uint8_t)((ctrl & QM_SS_SPI_CTRL_TMOD_MASK) >>
QM_SS_SPI_CTRL_TMOD_OFFS);
if (tx_c[spi] == 0 &&
!(__builtin_arc_lr(base[spi] + QM_SS_SPI_SR) & QM_SS_SPI_SR_BUSY)) {
if (tmode == QM_SS_SPI_TMOD_TX) {
spi_disable(spi);
if (transfer[spi]->callback) {
transfer[spi]->callback(transfer[spi]->data, 0,
QM_SS_SPI_IDLE,
transfer[spi]->tx_len);
}
} else {
QM_SS_REG_AUX_NAND(base[spi] + QM_SS_SPI_INTR_MASK,
QM_SS_SPI_INTR_TXEI);
}
return;
}
/* Make sure RX fifo does not overflow */
uint32_t rxflr = __builtin_arc_lr(base[spi] + QM_SS_SPI_RXFLR);
uint32_t txflr = __builtin_arc_lr(base[spi] + QM_SS_SPI_TXFLR);
int32_t cnt = FIFO_SIZE - rxflr - txflr - 1;
while (tx_c[spi] && cnt > 0) {
fifo_write(spi, tx_p[spi], bytes);
tx_p[spi] += bytes;
tx_c[spi]--;
cnt--;
}
}
static void handle_spi_rx_interrupt(const qm_ss_spi_t spi)
{
/* Clear RX-FIFO FULL interrupt */
__builtin_arc_sr(QM_SS_SPI_INTR_RXFI, base[spi] + QM_SS_SPI_CLR_INTR);
uint32_t ctrl = __builtin_arc_lr(base[spi] + QM_SS_SPI_CTRL);
/* Calculate number of bytes per frame (1 or 2)*/
uint8_t bytes = BYTES_PER_FRAME(ctrl);
while (__builtin_arc_lr(base[spi] + QM_SS_SPI_SR) & QM_SS_SPI_SR_RFNE &&
rx_c[spi]) {
fifo_read(spi, rx_p[spi], bytes);
rx_p[spi] += bytes;
rx_c[spi]--;
}
/* Set new FIFO threshold or complete transfer */
uint32_t new_irq_level =
(FIFO_RX_W_MARK < rx_c[spi] ? FIFO_RX_W_MARK : rx_c[spi]);
if (rx_c[spi]) {
new_irq_level--;
uint32_t ftlr = __builtin_arc_lr(base[spi] + QM_SS_SPI_FTLR);
ftlr &= ~QM_SS_SPI_FTLR_RFT_MASK;
ftlr |= (new_irq_level << QM_SS_SPI_FTLR_RFT_OFFS);
__builtin_arc_sr(ftlr, base[spi] + QM_SS_SPI_FTLR);
} else {
spi_disable(spi);
if (transfer[spi]->callback) {
transfer[spi]->callback(transfer[spi]->data, 0,
QM_SS_SPI_IDLE,
transfer[spi]->rx_len);
}
}
}
QM_ISR_DECLARE(qm_ss_spi_0_err_isr)
{
handle_spi_err_interrupt(QM_SS_SPI_0);
}
QM_ISR_DECLARE(qm_ss_spi_1_err_isr)
{
handle_spi_err_interrupt(QM_SS_SPI_1);
}
QM_ISR_DECLARE(qm_ss_spi_0_rx_isr)
{
handle_spi_rx_interrupt(QM_SS_SPI_0);
}
QM_ISR_DECLARE(qm_ss_spi_1_rx_isr)
{
handle_spi_rx_interrupt(QM_SS_SPI_1);
}
QM_ISR_DECLARE(qm_ss_spi_0_tx_isr)
{
handle_spi_tx_interrupt(QM_SS_SPI_0);
}
QM_ISR_DECLARE(qm_ss_spi_1_tx_isr)
{
handle_spi_tx_interrupt(QM_SS_SPI_1);
}

View file

@ -0,0 +1,92 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_ss_timer.h"
static void (*callback[QM_SS_TIMER_NUM])(void *data);
static void *callback_data[QM_SS_TIMER_NUM];
static uint32_t qm_ss_timer_base[QM_SS_TIMER_NUM] = {QM_SS_TIMER_0_BASE};
static __inline__ void qm_ss_timer_isr(qm_ss_timer_t timer)
{
uint32_t ctrl = 0;
if (callback[timer]) {
callback[timer](callback_data[timer]);
}
ctrl = __builtin_arc_lr(qm_ss_timer_base[timer] + QM_SS_TIMER_CONTROL);
ctrl &= ~BIT(QM_SS_TIMER_CONTROL_INT_PENDING_OFFSET);
__builtin_arc_sr(ctrl, qm_ss_timer_base[timer] + QM_SS_TIMER_CONTROL);
}
QM_ISR_DECLARE(qm_ss_timer_isr_0)
{
qm_ss_timer_isr(QM_SS_TIMER_0);
}
int qm_ss_timer_set_config(const qm_ss_timer_t timer,
const qm_ss_timer_config_t *const cfg)
{
uint32_t ctrl = 0;
QM_CHECK(cfg != NULL, -EINVAL);
QM_CHECK(timer < QM_SS_TIMER_NUM, -EINVAL);
ctrl = cfg->watchdog_mode << QM_SS_TIMER_CONTROL_WATCHDOG_OFFSET;
ctrl |= cfg->inc_run_only << QM_SS_TIMER_CONTROL_NON_HALTED_OFFSET;
ctrl |= cfg->int_en << QM_SS_TIMER_CONTROL_INT_EN_OFFSET;
__builtin_arc_sr(ctrl, qm_ss_timer_base[timer] + QM_SS_TIMER_CONTROL);
__builtin_arc_sr(cfg->count,
qm_ss_timer_base[timer] + QM_SS_TIMER_LIMIT);
callback[timer] = cfg->callback;
callback_data[timer] = cfg->callback_data;
return 0;
}
int qm_ss_timer_set(const qm_ss_timer_t timer, const uint32_t count)
{
QM_CHECK(timer < QM_SS_TIMER_NUM, -EINVAL);
__builtin_arc_sr(count, qm_ss_timer_base[timer] + QM_SS_TIMER_COUNT);
return 0;
}
int qm_ss_timer_get(const qm_ss_timer_t timer, uint32_t *const count)
{
QM_CHECK(timer < QM_SS_TIMER_NUM, -EINVAL);
QM_CHECK(count != NULL, -EINVAL);
*count = __builtin_arc_lr(qm_ss_timer_base[timer] + QM_SS_TIMER_COUNT);
return 0;
}

View file

@ -0,0 +1,118 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "qm_common.h"
#include "ss_clk.h"
int ss_clk_gpio_enable(const qm_ss_gpio_t gpio)
{
QM_CHECK(gpio < QM_SS_GPIO_NUM, -EINVAL);
int addr =
(gpio == QM_SS_GPIO_0) ? QM_SS_GPIO_0_BASE : QM_SS_GPIO_1_BASE;
__builtin_arc_sr(QM_SS_GPIO_LS_SYNC_CLK_EN |
QM_SS_GPIO_LS_SYNC_SYNC_LVL,
addr + QM_SS_GPIO_LS_SYNC);
return 0;
}
int ss_clk_gpio_disable(const qm_ss_gpio_t gpio)
{
QM_CHECK(gpio < QM_SS_GPIO_NUM, -EINVAL);
int addr =
(gpio == QM_SS_GPIO_0) ? QM_SS_GPIO_0_BASE : QM_SS_GPIO_1_BASE;
__builtin_arc_sr(0, addr + QM_SS_GPIO_LS_SYNC);
return 0;
}
int ss_clk_spi_enable(const qm_ss_spi_t spi)
{
QM_CHECK(spi < QM_SS_SPI_NUM, -EINVAL);
int addr = (spi == QM_SS_SPI_0) ? QM_SS_SPI_0_BASE : QM_SS_SPI_1_BASE;
QM_SS_REG_AUX_OR(addr + QM_SS_SPI_CTRL, QM_SS_SPI_CTRL_CLK_ENA);
return 0;
}
int ss_clk_spi_disable(const qm_ss_spi_t spi)
{
QM_CHECK(spi < QM_SS_SPI_NUM, -EINVAL);
int addr = (spi == QM_SS_SPI_0) ? QM_SS_SPI_0_BASE : QM_SS_SPI_1_BASE;
QM_SS_REG_AUX_NAND(addr + QM_SS_SPI_CTRL, QM_SS_SPI_CTRL_CLK_ENA);
return 0;
}
int ss_clk_i2c_enable(const qm_ss_i2c_t i2c)
{
QM_CHECK(i2c < QM_SS_I2C_NUM, -EINVAL);
int addr = (i2c == QM_SS_I2C_0) ? QM_SS_I2C_0_BASE : QM_SS_I2C_1_BASE;
QM_SS_REG_AUX_OR(addr + QM_SS_I2C_CON, QM_SS_I2C_CON_CLK_ENA);
return 0;
}
int ss_clk_i2c_disable(const qm_ss_i2c_t i2c)
{
QM_CHECK(i2c < QM_SS_I2C_NUM, -EINVAL);
int addr = (i2c == QM_SS_I2C_0) ? QM_SS_I2C_0_BASE : QM_SS_I2C_1_BASE;
QM_SS_REG_AUX_NAND(addr + QM_SS_I2C_CON, QM_SS_I2C_CON_CLK_ENA);
return 0;
}
int ss_clk_adc_enable(void)
{
/* Enable the ADC clock */
QM_SS_REG_AUX_OR(QM_SS_ADC_BASE + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_CLK_ENA);
return 0;
}
int ss_clk_adc_disable(void)
{
/* Disable the ADC clock */
QM_SS_REG_AUX_NAND(QM_SS_ADC_BASE + QM_SS_ADC_CTRL,
QM_SS_ADC_CTRL_CLK_ENA);
return 0;
}
int ss_clk_adc_set_div(const uint32_t div)
{
uint32_t reg;
/*
* Scale the max divisor with the system clock speed. Clock speeds less
* than 1 MHz will not work properly.
*/
QM_CHECK(div <= QM_SS_ADC_DIV_MAX * clk_sys_get_ticks_per_us(),
-EINVAL);
/* Set the ADC divisor */
reg = __builtin_arc_lr(QM_SS_ADC_BASE + QM_SS_ADC_DIVSEQSTAT);
reg &= ~(QM_SS_ADC_DIVSEQSTAT_CLK_RATIO_MASK);
__builtin_arc_sr(reg | div, QM_SS_ADC_BASE + QM_SS_ADC_DIVSEQSTAT);
return 0;
}

View file

@ -0,0 +1,88 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "ss_power_states.h"
/* Sensor Subsystem sleep operand definition.
* Only a subset applies as internal sensor RTC
* is not available.
*
* OP | Core | Timers | RTC
* 000 | 0 | 1 | 1 <-- used for SS1
* 001 | 0 | 0 | 1
* 010 | 0 | 1 | 0
* 011 | 0 | 0 | 0 <-- used for SS2
* 100 | 0 | 0 | 0
* 101 | 0 | 0 | 0
* 110 | 0 | 0 | 0
* 111 | 0 | 0 | 0
*
* sleep opcode argument:
* - [7:5] : Sleep Operand
* - [4] : Interrupt enable
* - [3:0] : Interrupt threshold value
*/
#define QM_SS_SLEEP_MODE_CORE_OFF (0x0)
#define QM_SS_SLEEP_MODE_CORE_OFF_TIMER_OFF (0x20)
#define QM_SS_SLEEP_MODE_CORE_TIMERS_RTC_OFF (0x60)
/* Enter SS1 :
* SLEEP + sleep operand
* __builtin_arc_sleep is not used here as it does not propagate sleep operand.
*/
void ss_power_cpu_ss1(const ss_power_cpu_ss1_mode_t mode)
{
/* Enter SS1 */
switch (mode) {
case SS_POWER_CPU_SS1_TIMER_OFF:
__asm__ __volatile__(
"sleep %0"
:
: "i"(QM_SS_SLEEP_MODE_CORE_OFF_TIMER_OFF));
break;
case SS_POWER_CPU_SS1_TIMER_ON:
default:
__asm__ __volatile__("sleep %0"
:
: "i"(QM_SS_SLEEP_MODE_CORE_OFF));
break;
}
}
/* Enter SS2 :
* SLEEP + sleep operand
* __builtin_arc_sleep is not used here as it does not propagate sleep operand.
*/
void ss_power_cpu_ss2(void)
{
/* Enter SS2 */
__asm__ __volatile__("sleep %0"
:
: "i"(QM_SS_SLEEP_MODE_CORE_TIMERS_RTC_OFF));
}

View file

@ -0,0 +1,269 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __QM_COMMON_H__
#define __QM_COMMON_H__
#if (UNIT_TEST)
#define __volatile__(x)
#define __asm__
#endif /* UNIT_TEST */
#include <stdint.h>
#include <stdbool.h>
#include <errno.h>
#define QM_R volatile const
#define QM_W volatile
#define QM_RW volatile
/* __attribute__((interrupt)) API requires that the interrupt handlers
* take an interrupt_frame parameter, but it is still undefined, so add
* an empty definition.
*/
struct interrupt_frame;
#ifndef NULL
#define NULL ((void *)0)
#endif
#define REG_VAL(addr) (*((volatile uint32_t *)addr))
/**
* In our reference implementation, by default DEBUG enables QM_PUTS and
* QM_ASSERT but not QM_PRINTF.
* User can modify this block to customise the default DEBUG configuration.
*/
#if (DEBUG)
#ifndef ASSERT_ENABLE
#define ASSERT_ENABLE (1)
#endif
#ifndef PUTS_ENABLE
#define PUTS_ENABLE (1)
#endif
#endif /* DEBUG */
/**
* Decide how to handle user input validation. Possible options upon discovering
* an invalid input parameter are:
* - Return an error code.
* - Assert.
* - Assert and save the error into the General Purpose Sticky Register 0.
* - Do nothing, only recommended when code size is a major concern.
*/
#if (DEBUG)
#ifndef QM_CHECK_RETURN_ERROR
#define QM_CHECK_RETURN_ERROR (1)
#endif
#ifndef QM_CHECK_ASSERT
#define QM_CHECK_ASSERT (0)
#endif
#ifndef QM_CHECK_ASSERT_SAVE_ERROR
#define QM_CHECK_ASSERT_SAVE_ERROR (0)
#endif
#endif /* DEBUG */
/*
* Setup UART for stdout/stderr.
*/
void stdout_uart_setup(uint32_t baud_divisors);
/*
* Default UART baudrate divisors at the sysclk speed set by Boot ROM
*/
#define BOOTROM_UART_115200 (QM_UART_CFG_BAUD_DL_PACK(0, 17, 6))
/**
* Selectively enable printf/puts/assert.
* User can modify the defines to divert the calls to custom implementations.
*/
#if (PRINTF_ENABLE || PUTS_ENABLE || ASSERT_ENABLE)
#include <stdio.h>
#endif /* PRINTF_ENABLE || PUTS_ENABLE || ASSERT_ENABLE */
#if (PRINTF_ENABLE)
#define QM_PRINTF(...) printf(__VA_ARGS__)
#else
#define QM_PRINTF(...)
#endif /* PRINTF_ENABLE */
#if (PUTS_ENABLE)
#define QM_PUTS(x) puts(x)
#else
#define QM_PUTS(x)
#endif /* PUTS_ENABLE */
#if (ASSERT_ENABLE)
#include <assert.h>
#define QM_ASSERT(x) assert(x)
#else
#define QM_ASSERT(x)
#endif /* ASSERT_ENABLE */
/**
* Select which UART to use for stdout/err (default: UART0)
*/
#if (STDOUT_UART_0 && STDOUT_UART_1)
#error "STDOUT_UART_0 and STDOUT_UART_1 are mutually exclusive"
#elif(!(STDOUT_UART_0 || STDOUT_UART_1))
#define STDOUT_UART_0 (1)
#endif
#if (STDOUT_UART_0)
#define STDOUT_UART (QM_UART_0)
#elif(STDOUT_UART_1)
#define STDOUT_UART (QM_UART_1)
#endif
/*
* Stdout UART intialization is enabled by default. Use this switch if you wish
* to disable it (e.g. if the UART is already initialized by an application
* running on the other core).
*/
#ifndef STDOUT_UART_INIT_DISABLE
#define STDOUT_UART_INIT (1)
#endif
/**
* Select assert action (default: put the IA core into HLT state)
*/
#if (ASSERT_ACTION_HALT && ASSERT_ACTION_RESET)
#error "ASSERT_ACTION_HALT and ASSERT_ACTION_RESET are mutually exclusive"
#elif(!(ASSERT_ACTION_HALT || ASSERT_ACTION_RESET))
#define ASSERT_ACTION_HALT (1)
#endif
/**
* Select check action
*/
#if (1 < QM_CHECK_RETURN_ERROR + QM_CHECK_ASSERT + QM_CHECK_ASSERT_SAVE_ERROR)
#error "Only a single check action may be performed"
#endif
#if (QM_CHECK_RETURN_ERROR)
#define QM_CHECK(cond, error) \
do { \
if (!(cond)) { \
return (error); \
} \
} while (0)
#elif(QM_CHECK_ASSERT)
#define QM_CHECK(cond, error) QM_ASSERT(cond)
#elif(QM_CHECK_ASSERT_SAVE_ERROR)
#define SAVE_LAST_ERROR(x) \
do { \
QM_SCSS_GP->gps[0] = x; \
} while (0)
#define QM_CHECK(cond, error) \
do { \
SAVE_LAST_ERROR(error); \
QM_ASSERT(cond); \
} while (0)
#else
/* Do nothing with checks */
#define QM_CHECK(cond, error)
#endif
/* Bitwise operation helpers */
#ifndef BIT
#define BIT(x) (1U << (x))
#endif
/* Set all bits */
#ifndef SET_ALL_BITS
#define SET_ALL_BITS (-1)
#endif
/*
* ISR declaration.
*
* The x86 'interrupt' attribute requires an interrupt_frame parameter.
* To keep consistency between different cores and compiler capabilities, we add
* the interrupt_frame parameter to all ISR handlers. When not needed, the value
* passed is a dummy one (NULL).
*/
#if (UNIT_TEST)
#define QM_ISR_DECLARE(handler) \
void handler(__attribute__( \
(unused)) struct interrupt_frame *__interrupt_frame__)
#else /* !UNIT_TEST */
#if (QM_SENSOR) && !(ISR_HANDLED)
/*
* Sensor Subsystem 'interrupt' attribute.
*/
#define QM_ISR_DECLARE(handler) \
__attribute__((interrupt("ilink"))) void handler(__attribute__( \
(unused)) struct interrupt_frame *__interrupt_frame__)
#elif(ISR_HANDLED)
/*
* Allow users to define their own ISR management. This includes optimisations
* and clearing EOI registers.
*/
#define QM_ISR_DECLARE(handler) void handler(__attribute__((unused)) void *data)
#elif(__iamcu__)
/*
* Lakemont with compiler supporting 'interrupt' attribute.
* We assume that if the compiler supports the IAMCU ABI it also supports the
* 'interrupt' attribute.
*/
#define QM_ISR_DECLARE(handler) \
__attribute__((interrupt)) void handler(__attribute__( \
(unused)) struct interrupt_frame *__interrupt_frame__)
#else
/*
* Lakemont with compiler not supporting the 'interrupt' attribute.
*/
#define QM_ISR_DECLARE(handler) \
void handler(__attribute__( \
(unused)) struct interrupt_frame *__interrupt_frame__)
#endif
#endif /* UNIT_TEST */
/**
* Helper to convert a macro parameter into its literal text.
*/
#define QM_STRINGIFY(s) #s
/**
* Convert the source version numbers into an ASCII string.
*/
#define QM_VER_STRINGIFY(major, minor, patch) \
QM_STRINGIFY(major) "." QM_STRINGIFY(minor) "." QM_STRINGIFY(patch)
#endif /* __QM_COMMON_H__ */

View file

@ -0,0 +1,60 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __SPINLOCK_H__
#define __SPINLOCK_H__
#include "qm_soc_regs.h"
/*
* Single, shared spinlock which can be used for synchronization between the
* Lakemont and ARC cores.
* The Spinlock lock size and position in RAM must be same on both cores.
*/
#if (QUARK_SE)
typedef struct {
volatile char flag[2];
volatile char turn;
} spinlock_t;
extern spinlock_t __esram_lock_start;
void spinlock_lock(spinlock_t *lock);
void spinlock_unlock(spinlock_t *lock);
#define QM_SPINLOCK_LOCK() spinlock_lock(&__esram_lock_start)
#define QM_SPINLOCK_UNLOCK() spinlock_unlock(&__esram_lock_start)
#else
#define QM_SPINLOCK_LOCK()
#define QM_SPINLOCK_UNLOCK()
#endif /* defined(QM_QUARK_SE) */
#endif /* __SPINLOCK_H__ */

View file

@ -0,0 +1,321 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "power_states.h"
#include "clk.h"
#include "qm_comparator.h"
#include "qm_adc.h"
#include "rar.h"
void cpu_halt(void)
{
__asm__ __volatile__("hlt");
}
static void clear_all_pending_interrupts(void)
{
/* Clear comparator interrupts. */
QM_SCSS_CMP->cmp_stat_clr = -1;
/* Clear RTC interrupts. */
QM_RTC->rtc_eoi;
/* Clear timers interrupt flag. */
QM_PWM->timerseoi;
/* Clear GPIO interrupts. */
QM_GPIO[QM_GPIO_0]->gpio_porta_eoi = -1;
}
void soc_sleep(void)
{
/* Variables to save register values. */
uint32_t ac_power_save;
uint32_t clk_gate_save = QM_SCSS_CCU->ccu_periph_clk_gate_ctl;
uint32_t sys_clk_ctl_save = QM_SCSS_CCU->ccu_sys_clk_ctl;
uint32_t osc0_cfg_save = QM_SCSS_CCU->osc0_cfg1;
uint32_t adc_mode_save = QM_ADC->adc_op_mode;
/* Clear any pending interrupts. */
clear_all_pending_interrupts();
qm_adc_set_mode(QM_ADC_0, QM_ADC_MODE_PWR_DOWN);
/* Turn off high power comparators. */
ac_power_save = QM_SCSS_CMP->cmp_pwr;
QM_SCSS_CMP->cmp_pwr &= QM_AC_HP_COMPARATORS_MASK;
/*
* Program WAKE_MASK.WAKE_MASK[31:0],
* CCU_LP_CLK_CTL.WAKE_PROBE_MODE_MASK registers identical to Interrupt
* Mask registers.
*/
QM_SCSS_CCU->ccu_lp_clk_ctl &= ~QM_WAKE_PROBE_MODE_MASK;
/*
* Ensure that powering down of oscillators is delayed by hardware until
* core executes HALT instruction.
*/
/* HYB_OSC_PD_LATCH_EN = 0, RTC_OSC_PD_LATCH_EN=0 */
QM_SCSS_CCU->ccu_lp_clk_ctl &=
~(QM_HYB_OSC_PD_LATCH_EN | QM_RTC_OSC_PD_LATCH_EN);
/* Ensure that at exit, hardware will switch system clock to Hybrid
* oscillator clock so as to minimize exit latency by running at higher
* frequency than RTC clock.
*/
/* CCU_LP_CLK_CTL.CCU_EXIT_TO_HYBOSC */
QM_SCSS_CCU->ccu_lp_clk_ctl |= QM_CCU_EXIT_TO_HYBOSC;
/* Power down hybrid oscillator after HALT instruction is executed. */
QM_SCSS_CCU->osc0_cfg1 |= QM_OSC0_PD;
/*
* Only the following peripherals can be used as a wakeup source:
* - GPIO Interrupts
* - AON timers
* - RTC
* - low power comparators
*/
clk_periph_disable(
CLK_PERIPH_I2C_M0 | CLK_PERIPH_SPI_S | CLK_PERIPH_SPI_M0 |
CLK_PERIPH_GPIO_DB | CLK_PERIPH_WDT_REGISTER |
CLK_PERIPH_PWM_REGISTER | CLK_PERIPH_GPIO_REGISTER |
CLK_PERIPH_SPI_M0_REGISTER | CLK_PERIPH_SPI_S_REGISTER |
CLK_PERIPH_UARTA_REGISTER | CLK_PERIPH_UARTB_REGISTER |
CLK_PERIPH_I2C_M0_REGISTER);
/* Set system clock source to hyb osc, 4 MHz, scaled to 512 kHz. */
clk_sys_set_mode(CLK_SYS_HYB_OSC_4MHZ, CLK_SYS_DIV_8);
/* Set the RAR to retention mode. */
rar_set_mode(RAR_RETENTION);
/*
* If wake source is any of AON Timer, RTC, GPIO interrupt, program
* CCU_SYS_CLK_CTL.CCU_SYS_CLK_SEL to RTC Oscillator.
*/
/* Enter SoC sleep mode. */
cpu_halt();
/* From here on, restore the SoC to an active state. */
/* Set the RAR to normal mode. */
rar_set_mode(RAR_NORMAL);
/* Restore all previous values. */
QM_SCSS_CCU->ccu_sys_clk_ctl = sys_clk_ctl_save;
/* Re-apply clock divider values. DIV_EN must go 0 -> 1. */
QM_SCSS_CCU->ccu_sys_clk_ctl &=
~(QM_CCU_SYS_CLK_DIV_EN | QM_CCU_RTC_CLK_DIV_EN);
QM_SCSS_CCU->ccu_sys_clk_ctl |=
QM_CCU_SYS_CLK_DIV_EN | QM_CCU_RTC_CLK_DIV_EN;
/* Wait for the XTAL or SI oscillator to stabilise. */
while (!(QM_SCSS_CCU->osc0_stat1 &
(QM_OSC0_LOCK_SI | QM_OSC0_LOCK_XTAL))) {
};
/* Restore original clocking, ADC, analog comparator states. */
QM_SCSS_CCU->osc0_cfg1 = osc0_cfg_save;
QM_SCSS_CCU->ccu_periph_clk_gate_ctl = clk_gate_save;
QM_SCSS_CMP->cmp_pwr = ac_power_save;
QM_ADC->adc_op_mode = adc_mode_save;
}
void soc_deep_sleep(void)
{
/* Variables to save register values. */
uint32_t ac_power_save;
uint32_t clk_gate_save = QM_SCSS_CCU->ccu_periph_clk_gate_ctl;
uint32_t sys_clk_ctl_save = QM_SCSS_CCU->ccu_sys_clk_ctl;
uint32_t osc0_cfg_save = QM_SCSS_CCU->osc0_cfg1;
uint32_t osc1_cfg_save = QM_SCSS_CCU->osc1_cfg0;
uint32_t adc_mode_save = QM_ADC->adc_op_mode;
uint32_t aon_vr_save = QM_SCSS_PMU->aon_vr;
uint32_t ext_clock_save;
uint32_t lp_clk_save, pmux_slew_save;
pmux_slew_save = QM_SCSS_PMUX->pmux_slew[0];
ext_clock_save = QM_SCSS_CCU->ccu_ext_clock_ctl;
lp_clk_save = QM_SCSS_CCU->ccu_lp_clk_ctl;
/* Clear any pending interrupts. */
clear_all_pending_interrupts();
/* Only clear the comparator wake mask bit. */
QM_SCSS_CCU->wake_mask =
SET_ALL_BITS & ~QM_CCU_WAKE_MASK_COMPARATOR_BIT;
QM_SCSS_GP->gps1 |= QM_SCSS_GP_POWER_STATE_DEEP_SLEEP;
qm_adc_set_mode(QM_ADC_0, QM_ADC_MODE_DEEP_PWR_DOWN);
/* Turn off high power comparators. */
ac_power_save = QM_SCSS_CMP->cmp_pwr;
QM_SCSS_CMP->cmp_pwr &= QM_AC_HP_COMPARATORS_MASK;
/* Disable all peripheral clocks. */
clk_periph_disable(CLK_PERIPH_REGISTER);
/* Disable external clocks. */
QM_SCSS_CCU->ccu_ext_clock_ctl = 0;
/* Set slew rate of all pins to 12mA. */
QM_SCSS_PMUX->pmux_slew[0] = 0;
/* Disable RTC. */
QM_SCSS_CCU->osc1_cfg0 &= ~QM_OSC1_PD;
/* Set system clock source to hyb osc, 4 MHz, scaled down to 32 kHz. */
clk_sys_set_mode(CLK_SYS_HYB_OSC_4MHZ, CLK_SYS_DIV_128);
/* Power down the oscillator after the halt instruction is executed. */
QM_SCSS_CCU->ccu_lp_clk_ctl &= ~QM_HYB_OSC_PD_LATCH_EN;
/*
* Enable memory halt and CPU halt. When exiting sleep mode, use hybrid
* oscillator.
*/
QM_SCSS_CCU->ccu_lp_clk_ctl |=
QM_CCU_EXIT_TO_HYBOSC | QM_CCU_MEM_HALT_EN | QM_CCU_CPU_HALT_EN;
/* Power down hybrid oscillator. */
QM_SCSS_CCU->osc0_cfg1 |= QM_OSC0_PD;
/* Disable gpio debounce clocking. */
QM_SCSS_CCU->ccu_gpio_db_clk_ctl &= ~QM_CCU_GPIO_DB_CLK_EN;
/* Set retention voltage to 1.35V. */
/* SCSS.OSC0_CFG0.OSC0_HYB_SET_REG1.OSC0_CFG0[0] = 1; */
QM_SCSS_CCU->osc0_cfg0 |= QM_SI_OSC_1V2_MODE;
/* Enable low voltage mode for flash controller. */
/* FlashCtrl.CTRL.LVE_MODE = 1; */
QM_FLASH[QM_FLASH_0]->ctrl |= QM_FLASH_LVE_MODE;
/* Select 1.35V for voltage regulator. */
/* SCSS.AON_VR.VSEL = 0xB; */
QM_SCSS_PMU->aon_vr =
(QM_AON_VR_PASS_CODE | (aon_vr_save & QM_AON_VR_VSEL_MASK) |
QM_AON_VR_VSEL_1V35);
/* SCSS.AON_VR.ROK_BUF_VREG_MASK = 1; */
QM_SCSS_PMU->aon_vr = (QM_AON_VR_PASS_CODE | QM_SCSS_PMU->aon_vr |
QM_AON_VR_ROK_BUF_VREG_MASK);
/* SCSS.AON_VR.VSEL_STROBE = 1; */
QM_SCSS_PMU->aon_vr =
(QM_AON_VR_PASS_CODE | QM_SCSS_PMU->aon_vr | QM_AON_VR_VSTRB);
/* Wait >= 1 usec, at 256 kHz this is 1 cycle. */
__asm__("nop");
/* SCSS.AON_VR.VSEL_STROBE = 0; */
QM_SCSS_PMU->aon_vr =
(QM_AON_VR_PASS_CODE | (QM_SCSS_PMU->aon_vr & ~QM_AON_VR_VSTRB));
/* Wait >= 2 usec, at 256 kHz this is 1 cycle. */
__asm__("nop");
/* Set the RAR to retention mode. */
rar_set_mode(RAR_RETENTION);
/* Enter SoC deep sleep mode. */
cpu_halt();
/* We are now exiting from deep sleep mode. */
/* Set the RAR to normal mode. */
rar_set_mode(RAR_NORMAL);
/* Restore operating voltage to 1.8V. */
/* SCSS.AON_VR.VSEL = 0x10; */
QM_SCSS_PMU->aon_vr =
(QM_AON_VR_PASS_CODE | (QM_SCSS_PMU->aon_vr & QM_AON_VR_VSEL_MASK) |
QM_AON_VR_VSEL_1V8 | QM_AON_VR_ROK_BUF_VREG_MASK);
/* SCSS.AON_VR.VSEL_STROBE = 1; */
QM_SCSS_PMU->aon_vr =
(QM_AON_VR_PASS_CODE | QM_SCSS_PMU->aon_vr | QM_AON_VR_VSTRB);
/* Wait >= 1 usec, at 256 kHz this is 1 cycle. */
__asm__("nop");
/* SCSS.AON_VR.VSEL_STROBE = 0; */
QM_SCSS_PMU->aon_vr =
(QM_AON_VR_PASS_CODE | (QM_SCSS_PMU->aon_vr & ~QM_AON_VR_VSTRB));
/* Wait >= 2 usec, at 256 kHz this is 1 cycle. */
__asm__("nop");
/* SCSS.AON_VR.ROK_BUF_VREG_MASK = 0; */
QM_SCSS_PMU->aon_vr =
(QM_AON_VR_PASS_CODE |
(QM_SCSS_PMU->aon_vr & ~QM_AON_VR_ROK_BUF_VREG_MASK));
/* Wait >= 1 usec, at 256 kHz this is 1 cycle. */
__asm__("nop");
/* SCSS.OSC0_CFG0.OSC0_HYB_SET_REG1.OSC0_CFG0[0] = 0; */
QM_SCSS_CCU->osc0_cfg0 &= ~QM_SI_OSC_1V2_MODE;
/* FlashCtrl.CTRL.LVE_MODE = 0; */
QM_FLASH[QM_FLASH_0]->ctrl &= ~QM_FLASH_LVE_MODE;
/* Restore all previous values. */
QM_SCSS_CCU->ccu_sys_clk_ctl = sys_clk_ctl_save;
/* Re-apply clock divider values. DIV_EN must go 0 -> 1. */
QM_SCSS_CCU->ccu_sys_clk_ctl &=
~(QM_CCU_SYS_CLK_DIV_EN | QM_CCU_RTC_CLK_DIV_EN);
QM_SCSS_CCU->ccu_sys_clk_ctl |=
QM_CCU_SYS_CLK_DIV_EN | QM_CCU_RTC_CLK_DIV_EN;
/* Wait for the XTAL or SI oscillator to stabilise. */
while (!(QM_SCSS_CCU->osc0_stat1 &
(QM_OSC0_LOCK_SI | QM_OSC0_LOCK_XTAL))) {
};
/* Re-enable clocks. */
clk_periph_enable(CLK_PERIPH_REGISTER);
/* Re-enable gpio debounce clocking. */
QM_SCSS_CCU->ccu_gpio_db_clk_ctl |= QM_CCU_GPIO_DB_CLK_EN;
/* Restore original clocking, ADC, analog comparator states. */
QM_SCSS_CCU->osc0_cfg1 = osc0_cfg_save;
QM_SCSS_CCU->ccu_periph_clk_gate_ctl = clk_gate_save;
QM_SCSS_CCU->osc1_cfg0 = osc1_cfg_save;
QM_SCSS_CMP->cmp_pwr = ac_power_save;
QM_ADC->adc_op_mode = adc_mode_save;
QM_SCSS_PMUX->pmux_slew[0] = pmux_slew_save;
QM_SCSS_CCU->ccu_ext_clock_ctl = ext_clock_save;
QM_SCSS_CCU->ccu_lp_clk_ctl = lp_clk_save;
QM_SCSS_CCU->wake_mask = SET_ALL_BITS;
QM_SCSS_GP->gps1 &= ~QM_SCSS_GP_POWER_STATE_DEEP_SLEEP;
}

View file

@ -0,0 +1,91 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __FLASH_LAYOUT_H__
#define __FLASH_LAYOUT_H__
/**
* Flash Layout for Quark D2000 Microcontrollers.
*
* @defgroup groupD2000Flash Quark D2000 Flash Layout
* @{
*/
typedef struct {
QM_RW uint16_t osc_trim_16mhz; /**< 16MHz Oscillator trim code. */
QM_RW uint16_t osc_trim_32mhz; /**< 32MHz Oscillator trim code. */
QM_RW uint16_t osc_trim_4mhz; /**< 4MHz Oscillator trim code. */
QM_RW uint16_t osc_trim_8mhz; /**< 8MHz Oscillator trim code. */
} qm_flash_otp_trim_t;
#if (UNIT_TEST)
extern uint8_t test_flash_page[0x800];
#define QM_FLASH_OTP_TRIM_CODE_BASE (&test_flash_page[0])
#else
#define QM_FLASH_OTP_TRIM_CODE_BASE (0x4)
#endif
#define QM_FLASH_OTP_TRIM_CODE \
((qm_flash_otp_trim_t *)QM_FLASH_OTP_TRIM_CODE_BASE)
#define QM_FLASH_OTP_SOC_DATA_VALID (0x24535021) /**< $SP! */
#define QM_FLASH_OTP_TRIM_MAGIC (QM_FLASH_OTP_SOC_DATA_VALID)
typedef union {
struct trim_fields {
QM_RW uint16_t
osc_trim_32mhz; /**< 32MHz Oscillator trim code. */
QM_RW uint16_t
osc_trim_16mhz; /**< 16MHz Oscillator trim code. */
QM_RW uint16_t osc_trim_8mhz; /**< 8MHz Oscillator trim code. */
QM_RW uint16_t osc_trim_4mhz; /**< 4MHz Oscillator trim code. */
} fields;
QM_RW uint32_t osc_trim_u32[2]; /**< Oscillator trim code array.*/
QM_RW uint16_t osc_trim_u16[4]; /**< Oscillator trim code array.*/
} qm_flash_data_trim_t;
#if (UNIT_TEST)
#define QM_FLASH_DATA_TRIM_BASE (&test_flash_page[100])
#define QM_FLASH_DATA_TRIM_OFFSET (100)
#else
#define QM_FLASH_DATA_TRIM_BASE (QM_FLASH_REGION_DATA_0_BASE)
#define QM_FLASH_DATA_TRIM_OFFSET ((uint32_t)QM_FLASH_DATA_TRIM_BASE & 0x3FFFF)
#endif
#define QM_FLASH_DATA_TRIM ((qm_flash_data_trim_t *)QM_FLASH_DATA_TRIM_BASE)
#define QM_FLASH_DATA_TRIM_CODE (&QM_FLASH_DATA_TRIM->fields)
#define QM_FLASH_DATA_TRIM_REGION QM_FLASH_REGION_DATA
#define QM_FLASH_TRIM_PRESENT_MASK (0xFC00)
#define QM_FLASH_TRIM_PRESENT (0x7C00)
/**
* @}
*/
#endif /* __FLASH_LAYOUT_H__ */

View file

@ -0,0 +1,85 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __POWER_STATES_H__
#define __POWER_STATES_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* Power mode control for Quark D2000 Microcontrollers.
*
* @defgroup groupD2000Power Quark D2000 Power states
* @{
*/
/**
* Put CPU in halt state.
*
* Halts the CPU until next interrupt or reset.
*/
void cpu_halt(void);
/**
* Put SoC to sleep.
*
* Enter into sleep mode. The hybrid oscillator is disabled, most peripherals
* are disabled and the voltage regulator is set into retention mode.
* The following peripherals are disabled in this mode:
* - I2C
* - SPI
* - GPIO debouncing
* - Watchdog timer
* - PWM / Timers
* - UART
*
* The SoC operates from the 32 kHz clock source and the following peripherals
* may bring the SoC back into an active state:
*
* - GPIO interrupts
* - AON Timers
* - RTC
* - Low power comparators
*/
void soc_sleep();
/**
* Put SoC to deep sleep.
*
* Enter into deep sleep mode. All clocks are gated. The only way to return
* from this is to have an interrupt trigger on the low power comparators.
*/
void soc_deep_sleep();
/**
* @}
*/
#endif /* __POWER_STATES_H__ */

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,84 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "power_states.h"
#include "vreg.h"
#if (QM_SENSOR)
#include "qm_sensor_regs.h"
#endif
void power_soc_lpss_enable()
{
QM_SCSS_CCU->ccu_lp_clk_ctl |= QM_SCSS_CCU_SS_LPS_EN;
}
void power_soc_lpss_disable()
{
QM_SCSS_CCU->ccu_lp_clk_ctl &= ~QM_SCSS_CCU_SS_LPS_EN;
}
void power_soc_sleep()
{
/* Go to sleep */
QM_SCSS_PMU->slp_cfg &= ~QM_SCSS_SLP_CFG_LPMODE_EN;
QM_SCSS_PMU->pm1c |= QM_SCSS_PM1C_SLPEN;
}
void power_soc_deep_sleep()
{
/* Switch to linear regulators */
vreg_plat1p8_set_mode(VREG_MODE_LINEAR);
vreg_plat3p3_set_mode(VREG_MODE_LINEAR);
/* Enable low power sleep mode */
QM_SCSS_PMU->slp_cfg |= QM_SCSS_SLP_CFG_LPMODE_EN;
QM_SCSS_PMU->pm1c |= QM_SCSS_PM1C_SLPEN;
}
#if (!QM_SENSOR)
void power_cpu_c1()
{
__asm__ __volatile__("hlt");
}
void power_cpu_c2()
{
QM_SCSS_CCU->ccu_lp_clk_ctl &= ~QM_SCSS_CCU_C2_LP_EN;
/* Read P_LVL2 to trigger a C2 request */
QM_SCSS_PMU->p_lvl2;
}
void power_cpu_c2lp()
{
QM_SCSS_CCU->ccu_lp_clk_ctl |= QM_SCSS_CCU_C2_LP_EN;
/* Read P_LVL2 to trigger a C2 request */
QM_SCSS_PMU->p_lvl2;
}
#endif

View file

@ -0,0 +1,94 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 "vreg.h"
typedef enum { AON_VR = 0, PLAT3P3_VR, PLAT1P8_VR, HOST_VR, VREG_NUM } vreg_t;
QM_RW uint32_t *vreg[VREG_NUM] = {
&QM_SCSS_PMU->aon_vr, &QM_SCSS_PMU->plat3p3_vr, &QM_SCSS_PMU->plat1p8_vr,
&QM_SCSS_PMU->host_vr};
static int vreg_set_mode(const vreg_t id, const vreg_mode_t mode)
{
QM_CHECK(mode < VREG_MODE_NUM, -EINVAL);
uint32_t vr;
vr = *vreg[id];
switch (mode) {
case VREG_MODE_SWITCHING:
vr |= QM_SCSS_VR_EN;
vr &= ~QM_SCSS_VR_VREG_SEL;
break;
case VREG_MODE_LINEAR:
vr |= QM_SCSS_VR_EN;
vr |= QM_SCSS_VR_VREG_SEL;
break;
case VREG_MODE_SHUTDOWN:
vr &= ~QM_SCSS_VR_EN;
break;
default:
break;
}
*vreg[id] = vr;
while ((mode == VREG_MODE_SWITCHING) &&
(*vreg[id] & QM_SCSS_VR_ROK) == 0) {
}
return 0;
}
int vreg_aon_set_mode(const vreg_mode_t mode)
{
QM_CHECK(mode < VREG_MODE_NUM, -EINVAL);
QM_CHECK(mode != VREG_MODE_SWITCHING, -EINVAL);
return vreg_set_mode(AON_VR, mode);
}
int vreg_plat3p3_set_mode(const vreg_mode_t mode)
{
QM_CHECK(mode < VREG_MODE_NUM, -EINVAL);
return vreg_set_mode(PLAT3P3_VR, mode);
}
int vreg_plat1p8_set_mode(const vreg_mode_t mode)
{
QM_CHECK(mode < VREG_MODE_NUM, -EINVAL);
return vreg_set_mode(PLAT1P8_VR, mode);
}
int vreg_host_set_mode(const vreg_mode_t mode)
{
QM_CHECK(mode < VREG_MODE_NUM, -EINVAL);
return vreg_set_mode(HOST_VR, mode);
}

View file

@ -0,0 +1,94 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __FLASH_LAYOUT_H__
#define __FLASH_LAYOUT_H__
/**
* Flash Layout for Quark SE Microcontrollers.
*
* @defgroup groupSEFlash Quark SE Flash Layout
* @{
*/
typedef struct {
QM_RW uint32_t magic; /**< Magic Number. */
QM_RW uint16_t version; /**< 0x0100. */
QM_RW uint16_t reserved; /**< Reserved. */
QM_RW uint16_t osc_trim_32mhz; /**< 32MHz Oscillator trim code. */
QM_RW uint16_t osc_trim_16mhz; /**< 16MHz Oscillator trim code. */
QM_RW uint16_t osc_trim_8mhz; /**< 8MHz Oscillator trim code. */
QM_RW uint16_t osc_trim_4mhz; /**< 4MHz Oscillator trim code. */
} qm_flash_otp_trim_t;
#if (UNIT_TEST)
extern uint8_t test_flash_page[0x800];
#define QM_FLASH_OTP_TRIM_CODE_BASE (&test_flash_page[0])
#else
#define QM_FLASH_OTP_TRIM_CODE_BASE (0xFFFFE1F0)
#endif
#define QM_FLASH_OTP_TRIM_CODE \
((qm_flash_otp_trim_t *)QM_FLASH_OTP_TRIM_CODE_BASE)
#define QM_FLASH_OTP_SOC_DATA_VALID (0x24535021) /**< $SP! */
#define QM_FLASH_OTP_TRIM_MAGIC (QM_FLASH_OTP_TRIM_CODE->magic)
typedef union {
struct trim_fields {
QM_RW uint16_t
osc_trim_32mhz; /**< 32MHz Oscillator trim code. */
QM_RW uint16_t
osc_trim_16mhz; /**< 16MHz Oscillator trim code. */
QM_RW uint16_t osc_trim_8mhz; /**< 8MHz Oscillator trim code. */
QM_RW uint16_t osc_trim_4mhz; /**< 4MHz Oscillator trim code. */
} fields;
QM_RW uint32_t osc_trim_u32[2]; /**< Oscillator trim code array.*/
QM_RW uint16_t osc_trim_u16[2]; /**< Oscillator trim code array.*/
} qm_flash_data_trim_t;
#if (UNIT_TEST)
#define QM_FLASH_DATA_TRIM_BASE (&test_flash_page[100])
#define QM_FLASH_DATA_TRIM_OFFSET (100)
#else
#define QM_FLASH_DATA_TRIM_BASE (0x4002F000)
#define QM_FLASH_DATA_TRIM_OFFSET ((uint32_t)QM_FLASH_DATA_TRIM_BASE & 0x3FFFF)
#endif
#define QM_FLASH_DATA_TRIM ((qm_flash_data_trim_t *)QM_FLASH_DATA_TRIM_BASE)
#define QM_FLASH_DATA_TRIM_CODE (&QM_FLASH_DATA_TRIM->fields)
#define QM_FLASH_DATA_TRIM_REGION QM_FLASH_REGION_SYS
#define QM_FLASH_TRIM_PRESENT_MASK (0xFC00)
#define QM_FLASH_TRIM_PRESENT (0x0000)
/**
* @}
*/
#endif /* __FLASH_LAYOUT_H__ */

View file

@ -0,0 +1,178 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __POWER_STATES_H__
#define __POWER_STATES_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
/**
* SoC Power mode control for Quark SE Microcontrollers.
*
* @defgroup groupSoCPower Quark SE SoC Power states
* @{
*/
/**
* Enter SoC sleep state.
*
* Put the SoC into sleep state until next SoC wake event.
*
* - Core well is turned off
* - Always on well is on
* - Hybrid Clock is off
* - RTC Clock is on
*
* Possible SoC wake events are:
* - Low Power Comparator Interrupt
* - AON GPIO Interrupt
* - AON Timer Interrupt
* - RTC Interrupt
*/
void power_soc_sleep(void);
/**
* Enter SoC deep sleep state.
*
* Put the SoC into deep sleep state until next SoC wake event.
*
* - Core well is turned off
* - Always on well is on
* - Hybrid Clock is off
* - RTC Clock is on
*
* Possible SoC wake events are:
* - Low Power Comparator Interrupt
* - AON GPIO Interrupt
* - AON Timer Interrupt
* - RTC Interrupt
*
* This function puts 1P8V regulators and 3P3V into Linear Mode.
*/
void power_soc_deep_sleep(void);
/**
* Enable LPSS state entry.
*
* Put the SoC into LPSS on next C2/C2LP and SS2 state combination.<BR>
* SoC Hybrid Clock is gated in this state.<BR>
* Core Well Clocks are gated.<BR>
* RTC is the only clock remaining running.
*
* Possible SoC wake events are:
* - Low Power Comparator Interrupt
* - AON GPIO Interrupt
* - AON Timer Interrupt
* - RTC Interrupt
*/
void power_soc_lpss_enable(void);
/**
* Disable LPSS state entry.
*
* Clear LPSS enable flag.<BR>
* This will prevent entry in LPSS when cores are in C2/C2LP and SS2 states.
*/
void power_soc_lpss_disable(void);
/**
* @}
*/
#if (!QM_SENSOR)
/**
* Host Power mode control for Quark SE Microcontrollers.<BR>
* These functions cannot be called from the Sensor Subsystem.
*
* @defgroup groupSEPower Quark SE Host Power states
* @{
*/
/**
* Enter Host C1 state.
*
* Put the Host into C1.<BR>
* Processor Clock is gated in this state.<BR>
* Nothing is turned off in this state.
*
* A wake event causes the Host to transition to C0.<BR>
* A wake event is a host interrupt.
*/
void power_cpu_c1(void);
/**
* Enter Host C2 state or SoC LPSS state.
*
* Put the Host into C2.
* Processor Clock is gated in this state.
* All rails are supplied.
*
* This enables entry in LPSS if:
* - Sensor Subsystem is in SS2.
* - LPSS entry is enabled.
*
* If C2 is entered:
* - A wake event causes the Host to transition to C0.
* - A wake event is a host interrupt.
*
* If LPSS is entered:
* - LPSS wake events applies.
* - If the Sensor Subsystem wakes the SoC from LPSS, Host is back in C2.
*/
void power_cpu_c2(void);
/**
* Enter Host C2LP state or SoC LPSS state.
*
* Put the Host into C2LP.
* Processor Complex Clock is gated in this state.
* All rails are supplied.
*
* This enables entry in LPSS if:
* - Sensor Subsystem is in SS2.
* - LPSS is allowed.
*
* If C2LP is entered:
* - A wake event causes the Host to transition to C0.
* - A wake event is a Host interrupt.
*
* If LPSS is entered:
* - LPSS wake events apply if LPSS is entered.
* - If the Sensor Subsystem wakes the SoC from LPSS,
* Host transitions back to C2LP.
*/
void power_cpu_c2lp(void);
#endif
/**
* @}
*/
#endif /* __POWER_STATES_H__ */

View file

@ -0,0 +1,574 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __SENSOR_REGISTERS_H__
#define __SENSOR_REGISTERS_H__
#include "qm_common.h"
/**
* Quark SE SoC Sensor Subsystem Registers.
*
* For detailed description please read the SOC datasheet.
*
* @defgroup groupSSSEREG SoC Registers (Sensor Subsystem)
* @{
*/
#if (UNIT_TEST)
#define QM_SS_BASE_AUX_REGS_NUM (0x701)
/* Peripherals auxiliary registers start at
* 0x80010000 and ends at 0x80018180 */
#define QM_SS_PERIPH_AUX_REGS_BASE (0x80010000)
#define QM_SS_PERIPH_AUX_REGS_SIZE (0x8181)
#define QM_SS_AUX_REGS_SIZE \
(QM_SS_BASE_AUX_REGS_NUM + QM_SS_PERIPH_AUX_REGS_SIZE)
uint32_t test_sensor_aux[QM_SS_AUX_REGS_SIZE];
#define __builtin_arc_lr(addr) \
({ \
uint32_t temp = addr; \
if (temp >= QM_SS_PERIPH_AUX_REGS_BASE) { \
temp -= QM_SS_PERIPH_AUX_REGS_BASE; \
temp += QM_SS_BASE_AUX_REGS_NUM; \
} \
(test_sensor_aux[temp]); \
})
#define __builtin_arc_sr(val, addr) \
({ \
uint32_t temp = addr; \
if (temp >= QM_SS_PERIPH_AUX_REGS_BASE) { \
temp -= QM_SS_PERIPH_AUX_REGS_BASE; \
temp += QM_SS_BASE_AUX_REGS_NUM; \
} \
(test_sensor_aux[temp] = val); \
})
#define __builtin_arc_kflag(sreg)
#define __builtin_arc_brk()
#define __builtin_arc_clri()
#define __builtin_arc_seti(val)
#define __builtin_arc_nop()
#endif
/**
* @name Bitwise Operation Macros
* @{
*/
/** Bitwise OR operation macro for registers in the auxiliary memory space. */
#define QM_SS_REG_AUX_OR(reg, mask) \
(__builtin_arc_sr(__builtin_arc_lr(reg) | (mask), reg))
/** Bitwise NAND operation macro for registers in the auxiliary memory space. */
#define QM_SS_REG_AUX_NAND(reg, mask) \
(__builtin_arc_sr(__builtin_arc_lr(reg) & (~mask), reg))
/** @} */
/**
* @name Status and Control Register
* @{
*/
#define QM_SS_AUX_STATUS32 (0xA) /**< Sensor Subsystem status32 register. */
#define QM_SS_AUX_IC_CTRL (0x11) /**< Sensor Subsystem control register. */
/**< Sensor Subsystem cache invalidate register. */
#define QM_SS_AUX_IC_IVIL (0x19)
/**< Sensor Subsystem vector base register. */
#define QM_SS_AUX_INT_VECTOR_BASE (0x25)
/** @} */
/**
* @name SS Timer
* @{
*/
typedef enum {
QM_SS_TIMER_COUNT = 0,
QM_SS_TIMER_CONTROL,
QM_SS_TIMER_LIMIT
} qm_ss_timer_reg_t;
/**
* Sensor Subsystem Timers.
*/
typedef enum { QM_SS_TIMER_0 = 0, QM_SS_TIMER_NUM } qm_ss_timer_t;
#define QM_SS_TIMER_0_BASE (0x21)
#define QM_SS_TIMER_1_BASE (0x100)
#define QM_SS_TSC_BASE QM_SS_TIMER_1_BASE
#define QM_SS_TIMER_CONTROL_INT_EN_OFFSET (0)
#define QM_SS_TIMER_CONTROL_NON_HALTED_OFFSET (1)
#define QM_SS_TIMER_CONTROL_WATCHDOG_OFFSET (2)
#define QM_SS_TIMER_CONTROL_INT_PENDING_OFFSET (3)
/** @} */
/**
* GPIO registers and definitions.
*
* @name SS GPIO
* @{
*/
typedef enum {
QM_SS_GPIO_SWPORTA_DR = 0,
QM_SS_GPIO_SWPORTA_DDR,
QM_SS_GPIO_INTEN = 3,
QM_SS_GPIO_INTMASK,
QM_SS_GPIO_INTTYPE_LEVEL,
QM_SS_GPIO_INT_POLARITY,
QM_SS_GPIO_INTSTATUS,
QM_SS_GPIO_DEBOUNCE,
QM_SS_GPIO_PORTA_EOI,
QM_SS_GPIO_EXT_PORTA,
QM_SS_GPIO_LS_SYNC
} qm_ss_gpio_reg_t;
/* Sensor Subsystem GPIO register block type */
#define QM_SS_GPIO_NUM_PINS (16)
#define QM_SS_GPIO_LS_SYNC_CLK_EN BIT(31)
#define QM_SS_GPIO_LS_SYNC_SYNC_LVL BIT(0)
/** Sensor Subsystem GPIO */
typedef enum { QM_SS_GPIO_0 = 0, QM_SS_GPIO_1, QM_SS_GPIO_NUM } qm_ss_gpio_t;
#define QM_SS_GPIO_0_BASE (0x80017800)
#define QM_SS_GPIO_1_BASE (0x80017900)
/** @} */
/**
* I2C registers and definitions.
*
* @name SS I2C
* @{
*/
/** Sensor Subsystem I2C Registers*/
typedef enum {
QM_SS_I2C_CON = 0,
QM_SS_I2C_DATA_CMD,
QM_SS_I2C_SS_SCL_CNT,
QM_SS_I2C_FS_SCL_CNT = 0x04,
QM_SS_I2C_INTR_STAT = 0x06,
QM_SS_I2C_INTR_MASK,
QM_SS_I2C_TL,
QM_SS_I2C_INTR_CLR = 0x0A,
QM_SS_I2C_STATUS,
QM_SS_I2C_TXFLR,
QM_SS_I2C_RXFLR,
QM_SS_I2C_SDA_CONFIG,
QM_SS_I2C_TX_ABRT_SOURCE,
QM_SS_I2C_ENABLE_STATUS = 0x11
} qm_ss_i2c_reg_t;
/** Sensor Subsystem I2C register block type */
#define QM_SS_I2C_CON_ENABLE BIT(0)
#define QM_SS_I2C_CON_ABORT BIT(1)
#define QM_SS_I2C_CON_SPEED_SS BIT(3)
#define QM_SS_I2C_CON_SPEED_FS BIT(4)
#define QM_SS_I2C_CON_SPEED_MASK (0x18)
#define QM_SS_I2C_CON_IC_10BITADDR BIT(5)
#define QM_SS_I2C_CON_IC_10BITADDR_OFFSET (5)
#define QM_SS_I2C_CON_IC_10BITADDR_MASK (5)
#define QM_SS_I2C_CON_RESTART_EN BIT(7)
#define QM_SS_I2C_CON_TAR_SAR_OFFSET (9)
#define QM_SS_I2C_CON_TAR_SAR_MASK (0x7FE00)
#define QM_SS_I2C_CON_TAR_SAR_10_BIT_MASK (0xFF)
#define QM_SS_I2C_CON_SPKLEN_OFFSET (22)
#define QM_SS_I2C_CON_SPKLEN_MASK (0x3FC00000)
#define QM_SS_I2C_CON_CLK_ENA BIT(31)
#define QM_SS_I2C_DATA_CMD_CMD BIT(8)
#define QM_SS_I2C_DATA_CMD_STOP BIT(9)
#define QM_SS_I2C_DATA_CMD_PUSH (0xC0000000)
#define QM_SS_I2C_DATA_CMD_POP (0x80000000)
#define QM_SS_I2C_SS_FS_SCL_CNT_HCNT_OFFSET (16)
#define QM_SS_I2C_SS_FS_SCL_CNT_16BIT_MASK (0xFFFF)
#define QM_SS_I2C_INTR_STAT_RX_UNDER BIT(0)
#define QM_SS_I2C_INTR_STAT_RX_OVER BIT(1)
#define QM_SS_I2C_INTR_STAT_RX_FULL BIT(2)
#define QM_SS_I2C_INTR_STAT_TX_OVER BIT(3)
#define QM_SS_I2C_INTR_STAT_TX_EMPTY BIT(4)
#define QM_SS_I2C_INTR_STAT_TX_ABRT BIT(6)
#define QM_SS_I2C_INTR_MASK_ALL (0x0)
#define QM_SS_I2C_INTR_MASK_RX_UNDER BIT(0)
#define QM_SS_I2C_INTR_MASK_RX_OVER BIT(1)
#define QM_SS_I2C_INTR_MASK_RX_FULL BIT(2)
#define QM_SS_I2C_INTR_MASK_TX_OVER BIT(3)
#define QM_SS_I2C_INTR_MASK_TX_EMPTY BIT(4)
#define QM_SS_I2C_INTR_MASK_TX_ABRT BIT(6)
#define QM_SS_I2C_TL_TX_TL_OFFSET (16)
#define QM_SS_I2C_TL_RX_TL_MASK (0xFF)
#define QM_SS_I2C_TL_TX_TL_MASK (0xFF0000)
#define QM_SS_I2C_INTR_CLR_TX_ABRT BIT(6)
#define QM_SS_I2C_TX_ABRT_SOURCE_NAK_MASK (0x09)
#define QM_SS_I2C_TX_ABRT_SOURCE_ALL_MASK (0x1FFFF)
#define QM_SS_I2C_TX_ABRT_SBYTE_NORSTRT BIT(9)
#define QM_SS_I2C_TX_ABRT_SOURCE_ART_LOST BIT(12)
#define QM_SS_I2C_ENABLE_CONTROLLER_EN BIT(0)
#define QM_SS_I2C_ENABLE_STATUS_IC_EN BIT(0)
#define QM_SS_I2C_STATUS_BUSY_MASK (0x21)
#define QM_SS_I2C_STATUS_RFNE BIT(3)
#define QM_SS_I2C_STATUS_TFE BIT(2)
#define QM_SS_I2C_STATUS_TFNF BIT(1)
#define QM_SS_I2C_IC_LCNT_MAX (65525)
#define QM_SS_I2C_IC_LCNT_MIN (8)
#define QM_SS_I2C_IC_HCNT_MAX (65525)
#define QM_SS_I2C_IC_HCNT_MIN (6)
#define QM_SS_I2C_FIFO_SIZE (8)
/** Sensor Subsystem I2C */
typedef enum { QM_SS_I2C_0 = 0, QM_SS_I2C_1, QM_SS_I2C_NUM } qm_ss_i2c_t;
#define QM_SS_I2C_0_BASE (0x80012000)
#define QM_SS_I2C_1_BASE (0x80012100)
/** Sensor Subsystem ADC @{*/
/** Sensor Subsystem ADC registers */
typedef enum {
QM_SS_ADC_SET = 0, /**< ADC and sequencer settings register. */
QM_SS_ADC_DIVSEQSTAT, /**< ADC clock and sequencer status register. */
QM_SS_ADC_SEQ, /**< ADC sequence entry register. */
QM_SS_ADC_CTRL, /**< ADC control register. */
QM_SS_ADC_INTSTAT, /**< ADC interrupt status register. */
QM_SS_ADC_SAMPLE /**< ADC sample register. */
} qm_ss_adc_reg_t;
/** Sensor Subsystem ADC */
typedef enum {
QM_SS_ADC_0 = 0, /**< ADC first module. */
QM_SS_ADC_NUM
} qm_ss_adc_t;
/** SS ADC register base */
#define QM_SS_ADC_BASE (0x80015000)
/** For 1MHz, the max divisor is 7. */
#define QM_SS_ADC_DIV_MAX (7)
#define QM_SS_ADC_FIFO_LEN (32)
#define QM_SS_ADC_SET_POP_RX BIT(31)
#define QM_SS_ADC_SET_FLUSH_RX BIT(30)
#define QM_SS_ADC_SET_THRESHOLD_MASK (0x3F000000)
#define QM_SS_ADC_SET_THRESHOLD_OFFSET (24)
#define QM_SS_ADC_SET_SEQ_ENTRIES_MASK (0x3F0000)
#define QM_SS_ADC_SET_SEQ_ENTRIES_OFFSET (16)
#define QM_SS_ADC_SET_SEQ_MODE BIT(13)
#define QM_SS_ADC_SET_SAMPLE_WIDTH_MASK (0x1F)
#define QM_SS_ADC_DIVSEQSTAT_CLK_RATIO_MASK (0x1FFFFF)
#define QM_SS_ADC_CTRL_CLR_SEQERROR BIT(19)
#define QM_SS_ADC_CTRL_CLR_UNDERFLOW BIT(18)
#define QM_SS_ADC_CTRL_CLR_OVERFLOW BIT(17)
#define QM_SS_ADC_CTRL_CLR_DATA_A BIT(16)
#define QM_SS_ADC_CTRL_MSK_SEQERROR BIT(11)
#define QM_SS_ADC_CTRL_MSK_UNDERFLOW BIT(10)
#define QM_SS_ADC_CTRL_MSK_OVERFLOW BIT(9)
#define QM_SS_ADC_CTRL_MSK_DATA_A BIT(8)
#define QM_SS_ADC_CTRL_SEQ_TABLE_RST BIT(6)
#define QM_SS_ADC_CTRL_SEQ_PTR_RST BIT(5)
#define QM_SS_ADC_CTRL_SEQ_START BIT(4)
#define QM_SS_ADC_CTRL_CLK_ENA BIT(2)
#define QM_SS_ADC_CTRL_ADC_ENA BIT(1)
#define QM_SS_ADC_CTRL_MSK_ALL_INT (0xF00)
#define QM_SS_ADC_CTRL_CLR_ALL_INT (0xF0000)
#define QM_SS_ADC_SEQ_DELAYODD_OFFSET (21)
#define QM_SS_ADC_SEQ_MUXODD_OFFSET (16)
#define QM_SS_ADC_SEQ_DELAYEVEN_OFFSET (5)
#define QM_SS_ADC_SEQ_DUMMY (0x480)
#define QM_SS_ADC_INTSTAT_SEQERROR BIT(3)
#define QM_SS_ADC_INTSTAT_UNDERFLOW BIT(2)
#define QM_SS_ADC_INTSTAT_OVERFLOW BIT(1)
#define QM_SS_ADC_INTSTAT_DATA_A BIT(0)
/** End of Sensor Subsystem ADC @}*/
/**
* CREG Registers.
*
* @name SS CREG
* @{
*/
/* Sensor Subsystem CREG */
typedef enum {
QM_SS_IO_CREG_MST0_CTRL = 0x0, /**< Master control register. */
QM_SS_IO_CREG_SLV0_OBSR = 0x80, /**< Slave control register. */
QM_SS_IO_CREG_SLV1_OBSR = 0x180 /**< Slave control register. */
} qm_ss_creg_reg_t;
#define QM_SS_ADC_CAL_MAX (0x7F)
/* MST0_CTRL fields */
#define QM_SS_ADC_PWR_MODE_OFFSET (1)
#define QM_SS_ADC_PWR_MODE_MASK (0x7)
#define QM_SS_ADC_DELAY_OFFSET (3)
#define QM_SS_ADC_DELAY_MASK (0xFFF8)
#define QM_SS_ADC_CAL_REQ BIT(16)
#define QM_SS_ADC_CAL_CMD_OFFSET (17)
#define QM_SS_ADC_CAL_CMD_MASK (0xE0000)
#define QM_SS_ADC_CAL_VAL_SET_OFFSET (20)
#define QM_SS_ADC_CAL_VAL_SET_MASK (0x7F00000)
/* SLV0_OBSR fields */
#define QM_SS_ADC_CAL_VAL_GET_OFFSET (5)
#define QM_SS_ADC_CAL_VAL_GET_MASK (0xFE0)
#define QM_SS_ADC_CAL_ACK BIT(4)
#define QM_SS_ADC_PWR_MODE_STS BIT(3) /*FIXME doesnt match doc */
#define SS_CLK_PERIPH_ALL_IN_CREG \
(SS_CLK_PERIPH_ADC | SS_CLK_PERIPH_I2C_1 | SS_CLK_PERIPH_I2C_0 | \
SS_CLK_PERIPH_SPI_1 | SS_CLK_PERIPH_SPI_0)
/** SS CREG base */
#define QM_SS_CREG_BASE (0x80018000)
/** @} */
/**
* IRQs and interrupt vectors.
*
* @name SS Interrupt
* @{
*/
#define QM_SS_EXCEPTION_NUM (16) /**< Exceptions and traps in ARC EM core */
#define QM_SS_INT_TIMER_NUM (2) /**< Internal interrupts in ARC EM core */
#define QM_SS_IRQ_SENSOR_NUM (18) /**< IRQ's from the Sensor Subsystem */
#define QM_SS_IRQ_COMMON_NUM (32) /**< IRQ's from the common SoC fabric */
#define QM_SS_INT_VECTOR_NUM \
(QM_SS_EXCEPTION_NUM + QM_SS_INT_TIMER_NUM + QM_SS_IRQ_SENSOR_NUM + \
QM_SS_IRQ_COMMON_NUM)
#define QM_SS_IRQ_NUM (QM_SS_IRQ_SENSOR_NUM + QM_SS_IRQ_COMMON_NUM)
/*
* The following definitions are Sensor Subsystem interrupt irq and vector
* numbers:
* #define QM_SS_xxx - irq number
* #define QM_SS_xxx_VECTOR - vector number
*/
#define QM_SS_INT_TIMER_0 (16)
#define QM_SS_INT_TIMER_1 (17)
#define QM_SS_IRQ_ADC_ERR (0)
#define QM_SS_IRQ_ADC_ERR_VECTOR (18)
#define QM_SS_IRQ_ADC_IRQ (1)
#define QM_SS_IRQ_ADC_IRQ_VECTOR (19)
#define QM_SS_IRQ_GPIO_INTR_0 (2)
#define QM_SS_IRQ_GPIO_INTR_0_VECTOR (20)
#define QM_SS_IRQ_GPIO_INTR_1 (3)
#define QM_SS_IRQ_GPIO_INTR_1_VECTOR (21)
#define QM_SS_IRQ_I2C_0_ERR (4)
#define QM_SS_IRQ_I2C_0_ERR_VECTOR (22)
#define QM_SS_IRQ_I2C_0_RX_AVAIL (5)
#define QM_SS_IRQ_I2C_0_RX_AVAIL_VECTOR (23)
#define QM_SS_IRQ_I2C_0_TX_REQ (6)
#define QM_SS_IRQ_I2C_0_TX_REQ_VECTOR (24)
#define QM_SS_IRQ_I2C_0_STOP_DET (7)
#define QM_SS_IRQ_I2C_0_STOP_DET_VECTOR (25)
#define QM_SS_IRQ_I2C_1_ERR (8)
#define QM_SS_IRQ_I2C_1_ERR_VECTOR (26)
#define QM_SS_IRQ_I2C_1_RX_AVAIL (9)
#define QM_SS_IRQ_I2C_1_RX_AVAIL_VECTOR (27)
#define QM_SS_IRQ_I2C_1_TX_REQ (10)
#define QM_SS_IRQ_I2C_1_TX_REQ_VECTOR (28)
#define QM_SS_IRQ_I2C_1_STOP_DET (11)
#define QM_SS_IRQ_I2C_1_STOP_DET_VECTOR (29)
#define QM_SS_IRQ_SPI_0_ERR_INT (12)
#define QM_SS_IRQ_SPI_0_ERR_INT_VECTOR (30)
#define QM_SS_IRQ_SPI_0_RX_AVAIL (13)
#define QM_SS_IRQ_SPI_0_RX_AVAIL_VECTOR (31)
#define QM_SS_IRQ_SPI_0_TX_REQ (14)
#define QM_SS_IRQ_SPI_0_TX_REQ_VECTOR (32)
#define QM_SS_IRQ_SPI_1_ERR_INT (15)
#define QM_SS_IRQ_SPI_1_ERR_INT_VECTOR (33)
#define QM_SS_IRQ_SPI_1_RX_AVAIL (16)
#define QM_SS_IRQ_SPI_1_RX_AVAIL_VECTOR (34)
#define QM_SS_IRQ_SPI_1_TX_REQ (17)
#define QM_SS_IRQ_SPI_1_TX_REQ_VECTOR (35)
typedef enum {
QM_SS_INT_PRIORITY_0 = 0,
QM_SS_INT_PRIORITY_1 = 1,
QM_SS_INT_PRIORITY_15 = 15,
QM_SS_INT_PRIORITY_NUM
} qm_ss_irq_priority_t;
typedef enum { QM_SS_INT_DISABLE = 0, QM_SS_INT_ENABLE = 1 } qm_ss_irq_mask_t;
typedef enum {
QM_SS_IRQ_LEVEL_SENSITIVE = 0,
QM_SS_IRQ_EDGE_SENSITIVE = 1
} qm_ss_irq_trigger_t;
#define QM_SS_AUX_IRQ_CTRL (0xE)
#define QM_SS_AUX_IRQ_HINT (0x201)
#define QM_SS_AUX_IRQ_PRIORITY (0x206)
#define QM_SS_AUX_IRQ_STATUS (0x406)
#define QM_SS_AUX_IRQ_SELECT (0x40B)
#define QM_SS_AUX_IRQ_ENABLE (0x40C)
#define QM_SS_AUX_IRQ_TRIGER (0x40D)
/** @} */
/**
* I2C registers and definitions.
*
* @name SS SPI
* @{
*/
/** Sensor Subsystem SPI register map. */
typedef enum {
QM_SS_SPI_CTRL = 0, /**< SPI control register. */
QM_SS_SPI_SPIEN = 2, /**< SPI enable register. */
QM_SS_SPI_TIMING = 4, /**< SPI serial clock divider value. */
QM_SS_SPI_FTLR, /**< Threshold value for TX/RX FIFO. */
QM_SS_SPI_TXFLR = 7, /**< Number of valid data entries in TX FIFO. */
QM_SS_SPI_RXFLR, /**< Number of valid data entries in RX FIFO. */
QM_SS_SPI_SR, /**< SPI status register. */
QM_SS_SPI_INTR_STAT, /**< Interrupt status register. */
QM_SS_SPI_INTR_MASK, /**< Interrupt mask register. */
QM_SS_SPI_CLR_INTR, /**< Interrupt clear register. */
QM_SS_SPI_DR, /**< RW buffer for FIFOs. */
} qm_ss_spi_reg_t;
/** Sensor Subsystem SPI modules. */
typedef enum {
QM_SS_SPI_0 = 0, /**< SPI module 0 */
QM_SS_SPI_1, /**< SPI module 1 */
QM_SS_SPI_NUM
} qm_ss_spi_t;
#define QM_SS_SPI_0_BASE (0x80010000)
#define QM_SS_SPI_1_BASE (0x80010100)
#define QM_SS_SPI_CTRL_DFS_OFFS (0)
#define QM_SS_SPI_CTRL_DFS_MASK (0x0000000F)
#define QM_SS_SPI_CTRL_BMOD_OFFS (6)
#define QM_SS_SPI_CTRL_BMOD_MASK (0x000000C0)
#define QM_SS_SPI_CTRL_SCPH BIT(6)
#define QM_SS_SPI_CTRL_SCPOL BIT(7)
#define QM_SS_SPI_CTRL_TMOD_OFFS (8)
#define QM_SS_SPI_CTRL_TMOD_MASK (0x00000300)
#define QM_SS_SPI_CTRL_SRL BIT(11)
#define QM_SS_SPI_CTRL_CLK_ENA BIT(15)
#define QM_SS_SPI_CTRL_NDF_OFFS (16)
#define QM_SS_SPI_CTRL_NDF_MASK (0xFFFF0000)
#define QM_SS_SPI_SPIEN_EN BIT(0)
#define QM_SS_SPI_SPIEN_SER_OFFS (4)
#define QM_SS_SPI_SPIEN_SER_MASK (0x000000F0)
#define QM_SS_SPI_TIMING_SCKDV_OFFS (0)
#define QM_SS_SPI_TIMING_SCKDV_MASK (0x0000FFFF)
#define QM_SS_SPI_TIMING_RSD_OFFS (16)
#define QM_SS_SPI_TIMING_RSD_MASK (0x00FF0000)
#define QM_SS_SPI_FTLR_RFT_OFFS (0)
#define QM_SS_SPI_FTLR_RFT_MASK (0x0000FFFF)
#define QM_SS_SPI_FTLR_TFT_OFFS (16)
#define QM_SS_SPI_FTLR_TFT_MASK (0xFFFF0000)
#define QM_SS_SPI_SR_BUSY BIT(0)
#define QM_SS_SPI_SR_TFNF BIT(1)
#define QM_SS_SPI_SR_TFE BIT(2)
#define QM_SS_SPI_SR_RFNE BIT(3)
#define QM_SS_SPI_SR_RFF BIT(4)
#define QM_SS_SPI_INTR_TXEI BIT(0)
#define QM_SS_SPI_INTR_TXOI BIT(1)
#define QM_SS_SPI_INTR_RXUI BIT(2)
#define QM_SS_SPI_INTR_RXOI BIT(3)
#define QM_SS_SPI_INTR_RXFI BIT(4)
#define QM_SS_SPI_INTR_ALL (0x0000001F)
#define QM_SS_SPI_INTR_STAT_TXEI QM_SS_SPI_INTR_TXEI
#define QM_SS_SPI_INTR_STAT_TXOI QM_SS_SPI_INTR_TXOI
#define QM_SS_SPI_INTR_STAT_RXUI QM_SS_SPI_INTR_RXUI
#define QM_SS_SPI_INTR_STAT_RXOI QM_SS_SPI_INTR_RXOI
#define QM_SS_SPI_INTR_STAT_RXFI QM_SS_SPI_INTR_RXFI
#define QM_SS_SPI_INTR_MASK_TXEI QM_SS_SPI_INTR_TXEI
#define QM_SS_SPI_INTR_MASK_TXOI QM_SS_SPI_INTR_TXOI
#define QM_SS_SPI_INTR_MASK_RXUI QM_SS_SPI_INTR_RXUI
#define QM_SS_SPI_INTR_MASK_RXOI QM_SS_SPI_INTR_RXOI
#define QM_SS_SPI_INTR_MASK_RXFI QM_SS_SPI_INTR_RXFI
#define QM_SS_SPI_CLR_INTR_TXEI QM_SS_SPI_INTR_TXEI
#define QM_SS_SPI_CLR_INTR_TXOI QM_SS_SPI_INTR_TXOI
#define QM_SS_SPI_CLR_INTR_RXUI QM_SS_SPI_INTR_RXUI
#define QM_SS_SPI_CLR_INTR_RXOI QM_SS_SPI_INTR_RXOI
#define QM_SS_SPI_CLR_INTR_RXFI QM_SS_SPI_INTR_RXFI
#define QM_SS_SPI_DR_DR_OFFS (0)
#define QM_SS_SPI_DR_DR_MASK (0x0000FFFF)
#define QM_SS_SPI_DR_WR BIT(30)
#define QM_SS_SPI_DR_STROBE BIT(31)
#define QM_SS_SPI_DR_W_MASK (0xc0000000)
#define QM_SS_SPI_DR_R_MASK (0x80000000)
/** @} */
#endif /* __SENSOR_REGISTERS_H__ */

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,104 @@
/*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of the Intel Corporation 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 INTEL CORPORATION 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 __VREG_H__
#define __VREG_H__
#include "qm_common.h"
#include "qm_soc_regs.h"
typedef enum {
VREG_MODE_SWITCHING = 0,
VREG_MODE_LINEAR,
VREG_MODE_SHUTDOWN,
VREG_MODE_NUM,
} vreg_mode_t;
/**
* Voltage Regulators Control.
*
* @defgroup groupVREG Quark SE Voltage Regulators
* @{
*/
/**
* Set AON Voltage Regulator mode.
*
* The AON Voltage Regulator is not a
* switching regulator and only acts as
* a linear regulator.
* VREG_SWITCHING_MODE is not a value mode
* for the AON Voltage Regulator.
*
* @param[in] mode Voltage Regulator mode.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int vreg_aon_set_mode(const vreg_mode_t mode);
/**
* Set Platform 3P3 Voltage Regulator mode.
*
* @param[in] mode Voltage Regulator mode.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int vreg_plat3p3_set_mode(const vreg_mode_t mode);
/**
* Set Platform 1P8 Voltage Regulator mode.
*
* @param[in] mode Voltage Regulator mode.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int vreg_plat1p8_set_mode(const vreg_mode_t mode);
/**
* Set Host Voltage Regulator mode.
*
* @param[in] mode Voltage Regulator mode.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
* @retval Negative @ref errno for possible error codes.
*/
int vreg_host_set_mode(const vreg_mode_t mode);
/**
* @}
*/
#endif /* __VREG_H__ */