Revert "ext qmsi: Update to QMSI 1.1.0 release"

This was merged prematurely.
This reverts commit 758355779c.

Change-Id: I19d27df0b9ea9acf49382d27b5ef6ce49b915542
Signed-off-by: Andrew Boie <andrew.p.boie@intel.com>
This commit is contained in:
Andrew Boie 2016-08-10 10:43:20 -07:00
commit 7da98a47a6
38 changed files with 755 additions and 815 deletions

View file

@ -10,7 +10,7 @@ ifeq ($(CONFIG_SOC_QUARK_SE),y)
obj-$(CONFIG_QMSI_BUILTIN) += soc/$(SOC_NAME)/drivers/vreg.o
endif
ifeq ($(CONFIG_SOC_QUARK_D2000),y)
obj-$(CONFIG_QMSI_BUILTIN) += soc/$(SOC_NAME)/drivers/rar.o
obj-$(CONFIG_QMSI_BUILTIN) += drivers/rar.o
endif
obj-$(CONFIG_RTC_QMSI) += drivers/qm_rtc.o
obj-$(CONFIG_WDT_QMSI) += drivers/qm_wdt.o

View file

@ -1,15 +1,15 @@
The sources in this directory are imported from QMSI project
at https://github.com/quark-mcu/qmsi.
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 supports the following SoCs:
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:
The current version supported in Zephyr is QMSI 1.1.0-Beta. See:
https://github.com/quark-mcu/qmsi/releases
https://github.com/01org/qmsi/releases/tag/v1.1.0-beta
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)

View file

@ -29,7 +29,6 @@
#include "clk.h"
#include "flash_layout.h"
#include "qm_flash.h"
#if (!QM_SENSOR) || (UNIT_TEST)
#include <x86intrin.h>
#endif
@ -52,85 +51,6 @@
*/
static uint32_t ticks_per_us = SYS_TICKS_PER_US_32MHZ;
/* Set up flash timings according to the target sysclk frequency.
*
* By POR prefetcher is disabled.
* Drivers do not expect the pre-fetcher to be enabled,
* therefore this function does assume the prefetcher is always turned off.
*/
static void apply_flash_timings(uint32_t sys_ticks_per_us)
{
uint32_t flash;
for (flash = QM_FLASH_0; flash < QM_FLASH_NUM; flash++) {
if (sys_ticks_per_us <= SYS_TICKS_PER_US_4MHZ) {
/*
* QM_FLASH_CLK_SLOW enables 0 wait states
* for flash accesses.
*/
QM_FLASH[flash]->tmg_ctrl |= QM_FLASH_CLK_SLOW;
QM_FLASH[flash]->tmg_ctrl &= ~QM_FLASH_WAIT_STATE_MASK;
} else if (sys_ticks_per_us <= SYS_TICKS_PER_US_16MHZ) {
QM_FLASH[flash]->tmg_ctrl &= ~QM_FLASH_CLK_SLOW;
/*
* READ_WAIT_STATE_L has an integrated +1 which
* results as 1 wait state for 8MHz and 16MHz.
*/
QM_FLASH[flash]->tmg_ctrl &= ~QM_FLASH_WAIT_STATE_MASK;
} else {
QM_FLASH[flash]->tmg_ctrl &= ~QM_FLASH_CLK_SLOW;
/*
* READ_WAIT_STATE_L has an integrated +1 which
* results as 2 wait states for 32MHz.
*/
QM_FLASH[flash]->tmg_ctrl =
(QM_FLASH[flash]->tmg_ctrl &
~QM_FLASH_WAIT_STATE_MASK) |
(1 << QM_FLASH_WAIT_STATE_OFFSET);
}
}
}
/*
* Compute the system clock ticks per microsecond and get the shadowed trim code
* from the Data Region of Flash.
*/
static void clk_sys_compute_new_frequency(clk_sys_mode_t mode,
clk_sys_div_t div,
uint32_t *sys_ticks_per_us,
uint16_t *trim)
{
switch (mode) {
case CLK_SYS_HYB_OSC_32MHZ:
*sys_ticks_per_us = SYS_TICKS_PER_US_32MHZ / BIT(div);
*trim = QM_FLASH_DATA_TRIM_CODE->osc_trim_32mhz;
break;
case CLK_SYS_HYB_OSC_16MHZ:
*sys_ticks_per_us = SYS_TICKS_PER_US_16MHZ / BIT(div);
*trim = QM_FLASH_DATA_TRIM_CODE->osc_trim_16mhz;
break;
case CLK_SYS_HYB_OSC_8MHZ:
*sys_ticks_per_us = SYS_TICKS_PER_US_8MHZ / BIT(div);
*trim = QM_FLASH_DATA_TRIM_CODE->osc_trim_8mhz;
break;
case CLK_SYS_HYB_OSC_4MHZ:
*sys_ticks_per_us = SYS_TICKS_PER_US_4MHZ / BIT(div);
*trim = QM_FLASH_DATA_TRIM_CODE->osc_trim_4mhz;
break;
case CLK_SYS_RTC_OSC:
*sys_ticks_per_us = 1;
break;
case CLK_SYS_CRYSTAL_OSC:
*sys_ticks_per_us = SYS_TICKS_PER_US_XTAL / BIT(div);
break;
}
}
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);
@ -147,17 +67,6 @@ int clk_sys_set_mode(const clk_sys_mode_t mode, const clk_sys_div_t div)
uint32_t ccu_sys_clk_ctl =
QM_SCSS_CCU->ccu_sys_clk_ctl & CLK_SYS_CLK_DIV_DEF_MASK;
/* Compute new frequency parameters. */
clk_sys_compute_new_frequency(mode, div, &sys_ticks_per_us, &trim);
/*
* Changing sysclk frequency requires flash settings (mainly
* wait states) to be realigned so as to avoid timing violations.
* During clock switching, we change flash timings to the
* most conservative settings (supporting up to 32MHz).
*/
apply_flash_timings(SYS_TICKS_PER_US_32MHZ);
/*
* Steps:
* 1. Enable the new oscillator and wait for it to stabilise.
@ -180,6 +89,22 @@ int clk_sys_set_mode(const clk_sys_mode_t mode, const clk_sys_div_t div)
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.
@ -235,11 +160,6 @@ int clk_sys_set_mode(const clk_sys_mode_t mode, const clk_sys_div_t div)
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);
/*
* Apply flash timings for the new clock settings.
*/
apply_flash_timings(sys_ticks_per_us);
/* Log any clock changes. */
SOC_WATCH_LOG_EVENT(SOCW_EVENT_REGISTER, SOCW_REG_OSC0_CFG1);
SOC_WATCH_LOG_EVENT(SOCW_EVENT_REGISTER, SOCW_REG_CCU_SYS_CLK_CTL);

View file

@ -43,19 +43,19 @@
* @{
*/
/*
/**
* 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. */
/** System ticks per microseconds for a 32MHz oscillator. */
#define SYS_TICKS_PER_US_32MHZ (32)
/* System ticks per microseconds for a 16MHz oscillator. */
/** System ticks per microseconds for a 16MHz oscillator. */
#define SYS_TICKS_PER_US_16MHZ (16)
/* System ticks per microseconds for a 8MHz oscillator. */
/** System ticks per microseconds for a 8MHz oscillator. */
#define SYS_TICKS_PER_US_8MHZ (8)
/* System ticks per microseconds for a 4MHz oscillator. */
/** System ticks per microseconds for a 4MHz oscillator. */
#define SYS_TICKS_PER_US_4MHZ (4)
/**

View file

@ -226,7 +226,7 @@ int qm_adc_irq_calibrate(const qm_adc_t adc,
* Set ADC calibration data.
*
* @param[in] adc Which ADC to set calibration for.
* @param[in] cal Calibration data.
* @param[in] cal_data Calibration data.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.
@ -238,7 +238,7 @@ 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] cal Calibration data. This must not be NULL.
* @param[out] adc Calibration data. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.

View file

@ -32,6 +32,7 @@
#include "qm_common.h"
#include "qm_soc_regs.h"
#include "qm_interrupt.h"
/**
* Flash controller.
*
@ -39,40 +40,40 @@
* @{
*/
/* Flash mask to clear timing. */
/** Flash mask to clear timing. */
#define QM_FLASH_TMG_DEF_MASK (0xFFFFFC00)
/* Flash mask to clear micro seconds. */
/** Flash mask to clear micro seconds. */
#define QM_FLASH_MICRO_SEC_COUNT_MASK (0x3F)
/* Flash mask to clear wait state. */
/** Flash mask to clear wait state. */
#define QM_FLASH_WAIT_STATE_MASK (0x3C0)
/* Flash wait state offset bit. */
/** Flash wait state offset bit. */
#define QM_FLASH_WAIT_STATE_OFFSET (6)
/* Flash write disable offset bit. */
/** Flash write disable offset bit. */
#define QM_FLASH_WRITE_DISABLE_OFFSET (4)
/* Flash write disable value. */
/** Flash write disable value. */
#define QM_FLASH_WRITE_DISABLE_VAL BIT(4)
/* Flash page size in dwords. */
/** Flash page size in dwords. */
#define QM_FLASH_PAGE_SIZE_DWORDS (0x200)
/* Flash page size in bytes. */
/** Flash page size in bytes. */
#define QM_FLASH_PAGE_SIZE_BYTES (0x800)
/* Flash page size in bits. */
/** Flash page size in bits. */
#define QM_FLASH_PAGE_SIZE_BITS (11)
/* Flash page erase request. */
/** Flash page erase request. */
#define ER_REQ BIT(1)
/* Flash page erase done. */
/** Flash page erase done. */
#define ER_DONE (1)
/* Flash page write request. */
/** Flash page write request. */
#define WR_REQ (1)
/* Flash page write done. */
/** Flash page write done. */
#define WR_DONE BIT(1)
/* Flash write address offset. */
/** Flash write address offset. */
#define WR_ADDR_OFFSET (2)
/* Flash perform mass erase includes OTP region. */
/** Flash perform mass erase includes OTP region. */
#define MASS_ERASE_INFO BIT(6)
/* Flash perform mass erase. */
/** Flash perform mass erase. */
#define MASS_ERASE BIT(7)
#define QM_FLASH_ADDRESS_MASK (0x7FF)
@ -161,7 +162,7 @@ int qm_flash_word_write(const qm_flash_t flash, const qm_flash_region_t region,
* meantime (e.g., by restarting it before calling this function).
*
* @param[in] flash Flash controller index.
* @param[in] reg Which Flash region to address.
* @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.

View file

@ -273,9 +273,9 @@ int qm_i2c_irq_transfer_terminate(const qm_i2c_t i2c);
* Note that qm_dma_init() must first be called before configuring a channel.
*
* @param[in] i2c I2C controller identifier.
* @param[in] dma_controller_id DMA controller identifier.
* @param[in] channel_id DMA channel identifier.
* @param[in] direction DMA channel direction, either
* @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).
*
@ -309,7 +309,6 @@ int qm_i2c_dma_channel_config(const qm_i2c_t i2c,
* @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.
* @param[in] slave_addr Slave address.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.

View file

@ -37,10 +37,10 @@
* Linear mapping between IRQs and interrupt vectors
*/
#if (QUARK_SE)
#define QM_IRQ_TO_VECTOR(irq) (irq + 36) /* Get the vector of and IRQ. */
#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. */
#define QM_IRQ_TO_VECTOR(irq) (irq + 32) /**< Get the vector of and irq. */
#endif
@ -84,14 +84,16 @@ 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 (QM_SENSOR)
#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); \
@ -104,7 +106,7 @@ void _qm_irq_setup(uint32_t irq, uint16_t register_offset);
\
_qm_irq_setup(irq, irq##_MASK_OFFSET); \
} while (0)
#endif /* QM_SENSOR */
#endif /* UNIT_TEST */
/**
* Request an interrupt vector and register Interrupt Service Routine to it.

View file

@ -60,6 +60,27 @@ QM_ISR_DECLARE(qm_adc_0_isr);
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.
*

View file

@ -130,8 +130,8 @@ int qm_mbox_ch_write(const qm_mbox_ch_t mbox_ch,
/**
* Read specified mailbox channel.
*
* @param[in] mbox_ch Mailbox channel identifier.
* @param[out] msg Pointer to the data to read from the mailbox channel. This
* @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.

View file

@ -40,17 +40,17 @@
* @{
*/
/* MPR mask enable. */
/** MPR mask enable */
#define QM_SRAM_MPR_EN_MASK_ENABLE BIT(0)
/* MPR mask lock. */
/** MPR mask lock */
#define QM_SRAM_MPR_EN_MASK_LOCK BIT(1)
/* MPR mask host. */
/** MPR mask host */
#define QM_SRAM_MPR_AGENT_MASK_HOST BIT(0)
/* MPR mask ss. */
/** MPR mask ss */
#if (QUARK_SE)
#define QM_SRAM_MPR_AGENT_MASK_SS BIT(1)
#endif
/* MPR mask dma. */
/** MPR mask dma */
#define QM_SRAM_MPR_AGENT_MASK_DMA BIT(2)
typedef void (*qm_mpr_callback_t)(void *);
@ -93,7 +93,7 @@ int qm_mpr_set_config(const qm_mpr_id_t id, const qm_mpr_config_t *const cfg);
*
* @param [in] mode (generate interrupt, warm reset, enter probe mode).
* @param [in] callback_fn for interrupt mode (only).
* @param [in] data user data 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,

View file

@ -41,97 +41,97 @@
* @{
*/
/* Divisor Latch Access Bit. */
/** Divisor Latch Access Bit. */
#define QM_UART_LCR_DLAB BIT(7)
/* Auto Flow Control Enable Bit. */
/** Auto Flow Control Enable Bit. */
#define QM_UART_MCR_AFCE BIT(5)
/* Request to Send Bit. */
/** Request to Send Bit. */
#define QM_UART_MCR_RTS BIT(1)
/* FIFO Enable Bit. */
/** FIFO Enable Bit. */
#define QM_UART_FCR_FIFOE BIT(0)
/* Reset Receive FIFO. */
/** Reset Receive FIFO. */
#define QM_UART_FCR_RFIFOR BIT(1)
/* Reset Transmit FIFO. */
/** Reset Transmit FIFO. */
#define QM_UART_FCR_XFIFOR BIT(2)
/* FIFO half RX, half TX Threshold. */
/** FIFO half RX, half TX Threshold. */
#define QM_UART_FCR_DEFAULT_TX_RX_THRESHOLD (0xB0)
/* FIFO 1 byte RX, half TX Threshold. */
/** FIFO 1 byte RX, half TX Threshold. */
#define QM_UART_FCR_TX_1_2_RX_0_THRESHOLD (0x30)
/* FIFO half RX, empty TX Threshold. */
/** FIFO half RX, empty TX Threshold. */
#define QM_UART_FCR_TX_0_RX_1_2_THRESHOLD (0x80)
/* Transmit Holding Register Empty. */
/** Transmit Holding Register Empty. */
#define QM_UART_IIR_THR_EMPTY (0x02)
/* Received Data Available. */
/** Received Data Available. */
#define QM_UART_IIR_RECV_DATA_AVAIL (0x04)
/* Receiver Line Status. */
/** Receiver Line Status. */
#define QM_UART_IIR_RECV_LINE_STATUS (0x06)
/* Character Timeout. */
/** Character Timeout. */
#define QM_UART_IIR_CHAR_TIMEOUT (0x0C)
/* Interrupt ID Mask. */
/** Interrupt ID Mask. */
#define QM_UART_IIR_IID_MASK (0x0F)
/* Data Ready Bit. */
/** Data Ready Bit. */
#define QM_UART_LSR_DR BIT(0)
/* Overflow Error Bit. */
/** Overflow Error Bit. */
#define QM_UART_LSR_OE BIT(1)
/* Parity Error Bit. */
/** Parity Error Bit. */
#define QM_UART_LSR_PE BIT(2)
/* Framing Error Bit. */
/** Framing Error Bit. */
#define QM_UART_LSR_FE BIT(3)
/* Break Interrupt Bit. */
/** Break Interrupt Bit. */
#define QM_UART_LSR_BI BIT(4)
/* Transmit Holding Register Empty Bit. */
/** Transmit Holding Register Empty Bit. */
#define QM_UART_LSR_THRE BIT(5)
/* Transmitter Empty Bit. */
/** Transmitter Empty Bit. */
#define QM_UART_LSR_TEMT BIT(6)
/* Receiver FIFO Error Bit. */
/** Receiver FIFO Error Bit. */
#define QM_UART_LSR_RFE BIT(7)
/* Enable Received Data Available Interrupt. */
/** Enable Received Data Available Interrupt. */
#define QM_UART_IER_ERBFI BIT(0)
/* Enable Transmit Holding Register Empty Interrupt. */
/** Enable Transmit Holding Register Empty Interrupt. */
#define QM_UART_IER_ETBEI BIT(1)
/* Enable Receiver Line Status Interrupt. */
/** Enable Receiver Line Status Interrupt. */
#define QM_UART_IER_ELSI BIT(2)
/* Programmable THRE Interrupt Mode. */
/** Programmable THRE Interrupt Mode. */
#define QM_UART_IER_PTIME BIT(7)
/* Line Status Errors. */
/** 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. */
/** FIFO Depth. */
#define QM_UART_FIFO_DEPTH (16)
/* FIFO Half Depth. */
/** FIFO Half Depth. */
#define QM_UART_FIFO_HALF_DEPTH (QM_UART_FIFO_DEPTH / 2)
/* Divisor Latch High Offset. */
/** Divisor Latch High Offset. */
#define QM_UART_CFG_BAUD_DLH_OFFS 16
/* Divisor Latch Low Offset. */
/** Divisor Latch Low Offset. */
#define QM_UART_CFG_BAUD_DLL_OFFS 8
/* Divisor Latch Fraction Offset. */
/** Divisor Latch Fraction Offset. */
#define QM_UART_CFG_BAUD_DLF_OFFS 0
/* Divisor Latch High Mask. */
/** Divisor Latch High Mask. */
#define QM_UART_CFG_BAUD_DLH_MASK (0xFF << QM_UART_CFG_BAUD_DLH_OFFS)
/* Divisor Latch Low Mask. */
/** Divisor Latch Low Mask. */
#define QM_UART_CFG_BAUD_DLL_MASK (0xFF << QM_UART_CFG_BAUD_DLL_OFFS)
/* Divisor Latch Fraction Mask. */
/** Divisor Latch Fraction Mask. */
#define QM_UART_CFG_BAUD_DLF_MASK (0xFF << QM_UART_CFG_BAUD_DLF_OFFS)
/* Divisor Latch Packing Helper. */
/** 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. */
/** 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. */
/** 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. */
/** 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)

View file

@ -40,12 +40,16 @@
* @{
*/
/* Create a single version number from the major, minor and patch numbers. */
/**
* 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. */
/**
* 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)

View file

@ -40,13 +40,14 @@
* @{
*/
/* Watchdog enable. */
/** Watchdog enable. */
#define QM_WDT_ENABLE (BIT(0))
/* Watchdog mode. */
/** Watchdog mode. */
#define QM_WDT_MODE (BIT(1))
/* Watchdog mode offset. */
/** Watchdog mode offset. */
#define QM_WDT_MODE_OFFSET (1)
/* Watchdog Timeout Mask. */
/** Watchdog Timeout Mask. */
#define QM_WDT_TIMEOUT_MASK (0xF)
/**

View file

@ -68,11 +68,6 @@ int qm_ac_set_config(const qm_ac_config_t *const config)
{
QM_CHECK(config != NULL, -EINVAL);
/* Avoid interrupts while configuring the comparators.
* This can happen when the polarity is changed
* compared to a previously configured interrupt. */
QM_SCSS_CMP->cmp_en = 0;
callback = config->callback;
callback_data = config->callback_data;
QM_SCSS_CMP->cmp_ref_sel = config->reference;

View file

@ -49,8 +49,8 @@ qm_i2c_reg_t *qm_i2c[QM_I2C_NUM] = {(qm_i2c_reg_t *)QM_I2C_0_BASE};
#endif
#endif
static volatile const qm_i2c_transfer_t *i2c_transfer[QM_I2C_NUM];
static volatile uint32_t i2c_write_pos[QM_I2C_NUM], i2c_read_pos[QM_I2C_NUM],
static const qm_i2c_transfer_t *i2c_transfer[QM_I2C_NUM];
static uint32_t i2c_write_pos[QM_I2C_NUM], i2c_read_pos[QM_I2C_NUM],
i2c_read_cmd_send[QM_I2C_NUM];
/**
@ -67,8 +67,7 @@ typedef struct {
qm_dma_transfer_t dma_cmd_transfer_config;
volatile bool ongoing_dma_tx_operation; /* Keep track of ongoing TX */
volatile bool ongoing_dma_rx_operation; /* Keep track of oingoing RX*/
int tx_abort_status;
int i2c_error_code;
int multimaster_abort_status;
} i2c_dma_context_t;
/* DMA context */
@ -98,13 +97,12 @@ static int controller_disable(const qm_i2c_t i2c);
static void qm_i2c_isr_handler(const qm_i2c_t i2c)
{
const volatile qm_i2c_transfer_t *const transfer = i2c_transfer[i2c];
const qm_i2c_transfer_t *const transfer = i2c_transfer[i2c];
uint32_t ic_data_cmd = 0, count_tx = (QM_I2C_FIFO_SIZE - TX_TL);
qm_i2c_status_t status = 0;
int rc = 0;
uint32_t read_buffer_remaining = transfer->rx_len - i2c_read_pos[i2c];
uint32_t write_buffer_remaining = transfer->tx_len - i2c_write_pos[i2c];
uint32_t missing_bytes;
qm_i2c_reg_t *const controller = QM_I2C[i2c];
@ -130,15 +128,13 @@ static void qm_i2c_isr_handler(const qm_i2c_t i2c)
if ((i2c_dma_context[i2c].ongoing_dma_rx_operation == true) ||
(i2c_dma_context[i2c].ongoing_dma_tx_operation == true)) {
/* If in DMA mode, raise a flag and stop the channels */
i2c_dma_context[i2c].tx_abort_status = status;
i2c_dma_context[i2c].i2c_error_code = rc;
i2c_dma_context[i2c].multimaster_abort_status = rc;
/* When terminating the DMA transfer, the DMA controller
* calls the TX or RX callback, which will trigger the
* error callback. This will disable the I2C controller
*/
qm_i2c_dma_transfer_terminate(i2c);
} else {
controller_disable(i2c);
if (transfer->callback) {
/* NOTE: currently 0 is returned for length but
* we may revisit that soon
@ -146,6 +142,7 @@ static void qm_i2c_isr_handler(const qm_i2c_t i2c)
transfer->callback(transfer->callback_data, rc,
status, 0);
}
controller_disable(i2c);
}
}
@ -205,13 +202,13 @@ static void qm_i2c_isr_handler(const qm_i2c_t i2c)
*/
if (transfer->stop) {
controller_disable(i2c);
}
/* callback */
if (transfer->callback) {
transfer->callback(transfer->callback_data, 0,
QM_I2C_IDLE,
i2c_write_pos[i2c]);
/* callback */
if (transfer->callback) {
transfer->callback(
transfer->callback_data, 0,
QM_I2C_IDLE, i2c_write_pos[i2c]);
}
}
}
@ -241,25 +238,9 @@ static void qm_i2c_isr_handler(const qm_i2c_t i2c)
*/
}
/* If missing_bytes is not null, then that means we are already
* waiting for some bytes after sending read request on the
* previous interruption. We have to take into account this
* value in order to not send too much request so we won't fall
* into rx overflow */
missing_bytes = read_buffer_remaining - i2c_read_cmd_send[i2c];
/* Sanity check: The number of read data but not processed
* cannot be more than the number of expected bytes */
QM_ASSERT(controller->ic_rxflr <= missing_bytes);
/* count_tx is the remaining size in the fifo */
count_tx = QM_I2C_FIFO_SIZE - controller->ic_txflr;
if (count_tx > missing_bytes) {
count_tx -= missing_bytes;
} else {
count_tx = 0;
}
/* TX read command */
count_tx = QM_I2C_FIFO_SIZE -
(controller->ic_txflr + controller->ic_rxflr + 1);
while (i2c_read_cmd_send[i2c] &&
(write_buffer_remaining == 0) && count_tx) {
@ -774,7 +755,8 @@ int qm_i2c_dma_transfer_terminate(const qm_i2c_t i2c)
static void i2c_dma_transfer_error_callback(uint32_t i2c, int error_code,
uint32_t len)
{
const volatile qm_i2c_transfer_t *const transfer = i2c_transfer[i2c];
const qm_i2c_transfer_t *const transfer = i2c_transfer[i2c];
qm_i2c_status_t status;
if (error_code != 0) {
if (i2c_dma_context[i2c].ongoing_dma_tx_operation == true) {
@ -789,14 +771,16 @@ static void i2c_dma_transfer_error_callback(uint32_t i2c, int error_code,
i2c_dma_context[i2c].ongoing_dma_rx_operation = false;
}
/* Disable the controller */
/* Wait until the controller is done and disable it */
while (!(QM_I2C[i2c]->ic_status & QM_I2C_IC_STATUS_TFE)) {
}
controller_disable(i2c);
/* If the user has provided a callback, let's call it */
if (transfer->callback != NULL) {
qm_i2c_get_status(i2c, &status);
transfer->callback(transfer->callback_data, error_code,
i2c_dma_context[i2c].tx_abort_status,
len);
status, len);
}
}
}
@ -812,9 +796,10 @@ static void i2c_dma_transmit_callback(void *callback_context, uint32_t len,
qm_i2c_status_t status;
qm_i2c_t i2c = ((i2c_dma_context_t *)callback_context)->i2c;
const volatile qm_i2c_transfer_t *const transfer = i2c_transfer[i2c];
const qm_i2c_transfer_t *const transfer = i2c_transfer[i2c];
if ((error_code == 0) && (i2c_dma_context[i2c].i2c_error_code == 0)) {
if ((error_code == 0) &&
(i2c_dma_context[i2c].multimaster_abort_status == 0)) {
/* Disable DMA transmit */
QM_I2C[i2c]->ic_dma_cr &= ~QM_I2C_IC_DMA_CR_TX_ENABLE;
i2c_dma_context[i2c].ongoing_dma_tx_operation = false;
@ -832,11 +817,9 @@ static void i2c_dma_transmit_callback(void *callback_context, uint32_t len,
.dma_tx_transfer_config.block_size];
/* Check if we must issue a stop condition and it's not
a combined transaction, or bytes transfered are less
than expected */
if (((transfer->stop == true) &&
(transfer->rx_len == 0)) ||
(len != transfer->tx_len - 1)) {
a combined transaction */
if ((transfer->stop == true) &&
(transfer->rx_len == 0)) {
data_command |=
QM_I2C_IC_DATA_CMD_STOP_BIT_CTRL;
}
@ -845,21 +828,17 @@ static void i2c_dma_transmit_callback(void *callback_context, uint32_t len,
len++;
/* Check if there is a pending read operation, meaning
this is a combined transaction, and transfered data
length is the expected */
if ((transfer->rx_len > 0) &&
(len == transfer->tx_len)) {
this is a combined transaction */
if (transfer->rx_len > 0) {
i2c_start_dma_read(i2c);
} else {
/* Let's disable the I2C controller if we are
done */
if ((transfer->stop == true) ||
(len != transfer->tx_len)) {
if (transfer->stop == true) {
/* This callback is called when DMA is
done, but I2C can still be
transmitting, so let's wait
until all data is sent */
while (!(QM_I2C[i2c]->ic_status &
QM_I2C_IC_STATUS_TFE)) {
}
@ -880,9 +859,9 @@ static void i2c_dma_transmit_callback(void *callback_context, uint32_t len,
/* If error code is 0, a multimaster arbitration loss has
happened, so use it as error code */
if (error_code == 0) {
error_code = i2c_dma_context[i2c].i2c_error_code;
error_code =
i2c_dma_context[i2c].multimaster_abort_status;
}
i2c_dma_transfer_error_callback(i2c, error_code, len);
}
}
@ -896,9 +875,10 @@ static void i2c_dma_receive_callback(void *callback_context, uint32_t len,
qm_i2c_status_t status;
qm_i2c_t i2c = ((i2c_dma_context_t *)callback_context)->i2c;
const volatile qm_i2c_transfer_t *const transfer = i2c_transfer[i2c];
const qm_i2c_transfer_t *const transfer = i2c_transfer[i2c];
if ((error_code == 0) && (i2c_dma_context[i2c].i2c_error_code == 0)) {
if ((error_code == 0) &&
(i2c_dma_context[i2c].multimaster_abort_status == 0)) {
/* Disable DMA receive */
QM_I2C[i2c]->ic_dma_cr &= ~QM_I2C_IC_DMA_CR_RX_ENABLE;
i2c_dma_context[i2c].ongoing_dma_rx_operation = false;
@ -1051,7 +1031,7 @@ int qm_i2c_master_dma_transfer(const qm_i2c_t i2c,
QM_I2C[i2c]->ic_dma_rdlr = 0;
QM_I2C[i2c]->ic_dma_tdlr = 0;
i2c_dma_context[i2c].i2c_error_code = 0;
i2c_dma_context[i2c].multimaster_abort_status = 0;
/* Setup RX if something to receive */
if (xfer->rx_len > 0) {

View file

@ -136,8 +136,7 @@ static void write_frame(const qm_spi_t spi, const uint8_t *const tx_buffer)
static void wait_for_controller(const qm_spi_reg_t *const controller)
{
/**
* The controller must poll TFE status waiting for 1
/* 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))
@ -377,7 +376,9 @@ int qm_spi_transfer(const qm_spi_t spi, const qm_spi_transfer_t *const xfer,
uint8_t *rx_buffer = xfer->rx;
const uint8_t *tx_buffer = xfer->tx;
/* RX Only transfers need a dummy byte to be sent for starting. */
/* 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;

View file

@ -85,7 +85,7 @@ static bool is_write_xfer_complete(const qm_uart_t uart)
return write_pos[uart] >= transfer->data_len;
}
static void uart_client_callback(qm_uart_t uart, void *data, int error,
static void uart_client_callback(void *data, int error, qm_uart_status_t status,
uint32_t len);
static void qm_uart_isr_handler(const qm_uart_t uart)
@ -114,9 +114,9 @@ static void qm_uart_isr_handler(const qm_uart_t uart)
regs->ier_dlh &= ~QM_UART_IER_ETBEI;
uart_client_callback(
uart, dma_delayed_callback_par[uart].context,
dma_delayed_callback_par[uart].context,
dma_delayed_callback_par[uart].error_code,
dma_delayed_callback_par[uart].len);
QM_UART_IDLE, dma_delayed_callback_par[uart].len);
dma_delayed_callback_par[uart].context = NULL;
return;
}
@ -475,7 +475,6 @@ int qm_uart_irq_read_terminate(const qm_uart_t uart)
static void uart_dma_callback(void *callback_context, uint32_t len,
int error_code)
{
qm_uart_t uart;
QM_ASSERT(callback_context);
/*
* On TX transfers, the DMA driver invokes this function as soon as all
@ -490,7 +489,8 @@ static void uart_dma_callback(void *callback_context, uint32_t len,
* TX transfer, we extract the uart index from the position in
* the array.
*/
uart = (dma_context_t *)callback_context - dma_context_tx;
const qm_uart_t uart =
(dma_context_t *)callback_context - dma_context_tx;
QM_ASSERT(callback_context == (void *)&dma_context_tx[uart]);
qm_uart_reg_t *const regs = QM_UART[uart];
@ -507,14 +507,13 @@ static void uart_dma_callback(void *callback_context, uint32_t len,
regs->ier_dlh |= QM_UART_IER_ETBEI;
} else {
/* RX transfer. */
uart = (dma_context_t *)callback_context - dma_context_rx;
QM_ASSERT(callback_context == (void *)&dma_context_rx[uart]);
uart_client_callback(uart, callback_context, error_code, len);
uart_client_callback(callback_context, error_code, QM_UART_IDLE,
len);
}
}
/* Invoke the UART client callback. */
static void uart_client_callback(qm_uart_t uart, void *data, int error,
static void uart_client_callback(void *data, int error, qm_uart_status_t status,
uint32_t len)
{
const qm_uart_transfer_t *const xfer = ((dma_context_t *)data)->xfer;
@ -522,16 +521,11 @@ static void uart_client_callback(qm_uart_t uart, void *data, int error,
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;
qm_uart_reg_t *const regs = QM_UART[uart];
qm_uart_status_t status;
if (!client_callback) {
return;
}
status = regs->lsr & QM_UART_LSR_ERROR_BITS;
status |= (regs->lsr & QM_UART_LSR_DR) ? QM_UART_RX_BUSY : 0;
if (error) {
/*
* Transfer failed, pass to client the error code returned by

View file

@ -245,7 +245,7 @@ int qm_ss_adc_set_calibration(const qm_ss_adc_t adc,
* Get the current calibration data for an SS ADC.
*
* @param[in] adc Which ADC to get calibration for.
* @param[out] cal Calibration data. This must not be NULL.
* @param[out] adc Calibration data. This must not be NULL.
*
* @return Standard errno return type for QMSI.
* @retval 0 on success.

View file

@ -40,20 +40,30 @@
* @{
*/
/* Standard speed High/low period for 50% duty cycle bus clock (in nanosecs). */
/**
* 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). */
/**
* 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). */
/**
* 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). */
/**
* 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). */
/**
* High speed minimum low period to meet timing requirements (in nanosecs).
*/
#define QM_I2C_MIN_FSP_NS (500)
/**

View file

@ -57,24 +57,6 @@ QM_ISR_DECLARE(qm_ss_adc_0_isr);
*/
QM_ISR_DECLARE(qm_ss_adc_0_err_isr);
/**
* 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);
/**
* ISR for GPIO 0 error interrupt.
*

View file

@ -48,40 +48,6 @@ typedef enum {
SS_POWER_CPU_SS1_TIMER_ON /**< Keep SS Timers enabled in SS1. */
} ss_power_cpu_ss1_mode_t;
/**
* Enable LPSS state entry.
*
* Put the SoC into LPSS on next C2/C2LP and SS2 state combination.<BR>
* This function needs to be called on the Sensor Core to
* Clock Gate ADC, I2C0, I2C1, SPI0 and SPI1 sensor peripherals.<BR>
* Clock Gating sensor peripherals is a requirement to enter LPSS state.<BR>
* After LPSS, ss_power_soc_lpss_disable needs to be called to
* restore clock gating.<BR>
*
* This needs to be called before any transition to C2/C2LP and SS2
* in order to enter LPSS.<BR>
* SoC Hybrid Clock is gated in this state.<BR>
* Core Well Clocks are gated.<BR>
* RTC is the only clock running.
*
* Possible SoC wake events are:
* - Low Power Comparator Interrupt
* - AON GPIO Interrupt
* - AON Timer Interrupt
* - RTC Interrupt
*/
void ss_power_soc_lpss_enable(void);
/**
* Disable LPSS state entry.
*
* Clear LPSS enable flag.<BR>
* Disable Clock Gating of ADC, I2C0, I2C1, SPI0 and SPI1 sensor
* peripherals.<BR>
* This will prevent entry in LPSS when cores are in C2/C2LP and SS2 states.
*/
void ss_power_soc_lpss_disable(void);
/**
* Enter Sensor SS1 state.
*

View file

@ -64,23 +64,22 @@
*/
static uint32_t i2c_base[QM_SS_I2C_NUM] = {QM_SS_I2C_0_BASE, QM_SS_I2C_1_BASE};
static volatile const qm_ss_i2c_transfer_t *i2c_transfer[QM_SS_I2C_NUM];
static volatile uint32_t i2c_write_pos[QM_SS_I2C_NUM],
i2c_read_pos[QM_SS_I2C_NUM], i2c_read_cmd_send[QM_SS_I2C_NUM];
static const 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_cmd_send[QM_SS_I2C_NUM];
static void controller_enable(const qm_ss_i2c_t i2c);
static int controller_disable(const qm_ss_i2c_t i2c);
static void qm_ss_i2c_isr_handler(const qm_ss_i2c_t i2c)
{
const volatile qm_ss_i2c_transfer_t *const transfer = i2c_transfer[i2c];
const qm_ss_i2c_transfer_t *const transfer = i2c_transfer[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;
uint32_t read_buffer_remaining = transfer->rx_len - i2c_read_pos[i2c];
uint32_t write_buffer_remaining = transfer->tx_len - i2c_write_pos[i2c];
uint32_t missing_bytes;
/* Check for errors */
QM_ASSERT(!(__builtin_arc_lr(controller + QM_SS_I2C_INTR_STAT) &
@ -110,11 +109,12 @@ static void qm_ss_i2c_isr_handler(const qm_ss_i2c_t i2c)
rc = (status & QM_I2C_TX_ABRT_USER_ABRT) ? -ECANCELED : -EIO;
controller_disable(i2c);
if (i2c_transfer[i2c]->callback) {
i2c_transfer[i2c]->callback(
i2c_transfer[i2c]->callback_data, rc, status, 0);
}
controller_disable(i2c);
}
/* RX read from buffer */
@ -184,13 +184,13 @@ static void qm_ss_i2c_isr_handler(const qm_ss_i2c_t i2c)
*/
if (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]);
/* callback */
if (i2c_transfer[i2c]->callback) {
i2c_transfer[i2c]->callback(
i2c_transfer[i2c]->callback_data, 0,
QM_I2C_IDLE, i2c_write_pos[i2c]);
}
}
}
@ -223,27 +223,11 @@ static void qm_ss_i2c_isr_handler(const qm_ss_i2c_t i2c)
*/
}
/* If missing_bytes is not null, then that means we are already
* waiting for some bytes after sending read request on the
* previous interruption. We have to take into account this
* value in order to not send too much request so we won't fall
* into rx overflow */
missing_bytes = read_buffer_remaining - i2c_read_cmd_send[i2c];
/* Sanity check: The number of read data but not processed
* cannot be more than the number of expected bytes */
QM_ASSERT(__builtin_arc_lr(controller + QM_SS_I2C_RXFLR) <=
missing_bytes);
/* count_tx is the remaining size in the fifo */
count_tx = QM_SS_I2C_FIFO_SIZE -
__builtin_arc_lr(controller + QM_SS_I2C_TXFLR);
if (count_tx > missing_bytes) {
count_tx -= missing_bytes;
} else {
count_tx = 0;
}
/* 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_read_cmd_send[i2c] &&
(write_buffer_remaining == 0) && count_tx) {

View file

@ -0,0 +1,44 @@
#
# 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.
#
### Variables
SENSOR_DIR = $(BASE_DIR)/drivers/sensor
OBJ_DIRS += $(SENSOR_DIR)/$(BUILD)/$(SOC)/$(TARGET)
SENSOR_SOURCES = $(wildcard $(SENSOR_DIR)/*.c)
OBJECTS += $(addprefix $(DRV_DIR)/$(BUILD)/$(SOC)/$(TARGET)/$(OBJ)/,$(notdir $(SENSOR_SOURCES:.c=.o)))
### Flags
CFLAGS += -I$(SENSOR_DIR)
CFLAGS += -I$(SENSOR_DIR)/include
CFLAGS += -I$(BASE_DIR)/soc/$(SOC_ROOT_DIR)/include
### Build C files
$(DRV_DIR)/$(BUILD)/$(SOC)/$(TARGET)/$(OBJ)/%.o: $(SENSOR_DIR)/%.c
$(call mkdir, $(DRV_DIR)/$(BUILD)/$(SOC)/$(TARGET)/$(OBJ))
$(CC) $(CFLAGS) -c -o $@ $<

View file

@ -54,52 +54,6 @@
#define QM_SS_SLEEP_MODE_CORE_OFF_TIMER_OFF (0x20)
#define QM_SS_SLEEP_MODE_CORE_TIMERS_RTC_OFF (0x60)
void ss_power_soc_lpss_enable()
{
uint32_t creg_mst0_ctrl = 0;
creg_mst0_ctrl = __builtin_arc_lr(QM_SS_CREG_BASE);
/*
* Clock gate the sensor peripherals at CREG level.
* This clock gating is independent of the peripheral-specific clock
* gating provided in ss_clk.h .
*/
creg_mst0_ctrl |= (QM_SS_IO_CREG_MST0_CTRL_ADC_CLK_GATE |
QM_SS_IO_CREG_MST0_CTRL_I2C1_CLK_GATE |
QM_SS_IO_CREG_MST0_CTRL_I2C0_CLK_GATE |
QM_SS_IO_CREG_MST0_CTRL_SPI1_CLK_GATE |
QM_SS_IO_CREG_MST0_CTRL_SPI0_CLK_GATE);
__builtin_arc_sr(creg_mst0_ctrl, QM_SS_CREG_BASE);
QM_SCSS_CCU->ccu_lp_clk_ctl |= QM_SCSS_CCU_SS_LPS_EN;
SOC_WATCH_LOG_EVENT(SOCW_EVENT_REGISTER, SOCW_REG_CCU_LP_CLK_CTL);
}
void ss_power_soc_lpss_disable()
{
uint32_t creg_mst0_ctrl = 0;
creg_mst0_ctrl = __builtin_arc_lr(QM_SS_CREG_BASE);
/*
* Restore clock gate of the sensor peripherals at CREG level.
* CREG is not used anywhere else so we can safely restore
* the configuration to its POR default.
*/
creg_mst0_ctrl &= ~(QM_SS_IO_CREG_MST0_CTRL_ADC_CLK_GATE |
QM_SS_IO_CREG_MST0_CTRL_I2C1_CLK_GATE |
QM_SS_IO_CREG_MST0_CTRL_I2C0_CLK_GATE |
QM_SS_IO_CREG_MST0_CTRL_SPI1_CLK_GATE |
QM_SS_IO_CREG_MST0_CTRL_SPI0_CLK_GATE);
__builtin_arc_sr(creg_mst0_ctrl, QM_SS_CREG_BASE);
QM_SCSS_CCU->ccu_lp_clk_ctl &= ~QM_SCSS_CCU_SS_LPS_EN;
SOC_WATCH_LOG_EVENT(SOCW_EVENT_REGISTER, SOCW_REG_CCU_LP_CLK_CTL);
}
/* Enter SS1 :
* SLEEP + sleep operand
* __builtin_arc_sleep is not used here as it does not propagate sleep operand.
@ -107,16 +61,13 @@ void ss_power_soc_lpss_disable()
void ss_power_cpu_ss1(const ss_power_cpu_ss1_mode_t mode)
{
/* The sensor cannot be woken up with an edge triggered
* interrupt from the RTC and the AON Counter.
* interrupt from the RTC.
* Switch to Level triggered interrupts and restore
* the setting when waking up.
* the setting after when waking up.
*/
__builtin_arc_sr(QM_IRQ_RTC_0_VECTOR, QM_SS_AUX_IRQ_SELECT);
__builtin_arc_sr(QM_SS_IRQ_LEVEL_SENSITIVE, QM_SS_AUX_IRQ_TRIGGER);
__builtin_arc_sr(QM_IRQ_AONPT_0_VECTOR, QM_SS_AUX_IRQ_SELECT);
__builtin_arc_sr(QM_SS_IRQ_LEVEL_SENSITIVE, QM_SS_AUX_IRQ_TRIGGER);
/* Enter SS1 */
switch (mode) {
case SS_POWER_CPU_SS1_TIMER_OFF:
@ -133,12 +84,9 @@ void ss_power_cpu_ss1(const ss_power_cpu_ss1_mode_t mode)
break;
}
/* Restore the RTC and AONC to edge interrupt after when waking up. */
/* Restore the RTC to edge interrupt after when waking up. */
__builtin_arc_sr(QM_IRQ_RTC_0_VECTOR, QM_SS_AUX_IRQ_SELECT);
__builtin_arc_sr(QM_SS_IRQ_EDGE_SENSITIVE, QM_SS_AUX_IRQ_TRIGGER);
__builtin_arc_sr(QM_IRQ_AONPT_0_VECTOR, QM_SS_AUX_IRQ_SELECT);
__builtin_arc_sr(QM_SS_IRQ_EDGE_SENSITIVE, QM_SS_AUX_IRQ_TRIGGER);
}
/* Enter SS2 :
@ -148,25 +96,19 @@ void ss_power_cpu_ss1(const ss_power_cpu_ss1_mode_t mode)
void ss_power_cpu_ss2(void)
{
/* The sensor cannot be woken up with an edge triggered
* interrupt from the RTC and the AON Counter.
* interrupt from the RTC.
* Switch to Level triggered interrupts and restore
* the setting when waking up.
* the setting after when waking up.
*/
__builtin_arc_sr(QM_IRQ_RTC_0_VECTOR, QM_SS_AUX_IRQ_SELECT);
__builtin_arc_sr(QM_SS_IRQ_LEVEL_SENSITIVE, QM_SS_AUX_IRQ_TRIGGER);
__builtin_arc_sr(QM_IRQ_AONPT_0_VECTOR, QM_SS_AUX_IRQ_SELECT);
__builtin_arc_sr(QM_SS_IRQ_LEVEL_SENSITIVE, QM_SS_AUX_IRQ_TRIGGER);
/* Enter SS2 */
__asm__ __volatile__("sleep %0"
:
: "i"(QM_SS_SLEEP_MODE_CORE_TIMERS_RTC_OFF));
/* Restore the RTC and AONC to edge interrupt after when waking up. */
/* Restore the RTC to edge interrupt after when waking up. */
__builtin_arc_sr(QM_IRQ_RTC_0_VECTOR, QM_SS_AUX_IRQ_SELECT);
__builtin_arc_sr(QM_SS_IRQ_EDGE_SENSITIVE, QM_SS_AUX_IRQ_TRIGGER);
__builtin_arc_sr(QM_IRQ_AONPT_0_VECTOR, QM_SS_AUX_IRQ_SELECT);
__builtin_arc_sr(QM_SS_IRQ_EDGE_SENSITIVE, QM_SS_AUX_IRQ_TRIGGER);
}

View file

@ -253,7 +253,7 @@ void soc_watch_log_app_event(soc_watch_event_t event_id, uint8_t ev_subtype,
uintptr_t ev_data)
{
static uint8_t record_rtc = 0;
const uint32_t *rtc_ctr = (uint32_t *)&QM_RTC->rtc_ccvr;
const uint32_t *rtc_ctr = (uint32_t *)&QM_RTC->rtc_ccr;
const char *cp;
uint64_t tsc = __builtin_ia32_rdtsc(); /* Grab hi-res timestamp */
uint32_t rtc_val = *rtc_ctr;

View file

@ -32,7 +32,6 @@
#include "qm_comparator.h"
#include "qm_isr.h"
#include "qm_adc.h"
#include "qm_flash.h"
#include "rar.h"
#include "soc_watch.h"
@ -66,7 +65,6 @@ void power_soc_sleep(void)
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;
uint32_t flash_tmg_save = QM_FLASH[QM_FLASH_0]->tmg_ctrl;
/* Clear any pending interrupts. */
clear_all_pending_interrupts();
@ -134,18 +132,6 @@ void power_soc_sleep(void)
/* From here on, restore the SoC to an active state. */
/* Set the RAR to normal mode. */
rar_set_mode(RAR_NORMAL);
/*
* Since we are running below 4MHz, 0 wait states are configured.
* If the previous frequency was > 4MHz, 0 wait states will
* violate the flash timings.
* In the worst case scenario, when switching back to 32MHz,
* 2 wait states will be restored.
* This setting will be too conservative until the frequency has been
* restored.
*/
QM_FLASH[QM_FLASH_0]->tmg_ctrl = flash_tmg_save;
/* 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. */
@ -181,7 +167,6 @@ void power_soc_deep_sleep(const power_wake_event_t wake_event)
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 flash_tmg_save = QM_FLASH[QM_FLASH_0]->tmg_ctrl;
uint32_t ext_clock_save;
uint32_t lp_clk_save, pmux_slew_save;
@ -193,9 +178,9 @@ void power_soc_deep_sleep(const power_wake_event_t wake_event)
clear_all_pending_interrupts();
/*
* Clear the wake mask bits. Default behaviour is to wake from GPIO /
* comparator.
*/
* Clear the wake mask bits. Default behaviour is to wake from GPIO /
* comparator.
*/
switch (wake_event) {
case POWER_WAKE_FROM_RTC:
QM_SCSS_CCU->wake_mask =
@ -301,17 +286,6 @@ void power_soc_deep_sleep(const power_wake_event_t wake_event)
/* Set the RAR to normal mode. */
rar_set_mode(RAR_NORMAL);
/*
* Since we are running below 4MHz, 0 wait states are configured.
* If the previous frequency was > 4MHz, 0 wait states will
* violate the flash timings.
* In the worst case scenario, when switching back to 32MHz,
* 2 wait states will be restored.
* This setting will be too conservative until the frequency has been
* restored.
*/
QM_FLASH[QM_FLASH_0]->tmg_ctrl = flash_tmg_save;
/* Restore operating voltage to 1.8V. */
/* SCSS.AON_VR.VSEL = 0x10; */
QM_SCSS_PMU->aon_vr =

View file

@ -53,7 +53,7 @@ extern uint8_t test_flash_page[0x800];
#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_SOC_DATA_VALID (0x24535021) /**< $SP! */
#define QM_FLASH_OTP_TRIM_MAGIC (QM_FLASH_OTP_SOC_DATA_VALID)
typedef union {
@ -88,26 +88,26 @@ typedef union {
* Bootloader data
*/
/* The flash controller where BL-Data is stored. */
/** The flash controller where BL-Data is stored. */
#define BL_DATA_FLASH_CONTROLLER QM_FLASH_0
/* The flash region where BL-Data is stored. */
/** The flash region where BL-Data is stored. */
#define BL_DATA_FLASH_REGION QM_FLASH_REGION_DATA
/* The flash address where the BL-Data Section starts. */
/** The flash address where the BL-Data Section starts. */
#define BL_DATA_FLASH_REGION_BASE QM_FLASH_REGION_DATA_0_BASE
/* The flash page where the BL-Data Section starts. */
/** The flash page where the BL-Data Section starts. */
#define BL_DATA_SECTION_BASE_PAGE (0)
/* The size (in pages) of the System flash region of Quark D2000. */
/** The size (in pages) of the System flash region of Quark D2000. */
#define QM_FLASH_REGION_SYS_0_PAGES (16)
/* The size of each flash partition for Lakemont application code. */
/** The size of each flash partition for Lakemont application code. */
#if (BL_CONFIG_DUAL_BANK)
#define BL_PARTITION_SIZE_LMT (QM_FLASH_REGION_SYS_0_PAGES / 2)
#else /* !BL_CONFIG_DUAL_BANK */
#define BL_PARTITION_SIZE_LMT (QM_FLASH_REGION_SYS_0_PAGES)
#endif /* BL_CONFIG_DUAL_BANK */
/* Number of boot targets. */
/** Number of boot targets. */
#define BL_BOOT_TARGETS_NUM (1)
#define BL_TARGET_IDX_LMT (0)

View file

@ -86,7 +86,7 @@ void power_soc_sleep();
* enable waking from GPIO or comparator pins and POWER_WAKE_FROM_RTC will
* enable waking from the RTC.
*
* @param[in] wake_event Select wake source for deep sleep mode.
* @param[in] wake_source Select wake source for deep sleep mode.
*/
void power_soc_deep_sleep(const power_wake_event_t wake_event);

View file

@ -50,28 +50,28 @@
/** System Core register map. */
typedef struct {
QM_RW uint32_t osc0_cfg0; /**< Hybrid Oscillator Configuration 0. */
QM_RW uint32_t osc0_stat1; /**< Hybrid Oscillator status 1. */
QM_RW uint32_t osc0_cfg1; /**< Hybrid Oscillator configuration 1. */
QM_RW uint32_t osc1_stat0; /**< RTC Oscillator status 0. */
QM_RW uint32_t osc1_cfg0; /**< RTC Oscillator Configuration 0. */
QM_RW uint32_t osc0_cfg0; /**< Hybrid Oscillator Configuration 0 */
QM_RW uint32_t osc0_stat1; /**< Hybrid Oscillator status 1 */
QM_RW uint32_t osc0_cfg1; /**< Hybrid Oscillator configuration 1 */
QM_RW uint32_t osc1_stat0; /**< RTC Oscillator status 0 */
QM_RW uint32_t osc1_cfg0; /**< RTC Oscillator Configuration 0 */
QM_RW uint32_t reserved;
QM_RW uint32_t
ccu_periph_clk_gate_ctl; /**< Peripheral Clock Gate Control. */
ccu_periph_clk_gate_ctl; /**< Peripheral Clock Gate Control */
QM_RW uint32_t
ccu_periph_clk_div_ctl0; /**< Peripheral Clock Divider Control 0. */
ccu_periph_clk_div_ctl0; /**< Peripheral Clock Divider Control 0 */
QM_RW uint32_t
ccu_gpio_db_clk_ctl; /**< Peripheral Clock Divider Control 1. */
ccu_gpio_db_clk_ctl; /**< Peripheral Clock Divider Control 1 */
QM_RW uint32_t
ccu_ext_clock_ctl; /**< External Clock Control Register. */
ccu_ext_clock_ctl; /**< External Clock Control Register */
QM_RW uint32_t reserved1;
QM_RW uint32_t ccu_lp_clk_ctl; /**< System Low Power Clock Control. */
QM_RW uint32_t wake_mask; /**< Wake Mask register. */
QM_RW uint32_t ccu_mlayer_ahb_ctl; /**< AHB Control Register. */
QM_RW uint32_t ccu_sys_clk_ctl; /**< System Clock Control Register. */
QM_RW uint32_t osc_lock_0; /**< Clocks Lock Register. */
QM_RW uint32_t soc_ctrl; /**< SoC Control Register. */
QM_RW uint32_t soc_ctrl_lock; /**< SoC Control Register Lock. */
QM_RW uint32_t ccu_lp_clk_ctl; /**< System Low Power Clock Control */
QM_RW uint32_t wake_mask; /**< Wake Mask register */
QM_RW uint32_t ccu_mlayer_ahb_ctl; /**< AHB Control Register */
QM_RW uint32_t ccu_sys_clk_ctl; /**< System Clock Control Register */
QM_RW uint32_t osc_lock_0; /**< Clocks Lock Register */
QM_RW uint32_t soc_ctrl; /**< SoC Control Register */
QM_RW uint32_t soc_ctrl_lock; /**< SoC Control Register Lock */
} qm_scss_ccu_reg_t;
#if (UNIT_TEST)
@ -109,11 +109,11 @@ qm_scss_ccu_reg_t test_scss_ccu;
#define QM_SI_OSC_1V2_MODE BIT(0)
/* Peripheral clock divider control. */
/** Peripheral clock divider control */
#define QM_CCU_PERIPH_PCLK_DIV_OFFSET (1)
#define QM_CCU_PERIPH_PCLK_DIV_EN BIT(0)
/* System clock control. */
/* System clock control */
#define QM_CCU_SYS_CLK_SEL BIT(0)
#define QM_CCU_PERIPH_CLK_EN BIT(1)
#define QM_CCU_ADC_CLK_DIV_OFFSET (16)
@ -161,19 +161,19 @@ qm_scss_ccu_reg_t test_scss_ccu;
/** General Purpose register map. */
typedef struct {
QM_RW uint32_t gps0; /**< General Purpose Sticky Register 0. */
QM_RW uint32_t gps1; /**< General Purpose Sticky Register 1. */
QM_RW uint32_t gps2; /**< General Purpose Sticky Register 2. */
QM_RW uint32_t gps3; /**< General Purpose Sticky Register 3. */
QM_RW uint32_t gps0; /**< General Purpose Sticky Register 0 */
QM_RW uint32_t gps1; /**< General Purpose Sticky Register 1 */
QM_RW uint32_t gps2; /**< General Purpose Sticky Register 2 */
QM_RW uint32_t gps3; /**< General Purpose Sticky Register 3 */
QM_RW uint32_t reserved;
QM_RW uint32_t gp0; /**< General Purpose Scratchpad Register 0. */
QM_RW uint32_t gp1; /**< General Purpose Scratchpad Register 1. */
QM_RW uint32_t gp2; /**< General Purpose Scratchpad Register 2. */
QM_RW uint32_t gp3; /**< General Purpose Scratchpad Register 3. */
QM_RW uint32_t gp0; /**< General Purpose Scratchpad Register 0 */
QM_RW uint32_t gp1; /**< General Purpose Scratchpad Register 1 */
QM_RW uint32_t gp2; /**< General Purpose Scratchpad Register 2 */
QM_RW uint32_t gp3; /**< General Purpose Scratchpad Register 3 */
QM_RW uint32_t reserved1[3];
QM_RW uint32_t wo_sp; /**< Write-One-to-Set Scratchpad Register. */
QM_RW uint32_t wo_sp; /**< Write-One-to-Set Scratchpad Register */
QM_RW uint32_t
wo_st; /**< Write-One-to-Set Sticky Scratchpad Register. */
wo_st; /**< Write-One-to-Set Sticky Scratchpad Register */
} qm_scss_gp_reg_t;
#if (UNIT_TEST)
@ -226,48 +226,46 @@ qm_scss_cmp_reg_t test_scss_cmp;
/** Interrupt register map. */
typedef struct {
QM_RW uint32_t int_i2c_mst_0_mask; /**< Interrupt Routing Mask 0. */
QM_RW uint32_t int_i2c_mst_0_mask; /**< Interrupt Routing Mask 0 */
QM_RW uint32_t reserved[2]; /* There is a hole in the address space. */
QM_RW uint32_t int_spi_mst_0_mask; /**< Interrupt Routing Mask 2. */
QM_RW uint32_t int_spi_mst_0_mask; /**< Interrupt Routing Mask 2 */
QM_RW uint32_t reserved1;
QM_RW uint32_t int_spi_slv_0_mask; /**< Interrupt Routing Mask 4. */
QM_RW uint32_t int_uart_0_mask; /**< Interrupt Routing Mask 5. */
QM_RW uint32_t int_uart_1_mask; /**< Interrupt Routing Mask 6. */
QM_RW uint32_t int_spi_slv_0_mask; /**< Interrupt Routing Mask 4 */
QM_RW uint32_t int_uart_0_mask; /**< Interrupt Routing Mask 5 */
QM_RW uint32_t int_uart_1_mask; /**< Interrupt Routing Mask 6 */
QM_RW uint32_t reserved2;
QM_RW uint32_t int_gpio_mask; /**< Interrupt Routing Mask 8. */
QM_RW uint32_t int_timer_mask; /**< Interrupt Routing Mask 9. */
QM_RW uint32_t int_gpio_mask; /**< Interrupt Routing Mask 8 */
QM_RW uint32_t int_timer_mask; /**< Interrupt Routing Mask 9 */
QM_RW uint32_t reserved3;
QM_RW uint32_t int_rtc_mask; /**< Interrupt Routing Mask 11. */
QM_RW uint32_t int_watchdog_mask; /**< Interrupt Routing Mask 12. */
QM_RW uint32_t
int_dma_channel_0_mask; /**< Interrupt Routing Mask 13. */
QM_RW uint32_t
int_dma_channel_1_mask; /**< Interrupt Routing Mask 14. */
QM_RW uint32_t int_rtc_mask; /**< Interrupt Routing Mask 11 */
QM_RW uint32_t int_watchdog_mask; /**< Interrupt Routing Mask 12 */
QM_RW uint32_t int_dma_channel_0_mask; /**< Interrupt Routing Mask 13 */
QM_RW uint32_t int_dma_channel_1_mask; /**< Interrupt Routing Mask 14 */
QM_RW uint32_t reserved4[8];
QM_RW uint32_t
int_comparators_host_halt_mask; /**< Interrupt Routing Mask 23. */
int_comparators_host_halt_mask; /**< Interrupt Routing Mask 23 */
QM_RW uint32_t reserved5;
QM_RW uint32_t
int_comparators_host_mask; /**< Interrupt Routing Mask 25. */
QM_RW uint32_t int_host_bus_err_mask; /**< Interrupt Routing Mask 26. */
QM_RW uint32_t int_dma_error_mask; /**< Interrupt Routing Mask 27. */
int_comparators_host_mask; /**< Interrupt Routing Mask 25 */
QM_RW uint32_t int_host_bus_err_mask; /**< Interrupt Routing Mask 26 */
QM_RW uint32_t int_dma_error_mask; /**< Interrupt Routing Mask 27 */
QM_RW uint32_t
int_sram_controller_mask; /**< Interrupt Routing Mask 28. */
int_sram_controller_mask; /**< Interrupt Routing Mask 28 */
QM_RW uint32_t
int_flash_controller_0_mask; /**< Interrupt Routing Mask 29. */
int_flash_controller_0_mask; /**< Interrupt Routing Mask 29 */
QM_RW uint32_t reserved6;
QM_RW uint32_t int_aon_timer_mask; /**< Interrupt Routing Mask 31. */
QM_RW uint32_t int_adc_pwr_mask; /**< Interrupt Routing Mask 32. */
QM_RW uint32_t int_adc_calib_mask; /**< Interrupt Routing Mask 33. */
QM_RW uint32_t int_aon_timer_mask; /**< Interrupt Routing Mask 31 */
QM_RW uint32_t int_adc_pwr_mask; /**< Interrupt Routing Mask 32 */
QM_RW uint32_t int_adc_calib_mask; /**< Interrupt Routing Mask 33 */
QM_RW uint32_t reserved7;
QM_RW uint32_t lock_int_mask_reg; /**< Interrupt Mask Lock Register. */
QM_RW uint32_t lock_int_mask_reg; /**< Interrupt Mask Lock Register */
} qm_scss_int_reg_t;
/* Number of SCSS interrupt mask registers (excluding mask lock register). */
/** Number of SCSS interrupt mask registers (excluding mask lock register) */
#define QM_SCSS_INT_MASK_NUMREG \
((sizeof(qm_scss_int_reg_t) / sizeof(uint32_t)) - 1)
/* Default POR SCSS interrupt mask (all interrupts masked). */
/** Default POR SCSS interrupt mask (all interrupts masked) */
#define QM_SCSS_INT_MASK_DEFAULT (0xFFFFFFFF)
#if (UNIT_TEST)
@ -294,16 +292,16 @@ qm_scss_int_reg_t test_scss_int;
/** Power Management register map. */
typedef struct {
QM_RW uint32_t aon_vr; /**< AON Voltage Regulator. */
QM_RW uint32_t aon_vr; /**< AON Voltage Regulator */
QM_RW uint32_t reserved[5];
QM_RW uint32_t pm_wait; /**< Power Management Wait. */
QM_RW uint32_t pm_wait; /**< Power Management Wait */
QM_RW uint32_t reserved1;
QM_RW uint32_t p_sts; /**< Processor Status. */
QM_RW uint32_t p_sts; /**< Processor Status */
QM_RW uint32_t reserved2[3];
QM_RW uint32_t rstc; /**< Reset Control. */
QM_RW uint32_t rsts; /**< Reset Status. */
QM_RW uint32_t rstc; /**< Reset Control */
QM_RW uint32_t rsts; /**< Reset Status */
QM_RW uint32_t reserved3[7];
QM_RW uint32_t pm_lock; /**< Power Management Lock. */
QM_RW uint32_t pm_lock; /**< Power Management Lock */
} qm_scss_pmu_reg_t;
#if (UNIT_TEST)
@ -365,9 +363,9 @@ qm_scss_aon_reg_t test_scss_aon;
/** Peripheral Registers register map. */
typedef struct {
QM_RW uint32_t periph_cfg0; /**< Peripheral Configuration. */
QM_RW uint32_t periph_cfg0; /**< Peripheral Configuration */
QM_RW uint32_t reserved[2];
QM_RW uint32_t cfg_lock; /**< Configuration Lock. */
QM_RW uint32_t cfg_lock; /**< Configuration Lock */
} qm_scss_peripheral_reg_t;
#if (UNIT_TEST)
@ -388,19 +386,19 @@ qm_scss_peripheral_reg_t test_scss_peripheral;
/** Pin MUX register map. */
typedef struct {
QM_RW uint32_t pmux_pullup[1]; /**< Pin Mux Pullup. */
QM_RW uint32_t pmux_pullup[1]; /**< Pin Mux Pullup */
QM_RW uint32_t reserved[3];
QM_RW uint32_t pmux_slew[1]; /**< Pin Mux Slew Rate. */
QM_RW uint32_t pmux_slew[1]; /**< Pin Mux Slew Rate */
QM_RW uint32_t reserved1[3];
QM_RW uint32_t pmux_in_en[1]; /**< Pin Mux Input Enable. */
QM_RW uint32_t pmux_in_en[1]; /**< Pin Mux Input Enable */
QM_RW uint32_t reserved2[3];
QM_RW uint32_t pmux_sel[2]; /**< Pin Mux Select. */
QM_RW uint32_t pmux_sel[2]; /**< Pin Mux Select */
QM_RW uint32_t reserved3[5];
QM_RW uint32_t pmux_pullup_lock; /**< Pin Mux Pullup Lock. */
QM_RW uint32_t pmux_slew_lock; /**< Pin Mux Slew Rate Lock. */
QM_RW uint32_t pmux_sel_0_lock; /**< Pin Mux Select Lock 0. */
QM_RW uint32_t pmux_pullup_lock; /**< Pin Mux Pullup Lock */
QM_RW uint32_t pmux_slew_lock; /**< Pin Mux Slew Rate Lock */
QM_RW uint32_t pmux_sel_0_lock; /**< Pin Mux Select Lock 0 */
QM_RW uint32_t reserved4[2];
QM_RW uint32_t pmux_in_en_lock; /**< Pin Mux Slew Rate Lock. */
QM_RW uint32_t pmux_in_en_lock; /**< Pin Mux Slew Rate Lock */
} qm_scss_pmux_reg_t;
#if (UNIT_TEST)
@ -421,12 +419,12 @@ qm_scss_pmux_reg_t test_scss_pmux;
/** Information register map. */
typedef struct {
QM_RW uint32_t id; /**< Identification Register. */
QM_RW uint32_t rev; /**< Revision Register. */
QM_RW uint32_t fs; /**< Flash Size Register. */
QM_RW uint32_t rs; /**< RAM Size Register. */
QM_RW uint32_t cotps; /**< Code OTP Size Register. */
QM_RW uint32_t dotps; /**< Data OTP Size Register. */
QM_RW uint32_t id; /**< Identification Register */
QM_RW uint32_t rev; /**< Revision Register */
QM_RW uint32_t fs; /**< Flash Size Register */
QM_RW uint32_t rs; /**< RAM Size Register */
QM_RW uint32_t cotps; /**< Code OTP Size Register */
QM_RW uint32_t dotps; /**< Data OTP Size Register */
} qm_scss_info_reg_t;
#if (UNIT_TEST)
@ -541,16 +539,16 @@ typedef enum { QM_PWM_ID_0 = 0, QM_PWM_ID_1, QM_PWM_ID_NUM } qm_pwm_id_t;
/** PWM / Timer channel register map. */
typedef struct {
QM_RW uint32_t loadcount; /**< Load Coun.t */
QM_RW uint32_t currentvalue; /**< Current Value. */
QM_RW uint32_t controlreg; /**< Control. */
QM_RW uint32_t eoi; /**< End Of Interrupt. */
QM_RW uint32_t intstatus; /**< Interrupt Status. */
QM_RW uint32_t loadcount; /**< Load Count */
QM_RW uint32_t currentvalue; /**< Current Value */
QM_RW uint32_t controlreg; /**< Control */
QM_RW uint32_t eoi; /**< End Of Interrupt */
QM_RW uint32_t intstatus; /**< Interrupt Status */
} qm_pwm_channel_t;
/** PWM / Timer register map. */
typedef struct {
qm_pwm_channel_t timer[QM_PWM_ID_NUM]; /**< 2 Timers. */
qm_pwm_channel_t timer[QM_PWM_ID_NUM]; /**< 4 Timers */
QM_RW uint32_t reserved[30];
QM_RW uint32_t timersintstatus; /**< Timers Interrupt Status */
QM_RW uint32_t timerseoi; /**< Timers End Of Interrupt */
@ -564,9 +562,9 @@ qm_pwm_reg_t test_pwm_t;
#define QM_PWM ((qm_pwm_reg_t *)(&test_pwm_t))
#else
/* PWM register base address. */
/** PWM register base address */
#define QM_PWM_BASE (0xB0000800)
/* PWM register block. */
/** PWM register block */
#define QM_PWM ((qm_pwm_reg_t *)QM_PWM_BASE)
#endif
@ -584,20 +582,20 @@ typedef enum { QM_WDT_0 = 0, QM_WDT_NUM } qm_wdt_t;
/** Watchdog timer register map. */
typedef struct {
QM_RW uint32_t wdt_cr; /**< Control Register. */
QM_RW uint32_t wdt_torr; /**< Timeout Range Register. */
QM_RW uint32_t wdt_ccvr; /**< Current Counter Value Register. */
QM_RW uint32_t wdt_crr; /**< Current Restart Register. */
QM_RW uint32_t wdt_stat; /**< Interrupt Status Register. */
QM_RW uint32_t wdt_eoi; /**< Interrupt Clear Register. */
QM_RW uint32_t wdt_comp_param_5; /**< Component Parameters. */
QM_RW uint32_t wdt_comp_param_4; /**< Component Parameters. */
QM_RW uint32_t wdt_comp_param_3; /**< Component Parameters. */
QM_RW uint32_t wdt_comp_param_2; /**< Component Parameters. */
QM_RW uint32_t wdt_cr; /**< Control Register */
QM_RW uint32_t wdt_torr; /**< Timeout Range Register */
QM_RW uint32_t wdt_ccvr; /**< Current Counter Value Register */
QM_RW uint32_t wdt_crr; /**< Current Restart Register */
QM_RW uint32_t wdt_stat; /**< Interrupt Status Register */
QM_RW uint32_t wdt_eoi; /**< Interrupt Clear Register */
QM_RW uint32_t wdt_comp_param_5; /**< Component Parameters */
QM_RW uint32_t wdt_comp_param_4; /**< Component Parameters */
QM_RW uint32_t wdt_comp_param_3; /**< Component Parameters */
QM_RW uint32_t wdt_comp_param_2; /**< Component Parameters */
QM_RW uint32_t
wdt_comp_param_1; /**< Component Parameters Register 1. */
QM_RW uint32_t wdt_comp_version; /**< Component Version Register. */
QM_RW uint32_t wdt_comp_type; /**< Component Type Register. */
wdt_comp_param_1; /**< Component Parameters Register 1 */
QM_RW uint32_t wdt_comp_version; /**< Component Version Register */
QM_RW uint32_t wdt_comp_type; /**< Component Type Register */
} qm_wdt_reg_t;
#if (UNIT_TEST)
@ -605,10 +603,10 @@ qm_wdt_reg_t test_wdt;
#define QM_WDT ((qm_wdt_reg_t *)(&test_wdt))
#else
/* WDT register base address. */
/** WDT register base address */
#define QM_WDT_BASE (0xB0000000)
/* WDT register block. */
/** WDT register block */
#define QM_WDT ((qm_wdt_reg_t *)QM_WDT_BASE)
#endif
@ -624,29 +622,28 @@ typedef enum { QM_UART_0 = 0, QM_UART_1, QM_UART_NUM } qm_uart_t;
/** UART register map. */
typedef struct {
QM_RW uint32_t
rbr_thr_dll; /**< Rx Buffer/ Tx Holding/ Div Latch Low. */
QM_RW uint32_t ier_dlh; /**< Interrupt Enable / Divisor Latch High. */
QM_RW uint32_t iir_fcr; /**< Interrupt Identification / FIFO Control. */
QM_RW uint32_t lcr; /**< Line Control. */
QM_RW uint32_t mcr; /**< MODEM Control. */
QM_RW uint32_t lsr; /**< Line Status. */
QM_RW uint32_t msr; /**< MODEM Status. */
QM_RW uint32_t scr; /**< Scratchpad. */
QM_RW uint32_t rbr_thr_dll; /**< Rx Buffer/ Tx Holding/ Div Latch Low */
QM_RW uint32_t ier_dlh; /**< Interrupt Enable / Divisor Latch High */
QM_RW uint32_t iir_fcr; /**< Interrupt Identification / FIFO Control */
QM_RW uint32_t lcr; /**< Line Control */
QM_RW uint32_t mcr; /**< MODEM Control */
QM_RW uint32_t lsr; /**< Line Status */
QM_RW uint32_t msr; /**< MODEM Status */
QM_RW uint32_t scr; /**< Scratchpad */
QM_RW uint32_t reserved[23];
QM_RW uint32_t usr; /**< UART Status. */
QM_RW uint32_t usr; /**< UART Status */
QM_RW uint32_t reserved1[9];
QM_RW uint32_t htx; /**< Halt Transmission. */
QM_RW uint32_t dmasa; /**< DMA Software Acknowledge. */
QM_RW uint32_t tcr; /**< Transceiver Control Register. */
QM_RW uint32_t de_en; /**< Driver Output Enable Register. */
QM_RW uint32_t re_en; /**< Receiver Output Enable Register. */
QM_RW uint32_t det; /**< Driver Output Enable Timing Register. */
QM_RW uint32_t tat; /**< TurnAround Timing Register. */
QM_RW uint32_t dlf; /**< Divisor Latch Fraction. */
QM_RW uint32_t rar; /**< Receive Address Register. */
QM_RW uint32_t tar; /**< Transmit Address Register. */
QM_RW uint32_t lcr_ext; /**< Line Extended Control Register. */
QM_RW uint32_t htx; /**< Halt Transmission */
QM_RW uint32_t dmasa; /**< DMA Software Acknowledge */
QM_RW uint32_t tcr; /**< Transceiver Control Register */
QM_RW uint32_t de_en; /**< Driver Output Enable Register */
QM_RW uint32_t re_en; /**< Receiver Output Enable Register */
QM_RW uint32_t det; /**< Driver Output Enable Timing Register */
QM_RW uint32_t tat; /**< TurnAround Timing Register */
QM_RW uint32_t dlf; /**< Divisor Latch Fraction */
QM_RW uint32_t rar; /**< Receive Address Register */
QM_RW uint32_t tar; /**< Transmit Address Register */
QM_RW uint32_t lcr_ext; /**< Line Extended Control Register */
QM_RW uint32_t padding[204]; /* 0x400 - 0xD0 */
} qm_uart_reg_t;
@ -656,10 +653,10 @@ qm_uart_reg_t *test_uart[QM_UART_NUM];
#define QM_UART test_uart
#else
/* UART register base address. */
/** UART register base address */
#define QM_UART_0_BASE (0xB0002000)
#define QM_UART_1_BASE (0xB0002400)
/* UART register block. */
/** UART register block */
extern qm_uart_reg_t *qm_uart[QM_UART_NUM];
#define QM_UART qm_uart
#endif
@ -676,35 +673,32 @@ typedef enum { QM_SPI_MST_0 = 0, QM_SPI_SLV_0 = 1, QM_SPI_NUM } qm_spi_t;
/** SPI register map. */
typedef struct {
QM_RW uint32_t ctrlr0; /**< Control Register 0. */
QM_RW uint32_t ctrlr1; /**< Control Register 1. */
QM_RW uint32_t ssienr; /**< SSI Enable Register. */
QM_RW uint32_t mwcr; /**< Microwire Control Register. */
QM_RW uint32_t ser; /**< Slave Enable Register. */
QM_RW uint32_t baudr; /**< Baud Rate Select. */
QM_RW uint32_t txftlr; /**< Transmit FIFO Threshold Level. */
QM_RW uint32_t rxftlr; /**< Receive FIFO Threshold Level. */
QM_RW uint32_t txflr; /**< Transmit FIFO Level Register. */
QM_RW uint32_t rxflr; /**< Receive FIFO Level Register. */
QM_RW uint32_t sr; /**< Status Register. */
QM_RW uint32_t imr; /**< Interrupt Mask Register. */
QM_RW uint32_t isr; /**< Interrupt Status Register. */
QM_RW uint32_t risr; /**< Raw Interrupt Status Register. */
QM_RW uint32_t
txoicr; /**< Tx FIFO Overflow Interrupt Clear Register. */
QM_RW uint32_t
rxoicr; /**< Rx FIFO Overflow Interrupt Clear Register. */
QM_RW uint32_t
rxuicr; /**< Rx FIFO Underflow Interrupt Clear Register. */
QM_RW uint32_t msticr; /**< Multi-Master Interrupt Clear Register. */
QM_RW uint32_t icr; /**< Interrupt Clear Register. */
QM_RW uint32_t dmacr; /**< DMA Control Register. */
QM_RW uint32_t dmatdlr; /**< DMA Transmit Data Level. */
QM_RW uint32_t dmardlr; /**< DMA Receive Data Level. */
QM_RW uint32_t idr; /**< Identification Register. */
QM_RW uint32_t ssi_comp_version; /**< coreKit Version ID register. */
QM_RW uint32_t dr[36]; /**< Data Register. */
QM_RW uint32_t rx_sample_dly; /**< RX Sample Delay Register. */
QM_RW uint32_t ctrlr0; /**< Control Register 0 */
QM_RW uint32_t ctrlr1; /**< Control Register 1 */
QM_RW uint32_t ssienr; /**< SSI Enable Register */
QM_RW uint32_t mwcr; /**< Microwire Control Register */
QM_RW uint32_t ser; /**< Slave Enable Register */
QM_RW uint32_t baudr; /**< Baud Rate Select */
QM_RW uint32_t txftlr; /**< Transmit FIFO Threshold Level */
QM_RW uint32_t rxftlr; /**< Receive FIFO Threshold Level */
QM_RW uint32_t txflr; /**< Transmit FIFO Level Register */
QM_RW uint32_t rxflr; /**< Receive FIFO Level Register */
QM_RW uint32_t sr; /**< Status Register */
QM_RW uint32_t imr; /**< Interrupt Mask Register */
QM_RW uint32_t isr; /**< Interrupt Status Register */
QM_RW uint32_t risr; /**< Raw Interrupt Status Register */
QM_RW uint32_t txoicr; /**< Tx FIFO Overflow Interrupt Clear Register*/
QM_RW uint32_t rxoicr; /**< Rx FIFO Overflow Interrupt Clear Register */
QM_RW uint32_t rxuicr; /**< Rx FIFO Underflow Interrupt Clear Register*/
QM_RW uint32_t msticr; /**< Multi-Master Interrupt Clear Register */
QM_RW uint32_t icr; /**< Interrupt Clear Register */
QM_RW uint32_t dmacr; /**< DMA Control Register */
QM_RW uint32_t dmatdlr; /**< DMA Transmit Data Level */
QM_RW uint32_t dmardlr; /**< DMA Receive Data Level */
QM_RW uint32_t idr; /**< Identification Register */
QM_RW uint32_t ssi_comp_version; /**< coreKit Version ID register */
QM_RW uint32_t dr[36]; /**< Data Register */
QM_RW uint32_t rx_sample_dly; /**< RX Sample Delay Register */
QM_RW uint32_t padding[0x1C4]; /* (0x800 - 0xF0) / 4 */
} qm_spi_reg_t;
@ -715,12 +709,12 @@ qm_spi_reg_t *test_spi_controllers[QM_SPI_NUM];
#define QM_SPI test_spi_controllers
#else
/* SPI Master register base address. */
/** SPI Master register base address */
#define QM_SPI_MST_0_BASE (0xB0001000)
extern qm_spi_reg_t *qm_spi_controllers[QM_SPI_NUM];
#define QM_SPI qm_spi_controllers
/* SPI Slave register base address. */
/** SPI Slave register base address */
#define QM_SPI_SLV_BASE (0xB0001800)
#endif
@ -782,14 +776,14 @@ typedef enum { QM_RTC_0 = 0, QM_RTC_NUM } qm_rtc_t;
/** RTC register map. */
typedef struct {
QM_RW uint32_t rtc_ccvr; /**< Current Counter Value Register. */
QM_RW uint32_t rtc_cmr; /**< Current Match Register. */
QM_RW uint32_t rtc_clr; /**< Counter Load Register. */
QM_RW uint32_t rtc_ccr; /**< Counter Control Register. */
QM_RW uint32_t rtc_stat; /**< Interrupt Status Register. */
QM_RW uint32_t rtc_rstat; /**< Interrupt Raw Status Register. */
QM_RW uint32_t rtc_eoi; /**< End of Interrupt Register. */
QM_RW uint32_t rtc_comp_version; /**< End of Interrupt Register. */
QM_RW uint32_t rtc_ccvr; /**< Current Counter Value Register */
QM_RW uint32_t rtc_cmr; /**< Current Match Register */
QM_RW uint32_t rtc_clr; /**< Counter Load Register */
QM_RW uint32_t rtc_ccr; /**< Counter Control Register */
QM_RW uint32_t rtc_stat; /**< Interrupt Status Register */
QM_RW uint32_t rtc_rstat; /**< Interrupt Raw Status Register */
QM_RW uint32_t rtc_eoi; /**< End of Interrupt Register */
QM_RW uint32_t rtc_comp_version; /**< End of Interrupt Register */
} qm_rtc_reg_t;
#if (UNIT_TEST)
@ -797,10 +791,10 @@ qm_rtc_reg_t test_rtc;
#define QM_RTC ((qm_rtc_reg_t *)(&test_rtc))
#else
/* RTC register base address. */
/** RTC register base address. */
#define QM_RTC_BASE (0xB0000400)
/* RTC register block. */
/** RTC register block. */
#define QM_RTC ((qm_rtc_reg_t *)QM_RTC_BASE)
#endif
@ -816,60 +810,60 @@ typedef enum { QM_I2C_0 = 0, QM_I2C_NUM } qm_i2c_t;
/** I2C register map. */
typedef struct {
QM_RW uint32_t ic_con; /**< Control Register. */
QM_RW uint32_t ic_tar; /**< Master Target Address. */
QM_RW uint32_t ic_sar; /**< Slave Address. */
QM_RW uint32_t ic_hs_maddr; /**< High Speed Master ID. */
QM_RW uint32_t ic_data_cmd; /**< Data Buffer and Command. */
QM_RW uint32_t ic_con; /**< Control Register */
QM_RW uint32_t ic_tar; /**< Master Target Address */
QM_RW uint32_t ic_sar; /**< Slave Address */
QM_RW uint32_t ic_hs_maddr; /**< High Speed Master ID */
QM_RW uint32_t ic_data_cmd; /**< Data Buffer and Command */
QM_RW uint32_t
ic_ss_scl_hcnt; /**< Standard Speed Clock SCL High Count. */
ic_ss_scl_hcnt; /**< Standard Speed Clock SCL High Count */
QM_RW uint32_t
ic_ss_scl_lcnt; /**< Standard Speed Clock SCL Low Count. */
QM_RW uint32_t ic_fs_scl_hcnt; /**< Fast Speed Clock SCL High Count. */
ic_ss_scl_lcnt; /**< Standard Speed Clock SCL Low Count */
QM_RW uint32_t ic_fs_scl_hcnt; /**< Fast Speed Clock SCL High Count */
QM_RW uint32_t
ic_fs_scl_lcnt; /**< Fast Speed I2C Clock SCL Low Count. */
ic_fs_scl_lcnt; /**< Fast Speed I2C Clock SCL Low Count */
QM_RW uint32_t
ic_hs_scl_hcnt; /**< High Speed I2C Clock SCL High Count. */
ic_hs_scl_hcnt; /**< High Speed I2C Clock SCL High Count */
QM_RW uint32_t
ic_hs_scl_lcnt; /**< High Speed I2C Clock SCL Low Count. */
QM_RW uint32_t ic_intr_stat; /**< Interrupt Status. */
QM_RW uint32_t ic_intr_mask; /**< Interrupt Mask. */
QM_RW uint32_t ic_raw_intr_stat; /**< Raw Interrupt Status. */
QM_RW uint32_t ic_rx_tl; /**< Receive FIFO Threshold Level. */
QM_RW uint32_t ic_tx_tl; /**< Transmit FIFO Threshold Level. */
ic_hs_scl_lcnt; /**< High Speed I2C Clock SCL Low Count */
QM_RW uint32_t ic_intr_stat; /**< Interrupt Status */
QM_RW uint32_t ic_intr_mask; /**< Interrupt Mask */
QM_RW uint32_t ic_raw_intr_stat; /**< Raw Interrupt Status */
QM_RW uint32_t ic_rx_tl; /**< Receive FIFO Threshold Level */
QM_RW uint32_t ic_tx_tl; /**< Transmit FIFO Threshold Level */
QM_RW uint32_t
ic_clr_intr; /**< Clear Combined and Individual Interrupt. */
QM_RW uint32_t ic_clr_rx_under; /**< Clear RX_UNDER Interrupt. */
QM_RW uint32_t ic_clr_rx_over; /**< Clear RX_OVER Interrupt. */
QM_RW uint32_t ic_clr_tx_over; /**< Clear TX_OVER Interrupt. */
QM_RW uint32_t ic_clr_rd_req; /**< Clear RD_REQ Interrupt. */
QM_RW uint32_t ic_clr_tx_abrt; /**< Clear TX_ABRT Interrupt. */
QM_RW uint32_t ic_clr_rx_done; /**< Clear RX_DONE Interrupt. */
QM_RW uint32_t ic_clr_activity; /**< Clear ACTIVITY Interrupt. */
QM_RW uint32_t ic_clr_stop_det; /**< Clear STOP_DET Interrupt. */
QM_RW uint32_t ic_clr_start_det; /**< Clear START_DET Interrupt. */
QM_RW uint32_t ic_clr_gen_call; /**< Clear GEN_CALL Interrupt. */
QM_RW uint32_t ic_enable; /**< Enable. */
QM_RW uint32_t ic_status; /**< Status. */
QM_RW uint32_t ic_txflr; /**< Transmit FIFO Level. */
QM_RW uint32_t ic_rxflr; /**< Receive FIFO Level. */
QM_RW uint32_t ic_sda_hold; /**< SDA Hold. */
QM_RW uint32_t ic_tx_abrt_source; /**< Transmit Abort Source. */
ic_clr_intr; /**< Clear Combined and Individual Interrupt */
QM_RW uint32_t ic_clr_rx_under; /**< Clear RX_UNDER Interrupt */
QM_RW uint32_t ic_clr_rx_over; /**< Clear RX_OVER Interrupt */
QM_RW uint32_t ic_clr_tx_over; /**< Clear TX_OVER Interrupt */
QM_RW uint32_t ic_clr_rd_req; /**< Clear RD_REQ Interrupt */
QM_RW uint32_t ic_clr_tx_abrt; /**< Clear TX_ABRT Interrupt */
QM_RW uint32_t ic_clr_rx_done; /**< Clear RX_DONE Interrupt */
QM_RW uint32_t ic_clr_activity; /**< Clear ACTIVITY Interrupt */
QM_RW uint32_t ic_clr_stop_det; /**< Clear STOP_DET Interrupt */
QM_RW uint32_t ic_clr_start_det; /**< Clear START_DET Interrupt */
QM_RW uint32_t ic_clr_gen_call; /**< Clear GEN_CALL Interrupt */
QM_RW uint32_t ic_enable; /**< Enable */
QM_RW uint32_t ic_status; /**< Status */
QM_RW uint32_t ic_txflr; /**< Transmit FIFO Level */
QM_RW uint32_t ic_rxflr; /**< Receive FIFO Level */
QM_RW uint32_t ic_sda_hold; /**< SDA Hold */
QM_RW uint32_t ic_tx_abrt_source; /**< Transmit Abort Source */
QM_RW uint32_t reserved;
QM_RW uint32_t ic_dma_cr; /**< SDA Setup. */
QM_RW uint32_t ic_dma_tdlr; /**< DMA Transmit Data Level Register. */
QM_RW uint32_t ic_dma_rdlr; /**< I2C Receive Data Level Register. */
QM_RW uint32_t ic_sda_setup; /**< SDA Setup. */
QM_RW uint32_t ic_ack_general_call; /**< General Call Ack. */
QM_RW uint32_t ic_enable_status; /**< Enable Status. */
QM_RW uint32_t ic_fs_spklen; /**< SS and FS Spike Suppression Limit. */
QM_RW uint32_t ic_hs_spklen; /**< HS spike suppression limit. */
QM_RW uint32_t ic_dma_cr; /**< SDA Setup */
QM_RW uint32_t ic_dma_tdlr; /**< DMA Transmit Data Level Register */
QM_RW uint32_t ic_dma_rdlr; /**< I2C Receive Data Level Register */
QM_RW uint32_t ic_sda_setup; /**< SDA Setup */
QM_RW uint32_t ic_ack_general_call; /**< General Call Ack */
QM_RW uint32_t ic_enable_status; /**< Enable Status */
QM_RW uint32_t ic_fs_spklen; /**< SS and FS Spike Suppression Limit */
QM_RW uint32_t ic_hs_spklen; /**< HS spike suppression limit */
QM_RW uint32_t
ic_clr_restart_det; /**< clear the RESTART_DET interrupt. */
ic_clr_restart_det; /**< clear the RESTART_DET interrupt */
QM_RW uint32_t reserved1[18];
QM_RW uint32_t ic_comp_param_1; /**< Configuration Parameters. */
QM_RW uint32_t ic_comp_version; /**< Component Version. */
QM_RW uint32_t ic_comp_type; /**< Component Type. */
QM_RW uint32_t ic_comp_param_1; /**< Configuration Parameters */
QM_RW uint32_t ic_comp_version; /**< Component Version */
QM_RW uint32_t ic_comp_type; /**< Component Type */
} qm_i2c_reg_t;
#if (UNIT_TEST)
@ -879,7 +873,7 @@ qm_i2c_reg_t *test_i2c[QM_I2C_NUM];
#define QM_I2C test_i2c
#else
/* I2C Master register base address. */
/** I2C Master register base address. */
#define QM_I2C_0_BASE (0xB0002800)
/** I2C register block. */
@ -952,25 +946,25 @@ typedef enum { QM_GPIO_0 = 0, QM_GPIO_NUM } qm_gpio_t;
/** GPIO register map. */
typedef struct {
QM_RW uint32_t gpio_swporta_dr; /**< Port A Data. */
QM_RW uint32_t gpio_swporta_ddr; /**< Port A Data Direction. */
QM_RW uint32_t gpio_swporta_dr; /**< Port A Data */
QM_RW uint32_t gpio_swporta_ddr; /**< Port A Data Direction */
QM_RW uint32_t reserved[10];
QM_RW uint32_t gpio_inten; /**< Interrupt Enable. */
QM_RW uint32_t gpio_intmask; /**< Interrupt Mask. */
QM_RW uint32_t gpio_inttype_level; /**< Interrupt Type. */
QM_RW uint32_t gpio_int_polarity; /**< Interrupt Polarity. */
QM_RW uint32_t gpio_intstatus; /**< Interrupt Status. */
QM_RW uint32_t gpio_raw_intstatus; /**< Raw Interrupt Status. */
QM_RW uint32_t gpio_debounce; /**< Debounce Enable. */
QM_RW uint32_t gpio_porta_eoi; /**< Clear Interrupt. */
QM_RW uint32_t gpio_ext_porta; /**< Port A External Port. */
QM_RW uint32_t gpio_inten; /**< Interrupt Enable */
QM_RW uint32_t gpio_intmask; /**< Interrupt Mask */
QM_RW uint32_t gpio_inttype_level; /**< Interrupt Type */
QM_RW uint32_t gpio_int_polarity; /**< Interrupt Polarity */
QM_RW uint32_t gpio_intstatus; /**< Interrupt Status */
QM_RW uint32_t gpio_raw_intstatus; /**< Raw Interrupt Status */
QM_RW uint32_t gpio_debounce; /**< Debounce Enable */
QM_RW uint32_t gpio_porta_eoi; /**< Clear Interrupt */
QM_RW uint32_t gpio_ext_porta; /**< Port A External Port */
QM_RW uint32_t reserved1[3];
QM_RW uint32_t gpio_ls_sync; /**< Synchronization Level. */
QM_RW uint32_t gpio_id_code; /**< GPIO ID code. */
QM_RW uint32_t gpio_int_bothedge; /**< Interrupt both edge type. */
QM_RW uint32_t gpio_ver_id_code; /**< GPIO Component Version. */
QM_RW uint32_t gpio_config_reg2; /**< GPIO Configuration Register 2. */
QM_RW uint32_t gpio_config_reg1; /**< GPIO Configuration Register 1. */
QM_RW uint32_t gpio_ls_sync; /**< Synchronization Level */
QM_RW uint32_t gpio_id_code; /**< GPIO ID code */
QM_RW uint32_t gpio_int_bothedge; /**< Interrupt both edge type */
QM_RW uint32_t gpio_ver_id_code; /**< GPIO Component Version */
QM_RW uint32_t gpio_config_reg2; /**< GPIO Configuration Register 2 */
QM_RW uint32_t gpio_config_reg1; /**< GPIO Configuration Register 1 */
} qm_gpio_reg_t;
#define QM_NUM_GPIO_PINS (25)
@ -982,10 +976,10 @@ qm_gpio_reg_t *test_gpio[QM_GPIO_NUM];
#define QM_GPIO test_gpio
#else
/* GPIO register base address. */
/** GPIO register base address */
#define QM_GPIO_BASE (0xB0000C00)
/* GPIO register block. */
/** GPIO register block */
extern qm_gpio_reg_t *qm_gpio[QM_GPIO_NUM];
#define QM_GPIO qm_gpio
#endif
@ -1024,10 +1018,10 @@ qm_adc_reg_t test_adc;
#define QM_ADC ((qm_adc_reg_t *)(&test_adc))
#else
/* ADC register block */
/** ADC register block */
#define QM_ADC ((qm_adc_reg_t *)QM_ADC_BASE)
/* ADC register base. */
/** ADC register base. */
#define QM_ADC_BASE (0xB0004000)
#endif
@ -1114,10 +1108,10 @@ uint8_t test_flash_page[0x800];
#define QM_FLASH_PAGE_MASK (0xF800)
#define QM_FLASH_MAX_ADDR (0x8000)
/* Flash controller register base address. */
/** Flash controller register base address. */
#define QM_FLASH_BASE_0 (0xB0100000)
/* Flash controller register block. */
/** Flash controller register block. */
extern qm_flash_reg_t *qm_flash[QM_FLASH_NUM];
#define QM_FLASH qm_flash
@ -1128,7 +1122,6 @@ extern qm_flash_reg_t *qm_flash[QM_FLASH_NUM];
#define QM_FLASH_MAX_US_COUNT (0x3F)
#define QM_FLASH_MAX_PAGE_NUM \
(QM_FLASH_MAX_ADDR / (4 * QM_FLASH_PAGE_SIZE_DWORDS))
#define QM_FLASH_CLK_SLOW BIT(14)
#define QM_FLASH_LVE_MODE BIT(5)
/** @} */
@ -1192,7 +1185,7 @@ qm_pic_timer_reg_t test_pic_timer;
#define QM_PIC_TIMER ((qm_pic_timer_reg_t *)(&test_pic_timer))
#else
/* PIC timer base address. */
/** PIC timer base address. */
#define QM_PIC_TIMER_BASE (0xFEE00320)
#define QM_PIC_TIMER ((qm_pic_timer_reg_t *)QM_PIC_TIMER_BASE)
#endif
@ -1253,32 +1246,32 @@ typedef struct {
/** MVIC register map. */
typedef struct {
QM_RW mvic_reg_pad_t tpr; /**< Task priority. */
QM_RW mvic_reg_pad_t tpr; /**< Task priority*/
QM_RW mvic_reg_pad_t reserved;
QM_RW mvic_reg_pad_t ppr; /**< Processor priority. */
QM_RW mvic_reg_pad_t eoi; /**< End of interrupt. */
QM_RW mvic_reg_pad_t ppr; /**< Processor priority */
QM_RW mvic_reg_pad_t eoi; /**< End of interrupt */
QM_RW mvic_reg_pad_t reserved1[3];
QM_RW mvic_reg_pad_t sivr; /**< Spurious vector. */
QM_RW mvic_reg_pad_t sivr; /**< Spurious vector */
QM_RW mvic_reg_pad_t reserved2;
QM_RW mvic_reg_pad_t isr; /**< In-service. */
QM_RW mvic_reg_pad_t isr; /**< In-service */
QM_RW mvic_reg_pad_t reserved3[15];
QM_RW mvic_reg_pad_t irr; /**< Interrupt request. */
QM_RW mvic_reg_pad_t irr; /**< Interrupt request */
QM_RW mvic_reg_pad_t reserved4[16];
QM_RW mvic_reg_pad_t lvttimer; /**< Timer vector. */
QM_RW mvic_reg_pad_t lvttimer; /**< Timer vector */
QM_RW mvic_reg_pad_t reserved5[5];
QM_RW mvic_reg_pad_t icr; /**< Timer initial count. */
QM_RW mvic_reg_pad_t ccr; /**< Timer current count. */
QM_RW mvic_reg_pad_t icr; /**< Timer initial count */
QM_RW mvic_reg_pad_t ccr; /**< Timer current count */
} qm_mvic_reg_t;
#define QM_MVIC_REG_VER (0x01) /* MVIC version. */
#define QM_MVIC_REG_REDTBL (0x10) /* Redirection table base. */
#define QM_MVIC_REG_VER (0x01) /**< MVIC version */
#define QM_MVIC_REG_REDTBL (0x10) /**< Redirection table base */
#if (UNIT_TEST)
qm_mvic_reg_t test_mvic;
#define QM_MVIC ((qm_mvic_reg_t *)(&test_mvic))
#else
/* Interrupt Controller base address. */
/** Interrupt Controller base address. */
#define QM_MVIC_BASE (0xFEE00080)
#define QM_MVIC ((qm_mvic_reg_t *)QM_MVIC_BASE)
#endif
@ -1293,8 +1286,8 @@ qm_mvic_reg_t test_mvic;
#endif
typedef struct {
QM_RW mvic_reg_pad_t ioregsel; /**< Register selector. */
QM_RW mvic_reg_pad_t iowin; /**< Register window. */
QM_RW mvic_reg_pad_t ioregsel; /**< Register selector */
QM_RW mvic_reg_pad_t iowin; /**< Register window */
} qm_ioapic_reg_t;
#if (UNIT_TEST)
@ -1302,7 +1295,7 @@ qm_ioapic_reg_t test_ioapic;
#define QM_IOAPIC ((qm_ioapic_reg_t *)(&test_ioapic))
#else
/* IO/APIC. */
/** IO/APIC */
#define QM_IOAPIC_BASE (0xFEC00000)
#define QM_IOAPIC ((qm_ioapic_reg_t *)QM_IOAPIC_BASE)
#endif
@ -1471,10 +1464,10 @@ typedef struct {
QM_RW uint32_t reserved[4]; /**< Reserved */
} qm_dma_misc_reg_t;
/* Channel write enable in the misc channel enable register. */
/** Channel write enable in the misc channel enable register. */
#define QM_DMA_MISC_CHAN_EN_WE_OFFSET (8)
/* Controller enable bit in the misc config register. */
/** Controller enable bit in the misc config register. */
#define QM_DMA_MISC_CFG_DMA_EN BIT(0)
typedef struct {

View file

@ -35,6 +35,18 @@
#endif
#include "soc_watch.h"
void power_soc_lpss_enable()
{
QM_SCSS_CCU->ccu_lp_clk_ctl |= QM_SCSS_CCU_SS_LPS_EN;
SOC_WATCH_LOG_EVENT(SOCW_EVENT_REGISTER, SOCW_REG_CCU_LP_CLK_CTL);
}
void power_soc_lpss_disable()
{
QM_SCSS_CCU->ccu_lp_clk_ctl &= ~QM_SCSS_CCU_SS_LPS_EN;
SOC_WATCH_LOG_EVENT(SOCW_EVENT_REGISTER, SOCW_REG_CCU_LP_CLK_CTL);
}
void power_soc_sleep()
{
#if (QM_SENSOR)
@ -85,7 +97,6 @@ void power_soc_deep_sleep()
#if (!QM_SENSOR)
void power_cpu_c1()
{
SOC_WATCH_LOG_EVENT(SOCW_EVENT_HALT, 0);
__asm__ __volatile__("hlt");
}

View file

@ -56,7 +56,7 @@ extern uint8_t test_flash_page[0x800];
#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_SOC_DATA_VALID (0x24535021) /**< $SP! */
#define QM_FLASH_OTP_TRIM_MAGIC (QM_FLASH_OTP_TRIM_CODE->magic)
typedef union {
@ -91,21 +91,21 @@ typedef union {
* Bootloader data
*/
/* The flash controller where BL-Data is stored. */
/** The flash controller where BL-Data is stored. */
#define BL_DATA_FLASH_CONTROLLER QM_FLASH_0
/* The flash region where BL-Data is stored. */
/** The flash region where BL-Data is stored. */
#define BL_DATA_FLASH_REGION QM_FLASH_REGION_SYS
/* The flash address where the BL-Data Section starts. */
/** The flash address where the BL-Data Section starts. */
#define BL_DATA_FLASH_REGION_BASE QM_FLASH_REGION_SYS_0_BASE
/* The flash page where the BL-Data Section starts. */
/** The flash page where the BL-Data Section starts. */
#define BL_DATA_SECTION_BASE_PAGE (94)
/* The size (in pages) of the System_0 flash region of Quark SE. */
/** The size (in pages) of the System_0 flash region of Quark SE. */
#define QM_FLASH_REGION_SYS_0_PAGES (96)
/* The size (in pages) of the System_1 flash region of Quark SE. */
/** The size (in pages) of the System_1 flash region of Quark SE. */
#define QM_FLASH_REGION_SYS_1_PAGES (96)
/* The size (in pages) of the Bootloader Data section. */
/** The size (in pages) of the Bootloader Data section. */
#define BL_DATA_SECTION_PAGES (2)
#if (BL_CONFIG_DUAL_BANK)
@ -119,7 +119,7 @@ typedef union {
#define BL_PARTITION_SIZE_LMT (QM_FLASH_REGION_SYS_1_PAGES)
#endif /* BL_CONFIG_DUAL_BANK */
/* Number of boot targets. */
/** Number of boot targets. */
#define BL_BOOT_TARGETS_NUM (2)
#define BL_TARGET_IDX_LMT (0)

View file

@ -78,6 +78,30 @@ void power_soc_sleep(void);
*/
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);
/**
* @}
*/

View file

@ -80,21 +80,29 @@ uint32_t test_sensor_aux[QM_SS_AUX_REGS_SIZE];
#define __builtin_arc_nop()
#endif
/* Bitwise OR operation macro for registers in the auxiliary memory space. */
/**
* @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. */
/** 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))
/** @} */
/* Sensor Subsystem status32 register. */
#define QM_SS_AUX_STATUS32 (0xA)
/* Sensor Subsystem control register. */
#define QM_SS_AUX_IC_CTRL (0x11)
/* Sensor Subsystem cache invalidate register. */
/**
* @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. */
/**< Sensor Subsystem vector base register. */
#define QM_SS_AUX_INT_VECTOR_BASE (0x25)
/** @} */
/**
* @name SS Timer
@ -129,7 +137,6 @@ typedef enum { QM_SS_TIMER_0 = 0, QM_SS_TIMER_NUM } qm_ss_timer_t;
* @{
*/
/** Sensor Subsystem GPIO register block type. */
typedef enum {
QM_SS_GPIO_SWPORTA_DR = 0,
QM_SS_GPIO_SWPORTA_DDR,
@ -144,11 +151,13 @@ typedef enum {
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. */
/** 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)
@ -163,7 +172,7 @@ typedef enum { QM_SS_GPIO_0 = 0, QM_SS_GPIO_1, QM_SS_GPIO_NUM } qm_ss_gpio_t;
* @{
*/
/** Sensor Subsystem I2C register block type. */
/** Sensor Subsystem I2C Registers*/
typedef enum {
QM_SS_I2C_CON = 0,
QM_SS_I2C_DATA_CMD,
@ -181,6 +190,7 @@ typedef enum {
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)
@ -253,7 +263,6 @@ 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 */
@ -272,10 +281,10 @@ typedef enum {
QM_SS_ADC_NUM
} qm_ss_adc_t;
/* SS ADC register base. */
/** SS ADC register base */
#define QM_SS_ADC_BASE (0x80015000)
/* For 1MHz, the max divisor is 7. */
/** For 1MHz, the max divisor is 7. */
#define QM_SS_ADC_DIV_MAX (7)
#define QM_SS_ADC_FIFO_LEN (32)
@ -346,12 +355,6 @@ typedef enum {
#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)
#define QM_SS_IO_CREG_MST0_CTRL_ADC_CLK_GATE BIT(31)
#define QM_SS_IO_CREG_MST0_CTRL_I2C1_CLK_GATE BIT(30)
#define QM_SS_IO_CREG_MST0_CTRL_I2C0_CLK_GATE BIT(29)
#define QM_SS_IO_CREG_MST0_CTRL_SPI0_CLK_GATE BIT(28)
#define QM_SS_IO_CREG_MST0_CTRL_SPI1_CLK_GATE BIT(27)
/* SLV0_OBSR fields */
#define QM_SS_ADC_CAL_VAL_GET_OFFSET (5)
#define QM_SS_ADC_CAL_VAL_GET_MASK (0xFE0)
@ -362,7 +365,7 @@ typedef enum {
(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. */
/** SS CREG base */
#define QM_SS_CREG_BASE (0x80018000)
/** @} */
@ -374,10 +377,10 @@ typedef enum {
* @{
*/
#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_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)
@ -567,7 +570,6 @@ typedef enum {
#define QM_SS_SPI_DR_W_MASK (0xc0000000)
#define QM_SS_SPI_DR_R_MASK (0x80000000)
/** @} */
/** @} */
#endif /* __SENSOR_REGISTERS_H__ */

View file

@ -55,27 +55,27 @@
/** System Core register map. */
typedef struct {
QM_RW uint32_t osc0_cfg0; /**< Hybrid Oscillator Configuration 0. */
QM_RW uint32_t osc0_stat1; /**< Hybrid Oscillator status 1. */
QM_RW uint32_t osc0_cfg1; /**< Hybrid Oscillator configuration 1. */
QM_RW uint32_t osc1_stat0; /**< RTC Oscillator status 0. */
QM_RW uint32_t osc1_cfg0; /**< RTC Oscillator Configuration 0. */
QM_RW uint32_t usb_pll_cfg0; /**< USB Phase lock look configuration. */
QM_RW uint32_t osc0_cfg0; /**< Hybrid Oscillator Configuration 0 */
QM_RW uint32_t osc0_stat1; /**< Hybrid Oscillator status 1 */
QM_RW uint32_t osc0_cfg1; /**< Hybrid Oscillator configuration 1 */
QM_RW uint32_t osc1_stat0; /**< RTC Oscillator status 0 */
QM_RW uint32_t osc1_cfg0; /**< RTC Oscillator Configuration 0 */
QM_RW uint32_t usb_pll_cfg0; /**< USB Phase lock look configuration */
QM_RW uint32_t
ccu_periph_clk_gate_ctl; /**< Peripheral Clock Gate Control. */
ccu_periph_clk_gate_ctl; /**< Peripheral Clock Gate Control */
QM_RW uint32_t
ccu_periph_clk_div_ctl0; /**< Peripheral Clock Divider Control. 0 */
ccu_periph_clk_div_ctl0; /**< Peripheral Clock Divider Control 0 */
QM_RW uint32_t
ccu_gpio_db_clk_ctl; /**< Peripheral Clock Divider Control 1. */
ccu_gpio_db_clk_ctl; /**< Peripheral Clock Divider Control 1 */
QM_RW uint32_t
ccu_ext_clock_ctl; /**< External Clock Control Register. */
/** Sensor Subsystem peripheral clock gate control. */
ccu_ext_clock_ctl; /**< External Clock Control Register */
/** Sensor Subsystem peripheral clock gate control */
QM_RW uint32_t ccu_ss_periph_clk_gate_ctl;
QM_RW uint32_t ccu_lp_clk_ctl; /**< System Low Power Clock Control. */
QM_RW uint32_t ccu_lp_clk_ctl; /**< System Low Power Clock Control */
QM_RW uint32_t reserved;
QM_RW uint32_t ccu_mlayer_ahb_ctl; /**< AHB Control Register. */
QM_RW uint32_t ccu_sys_clk_ctl; /**< System Clock Control Register. */
QM_RW uint32_t osc_lock_0; /**< Clocks Lock Register. */
QM_RW uint32_t ccu_mlayer_ahb_ctl; /**< AHB Control Register */
QM_RW uint32_t ccu_sys_clk_ctl; /**< System Clock Control Register */
QM_RW uint32_t osc_lock_0; /**< Clocks Lock Register */
} qm_scss_ccu_reg_t;
#if (UNIT_TEST)
@ -114,7 +114,7 @@ qm_scss_ccu_reg_t test_scss_ccu;
#define QM_SI_OSC_1V2_MODE BIT(0)
/* Peripheral clock divider control. */
/** Peripheral clock divider control */
#define QM_CCU_PERIPH_PCLK_DIV_OFFSET (1)
#define QM_CCU_PERIPH_PCLK_DIV_EN BIT(0)
@ -274,7 +274,7 @@ qm_lapic_reg_t test_lapic;
#define QM_LAPIC ((qm_lapic_reg_t *)(&test_lapic))
#else
/* Local APIC. */
/** Local APIC */
#define QM_LAPIC_BASE (0xFEE00000)
#define QM_LAPIC ((qm_lapic_reg_t *)QM_LAPIC_BASE)
#endif
@ -297,21 +297,21 @@ qm_lapic_reg_t test_lapic;
#endif
typedef struct {
QM_RW apic_reg_pad_t ioregsel; /**< Register selector. */
QM_RW apic_reg_pad_t iowin; /**< Register window. */
QM_RW apic_reg_pad_t ioregsel; /**< Register selector */
QM_RW apic_reg_pad_t iowin; /**< Register window */
QM_RW apic_reg_pad_t reserved[2];
QM_RW apic_reg_pad_t eoi; /**< EOI register. */
QM_RW apic_reg_pad_t eoi; /**< EOI register */
} qm_ioapic_reg_t;
#define QM_IOAPIC_REG_VER (0x01) /* IOAPIC version. */
#define QM_IOAPIC_REG_REDTBL (0x10) /* Redirection table base. */
#define QM_IOAPIC_REG_VER (0x01) /**< IOAPIC version */
#define QM_IOAPIC_REG_REDTBL (0x10) /**< Redirection table base */
#if (UNIT_TEST)
qm_ioapic_reg_t test_ioapic;
#define QM_IOAPIC ((qm_ioapic_reg_t *)(&test_ioapic))
#else
/* IO / APIC base address. */
/** IO / APIC base address. */
#define QM_IOAPIC_BASE (0xFEC00000)
#define QM_IOAPIC ((qm_ioapic_reg_t *)QM_IOAPIC_BASE)
#endif
@ -378,23 +378,23 @@ typedef struct {
QM_RW uint32_t int_host_bus_err_mask;
QM_RW uint32_t int_dma_error_mask;
QM_RW uint32_t
int_sram_controller_mask; /**< Interrupt Routing Mask 28. */
int_sram_controller_mask; /**< Interrupt Routing Mask 28 */
QM_RW uint32_t
int_flash_controller_0_mask; /**< Interrupt Routing Mask 29. */
int_flash_controller_0_mask; /**< Interrupt Routing Mask 29 */
QM_RW uint32_t
int_flash_controller_1_mask; /**< Interrupt Routing Mask 30. */
QM_RW uint32_t int_aon_timer_mask; /**< Interrupt Routing Mask 31. */
QM_RW uint32_t int_adc_pwr_mask; /**< Interrupt Routing Mask 32. */
QM_RW uint32_t int_adc_calib_mask; /**< Interrupt Routing Mask 33. */
int_flash_controller_1_mask; /**< Interrupt Routing Mask 30 */
QM_RW uint32_t int_aon_timer_mask; /**< Interrupt Routing Mask 31 */
QM_RW uint32_t int_adc_pwr_mask; /**< Interrupt Routing Mask 32 */
QM_RW uint32_t int_adc_calib_mask; /**< Interrupt Routing Mask 33 */
QM_RW uint32_t int_aon_gpio_mask;
QM_RW uint32_t lock_int_mask_reg; /**< Interrupt Mask Lock Register. */
QM_RW uint32_t lock_int_mask_reg; /**< Interrupt Mask Lock Register */
} qm_scss_int_reg_t;
/* Number of SCSS interrupt mask registers (excluding mask lock register). */
/** Number of SCSS interrupt mask registers (excluding mask lock register) */
#define QM_SCSS_INT_MASK_NUMREG \
((sizeof(qm_scss_int_reg_t) / sizeof(uint32_t)) - 1)
/* Default POR SCSS interrupt mask (all interrupts masked). */
/** Default POR SCSS interrupt mask (all interrupts masked) */
#define QM_SCSS_INT_MASK_DEFAULT (0xFFFFFFFF)
#if (UNIT_TEST)
@ -651,16 +651,6 @@ qm_scss_mailbox_reg_t test_scss_mailbox;
/** @} */
/**
* @name USB
* @{
*/
/** USB register base address. */
#define QM_USB_BASE (0xB0500000)
/** @} */
/**
* @name IRQs and Interrupts
* @{
@ -836,9 +826,9 @@ qm_pwm_reg_t test_pwm_t;
#define QM_PWM ((qm_pwm_reg_t *)(&test_pwm_t))
#else
/* PWM register base address. */
/** PWM register base address */
#define QM_PWM_BASE (0xB0000800)
/* PWM register block. */
/** PWM register block */
#define QM_PWM ((qm_pwm_reg_t *)QM_PWM_BASE)
#endif
@ -877,10 +867,10 @@ qm_wdt_reg_t test_wdt;
#define QM_WDT ((qm_wdt_reg_t *)(&test_wdt))
#else
/* WDT register base address. */
/** WDT register base address */
#define QM_WDT_BASE (0xB0000000)
/* WDT register block. */
/** WDT register block */
#define QM_WDT ((qm_wdt_reg_t *)QM_WDT_BASE)
#endif
@ -920,10 +910,10 @@ qm_uart_reg_t *test_uart[QM_UART_NUM];
#define QM_UART test_uart
#else
/* UART register base address. */
/** UART register base address */
#define QM_UART_0_BASE (0xB0002000)
#define QM_UART_1_BASE (0xB0002400)
/* UART register block. */
/** UART register block */
extern qm_uart_reg_t *qm_uart[QM_UART_NUM];
#define QM_UART qm_uart
#endif
@ -981,17 +971,17 @@ qm_spi_reg_t *test_spi_controllers[QM_SPI_NUM];
#define QM_SPI test_spi_controllers
#else
/* SPI Master register base address. */
/** SPI Master register base address */
#define QM_SPI_MST_0_BASE (0xB0001000)
#define QM_SPI_MST_1_BASE (0xB0001400)
extern qm_spi_reg_t *qm_spi_controllers[QM_SPI_NUM];
#define QM_SPI qm_spi_controllers
/* SPI Slave register base address. */
/** SPI Slave register base address */
#define QM_SPI_SLV_BASE (0xB0001800)
#endif
/* SPI Ctrlr0 register. */
/* SPI Ctrlr0 register */
#define QM_SPI_CTRLR0_DFS_32_MASK (0x001F0000)
#define QM_SPI_CTRLR0_TMOD_MASK (0x00000300)
#define QM_SPI_CTRLR0_SCPOL_SCPH_MASK (0x000000C0)
@ -1001,17 +991,17 @@ extern qm_spi_reg_t *qm_spi_controllers[QM_SPI_NUM];
#define QM_SPI_CTRLR0_SCPOL_SCPH_OFFSET (6)
#define QM_SPI_CTRLR0_FRF_OFFSET (4)
/* SPI SSI Enable register. */
/* SPI SSI Enable register */
#define QM_SPI_SSIENR_SSIENR BIT(0)
/* SPI Status register. */
/* SPI Status register */
#define QM_SPI_SR_BUSY BIT(0)
#define QM_SPI_SR_TFNF BIT(1)
#define QM_SPI_SR_TFE BIT(2)
#define QM_SPI_SR_RFNE BIT(3)
#define QM_SPI_SR_RFF BIT(4)
/* SPI Interrupt Mask register. */
/* SPI Interrupt Mask register */
#define QM_SPI_IMR_MASK_ALL (0x00)
#define QM_SPI_IMR_TXEIM BIT(0)
#define QM_SPI_IMR_TXOIM BIT(1)
@ -1019,21 +1009,21 @@ extern qm_spi_reg_t *qm_spi_controllers[QM_SPI_NUM];
#define QM_SPI_IMR_RXOIM BIT(3)
#define QM_SPI_IMR_RXFIM BIT(4)
/* SPI Interrupt Status register. */
/* SPI Interrupt Status register */
#define QM_SPI_ISR_TXEIS BIT(0)
#define QM_SPI_ISR_TXOIS BIT(1)
#define QM_SPI_ISR_RXUIS BIT(2)
#define QM_SPI_ISR_RXOIS BIT(3)
#define QM_SPI_ISR_RXFIS BIT(4)
/* SPI Raw Interrupt Status register. */
/* SPI Raw Interrupt Status register */
#define QM_SPI_RISR_TXEIR BIT(0)
#define QM_SPI_RISR_TXOIR BIT(1)
#define QM_SPI_RISR_RXUIR BIT(2)
#define QM_SPI_RISR_RXOIR BIT(3)
#define QM_SPI_RISR_RXFIR BIT(4)
/* SPI DMA control. */
/* SPI DMA control */
#define QM_SPI_DMACR_RDMAE BIT(0)
#define QM_SPI_DMACR_TDMAE BIT(1)
@ -1064,10 +1054,10 @@ qm_rtc_reg_t test_rtc;
#define QM_RTC ((qm_rtc_reg_t *)(&test_rtc))
#else
/* RTC register base address. */
/** RTC register base address. */
#define QM_RTC_BASE (0xB0000400)
/* RTC register block. */
/** RTC register block. */
#define QM_RTC ((qm_rtc_reg_t *)QM_RTC_BASE)
#endif
@ -1145,7 +1135,7 @@ qm_i2c_reg_t *test_i2c[QM_I2C_NUM];
#define QM_I2C test_i2c
#else
/* I2C Master register base address. */
/** I2C Master register base address. */
#define QM_I2C_0_BASE (0xB0002800)
#define QM_I2C_1_BASE (0xB0002C00)
@ -1251,7 +1241,7 @@ qm_gpio_reg_t *test_gpio[QM_GPIO_NUM];
#define QM_GPIO test_gpio
#else
/* GPIO register base address */
/** GPIO register base address */
#define QM_GPIO_BASE (0xB0000C00)
#define QM_AON_GPIO_BASE (QM_SCSS_CCU_BASE + 0xB00)
@ -1311,11 +1301,11 @@ uint8_t test_flash_page[0x800];
#define QM_FLASH_PAGE_MASK (0x3F800)
#define QM_FLASH_MAX_ADDR (0x30000)
/* Flash controller register base address. */
/** Flash controller register base address. */
#define QM_FLASH_BASE_0 (0xB0100000)
#define QM_FLASH_BASE_1 (0xB0200000)
/* Flash controller register block. */
/** Flash controller register block. */
extern qm_flash_reg_t *qm_flash[QM_FLASH_NUM];
#define QM_FLASH qm_flash
@ -1326,7 +1316,6 @@ extern qm_flash_reg_t *qm_flash[QM_FLASH_NUM];
#define QM_FLASH_MAX_US_COUNT (0x3F)
#define QM_FLASH_MAX_PAGE_NUM \
(QM_FLASH_MAX_ADDR / (4 * QM_FLASH_PAGE_SIZE_DWORDS))
#define QM_FLASH_CLK_SLOW BIT(14)
#define QM_FLASH_LVE_MODE BIT(5)
/** @} */
@ -1363,12 +1352,15 @@ qm_mpr_reg_t test_mpr;
#define QM_MPR_EN_LOCK_MASK 0xC0000000
#define QM_MPR_UP_BOUND_OFFSET (10)
#define QM_MPR_VSTS_VALID BIT(31)
/** @} */
#define QM_OSC0_PD BIT(2)
/** External Clock Control @{*/
#define QM_CCU_EXTERN_DIV_OFFSET (3)
#define QM_CCU_EXT_CLK_DIV_EN BIT(2)
/** End of External clock control @}*/
/** @} */
/**
* @name Peripheral Clock
@ -1590,10 +1582,10 @@ typedef struct {
QM_RW uint32_t reserved[4]; /**< Reserved */
} qm_dma_misc_reg_t;
/* Channel write enable in the misc channel enable register. */
/** Channel write enable in the misc channel enable register. */
#define QM_DMA_MISC_CHAN_EN_WE_OFFSET (8)
/* Controller enable bit in the misc config register. */
/** Controller enable bit in the misc config register. */
#define QM_DMA_MISC_CFG_DMA_EN BIT(0)
typedef struct {
@ -1620,12 +1612,15 @@ extern qm_dma_reg_t *qm_dma[QM_DMA_NUM];
* @{
*/
/** USB register base address */
#define QM_USB_BASE (0xB0500000)
/* USB PLL enable bit*/
#define QM_USB_PLL_PDLD BIT(0)
/* USB PLL has locked when this bit is 1*/
#define QM_USB_PLL_LOCK BIT(14)
/* Default values to setup the USB PLL*/
#define QM_USB_PLL_CFG0_DEFAULT (0x00001904)
#define QM_USB_PLL_CFG0_DEFAULT (0x00003104)
/* USB PLL register*/
#define QM_USB_PLL_CFG0 (REG_VAL(0xB0800014))