diff --git a/src/include/arc32/power_states.h b/src/include/arc32/power_states.h
new file mode 100644
index 0000000..eb5fecf
--- /dev/null
+++ b/src/include/arc32/power_states.h
@@ -0,0 +1,89 @@
+/*
+ * Copyright (c) 2016, Intel Corporation
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of the Intel Corporation nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INTEL CORPORATION OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __POWER_STATES_H__
+#define __POWER_STATES_H__
+
+/**
+ * SoC Power mode control for Quark SE Microcontrollers.
+ *
+ * Available SoC states are:
+ * - Low Power Sensing Standby (LPSS)
+ * - Sleep
+ *
+ * LPSS can only be enabled from the Sensor core,
+ * refer to @ref ss_power_soc_lpss_enable for further details.
+ *
+ * @defgroup groupSoCPower Quark SE SoC Power states
+ * @{
+ */
+
+/**
+ * Enter SoC sleep state.
+ *
+ * Put the SoC into sleep state until next SoC wake event.
+ *
+ * - Core well is turned off
+ * - Always on well is on
+ * - Hybrid Clock is off
+ * - RTC Clock is on
+ *
+ * Possible SoC wake events are:
+ * - Low Power Comparator Interrupt
+ * - AON GPIO Interrupt
+ * - AON Timer Interrupt
+ * - RTC Interrupt
+ */
+void power_soc_sleep(void);
+
+/**
+ * Enter SoC deep sleep state.
+ *
+ * Put the SoC into deep sleep state until next SoC wake event.
+ *
+ * - Core well is turned off
+ * - Always on well is on
+ * - Hybrid Clock is off
+ * - RTC Clock is on
+ *
+ * Possible SoC wake events are:
+ * - Low Power Comparator Interrupt
+ * - AON GPIO Interrupt
+ * - AON Timer Interrupt
+ * - RTC Interrupt
+ *
+ * This function puts 1P8V regulators and 3P3V into Linear Mode.
+ */
+void power_soc_deep_sleep(void);
+
+/**
+ * @}
+ */
+
+#endif /* __POWER_STATES_H__ */
diff --git a/src/include/arc32/qm_interrupt_router_regs.h b/src/include/arc32/qm_interrupt_router_regs.h
new file mode 100644
index 0000000..216612e
--- /dev/null
+++ b/src/include/arc32/qm_interrupt_router_regs.h
@@ -0,0 +1,207 @@
+/*
+ * Copyright (c) 2016, Intel Corporation
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of the Intel Corporation nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INTEL CORPORATION OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __QM_INTERRUPT_ROUTER_REGS_H__
+#define __QM_INTERRUPT_ROUTER_REGS_H__
+
+/**
+ * Quark SE SoC Event Router registers.
+ *
+ * @defgroup groupQUARKSESEEVENTROUTER SoC Event Router (SE)
+ * @{
+ */
+
+/**
+ * Masks for single source interrupts in the Event Router.
+ * To enable: reg &= ~(MASK)
+ * To disable: reg |= MASK;
+ */
+#define QM_IR_INT_LMT_MASK BIT(0)
+#define QM_IR_INT_SS_MASK BIT(8)
+
+/* Masks for single source halts in the Event Router. */
+#define QM_IR_INT_LMT_HALT_MASK BIT(16)
+#define QM_IR_INT_SS_HALT_MASK BIT(24)
+
+/* Event Router Unmask interrupts for a peripheral. */
+#define QM_IR_UNMASK_LMT_INTERRUPTS(_peripheral_) \
+ (_peripheral_ &= ~(QM_IR_INT_LMT_MASK))
+#define QM_IR_UNMASK_SS_INTERRUPTS(_peripheral_) \
+ (_peripheral_ &= ~(QM_IR_INT_SS_MASK))
+
+/* Mask interrupts for a peripheral. */
+#define QM_IR_MASK_LMT_INTERRUPTS(_peripheral_) \
+ (_peripheral_ |= QM_IR_INT_LMT_MASK)
+#define QM_IR_MASK_SS_INTERRUPTS(_peripheral_) \
+ (_peripheral_ |= QM_IR_INT_SS_MASK)
+
+/* Unmask halt for a peripheral. */
+#define QM_IR_UNMASK_LMT_HALTS(_peripheral_) \
+ (_peripheral_ &= ~(QM_IR_INT_LMT_HALT_MASK))
+#define QM_IR_UNMASK_SS_HALTS(_peripheral_) \
+ (_peripheral_ &= ~(QM_IR_INT_SS_HALT_MASK))
+
+/* Mask halt for a peripheral. */
+#define QM_IR_MASK_LMT_HALTS(_peripheral_) \
+ (_peripheral_ |= QM_IR_INT_LMT_HALT_MASK)
+#define QM_IR_MASK_SS_HALTS(_peripheral_) \
+ (_peripheral_ |= QM_IR_INT_SS_HALT_MASK)
+
+#define QM_IR_GET_LMT_MASK(_peripheral_) (_peripheral_ & QM_IR_INT_LMT_MASK)
+#define QM_IR_GET_LMT_HALT_MASK(_peripheral_) \
+ (_peripheral_ & QM_IR_INT_LMT_HALT_MASK)
+
+#define QM_IR_GET_SS_MASK(_peripheral_) (_peripheral_ & QM_IR_INT_SS_MASK)
+#define QM_IR_GET_SS_HALT_MASK(_peripheral_) \
+ (_peripheral_ & QM_IR_INT_SS_HALT_MASK)
+
+/* Define macros for use by the active core. */
+#if (QM_LAKEMONT)
+#define QM_IR_UNMASK_INTERRUPTS(_peripheral_) \
+ QM_IR_UNMASK_LMT_INTERRUPTS(_peripheral_)
+#define QM_IR_MASK_INTERRUPTS(_peripheral_) \
+ QM_IR_MASK_LMT_INTERRUPTS(_peripheral_)
+#define QM_IR_UNMASK_HALTS(_peripheral_) QM_IR_UNMASK_LMT_HALTS(_peripheral_)
+#define QM_IR_MASK_HALTS(_peripheral_) QM_IR_MASK_LMT_HALTS(_peripheral_)
+
+#define QM_IR_INT_MASK QM_IR_INT_LMT_MASK
+#define QM_IR_INT_HALT_MASK QM_IR_INT_LMT_HALT_MASK
+#define QM_IR_GET_MASK(_peripheral_) QM_IR_GET_LMT_MASK(_peripheral_)
+#define QM_IR_GET_HALT_MASK(_peripheral_) QM_IR_GET_LMT_HALT_MASK(_peripheral_)
+
+#elif(QM_SENSOR)
+#define QM_IR_UNMASK_INTERRUPTS(_peripheral_) \
+ QM_IR_UNMASK_SS_INTERRUPTS(_peripheral_)
+#define QM_IR_MASK_INTERRUPTS(_peripheral_) \
+ QM_IR_MASK_SS_INTERRUPTS(_peripheral_)
+#define QM_IR_UNMASK_HALTS(_peripheral_) QM_IR_UNMASK_SS_HALTS(_peripheral_)
+#define QM_IR_MASK_HALTS(_peripheral_) QM_IR_MASK_SS_HALTS(_peripheral_)
+
+#define QM_IR_INT_MASK QM_IR_INT_SS_MASK
+#define QM_IR_INT_HALT_MASK QM_IR_INT_SS_HALT_MASK
+#define QM_IR_GET_MASK(_peripheral_) QM_IR_GET_SS_MASK(_peripheral_)
+#define QM_IR_GET_HALT_MASK(_peripheral_) QM_IR_GET_SS_HALT_MASK(_peripheral_)
+#else
+#error "No active core selected."
+#endif
+
+/** SS I2C Interrupt register map. */
+typedef struct {
+ QM_RW uint32_t err_mask;
+ QM_RW uint32_t rx_avail_mask;
+ QM_RW uint32_t tx_req_mask;
+ QM_RW uint32_t stop_det_mask;
+} int_ss_i2c_reg_t;
+
+/** SS SPI Interrupt register map. */
+typedef struct {
+ QM_RW uint32_t err_int_mask;
+ QM_RW uint32_t rx_avail_mask;
+ QM_RW uint32_t tx_req_mask;
+} int_ss_spi_reg_t;
+
+/** Interrupt register map. */
+typedef struct {
+ QM_RW uint32_t ss_adc_0_error_int_mask; /**< Sensor ADC 0 Error. */
+ QM_RW uint32_t ss_adc_0_int_mask; /**< Sensor ADC 0. */
+ QM_RW uint32_t ss_gpio_0_int_mask; /**< Sensor GPIO 0. */
+ QM_RW uint32_t ss_gpio_1_int_mask; /**< Sensor GPIO 1. */
+ int_ss_i2c_reg_t ss_i2c_0_int; /**< Sensor I2C 0 Masks. */
+ int_ss_i2c_reg_t ss_i2c_1_int; /**< Sensor I2C 1 Masks. */
+ int_ss_spi_reg_t ss_spi_0_int; /**< Sensor SPI 0 Masks. */
+ int_ss_spi_reg_t ss_spi_1_int; /**< Sensor SPI 1 Masks. */
+ QM_RW uint32_t i2c_master_0_int_mask; /**< I2C Master 0. */
+ QM_RW uint32_t i2c_master_1_int_mask; /**< I2C Master 1. */
+ QM_R uint32_t reserved;
+ QM_RW uint32_t spi_master_0_int_mask; /**< SPI Master 0. */
+ QM_RW uint32_t spi_master_1_int_mask; /**< SPI Master 1. */
+ QM_RW uint32_t spi_slave_0_int_mask; /**< SPI Slave 0. */
+ QM_RW uint32_t uart_0_int_mask; /**< UART 0. */
+ QM_RW uint32_t uart_1_int_mask; /**< UART 1. */
+ QM_RW uint32_t i2s_0_int_mask; /**< I2S 0. */
+ QM_RW uint32_t gpio_0_int_mask; /**< GPIO 0. */
+ QM_RW uint32_t pwm_0_int_mask; /**< PWM 0. */
+ QM_RW uint32_t usb_0_int_mask; /**< USB 0. */
+ QM_RW uint32_t rtc_0_int_mask; /**< RTC 0. */
+ QM_RW uint32_t wdt_0_int_mask; /**< WDT 0. */
+ QM_RW uint32_t dma_0_int_0_mask; /**< DMA 0 Ch 0. */
+ QM_RW uint32_t dma_0_int_1_mask; /**< DMA 0 Ch 1. */
+ QM_RW uint32_t dma_0_int_2_mask; /**< DMA 0 Ch 2. */
+ QM_RW uint32_t dma_0_int_3_mask; /**< DMA 0 Ch 3. */
+ QM_RW uint32_t dma_0_int_4_mask; /**< DMA 0 Ch 4. */
+ QM_RW uint32_t dma_0_int_5_mask; /**< DMA 0 Ch 5. */
+ QM_RW uint32_t dma_0_int_6_mask; /**< DMA 0 Ch 6. */
+ QM_RW uint32_t dma_0_int_7_mask; /**< DMA 0 Ch 7. */
+ /** Mailbox 0 Combined 8 Channel Host and Sensor Masks. */
+ QM_RW uint32_t mailbox_0_int_mask;
+ /** Comparator Sensor Halt Mask. */
+ QM_RW uint32_t comparator_0_ss_halt_int_mask;
+ /** Comparator Host Halt Mask. */
+ QM_RW uint32_t comparator_0_host_halt_int_mask;
+ /** Comparator Sensor Mask. */
+ QM_RW uint32_t comparator_0_ss_int_mask;
+ /** Comparator Host Mask. */
+ QM_RW uint32_t comparator_0_host_int_mask;
+ QM_RW uint32_t host_bus_error_int_mask; /**< Host bus error. */
+ QM_RW uint32_t dma_0_error_int_mask; /**< DMA 0 Error. */
+ QM_RW uint32_t sram_mpr_0_int_mask; /**< SRAM MPR 0. */
+ QM_RW uint32_t flash_mpr_0_int_mask; /**< Flash MPR 0. */
+ QM_RW uint32_t flash_mpr_1_int_mask; /**< Flash MPR 1. */
+ QM_RW uint32_t aonpt_0_int_mask; /**< AONPT 0. */
+ QM_RW uint32_t adc_0_pwr_int_mask; /**< ADC 0 PWR. */
+ QM_RW uint32_t adc_0_cal_int_mask; /**< ADC 0 CAL. */
+ QM_RW uint32_t aon_gpio_0_int_mask; /**< AON GPIO 0. */
+ QM_RW uint32_t lock_int_mask_reg; /**< Interrupt Mask Lock Register. */
+} qm_interrupt_router_reg_t;
+
+/* Number of SCSS interrupt mask registers (excluding mask lock register). */
+#define QM_INTERRUPT_ROUTER_MASK_NUMREG \
+ ((sizeof(qm_interrupt_router_reg_t) / sizeof(uint32_t)) - 1)
+
+/* Default POR SCSS interrupt mask (all interrupts masked). */
+#define QM_INTERRUPT_ROUTER_MASK_DEFAULT (0xFFFFFFFF)
+
+#if (UNIT_TEST)
+qm_interrupt_router_reg_t test_interrupt_router;
+#define QM_INTERRUPT_ROUTER \
+ ((qm_interrupt_router_reg_t *)(&test_interrupt_router))
+
+#else
+/* System control subsystem interrupt masking register block. */
+#define QM_INTERRUPT_ROUTER_BASE (0xB0800400)
+#define QM_INTERRUPT_ROUTER \
+ ((qm_interrupt_router_reg_t *)QM_INTERRUPT_ROUTER_BASE)
+#endif
+
+#define QM_IR_DMA_ERROR_HOST_MASK (0x000000FF)
+#define QM_IR_DMA_ERROR_SS_MASK (0x0000FF00)
+
+/** @} */
+
+#endif /* __QM_INTERRUPT_ROUTER_REGS_H__ */
diff --git a/src/include/arc32/qm_sensor_regs.h b/src/include/arc32/qm_sensor_regs.h
new file mode 100644
index 0000000..324d001
--- /dev/null
+++ b/src/include/arc32/qm_sensor_regs.h
@@ -0,0 +1,673 @@
+/*
+ * Copyright (c) 2016, Intel Corporation
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of the Intel Corporation nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INTEL CORPORATION OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __SENSOR_REGISTERS_H__
+#define __SENSOR_REGISTERS_H__
+
+/**
+ * Quark SE SoC Sensor Subsystem Registers.
+ *
+ * For detailed description please read the SOC datasheet.
+ *
+ * @defgroup groupSSSEREG SoC Registers (Sensor Subsystem)
+ * @{
+ */
+
+#define BIT(x) (1U << (x))
+
+/* Bitwise OR operation macro for registers in the auxiliary memory space. */
+#define QM_SS_REG_AUX_OR(reg, mask) \
+ (__builtin_arc_sr(__builtin_arc_lr(reg) | (mask), reg))
+/* Bitwise NAND operation macro for registers in the auxiliary memory space. */
+#define QM_SS_REG_AUX_NAND(reg, mask) \
+ (__builtin_arc_sr(__builtin_arc_lr(reg) & (~(mask)), reg))
+
+/* Sensor Subsystem status32 register. */
+#define QM_SS_AUX_STATUS32 (0xA)
+/** Interrupt priority threshold. */
+#define QM_SS_STATUS32_E_MASK (0x1E)
+/** Interrupt enable. */
+#define QM_SS_STATUS32_IE_MASK BIT(31)
+/* Sensor Subsystem control register. */
+#define QM_SS_AUX_IC_CTRL (0x11)
+/* Sensor Subsystem cache invalidate register. */
+#define QM_SS_AUX_IC_IVIL (0x19)
+/* Sensor Subsystem vector base register. */
+#define QM_SS_AUX_INT_VECTOR_BASE (0x25)
+
+/**
+ * @name SS Interrupt
+ * @{
+ */
+
+#define QM_SS_EXCEPTION_NUM (16) /* Exceptions and traps in ARC EM core. */
+#define QM_SS_INT_TIMER_NUM (2) /* Internal interrupts in ARC EM core. */
+#define QM_SS_IRQ_SENSOR_NUM (18) /* IRQ's from the Sensor Subsystem. */
+#define QM_SS_IRQ_COMMON_NUM (32) /* IRQ's from the common SoC fabric. */
+#define QM_SS_INT_VECTOR_NUM \
+ (QM_SS_EXCEPTION_NUM + QM_SS_INT_TIMER_NUM + QM_SS_IRQ_SENSOR_NUM + \
+ QM_SS_IRQ_COMMON_NUM)
+#define QM_SS_IRQ_NUM (QM_SS_IRQ_SENSOR_NUM + QM_SS_IRQ_COMMON_NUM)
+
+/**
+ * SS IRQ context type.
+ *
+ * Applications should not modify the content.
+ * This structure is only intended to be used by
+ * qm_irq_save_context and qm_irq_restore_context functions.
+ */
+typedef struct {
+ uint32_t status32_irq_threshold; /**< STATUS32 Interrupt Threshold. */
+ uint32_t status32_irq_enable; /**< STATUS32 Interrupt Enable. */
+ uint32_t irq_ctrl; /**< Interrupt Context Saving Control Register. */
+
+ /**
+ * IRQ configuration:
+ * - IRQ Priority:BIT(6):BIT(2)
+ * - IRQ Trigger:BIT(1)
+ * - IRQ Enable:BIT(0)
+ */
+ uint8_t irq_config[QM_SS_INT_VECTOR_NUM - 1];
+} qm_irq_context_t;
+
+/** General Purpose register map. */
+typedef struct {
+ volatile uint32_t gps0; /**< General Purpose Sticky Register 0 */
+ volatile uint32_t gps1; /**< General Purpose Sticky Register 1 */
+ volatile uint32_t gps2; /**< General Purpose Sticky Register 2 */
+ volatile uint32_t gps3; /**< General Purpose Sticky Register 3 */
+ volatile uint32_t reserved;
+ volatile uint32_t gp0; /**< General Purpose Scratchpad Register 0 */
+ volatile uint32_t gp1; /**< General Purpose Scratchpad Register 1 */
+ volatile uint32_t gp2; /**< General Purpose Scratchpad Register 2 */
+ volatile uint32_t gp3; /**< General Purpose Scratchpad Register 3 */
+ volatile uint32_t reserved1;
+ volatile uint32_t id; /**< Identification Register */
+ volatile uint32_t rev; /**< Revision Register */
+ volatile uint32_t wo_sp; /**< Write-One-to-Set Scratchpad Register */
+ volatile uint32_t
+ wo_st; /**< Write-One-to-Set Sticky Scratchpad Register */
+} qm_scss_gp_reg_t;
+
+#define QM_SCSS_GP_BASE (0xB0800100)
+#define QM_SCSS_GP ((qm_scss_gp_reg_t *)QM_SCSS_GP_BASE)
+
+/* The GPS0 register usage. */
+#define QM_GPS0_BIT_FM (0) /**< Start Firmware Manager. */
+#define QM_GPS0_BIT_X86_WAKEUP (1) /**< Lakemont core reset type. */
+#define QM_GPS0_BIT_SENSOR_WAKEUP (2) /**< Sensor core reset type. */
+
+/** System Core register map. */
+typedef struct {
+ volatile uint32_t osc0_cfg0; /**< Hybrid Oscillator Configuration 0. */
+ volatile uint32_t osc0_stat1; /**< Hybrid Oscillator status 1. */
+ volatile uint32_t osc0_cfg1; /**< Hybrid Oscillator configuration 1. */
+ volatile uint32_t osc1_stat0; /**< RTC Oscillator status 0. */
+ volatile uint32_t osc1_cfg0; /**< RTC Oscillator Configuration 0. */
+ volatile uint32_t usb_pll_cfg0; /**< USB Phase lock look configuration. */
+ volatile uint32_t
+ ccu_periph_clk_gate_ctl; /**< Peripheral Clock Gate Control. */
+ volatile uint32_t
+ ccu_periph_clk_div_ctl0; /**< Peripheral Clock Divider Control. 0 */
+ volatile uint32_t
+ ccu_gpio_db_clk_ctl; /**< Peripheral Clock Divider Control 1. */
+ volatile uint32_t
+ ccu_ext_clock_ctl; /**< External Clock Control Register. */
+ /** Sensor Subsystem peripheral clock gate control. */
+ volatile uint32_t ccu_ss_periph_clk_gate_ctl;
+ volatile uint32_t ccu_lp_clk_ctl; /**< System Low Power Clock Control. */
+ volatile uint32_t reserved;
+ volatile uint32_t ccu_mlayer_ahb_ctl; /**< AHB Control Register. */
+ volatile uint32_t ccu_sys_clk_ctl; /**< System Clock Control Register. */
+ volatile uint32_t osc_lock_0; /**< Clocks Lock Register. */
+} qm_scss_ccu_reg_t;
+
+#define QM_SCSS_CCU ((qm_scss_ccu_reg_t *)SCSS_REGISTER_BASE)
+
+/** Power Management register map. */
+typedef struct {
+ volatile uint32_t p_lvl2; /**< Processor level 2 */
+ volatile uint32_t reserved[4];
+ volatile uint32_t pm1c; /**< Power management 1 control */
+ volatile uint32_t reserved1[9];
+ volatile uint32_t aon_vr; /**< AON Voltage Regulator */
+ volatile uint32_t plat3p3_vr; /**< Platform 3p3 voltage regulator */
+ volatile uint32_t plat1p8_vr; /**< Platform 1p8 voltage regulator */
+ volatile uint32_t host_vr; /**< Host Voltage Regulator */
+ volatile uint32_t slp_cfg; /**< Sleeping Configuration */
+ /** Power Management Network (PMNet) Control and Status */
+ volatile uint32_t pmnetcs;
+ volatile uint32_t pm_wait; /**< Power Management Wait */
+ volatile uint32_t reserved2;
+ volatile uint32_t p_sts; /**< Processor Status */
+ volatile uint32_t reserved3[3];
+ volatile uint32_t rstc; /**< Reset Control */
+ volatile uint32_t rsts; /**< Reset Status */
+ volatile uint32_t reserved4[6];
+ volatile uint32_t vr_lock; /**< Voltage regulator lock */
+ volatile uint32_t pm_lock; /**< Power Management Lock */
+} qm_scss_pmu_reg_t;
+
+#define QM_SCSS_PMU_BASE (0xB0800504)
+#define QM_SCSS_PMU ((qm_scss_pmu_reg_t *)QM_SCSS_PMU_BASE)
+
+#define QM_SS_CFG_ARC_RUN_REQ_A BIT(24)
+#define QM_P_STS_HALT_INTERRUPT_REDIRECTION BIT(26)
+#define QM_P_STS_ARC_HALT BIT(14)
+
+#define QM_AON_VR_VSEL_MASK (0xFFE0)
+#define QM_AON_VR_VSEL_1V2 (0x8)
+#define QM_AON_VR_VSEL_1V35 (0xB)
+#define QM_AON_VR_VSEL_1V8 (0x10)
+#define QM_AON_VR_EN BIT(7)
+#define QM_AON_VR_VSTRB BIT(5)
+
+#define QM_SCSS_SLP_CFG_LPMODE_EN BIT(8)
+#define QM_SCSS_SLP_CFG_RTC_DIS BIT(7)
+#define QM_SCSS_PM1C_SLPEN BIT(13)
+#define QM_SCSS_HOST_VR_EN BIT(7)
+#define QM_SCSS_PLAT3P3_VR_EN BIT(7)
+#define QM_SCSS_PLAT1P8_VR_EN BIT(7)
+#define QM_SCSS_HOST_VR_VREG_SEL BIT(6)
+#define QM_SCSS_PLAT3P3_VR_VREG_SEL BIT(6)
+#define QM_SCSS_PLAT1P8_VR_VREG_SEL BIT(6)
+#define QM_SCSS_VR_ROK BIT(10)
+#define QM_SCSS_VR_EN BIT(7)
+#define QM_SCSS_VR_VREG_SEL BIT(6)
+
+#define QM_SCSS_CCU_SS_LPS_EN BIT(0)
+
+typedef enum {
+ QM_SS_IRQ_LEVEL_SENSITIVE = 0,
+ QM_SS_IRQ_EDGE_SENSITIVE = 1
+} qm_ss_irq_trigger_t;
+
+#define QM_SS_AUX_IRQ_CTRL (0xE)
+#define QM_SS_AUX_IRQ_HINT (0x201)
+#define QM_SS_AUX_IRQ_PRIORITY (0x206)
+#define QM_SS_AUX_IRQ_STATUS (0x406)
+#define QM_SS_AUX_IRQ_SELECT (0x40B)
+#define QM_SS_AUX_IRQ_ENABLE (0x40C)
+#define QM_SS_AUX_IRQ_TRIGGER (0x40D)
+
+/** Always-On Timer Interrupt. */
+#define QM_IRQ_AONPT_0_INT 28
+#define QM_IRQ_AONPT_0_INT_MASK_OFFSET 32
+#define QM_IRQ_AONPT_0_INT_VECTOR 64
+
+/** RTC Single Interrupt. */
+#define QM_IRQ_RTC_0_INT 11
+#define QM_IRQ_RTC_0_INT_MASK_OFFSET 12
+#define QM_IRQ_RTC_0_INT_VECTOR 47
+
+/** @} */
+
+/**
+ * @name SS Timer
+ * @{
+ */
+
+typedef enum {
+ QM_SS_TIMER_COUNT = 0,
+ QM_SS_TIMER_CONTROL,
+ QM_SS_TIMER_LIMIT
+} qm_ss_timer_reg_t;
+
+/**
+ * Sensor Subsystem Timers.
+ */
+typedef enum { QM_SS_TIMER_0 = 0, QM_SS_TIMER_NUM } qm_ss_timer_t;
+
+/*
+ * SS TIMER context type.
+ *
+ * Application should not modify the content.
+ * This structure is only intended to be used by the qm_ss_timer_save_context
+ * and qm_ss_timer_restore_context functions.
+ */
+typedef struct {
+ uint32_t timer_count; /**< Timer count. */
+ uint32_t timer_control; /**< Timer control. */
+ uint32_t timer_limit; /**< Timer limit. */
+} qm_ss_timer_context_t;
+
+#define QM_SS_TIMER_0_BASE (0x21)
+#define QM_SS_TIMER_1_BASE (0x100)
+#define QM_SS_TSC_BASE QM_SS_TIMER_1_BASE
+
+#define QM_SS_TIMER_CONTROL_INT_EN_OFFSET (0)
+#define QM_SS_TIMER_CONTROL_NON_HALTED_OFFSET (1)
+#define QM_SS_TIMER_CONTROL_WATCHDOG_OFFSET (2)
+#define QM_SS_TIMER_CONTROL_INT_PENDING_OFFSET (3)
+/** @} */
+
+/**
+ * GPIO registers and definitions.
+ *
+ * @name SS GPIO
+ * @{
+ */
+
+/** Sensor Subsystem GPIO register block type. */
+typedef enum {
+ QM_SS_GPIO_SWPORTA_DR = 0,
+ QM_SS_GPIO_SWPORTA_DDR,
+ QM_SS_GPIO_INTEN = 3,
+ QM_SS_GPIO_INTMASK,
+ QM_SS_GPIO_INTTYPE_LEVEL,
+ QM_SS_GPIO_INT_POLARITY,
+ QM_SS_GPIO_INTSTATUS,
+ QM_SS_GPIO_DEBOUNCE,
+ QM_SS_GPIO_PORTA_EOI,
+ QM_SS_GPIO_EXT_PORTA,
+ QM_SS_GPIO_LS_SYNC
+} qm_ss_gpio_reg_t;
+
+/**
+ * SS GPIO context type.
+ *
+ * Application should not modify the content.
+ * This structure is only intended to be used by the qm_ss_gpio_save_context and
+ * qm_ss_gpio_restore_context functions.
+ */
+typedef struct {
+ uint32_t gpio_swporta_dr; /**< Port A Data. */
+ uint32_t gpio_swporta_ddr; /**< Port A Data Direction. */
+ uint32_t gpio_inten; /**< Interrupt Enable. */
+ uint32_t gpio_intmask; /**< Interrupt Mask. */
+ uint32_t gpio_inttype_level; /**< Interrupt Type. */
+ uint32_t gpio_int_polarity; /**< Interrupt Polarity. */
+ uint32_t gpio_debounce; /**< Debounce Enable. */
+ uint32_t gpio_ls_sync; /**< Synchronization Level. */
+} qm_ss_gpio_context_t;
+
+#define QM_SS_GPIO_NUM_PINS (16)
+#define QM_SS_GPIO_LS_SYNC_CLK_EN BIT(31)
+#define QM_SS_GPIO_LS_SYNC_SYNC_LVL BIT(0)
+
+/** Sensor Subsystem GPIO. */
+typedef enum { QM_SS_GPIO_0 = 0, QM_SS_GPIO_1, QM_SS_GPIO_NUM } qm_ss_gpio_t;
+
+#define QM_SS_GPIO_0_BASE (0x80017800)
+#define QM_SS_GPIO_1_BASE (0x80017900)
+
+/** @} */
+
+/**
+ * I2C registers and definitions.
+ *
+ * @name SS I2C
+ * @{
+ */
+
+/** Sensor Subsystem I2C register block type. */
+typedef enum {
+ QM_SS_I2C_CON = 0,
+ QM_SS_I2C_DATA_CMD,
+ QM_SS_I2C_SS_SCL_CNT,
+ QM_SS_I2C_FS_SCL_CNT = 0x04,
+ QM_SS_I2C_INTR_STAT = 0x06,
+ QM_SS_I2C_INTR_MASK,
+ QM_SS_I2C_TL,
+ QM_SS_I2C_INTR_CLR = 0x0A,
+ QM_SS_I2C_STATUS,
+ QM_SS_I2C_TXFLR,
+ QM_SS_I2C_RXFLR,
+ QM_SS_I2C_SDA_CONFIG,
+ QM_SS_I2C_TX_ABRT_SOURCE,
+ QM_SS_I2C_ENABLE_STATUS = 0x11
+} qm_ss_i2c_reg_t;
+
+/**
+ * SS I2C context type.
+ *
+ * Application should not modify the content.
+ * This structure is only intended to be used by the qm_ss_gpio_save_context and
+ * qm_ss_gpio_restore_context functions.
+ */
+typedef struct {
+ uint32_t i2c_con;
+ uint32_t i2c_ss_scl_cnt;
+ uint32_t i2c_fs_scl_cnt;
+} qm_ss_i2c_context_t;
+
+#define QM_SS_I2C_CON_ENABLE BIT(0)
+#define QM_SS_I2C_CON_ABORT BIT(1)
+#define QM_SS_I2C_CON_SPEED_SS BIT(3)
+#define QM_SS_I2C_CON_SPEED_FS BIT(4)
+#define QM_SS_I2C_CON_SPEED_MASK (0x18)
+#define QM_SS_I2C_CON_IC_10BITADDR BIT(5)
+#define QM_SS_I2C_CON_IC_10BITADDR_OFFSET (5)
+#define QM_SS_I2C_CON_IC_10BITADDR_MASK (5)
+#define QM_SS_I2C_CON_RESTART_EN BIT(7)
+#define QM_SS_I2C_CON_TAR_SAR_OFFSET (9)
+#define QM_SS_I2C_CON_TAR_SAR_MASK (0x7FE00)
+#define QM_SS_I2C_CON_TAR_SAR_10_BIT_MASK (0x3FF)
+#define QM_SS_I2C_CON_SPKLEN_OFFSET (22)
+#define QM_SS_I2C_CON_SPKLEN_MASK (0x3FC00000)
+#define QM_SS_I2C_CON_CLK_ENA BIT(31)
+
+#define QM_SS_I2C_DATA_CMD_CMD BIT(8)
+#define QM_SS_I2C_DATA_CMD_STOP BIT(9)
+#define QM_SS_I2C_DATA_CMD_PUSH (0xC0000000)
+#define QM_SS_I2C_DATA_CMD_POP (0x80000000)
+
+#define QM_SS_I2C_SS_FS_SCL_CNT_HCNT_OFFSET (16)
+#define QM_SS_I2C_SS_FS_SCL_CNT_16BIT_MASK (0xFFFF)
+
+#define QM_SS_I2C_INTR_STAT_RX_UNDER BIT(0)
+#define QM_SS_I2C_INTR_STAT_RX_OVER BIT(1)
+#define QM_SS_I2C_INTR_STAT_RX_FULL BIT(2)
+#define QM_SS_I2C_INTR_STAT_TX_OVER BIT(3)
+#define QM_SS_I2C_INTR_STAT_TX_EMPTY BIT(4)
+#define QM_SS_I2C_INTR_STAT_TX_ABRT BIT(6)
+
+#define QM_SS_I2C_INTR_MASK_ALL (0x0)
+#define QM_SS_I2C_INTR_MASK_RX_UNDER BIT(0)
+#define QM_SS_I2C_INTR_MASK_RX_OVER BIT(1)
+#define QM_SS_I2C_INTR_MASK_RX_FULL BIT(2)
+#define QM_SS_I2C_INTR_MASK_TX_OVER BIT(3)
+#define QM_SS_I2C_INTR_MASK_TX_EMPTY BIT(4)
+#define QM_SS_I2C_INTR_MASK_TX_ABRT BIT(6)
+
+#define QM_SS_I2C_TL_TX_TL_OFFSET (16)
+#define QM_SS_I2C_TL_RX_TL_MASK (0xFF)
+#define QM_SS_I2C_TL_TX_TL_MASK (0xFF0000)
+
+#define QM_SS_I2C_INTR_CLR_ALL (0xFF)
+#define QM_SS_I2C_INTR_CLR_TX_ABRT BIT(6)
+
+#define QM_SS_I2C_TX_ABRT_SOURCE_NAK_MASK (0x09)
+#define QM_SS_I2C_TX_ABRT_SOURCE_ALL_MASK (0x1FFFF)
+#define QM_SS_I2C_TX_ABRT_SBYTE_NORSTRT BIT(9)
+#define QM_SS_I2C_TX_ABRT_SOURCE_ART_LOST BIT(12)
+
+#define QM_SS_I2C_ENABLE_CONTROLLER_EN BIT(0)
+#define QM_SS_I2C_ENABLE_STATUS_IC_EN BIT(0)
+
+#define QM_SS_I2C_STATUS_BUSY_MASK (0x21)
+#define QM_SS_I2C_STATUS_RFNE BIT(3)
+#define QM_SS_I2C_STATUS_TFE BIT(2)
+#define QM_SS_I2C_STATUS_TFNF BIT(1)
+
+#define QM_SS_I2C_IC_LCNT_MAX (65525)
+#define QM_SS_I2C_IC_LCNT_MIN (8)
+#define QM_SS_I2C_IC_HCNT_MAX (65525)
+#define QM_SS_I2C_IC_HCNT_MIN (6)
+
+#define QM_SS_I2C_FIFO_SIZE (8)
+
+/** Sensor Subsystem I2C */
+typedef enum { QM_SS_I2C_0 = 0, QM_SS_I2C_1, QM_SS_I2C_NUM } qm_ss_i2c_t;
+
+#define QM_SS_I2C_0_BASE (0x80012000)
+#define QM_SS_I2C_1_BASE (0x80012100)
+
+/** @} */
+/** Sensor Subsystem ADC @{*/
+
+/** Sensor Subsystem ADC registers */
+typedef enum {
+ QM_SS_ADC_SET = 0, /**< ADC and sequencer settings register. */
+ QM_SS_ADC_DIVSEQSTAT, /**< ADC clock and sequencer status register. */
+ QM_SS_ADC_SEQ, /**< ADC sequence entry register. */
+ QM_SS_ADC_CTRL, /**< ADC control register. */
+ QM_SS_ADC_INTSTAT, /**< ADC interrupt status register. */
+ QM_SS_ADC_SAMPLE /**< ADC sample register. */
+} qm_ss_adc_reg_t;
+
+/** Sensor Subsystem ADC */
+typedef enum {
+ QM_SS_ADC_0 = 0, /**< ADC first module. */
+ QM_SS_ADC_NUM
+} qm_ss_adc_t;
+
+/**
+ * SS ADC context type.
+ *
+ * The application should not modify the content of this structure.
+ *
+ * This structure is intented to be used by qm_ss_adc_save_context and
+ * qm_ss_adc_restore_context functions only.
+ */
+typedef struct {
+ uint32_t adc_set; /**< ADC settings. */
+ uint32_t adc_divseqstat; /**< ADC clock divider and sequencer status. */
+ uint32_t adc_seq; /**< ADC sequencer entry. */
+ uint32_t adc_ctrl; /**< ADC control. */
+} qm_ss_adc_context_t;
+
+/* SS ADC register base. */
+#define QM_SS_ADC_BASE (0x80015000)
+
+/* For 1MHz, the max divisor is 7. */
+#define QM_SS_ADC_DIV_MAX (7)
+
+#define QM_SS_ADC_FIFO_LEN (32)
+
+#define QM_SS_ADC_SET_POP_RX BIT(31)
+#define QM_SS_ADC_SET_FLUSH_RX BIT(30)
+#define QM_SS_ADC_SET_THRESHOLD_MASK (0x3F000000)
+#define QM_SS_ADC_SET_THRESHOLD_OFFSET (24)
+#define QM_SS_ADC_SET_SEQ_ENTRIES_MASK (0x3F0000)
+#define QM_SS_ADC_SET_SEQ_ENTRIES_OFFSET (16)
+#define QM_SS_ADC_SET_SEQ_MODE BIT(13)
+#define QM_SS_ADC_SET_SAMPLE_WIDTH_MASK (0x1F)
+
+#define QM_SS_ADC_DIVSEQSTAT_CLK_RATIO_MASK (0x1FFFFF)
+
+#define QM_SS_ADC_CTRL_CLR_SEQERROR BIT(19)
+#define QM_SS_ADC_CTRL_CLR_UNDERFLOW BIT(18)
+#define QM_SS_ADC_CTRL_CLR_OVERFLOW BIT(17)
+#define QM_SS_ADC_CTRL_CLR_DATA_A BIT(16)
+#define QM_SS_ADC_CTRL_MSK_SEQERROR BIT(11)
+#define QM_SS_ADC_CTRL_MSK_UNDERFLOW BIT(10)
+#define QM_SS_ADC_CTRL_MSK_OVERFLOW BIT(9)
+#define QM_SS_ADC_CTRL_MSK_DATA_A BIT(8)
+#define QM_SS_ADC_CTRL_SEQ_TABLE_RST BIT(6)
+#define QM_SS_ADC_CTRL_SEQ_PTR_RST BIT(5)
+#define QM_SS_ADC_CTRL_SEQ_START BIT(4)
+#define QM_SS_ADC_CTRL_CLK_ENA BIT(2)
+#define QM_SS_ADC_CTRL_ADC_ENA BIT(1)
+
+#define QM_SS_ADC_CTRL_MSK_ALL_INT (0xF00)
+#define QM_SS_ADC_CTRL_CLR_ALL_INT (0xF0000)
+
+#define QM_SS_ADC_SEQ_DELAYODD_OFFSET (21)
+#define QM_SS_ADC_SEQ_MUXODD_OFFSET (16)
+#define QM_SS_ADC_SEQ_DELAYEVEN_OFFSET (5)
+
+#define QM_SS_ADC_SEQ_DUMMY (0x480)
+
+#define QM_SS_ADC_INTSTAT_SEQERROR BIT(3)
+#define QM_SS_ADC_INTSTAT_UNDERFLOW BIT(2)
+#define QM_SS_ADC_INTSTAT_OVERFLOW BIT(1)
+#define QM_SS_ADC_INTSTAT_DATA_A BIT(0)
+
+/** End of Sensor Subsystem ADC @}*/
+
+/**
+ * CREG Registers.
+ *
+ * @name SS CREG
+ * @{
+ */
+
+/* Sensor Subsystem CREG */
+typedef enum {
+ QM_SS_IO_CREG_MST0_CTRL = 0x0, /**< Master control register. */
+ QM_SS_IO_CREG_SLV0_OBSR = 0x80, /**< Slave control register. */
+ QM_SS_IO_CREG_SLV1_OBSR = 0x180 /**< Slave control register. */
+} qm_ss_creg_reg_t;
+
+/* MST0_CTRL fields */
+#define QM_SS_IO_CREG_MST0_CTRL_ADC_PWR_MODE_OFFSET (1)
+#define QM_SS_IO_CREG_MST0_CTRL_ADC_PWR_MODE_MASK (0x7)
+#define QM_SS_IO_CREG_MST0_CTRL_ADC_DELAY_OFFSET (3)
+#define QM_SS_IO_CREG_MST0_CTRL_ADC_DELAY_MASK (0xFFF8)
+#define QM_SS_IO_CREG_MST0_CTRL_ADC_CAL_REQ BIT(16)
+#define QM_SS_IO_CREG_MST0_CTRL_ADC_CAL_CMD_OFFSET (17)
+#define QM_SS_IO_CREG_MST0_CTRL_ADC_CAL_CMD_MASK (0xE0000)
+#define QM_SS_IO_CREG_MST0_CTRL_ADC_CAL_VAL_OFFSET (20)
+#define QM_SS_IO_CREG_MST0_CTRL_ADC_CAL_VAL_MASK (0x7F00000)
+#define QM_SS_IO_CREG_MST0_CTRL_ADC_CAL_VAL_MAX (0x7F)
+#define QM_SS_IO_CREG_MST0_CTRL_SPI1_CLK_GATE BIT(27)
+#define QM_SS_IO_CREG_MST0_CTRL_SPI0_CLK_GATE BIT(28)
+#define QM_SS_IO_CREG_MST0_CTRL_I2C0_CLK_GATE BIT(29)
+#define QM_SS_IO_CREG_MST0_CTRL_I2C1_CLK_GATE BIT(30)
+#define QM_SS_IO_CREG_MST0_CTRL_ADC_CLK_GATE BIT(31)
+/* SLV0_OBSR fields */
+#define QM_SS_IO_CREG_SLV0_OBSR_ADC_CAL_VAL_OFFSET (5)
+#define QM_SS_IO_CREG_SLV0_OBSR_ADC_CAL_VAL_MASK (0xFE0)
+#define QM_SS_IO_CREG_SLV0_OBSR_ADC_CAL_ACK BIT(4)
+#define QM_SS_IO_CREG_SLV0_OBSR_ADC_PWR_MODE_STS BIT(3)
+
+#define SS_CLK_PERIPH_ALL_IN_CREG \
+ (SS_CLK_PERIPH_ADC | SS_CLK_PERIPH_I2C_1 | SS_CLK_PERIPH_I2C_0 | \
+ SS_CLK_PERIPH_SPI_1 | SS_CLK_PERIPH_SPI_0)
+
+/* SS CREG base. */
+#define QM_SS_CREG_BASE (0x80018000)
+
+/** @} */
+
+/**
+ * I2C registers and definitions.
+ *
+ * @name SS SPI
+ * @{
+ */
+
+/** Sensor Subsystem SPI register map. */
+typedef enum {
+ QM_SS_SPI_CTRL = 0, /**< SPI control register. */
+ QM_SS_SPI_SPIEN = 2, /**< SPI enable register. */
+ QM_SS_SPI_TIMING = 4, /**< SPI serial clock divider value. */
+ QM_SS_SPI_FTLR, /**< Threshold value for TX/RX FIFO. */
+ QM_SS_SPI_TXFLR = 7, /**< Number of valid data entries in TX FIFO. */
+ QM_SS_SPI_RXFLR, /**< Number of valid data entries in RX FIFO. */
+ QM_SS_SPI_SR, /**< SPI status register. */
+ QM_SS_SPI_INTR_STAT, /**< Interrupt status register. */
+ QM_SS_SPI_INTR_MASK, /**< Interrupt mask register. */
+ QM_SS_SPI_CLR_INTR, /**< Interrupt clear register. */
+ QM_SS_SPI_DR, /**< RW buffer for FIFOs. */
+} qm_ss_spi_reg_t;
+
+/**
+ * Sensor Subsystem SPI context type.
+ *
+ * Applications should not modify the content.
+ * This structure is only intended to be used by
+ * the qm_ss_spi_save_context and qm_ss_spi_restore_context functions.
+ */
+typedef struct {
+ uint32_t spi_ctrl; /**< Control Register. */
+ uint32_t spi_spien; /**< SPI Enable Register. */
+ uint32_t spi_timing; /**< Timing Register. */
+} qm_ss_spi_context_t;
+
+/** Sensor Subsystem SPI modules. */
+typedef enum {
+ QM_SS_SPI_0 = 0, /**< SPI module 0 */
+ QM_SS_SPI_1, /**< SPI module 1 */
+ QM_SS_SPI_NUM
+} qm_ss_spi_t;
+
+#define QM_SS_SPI_0_BASE (0x80010000)
+#define QM_SS_SPI_1_BASE (0x80010100)
+
+#define QM_SS_SPI_CTRL_DFS_OFFS (0)
+#define QM_SS_SPI_CTRL_DFS_MASK (0x0000000F)
+#define QM_SS_SPI_CTRL_BMOD_OFFS (6)
+#define QM_SS_SPI_CTRL_BMOD_MASK (0x000000C0)
+#define QM_SS_SPI_CTRL_SCPH BIT(6)
+#define QM_SS_SPI_CTRL_SCPOL BIT(7)
+#define QM_SS_SPI_CTRL_TMOD_OFFS (8)
+#define QM_SS_SPI_CTRL_TMOD_MASK (0x00000300)
+#define QM_SS_SPI_CTRL_SRL BIT(11)
+#define QM_SS_SPI_CTRL_CLK_ENA BIT(15)
+#define QM_SS_SPI_CTRL_NDF_OFFS (16)
+#define QM_SS_SPI_CTRL_NDF_MASK (0xFFFF0000)
+
+#define QM_SS_SPI_SPIEN_EN BIT(0)
+#define QM_SS_SPI_SPIEN_SER_OFFS (4)
+#define QM_SS_SPI_SPIEN_SER_MASK (0x000000F0)
+
+#define QM_SS_SPI_TIMING_SCKDV_OFFS (0)
+#define QM_SS_SPI_TIMING_SCKDV_MASK (0x0000FFFF)
+#define QM_SS_SPI_TIMING_RSD_OFFS (16)
+#define QM_SS_SPI_TIMING_RSD_MASK (0x00FF0000)
+
+#define QM_SS_SPI_FTLR_RFT_OFFS (0)
+#define QM_SS_SPI_FTLR_RFT_MASK (0x0000FFFF)
+#define QM_SS_SPI_FTLR_TFT_OFFS (16)
+#define QM_SS_SPI_FTLR_TFT_MASK (0xFFFF0000)
+
+#define QM_SS_SPI_SR_BUSY BIT(0)
+#define QM_SS_SPI_SR_TFNF BIT(1)
+#define QM_SS_SPI_SR_TFE BIT(2)
+#define QM_SS_SPI_SR_RFNE BIT(3)
+#define QM_SS_SPI_SR_RFF BIT(4)
+
+#define QM_SS_SPI_INTR_TXEI BIT(0)
+#define QM_SS_SPI_INTR_TXOI BIT(1)
+#define QM_SS_SPI_INTR_RXUI BIT(2)
+#define QM_SS_SPI_INTR_RXOI BIT(3)
+#define QM_SS_SPI_INTR_RXFI BIT(4)
+#define QM_SS_SPI_INTR_ALL (0x0000001F)
+
+#define QM_SS_SPI_INTR_STAT_TXEI QM_SS_SPI_INTR_TXEI
+#define QM_SS_SPI_INTR_STAT_TXOI QM_SS_SPI_INTR_TXOI
+#define QM_SS_SPI_INTR_STAT_RXUI QM_SS_SPI_INTR_RXUI
+#define QM_SS_SPI_INTR_STAT_RXOI QM_SS_SPI_INTR_RXOI
+#define QM_SS_SPI_INTR_STAT_RXFI QM_SS_SPI_INTR_RXFI
+
+#define QM_SS_SPI_INTR_MASK_TXEI QM_SS_SPI_INTR_TXEI
+#define QM_SS_SPI_INTR_MASK_TXOI QM_SS_SPI_INTR_TXOI
+#define QM_SS_SPI_INTR_MASK_RXUI QM_SS_SPI_INTR_RXUI
+#define QM_SS_SPI_INTR_MASK_RXOI QM_SS_SPI_INTR_RXOI
+#define QM_SS_SPI_INTR_MASK_RXFI QM_SS_SPI_INTR_RXFI
+
+#define QM_SS_SPI_CLR_INTR_TXEI QM_SS_SPI_INTR_TXEI
+#define QM_SS_SPI_CLR_INTR_TXOI QM_SS_SPI_INTR_TXOI
+#define QM_SS_SPI_CLR_INTR_RXUI QM_SS_SPI_INTR_RXUI
+#define QM_SS_SPI_CLR_INTR_RXOI QM_SS_SPI_INTR_RXOI
+#define QM_SS_SPI_CLR_INTR_RXFI QM_SS_SPI_INTR_RXFI
+
+#define QM_SS_SPI_DR_DR_OFFS (0)
+#define QM_SS_SPI_DR_DR_MASK (0x0000FFFF)
+#define QM_SS_SPI_DR_WR BIT(30)
+#define QM_SS_SPI_DR_STROBE BIT(31)
+#define QM_SS_SPI_DR_W_MASK (0xc0000000)
+#define QM_SS_SPI_DR_R_MASK (0x80000000)
+
+/** @} */
+/** @} */
+
+#endif /* __SENSOR_REGISTERS_H__ */
diff --git a/src/include/arc32/qm_soc_interrupts.h b/src/include/arc32/qm_soc_interrupts.h
new file mode 100644
index 0000000..9acd4c3
--- /dev/null
+++ b/src/include/arc32/qm_soc_interrupts.h
@@ -0,0 +1,410 @@
+/*
+ * Copyright (c) 2016, Intel Corporation
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of the Intel Corporation nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INTEL CORPORATION OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __QM_SOC_INTERRUPTS_H__
+#define __QM_SOC_INTERRUPTS_H__
+
+/**
+ * Quark SE SoC Interrupts.
+ *
+ * @defgroup groupQUARKSESEINT SoC Interrupts (SE)
+ * @{
+ */
+
+#if (QM_LAKEMONT)
+
+/* x86 internal interrupt vectors. */
+#define QM_X86_DIVIDE_ERROR_INT (0)
+#define QM_X86_DEBUG_EXCEPTION_INT (1)
+#define QM_X86_NMI_INTERRUPT_INT (2)
+#define QM_X86_BREAKPOINT_INT (3)
+#define QM_X86_OVERFLOW_INT (4)
+#define QM_X86_BOUND_RANGE_EXCEEDED_INT (5)
+#define QM_X86_INVALID_OPCODE_INT (6)
+#define QM_X86_DEVICE_NOT_AVAILABLE_INT (7)
+#define QM_X86_DOUBLE_FAULT_INT (8)
+#define QM_X86_INTEL_RESERVED_09_INT (9)
+#define QM_X86_INVALID_TSS_INT (10)
+#define QM_X86_SEGMENT_NOT_PRESENT_INT (11)
+#define QM_X86_STACK_SEGMENT_FAULT_INT (12)
+#define QM_X86_GENERAL_PROTECT_FAULT_INT (13)
+#define QM_X86_PAGE_FAULT_INT (14)
+#define QM_X86_INTEL_RESERVED_15_INT (15)
+#define QM_X86_FLOATING_POINT_ERROR_INT (16)
+#define QM_X86_ALIGNMENT_CHECK_INT (17)
+#define QM_X86_INTEL_RESERVED_18_INT (18)
+#define QM_X86_INTEL_RESERVED_19_INT (19)
+#define QM_X86_INTEL_RESERVED_20_INT (20)
+#define QM_X86_INTEL_RESERVED_21_INT (21)
+#define QM_X86_INTEL_RESERVED_22_INT (22)
+#define QM_X86_INTEL_RESERVED_23_INT (23)
+#define QM_X86_INTEL_RESERVED_24_INT (24)
+#define QM_X86_INTEL_RESERVED_25_INT (25)
+#define QM_X86_INTEL_RESERVED_26_INT (26)
+#define QM_X86_INTEL_RESERVED_27_INT (27)
+#define QM_X86_INTEL_RESERVED_28_INT (28)
+#define QM_X86_INTEL_RESERVED_29_INT (29)
+#define QM_X86_INTEL_RESERVED_30_INT (30)
+#define QM_X86_INTEL_RESERVED_31_INT (31)
+
+#define QM_X86_PIC_TIMER_INT_VECTOR (32)
+
+#endif /* QM_LAKEMONT */
+
+#if (QM_SENSOR)
+
+/* ARC EM processor internal interrupt vector assignments. */
+#define QM_ARC_RESET_INT (0)
+#define QM_ARC_MEMORY_ERROR_INT (1)
+#define QM_ARC_INSTRUCTION_ERROR_INT (2)
+#define QM_ARC_MACHINE_CHECK_EXCEPTION_INT (3)
+#define QM_ARC_INSTRUCTION_TLB_MISS_INT (4)
+#define QM_ARC_DATA_TLB_MISS_INT (5)
+#define QM_ARC_PROTECTION_VIOLATION_INT (6)
+#define QM_ARC_PRIVILEGE_VIOLATION_INT (7)
+#define QM_ARC_SOFTWARE_INTERRUPT_INT (8)
+#define QM_ARC_TRAP_INT (9)
+#define QM_ARC_EXTENSION_INSTRUCTION_EXCEPTION_INT (10)
+#define QM_ARC_DIVIDE_BY_ZERO_INT (11)
+#define QM_ARC_DATA_CACHE_CONSISTENCY_ERROR_INT (12)
+#define QM_ARC_MISALIGNED_DATA_ACCESS_INT (13)
+#define QM_ARC_RESERVED_14_INT (14)
+#define QM_ARC_RESERVED_15_INT (15)
+#define QM_ARC_TIMER_0_INT (16)
+#define QM_ARC_TIMER_1_INT (17)
+
+#endif /* QM_SENSOR */
+
+#if (QM_SENSOR)
+/**
+ * Sensor Sub-System Specific IRQs and interrupt vectors.
+ *
+ * @name SS Interrupt
+ * @{
+ */
+
+#define QM_SS_EXCEPTION_NUM (16) /* Exceptions and traps in ARC EM core. */
+#define QM_SS_INT_TIMER_NUM (2) /* Internal interrupts in ARC EM core. */
+#define QM_SS_IRQ_SENSOR_NUM (18) /* IRQ's from the Sensor Subsystem. */
+#define QM_SS_IRQ_COMMON_NUM (32) /* IRQ's from the common SoC fabric. */
+#define QM_SS_INT_VECTOR_NUM \
+ (QM_SS_EXCEPTION_NUM + QM_SS_INT_TIMER_NUM + QM_SS_IRQ_SENSOR_NUM + \
+ QM_SS_IRQ_COMMON_NUM)
+#define QM_SS_IRQ_NUM (QM_SS_IRQ_SENSOR_NUM + QM_SS_IRQ_COMMON_NUM)
+
+/*
+ * The following definitions are Sensor Subsystem interrupt irq and vector
+ * numbers:
+ * #define QM_SS_xxx - irq number
+ * #define QM_SS_xxx_VECTOR - vector number
+ */
+
+/** Sensor Subsystem ADC Rx Fifo Error Interrupt. */
+#define QM_SS_IRQ_ADC_0_ERROR_INT 0
+#define QM_SS_IRQ_ADC_0_ERROR_INT_VECTOR 18
+
+/** Sensor Subsystem ADC Data Available Interrupt. */
+#define QM_SS_IRQ_ADC_0_INT 1
+#define QM_SS_IRQ_ADC_0_INT_VECTOR 19
+
+/** Sensor Subsystem GPIO Single Interrupt 0 */
+#define QM_SS_IRQ_GPIO_0_INT 2
+#define QM_SS_IRQ_GPIO_0_INT_VECTOR 20
+
+/** Sensor Subsystem GPIO Single Interrupt 1. */
+#define QM_SS_IRQ_GPIO_1_INT 3
+#define QM_SS_IRQ_GPIO_1_INT_VECTOR 21
+
+/** Sensor Subsystem I2C 0 Error Interrupt. */
+#define QM_SS_IRQ_I2C_0_ERROR_INT 4
+#define QM_SS_IRQ_I2C_0_ERROR_INT_VECTOR 22
+
+/** Sensor Subsystem I2C 0 Data Available Interrupt. */
+#define QM_SS_IRQ_I2C_0_RX_AVAIL_INT 5
+#define QM_SS_IRQ_I2C_0_RX_AVAIL_INT_VECTOR 23
+
+/** Sensor Subsystem I2C 0 Data Required Interrupt. */
+#define QM_SS_IRQ_I2C_0_TX_REQ_INT 6
+#define QM_SS_IRQ_I2C_0_TX_REQ_INT_VECTOR 24
+
+/** Sensor Subsystem I2C 0 Stop Detect Interrupt. */
+#define QM_SS_IRQ_I2C_0_STOP_DET_INT 7
+#define QM_SS_IRQ_I2C_0_STOP_DET_INT_VECTOR 25
+
+/** Sensor Subsystem I2C 1 Error Interrupt. */
+#define QM_SS_IRQ_I2C_1_ERROR_INT 8
+#define QM_SS_IRQ_I2C_1_ERROR_INT_VECTOR 26
+
+/** Sensor Subsystem I2C 1 Data Available Interrupt. */
+#define QM_SS_IRQ_I2C_1_RX_AVAIL_INT 9
+#define QM_SS_IRQ_I2C_1_RX_AVAIL_INT_VECTOR 27
+
+/** Sensor Subsystem I2C 1 Data Required Interrupt. */
+#define QM_SS_IRQ_I2C_1_TX_REQ_INT 10
+#define QM_SS_IRQ_I2C_1_TX_REQ_INT_VECTOR 28
+
+/** Sensor Subsystem I2C 1 Stop Detect Interrupt. */
+#define QM_SS_IRQ_I2C_1_STOP_DET_INT 11
+#define QM_SS_IRQ_I2C_1_STOP_DET_INT_VECTOR 29
+
+/** Sensor Subsystem SPI 0 Error Interrupt. */
+#define QM_SS_IRQ_SPI_0_ERROR_INT 12
+#define QM_SS_IRQ_SPI_0_ERROR_INT_VECTOR 30
+
+/** Sensor Subsystem SPI 0 Data Available Interrupt. */
+#define QM_SS_IRQ_SPI_0_RX_AVAIL_INT 13
+#define QM_SS_IRQ_SPI_0_RX_AVAIL_INT_VECTOR 31
+
+/** Sensor Subsystem SPI 0 Data Required Interrupt. */
+#define QM_SS_IRQ_SPI_0_TX_REQ_INT 14
+#define QM_SS_IRQ_SPI_0_TX_REQ_INT_VECTOR 32
+
+/** Sensor Subsystem SPI 1 Error Interrupt. */
+#define QM_SS_IRQ_SPI_1_ERROR_INT 15
+#define QM_SS_IRQ_SPI_1_ERROR_INT_VECTOR 33
+
+/** Sensor Subsystem SPI 1 Data Available Interrupt. */
+#define QM_SS_IRQ_SPI_1_RX_AVAIL_INT 16
+#define QM_SS_IRQ_SPI_1_RX_AVAIL_INT_VECTOR 34
+
+/** Sensor Subsystem SPI 1 Data Required Interrupt. */
+#define QM_SS_IRQ_SPI_1_TX_REQ_INT 17
+#define QM_SS_IRQ_SPI_1_TX_REQ_INT_VECTOR 35
+
+typedef enum {
+ QM_SS_INT_PRIORITY_0 = 0,
+ QM_SS_INT_PRIORITY_1 = 1,
+ QM_SS_INT_PRIORITY_15 = 15,
+ QM_SS_INT_PRIORITY_NUM
+} qm_ss_irq_priority_t;
+
+typedef enum { QM_SS_INT_DISABLE = 0, QM_SS_INT_ENABLE = 1 } qm_ss_irq_mask_t;
+
+typedef enum {
+ QM_SS_IRQ_LEVEL_SENSITIVE = 0,
+ QM_SS_IRQ_EDGE_SENSITIVE = 1
+} qm_ss_irq_trigger_t;
+
+#define QM_SS_AUX_IRQ_CTRL (0xE)
+#define QM_SS_AUX_IRQ_HINT (0x201)
+#define QM_SS_AUX_IRQ_PRIORITY (0x206)
+#define QM_SS_AUX_IRQ_STATUS (0x406)
+#define QM_SS_AUX_IRQ_SELECT (0x40B)
+#define QM_SS_AUX_IRQ_ENABLE (0x40C)
+#define QM_SS_AUX_IRQ_TRIGGER (0x40D)
+
+/** @} */
+
+#endif /* QM_SENSOR */
+
+/**
+ * @name Common SoC IRQs and Interrupts
+ * @{
+ */
+
+/* IRQs and interrupt vectors.
+ *
+ * Any IRQ > 1 actually has a event router mask register offset of +1.
+ * The vector numbers must be defined without arithmetic expressions nor
+ * parentheses because they are expanded as token concatenation.
+ */
+
+/** I2C Master 0 Single Interrupt. */
+#define QM_IRQ_I2C_0_INT 0
+#define QM_IRQ_I2C_0_INT_MASK_OFFSET 0
+#define QM_IRQ_I2C_0_INT_VECTOR 36
+
+/** I2C Master 1 Single Interrupt. */
+#define QM_IRQ_I2C_1_INT 1
+#define QM_IRQ_I2C_1_INT_MASK_OFFSET 1
+#define QM_IRQ_I2C_1_INT_VECTOR 37
+
+/** SPI Master 0 Single Interrupt. */
+#define QM_IRQ_SPI_MASTER_0_INT 2
+#define QM_IRQ_SPI_MASTER_0_INT_MASK_OFFSET 3
+#define QM_IRQ_SPI_MASTER_0_INT_VECTOR 38
+
+/** SPI Master 1 Single Interrupt. */
+#define QM_IRQ_SPI_MASTER_1_INT 3
+#define QM_IRQ_SPI_MASTER_1_INT_MASK_OFFSET 4
+#define QM_IRQ_SPI_MASTER_1_INT_VECTOR 39
+
+/** SPI Slave Single Interrupt. */
+#define QM_IRQ_SPI_SLAVE_0_INT 4
+#define QM_IRQ_SPI_SLAVE_0_INT_MASK_OFFSET 5
+#define QM_IRQ_SPI_SLAVE_0_INT_VECTOR 40
+
+/** UART 0 Single Interrupt. */
+#define QM_IRQ_UART_0_INT 5
+#define QM_IRQ_UART_0_INT_MASK_OFFSET 6
+#define QM_IRQ_UART_0_INT_VECTOR 41
+
+/** UART 1 Single Interrupt. */
+#define QM_IRQ_UART_1_INT 6
+#define QM_IRQ_UART_1_INT_MASK_OFFSET 7
+#define QM_IRQ_UART_1_INT_VECTOR 42
+
+/** I2S Single Interrupt. */
+#define QM_IRQ_I2S_0_INT 7
+#define QM_IRQ_I2S_0_INT_MASK_OFFSET 8
+#define QM_IRQ_I2S_0_INT_VECTOR 43
+
+/** GPIO Single Interrupt. */
+#define QM_IRQ_GPIO_0_INT 8
+#define QM_IRQ_GPIO_0_INT_MASK_OFFSET 9
+#define QM_IRQ_GPIO_0_INT_VECTOR 44
+
+/** PWM/Timer Single Interrupt. */
+#define QM_IRQ_PWM_0_INT 9
+#define QM_IRQ_PWM_0_INT_MASK_OFFSET 10
+#define QM_IRQ_PWM_0_INT_VECTOR 45
+
+/** USB Single Interrupt. */
+#define QM_IRQ_USB_0_INT (10)
+#define QM_IRQ_USB_0_INT_MASK_OFFSET (11)
+#define QM_IRQ_USB_0_INT_VECTOR 46
+
+/** RTC Single Interrupt. */
+#define QM_IRQ_RTC_0_INT 11
+#define QM_IRQ_RTC_0_INT_MASK_OFFSET 12
+#define QM_IRQ_RTC_0_INT_VECTOR 47
+
+/** WDT Single Interrupt. */
+#define QM_IRQ_WDT_0_INT 12
+#define QM_IRQ_WDT_0_INT_MASK_OFFSET 13
+#define QM_IRQ_WDT_0_INT_VECTOR 48
+
+/** DMA Channel 0 Single Interrupt. */
+#define QM_IRQ_DMA_0_INT_0 13
+#define QM_IRQ_DMA_0_INT_0_MASK_OFFSET 14
+#define QM_IRQ_DMA_0_INT_0_VECTOR 49
+
+/** DMA Channel 1 Single Interrupt. */
+#define QM_IRQ_DMA_0_INT_1 14
+#define QM_IRQ_DMA_0_INT_1_MASK_OFFSET 15
+#define QM_IRQ_DMA_0_INT_1_VECTOR 50
+
+/** DMA Channel 2 Single Interrupt. */
+#define QM_IRQ_DMA_0_INT_2 15
+#define QM_IRQ_DMA_0_INT_2_MASK_OFFSET 16
+#define QM_IRQ_DMA_0_INT_2_VECTOR 51
+
+/** DMA Channel 3 Single Interrupt. */
+#define QM_IRQ_DMA_0_INT_3 16
+#define QM_IRQ_DMA_0_INT_3_MASK_OFFSET 17
+#define QM_IRQ_DMA_0_INT_3_VECTOR 52
+
+/** DMA Channel 4 Single Interrupt. */
+#define QM_IRQ_DMA_0_INT_4 17
+#define QM_IRQ_DMA_0_INT_4_MASK_OFFSET 18
+#define QM_IRQ_DMA_0_INT_4_VECTOR 53
+
+/** DMA Channel 5 Single Interrupt. */
+#define QM_IRQ_DMA_0_INT_5 18
+#define QM_IRQ_DMA_0_INT_5_MASK_OFFSET 19
+#define QM_IRQ_DMA_0_INT_5_VECTOR 54
+
+/** DMA Channel 6 Single Interrupt. */
+#define QM_IRQ_DMA_0_INT_6 19
+#define QM_IRQ_DMA_0_INT_6_MASK_OFFSET 20
+#define QM_IRQ_DMA_0_INT_6_VECTOR 55
+
+/** DMA Channel 7 Single Interrupt. */
+#define QM_IRQ_DMA_0_INT_7 20
+#define QM_IRQ_DMA_0_INT_7_MASK_OFFSET 21
+#define QM_IRQ_DMA_0_INT_7_VECTOR 56
+
+/**
+ * 8 Mailbox Channel Interrupts Routed to Single Interrupt
+ * with 8bit Mask per Destination.
+ */
+#define QM_IRQ_MAILBOX_0_INT 21
+#define QM_IRQ_MAILBOX_0_INT_MASK_OFFSET 22
+#define QM_IRQ_MAILBOX_0_INT_VECTOR 57
+
+/**
+ * 19 Comparators Routed to Single Interrupt with 19bit Mask per Destination.
+ */
+#define QM_IRQ_COMPARATOR_0_INT 22
+#define QM_IRQ_COMPARATOR_0_INT_MASK_OFFSET 26
+#define QM_IRQ_COMPARATOR_0_INT_VECTOR 58
+
+/** System and Power Management Single Interrupt. */
+#define QM_IRQ_PMU_0_INT 23
+#define QM_IRQ_PMU_0_INT_MASK_OFFSET 26
+#define QM_IRQ_PMU_0_INT_VECTOR 58
+
+/**
+ * 8 DMA Channel Error Interrupts Routed to Single Interrupt with 8bit Mask
+ * per Destination.
+ */
+#define QM_IRQ_DMA_0_ERROR_INT 24
+#define QM_IRQ_DMA_0_ERROR_INT_MASK_OFFSET 28
+#define QM_IRQ_DMA_0_ERROR_INT_VECTOR 60
+
+/** Internal SRAM Memory Protection Error Single Interrupt. */
+#define QM_IRQ_SRAM_MPR_0_INT 25
+#define QM_IRQ_SRAM_MPR_0_INT_MASK_OFFSET 29
+#define QM_IRQ_SRAM_MPR_0_INT_VECTOR 61
+
+/** Internal Flash Controller 0 Memory Protection Error Single Interrupt. */
+#define QM_IRQ_FLASH_MPR_0_INT 26
+#define QM_IRQ_FLASH_MPR_0_INT_MASK_OFFSET 30
+#define QM_IRQ_FLASH_MPR_0_INT_VECTOR 62
+
+/** Internal Flash Controller 1 Memory Protection Error Single Interrupt. */
+#define QM_IRQ_FLASH_MPR_1_INT 27
+#define QM_IRQ_FLASH_MPR_1_INT_MASK_OFFSET 31
+#define QM_IRQ_FLASH_MPR_1_INT_VECTOR 63
+
+/** Always-On Timer Interrupt. */
+#define QM_IRQ_AONPT_0_INT 28
+#define QM_IRQ_AONPT_0_INT_MASK_OFFSET 32
+#define QM_IRQ_AONPT_0_INT_VECTOR 64
+
+/** ADC power sequence done. */
+#define QM_SS_IRQ_ADC_0_PWR_INT 29
+#define QM_SS_IRQ_ADC_0_PWR_INT_MASK_OFFSET 33
+#define QM_SS_IRQ_ADC_0_PWR_INT_VECTOR 65
+
+/** ADC calibration done. */
+#define QM_SS_IRQ_ADC_0_CAL_INT 30
+#define QM_SS_IRQ_ADC_0_CAL_INT_MASK_OFFSET 34
+#define QM_SS_IRQ_ADC_0_CAL_INT_VECTOR 66
+
+/** Always-On GPIO Interrupt. */
+#define QM_IRQ_AON_GPIO_0_INT 31
+#define QM_IRQ_AON_GPIO_0_INT_MASK_OFFSET 35
+#define QM_IRQ_AON_GPIO_0_INT_VECTOR 67
+
+/** @} */
+
+/** @} */
+
+#endif /* __QM_SOC_INTERRUPTS_H__ */
diff --git a/src/include/arc32/qm_soc_regs.h b/src/include/arc32/qm_soc_regs.h
new file mode 100644
index 0000000..5488738
--- /dev/null
+++ b/src/include/arc32/qm_soc_regs.h
@@ -0,0 +1,2105 @@
+/*
+ * Copyright (c) 2016, Intel Corporation
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of the Intel Corporation nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INTEL CORPORATION OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __REGISTERS_H__
+#define __REGISTERS_H__
+
+#include "qm_common.h"
+#include "qm_soc_interrupts.h"
+#include "qm_interrupt_router_regs.h"
+
+/**
+ * Quark SE SoC Registers.
+ *
+ * @defgroup groupQUARKSESEREG SoC Registers (SE)
+ * @{
+ */
+
+#define QUARK_SE (1)
+#define HAS_4_TIMERS (1)
+#define HAS_AON_GPIO (1)
+#define HAS_MAILBOX (1)
+#define HAS_USB (1)
+
+#if !defined(QM_SENSOR)
+#define HAS_APIC (1)
+#endif
+
+/**
+ * @name System Core
+ * @{
+ */
+
+/** 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
+ ccu_periph_clk_gate_ctl; /**< Peripheral Clock Gate Control. */
+ QM_RW uint32_t
+ ccu_periph_clk_div_ctl0; /**< Peripheral Clock Divider Control. 0 */
+ QM_RW uint32_t
+ 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. */
+ 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 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_scss_ccu_reg_t;
+
+#if (UNIT_TEST)
+qm_scss_ccu_reg_t test_scss_ccu;
+#define QM_SCSS_CCU ((qm_scss_ccu_reg_t *)(&test_scss_ccu))
+
+#else
+#define QM_SCSS_CCU_BASE (0xB0800000)
+#define QM_SCSS_CCU ((qm_scss_ccu_reg_t *)QM_SCSS_CCU_BASE)
+#endif
+
+/* Hybrid oscillator output select select (0=Silicon, 1=Crystal) */
+#define QM_OSC0_MODE_SEL BIT(3)
+#define QM_OSC0_PD BIT(2)
+#define QM_OSC1_PD BIT(1)
+
+/* Enable Crystal oscillator. */
+#define QM_OSC0_EN_CRYSTAL BIT(0)
+
+/* Crystal oscillator parameters. */
+#define OSC0_CFG1_OSC0_FADJ_XTAL_MASK (0x000F0000)
+#define OSC0_CFG1_OSC0_FADJ_XTAL_OFFS (16)
+#define OSC0_CFG0_OSC0_XTAL_COUNT_VALUE_MASK (0x00600000)
+#define OSC0_CFG0_OSC0_XTAL_COUNT_VALUE_OFFS (21)
+
+/* Silicon Oscillator parameters. */
+#define OSC0_CFG1_FTRIMOTP_MASK (0x3FF00000)
+#define OSC0_CFG1_FTRIMOTP_OFFS (20)
+#define OSC0_CFG1_SI_FREQ_SEL_MASK (0x00000300)
+#define OSC0_CFG1_SI_FREQ_SEL_OFFS (8)
+
+#define QM_OSC0_MODE_SEL BIT(3)
+#define QM_OSC0_LOCK_SI BIT(0)
+#define QM_OSC0_LOCK_XTAL BIT(1)
+#define QM_OSC0_EN_SI_OSC BIT(1)
+
+#define QM_SI_OSC_1V2_MODE BIT(0)
+
+/* Peripheral clock divider control. */
+#define QM_CCU_PERIPH_PCLK_DIV_OFFSET (1)
+#define QM_CCU_PERIPH_PCLK_DIV_EN BIT(0)
+
+/* Clock enable / disable register. */
+#define QM_CCU_MLAYER_AHB_CTL (REG_VAL(0xB0800034))
+
+/* System clock control */
+#define QM_CCU_SYS_CLK_SEL BIT(0)
+#define QM_SCSS_CCU_SYS_CLK_SEL BIT(0)
+#define QM_SCSS_CCU_C2_LP_EN BIT(1)
+#define QM_SCSS_CCU_SS_LPS_EN BIT(0)
+#define QM_CCU_RTC_CLK_EN BIT(1)
+#define QM_CCU_RTC_CLK_DIV_EN BIT(2)
+#define QM_CCU_SYS_CLK_DIV_EN BIT(7)
+#define QM_CCU_SYS_CLK_DIV_MASK (0x00000300)
+
+#define QM_OSC0_SI_FREQ_SEL_DEF_MASK (0xFFFFFCFF)
+#define QM_CCU_GPIO_DB_DIV_OFFSET (2)
+#define QM_CCU_GPIO_DB_CLK_DIV_EN BIT(1)
+#define QM_CCU_GPIO_DB_CLK_EN BIT(0)
+#define QM_CCU_RTC_CLK_DIV_OFFSET (3)
+#define QM_CCU_SYS_CLK_DIV_OFFSET (8)
+#define QM_CCU_DMA_CLK_EN BIT(6)
+
+/** @} */
+
+/**
+ * @name General Purpose
+ * @{
+ */
+
+/** 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 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 reserved1;
+ QM_RW uint32_t id; /**< Identification Register */
+ QM_RW uint32_t rev; /**< Revision 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 */
+} qm_scss_gp_reg_t;
+
+#if (UNIT_TEST)
+qm_scss_gp_reg_t test_scss_gp;
+#define QM_SCSS_GP ((qm_scss_gp_reg_t *)(&test_scss_gp))
+
+#else
+#define QM_SCSS_GP_BASE (0xB0800100)
+#define QM_SCSS_GP ((qm_scss_gp_reg_t *)QM_SCSS_GP_BASE)
+#endif
+
+/* The GPS0 register usage. */
+#define QM_GPS0_BIT_FM (0) /**< Start Firmware Manager. */
+#define QM_GPS0_BIT_X86_WAKEUP (1) /**< Lakemont core reset type. */
+#define QM_GPS0_BIT_SENSOR_WAKEUP (2) /**< Sensor core reset type. */
+
+/** @} */
+
+/**
+ * @name Memory Control
+ * @{
+ */
+
+/** Memory Control register map. */
+typedef struct {
+ QM_RW uint32_t mem_ctrl; /**< Memory control */
+} qm_scss_mem_reg_t;
+
+#if (UNIT_TEST)
+qm_scss_mem_reg_t test_scss_mem;
+#define QM_SCSS_MEM ((qm_scss_mem_reg_t *)(&test_scss_mem))
+
+#else
+#define QM_SCSS_MEM_BASE (0xB0800200)
+#define QM_SCSS_MEM ((qm_scss_mem_reg_t *)QM_SCSS_MEM_BASE)
+#endif
+
+/** @} */
+
+/**
+ * @name Comparator
+ * @{
+ */
+
+/** Comparator register map. */
+typedef struct {
+ QM_RW uint32_t cmp_en; /**< Comparator enable. */
+ QM_RW uint32_t cmp_ref_sel; /**< Comparator reference select. */
+ QM_RW uint32_t
+ cmp_ref_pol; /**< Comparator reference polarity select register. */
+ QM_RW uint32_t cmp_pwr; /**< Comparator power enable register. */
+ QM_RW uint32_t reserved[6];
+ QM_RW uint32_t cmp_stat_clr; /**< Comparator clear register. */
+} qm_scss_cmp_reg_t;
+
+#if (UNIT_TEST)
+qm_scss_cmp_reg_t test_scss_cmp;
+#define QM_SCSS_CMP ((qm_scss_cmp_reg_t *)(&test_scss_cmp))
+
+#else
+#define QM_SCSS_CMP_BASE (0xB0800300)
+#define QM_SCSS_CMP ((qm_scss_cmp_reg_t *)QM_SCSS_CMP_BASE)
+#endif
+
+#define QM_AC_HP_COMPARATORS_MASK (0x7FFC0)
+
+/** @} */
+
+/**
+ * @name APIC
+ * @{
+ */
+
+typedef struct {
+ QM_RW uint32_t reg;
+ QM_RW uint32_t pad[3];
+} apic_reg_pad_t;
+
+/** APIC register block type. */
+typedef struct {
+ QM_RW apic_reg_pad_t reserved0[2];
+ QM_RW apic_reg_pad_t id; /**< LAPIC ID */
+ QM_RW apic_reg_pad_t version; /**< LAPIC version*/
+ QM_RW apic_reg_pad_t reserved1[4];
+ QM_RW apic_reg_pad_t tpr; /**< Task priority*/
+ QM_RW apic_reg_pad_t apr; /**< Arbitration priority */
+ QM_RW apic_reg_pad_t ppr; /**< Processor priority */
+ QM_RW apic_reg_pad_t eoi; /**< End of interrupt */
+ QM_RW apic_reg_pad_t rrd; /**< Remote read */
+ QM_RW apic_reg_pad_t ldr; /**< Logical destination */
+ QM_RW apic_reg_pad_t dfr; /**< Destination format */
+ QM_RW apic_reg_pad_t svr; /**< Spurious vector */
+ QM_RW apic_reg_pad_t isr[8]; /**< In-service */
+ QM_RW apic_reg_pad_t tmr[8]; /**< Trigger mode */
+ QM_RW apic_reg_pad_t irr[8]; /**< Interrupt request */
+ QM_RW apic_reg_pad_t esr; /**< Error status */
+ QM_RW apic_reg_pad_t reserved2[6];
+ QM_RW apic_reg_pad_t lvtcmci; /**< Corrected Machine Check vector */
+ QM_RW apic_reg_pad_t icr[2]; /**< Interrupt command */
+ QM_RW apic_reg_pad_t lvttimer; /**< Timer vector */
+ QM_RW apic_reg_pad_t lvtts; /**< Thermal sensor vector */
+ QM_RW apic_reg_pad_t lvtpmcr; /**< Perfmon counter vector */
+ QM_RW apic_reg_pad_t lvtlint0; /**< Local interrupt 0 vector */
+ QM_RW apic_reg_pad_t lvtlint1; /**< Local interrupt 1 vector */
+ QM_RW apic_reg_pad_t lvterr; /**< Error vector */
+ QM_RW apic_reg_pad_t timer_icr; /**< Timer initial count */
+ QM_RW apic_reg_pad_t timer_ccr; /**< Timer current count */
+ QM_RW apic_reg_pad_t reserved3[4];
+ QM_RW apic_reg_pad_t timer_dcr; /**< Timer divide configuration */
+} qm_lapic_reg_t;
+
+#if (HAS_APIC)
+/*
+ * The size of IOAPIC redirection table, as returned by _ioapic_get_redtbl_size
+ * function.
+ */
+#define QM_IOAPIC_NUM_RTES (32)
+
+/**
+ * IRQ context type.
+ *
+ * Applications should not modify the content.
+ * This structure is only intended to be used by
+ * qm_irq_save_context and qm_irq_restore_context functions.
+ */
+typedef struct {
+ /** Redirection Table Entries. */
+ uint32_t redtbl_entries[QM_IOAPIC_NUM_RTES];
+} qm_irq_context_t;
+#endif
+
+/**
+ * PIC TIMER context type.
+ *
+ * Applications should not modify the content.
+ * This structure is only intended to be used by the qm_pic_timer_save_context
+ * and qm_pic_timer_restore_context functions.
+ */
+typedef struct {
+ uint32_t timer_icr; /**< Initial Count Register. */
+ uint32_t timer_dcr; /**< Divide Configuration Register. */
+ uint32_t lvttimer; /**< Timer Entry in Local Vector Table. */
+} qm_pic_timer_context_t;
+
+#if (UNIT_TEST)
+qm_lapic_reg_t test_lapic;
+#define QM_LAPIC ((qm_lapic_reg_t *)(&test_lapic))
+
+#else
+/* Local APIC. */
+#define QM_LAPIC_BASE (0xFEE00000)
+#define QM_LAPIC ((qm_lapic_reg_t *)QM_LAPIC_BASE)
+#endif
+
+#define QM_INT_CONTROLLER QM_LAPIC
+
+/*
+ * Quark SE has a HW limitation that prevents a LAPIC EOI from being broadcast
+ * into IOAPIC. To trigger this manually we must write the vector number being
+ * serviced into the IOAPIC EOI register.
+ */
+#if defined(ENABLE_EXTERNAL_ISR_HANDLING) || defined(QM_SENSOR)
+#define QM_ISR_EOI(vector)
+#else
+#define QM_ISR_EOI(vector) \
+ do { \
+ QM_INT_CONTROLLER->eoi.reg = 0; \
+ QM_IOAPIC->eoi.reg = vector; \
+ } while (0)
+#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 reserved[2];
+ 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. */
+
+#if (UNIT_TEST)
+qm_ioapic_reg_t test_ioapic;
+#define QM_IOAPIC ((qm_ioapic_reg_t *)(&test_ioapic))
+
+#else
+/* IO / APIC base address. */
+#define QM_IOAPIC_BASE (0xFEC00000)
+#define QM_IOAPIC ((qm_ioapic_reg_t *)QM_IOAPIC_BASE)
+#endif
+
+/** @} */
+
+/**
+ * @name Power Management
+ * @{
+ */
+
+/** Power Management register map. */
+typedef struct {
+ QM_RW uint32_t p_lvl2; /**< Processor level 2 */
+ QM_RW uint32_t reserved[4];
+ QM_RW uint32_t pm1c; /**< Power management 1 control */
+ QM_RW uint32_t reserved1[9];
+ QM_RW uint32_t aon_vr; /**< AON Voltage Regulator */
+ QM_RW uint32_t plat3p3_vr; /**< Platform 3p3 voltage regulator */
+ QM_RW uint32_t plat1p8_vr; /**< Platform 1p8 voltage regulator */
+ QM_RW uint32_t host_vr; /**< Host Voltage Regulator */
+ QM_RW uint32_t slp_cfg; /**< Sleeping Configuration */
+ /** Power Management Network (PMNet) Control and Status */
+ QM_RW uint32_t pmnetcs;
+ QM_RW uint32_t pm_wait; /**< Power Management Wait */
+ QM_RW uint32_t reserved2;
+ QM_RW uint32_t p_sts; /**< Processor Status */
+ QM_RW uint32_t reserved3[3];
+ QM_RW uint32_t rstc; /**< Reset Control */
+ QM_RW uint32_t rsts; /**< Reset Status */
+ QM_RW uint32_t reserved4[6];
+ QM_RW uint32_t vr_lock; /**< Voltage regulator lock */
+ QM_RW uint32_t pm_lock; /**< Power Management Lock */
+} qm_scss_pmu_reg_t;
+
+#if (UNIT_TEST)
+qm_scss_pmu_reg_t test_scss_pmu;
+#define QM_SCSS_PMU ((qm_scss_pmu_reg_t *)(&test_scss_pmu))
+
+#else
+#define QM_SCSS_PMU_BASE (0xB0800504)
+#define QM_SCSS_PMU ((qm_scss_pmu_reg_t *)QM_SCSS_PMU_BASE)
+#endif
+
+#define QM_SS_CFG_ARC_RUN_REQ_A BIT(24)
+#define QM_P_STS_HALT_INTERRUPT_REDIRECTION BIT(26)
+#define QM_P_STS_ARC_HALT BIT(14)
+
+#define QM_AON_VR_VSEL_MASK (0xFFE0)
+#define QM_AON_VR_VSEL_1V2 (0x8)
+#define QM_AON_VR_VSEL_1V35 (0xB)
+#define QM_AON_VR_VSEL_1V8 (0x10)
+#define QM_AON_VR_EN BIT(7)
+#define QM_AON_VR_VSTRB BIT(5)
+
+#define QM_SCSS_SLP_CFG_LPMODE_EN BIT(8)
+#define QM_SCSS_SLP_CFG_RTC_DIS BIT(7)
+#define QM_SCSS_PM1C_SLPEN BIT(13)
+#define QM_SCSS_HOST_VR_EN BIT(7)
+#define QM_SCSS_PLAT3P3_VR_EN BIT(7)
+#define QM_SCSS_PLAT1P8_VR_EN BIT(7)
+#define QM_SCSS_HOST_VR_VREG_SEL BIT(6)
+#define QM_SCSS_PLAT3P3_VR_VREG_SEL BIT(6)
+#define QM_SCSS_PLAT1P8_VR_VREG_SEL BIT(6)
+#define QM_SCSS_VR_ROK BIT(10)
+#define QM_SCSS_VR_EN BIT(7)
+#define QM_SCSS_VR_VREG_SEL BIT(6)
+
+/** @} */
+
+/**
+ * @name Sensor Subsystem
+ * @{
+ */
+
+/** Sensor Subsystem register map. */
+typedef struct {
+ QM_RW uint32_t ss_cfg; /**< Sensor Subsystem Configuration */
+ QM_RW uint32_t ss_sts; /**< Sensor Subsystem status */
+} qm_scss_ss_reg_t;
+
+#if (UNIT_TEST)
+qm_scss_ss_reg_t test_scss_ss;
+#define QM_SCSS_SS ((qm_scss_ss_reg_t *)(&test_scss_ss))
+
+#else
+#define QM_SCSS_SS_BASE (0xB0800600)
+#define QM_SCSS_SS ((qm_scss_ss_reg_t *)QM_SCSS_SS_BASE)
+#endif
+
+#define QM_SS_STS_HALT_INTERRUPT_REDIRECTION BIT(26)
+
+/** @} */
+
+/**
+ * @name Always-on Counters.
+ * @{
+ */
+
+/** Number of Always-on counter controllers. */
+typedef enum { QM_AONC_0 = 0, QM_AONC_NUM } qm_aonc_t;
+
+/** Always-on Counter Controller register map. */
+typedef struct {
+ QM_RW uint32_t aonc_cnt; /**< Always-on counter register. */
+ QM_RW uint32_t aonc_cfg; /**< Always-on counter enable. */
+ QM_RW uint32_t aonpt_cnt; /**< Always-on periodic timer. */
+ QM_RW uint32_t
+ aonpt_stat; /**< Always-on periodic timer status register. */
+ QM_RW uint32_t aonpt_ctrl; /**< Always-on periodic timer control. */
+ QM_RW uint32_t
+ aonpt_cfg; /**< Always-on periodic timer configuration register. */
+} qm_aonc_reg_t;
+
+#if (UNIT_TEST)
+qm_aonc_reg_t test_aonc;
+#define QM_AONC ((qm_aonc_reg_t *)(&test_aonc))
+
+#else
+#define QM_AONC_BASE (0xB0800700)
+#define QM_AONC ((qm_aonc_reg_t *)QM_AONC_BASE)
+#endif
+
+/** @} */
+
+/**
+ * @name Peripheral Registers
+ * @{
+ */
+
+/** Peripheral Registers register map. */
+typedef struct {
+ QM_RW uint32_t usb_phy_cfg0; /**< USB Configuration */
+ QM_RW uint32_t periph_cfg0; /**< Peripheral Configuration */
+ QM_RW uint32_t reserved[2];
+ QM_RW uint32_t cfg_lock; /**< Configuration Lock */
+} qm_scss_peripheral_reg_t;
+
+#if (UNIT_TEST)
+qm_scss_peripheral_reg_t test_scss_peripheral;
+#define QM_SCSS_PERIPHERAL ((qm_scss_peripheral_reg_t *)(&test_scss_peripheral))
+
+#else
+#define QM_SCSS_PERIPHERAL_BASE (0xB0800800)
+#define QM_SCSS_PERIPHERAL ((qm_scss_peripheral_reg_t *)QM_SCSS_PERIPHERAL_BASE)
+#endif
+
+/** @} */
+
+/**
+ * @name Pin MUX
+ * @{
+ */
+
+/** Pin MUX register map. */
+typedef struct {
+ QM_RW uint32_t pmux_pullup[4]; /**< Pin Mux Pullup */
+ QM_RW uint32_t pmux_slew[4]; /**< Pin Mux Slew Rate */
+ QM_RW uint32_t pmux_in_en[4]; /**< Pin Mux Input Enable */
+ QM_RW uint32_t pmux_sel[5]; /**< Pin Mux Select */
+ QM_RW uint32_t reserved[2];
+ 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_lock[3]; /**< Pin Mux Select Lock */
+ QM_RW uint32_t pmux_in_en_lock; /**< Pin Mux Slew Rate Lock */
+} qm_scss_pmux_reg_t;
+
+#if (UNIT_TEST)
+qm_scss_pmux_reg_t test_scss_pmux;
+#define QM_SCSS_PMUX ((qm_scss_pmux_reg_t *)(&test_scss_pmux))
+
+#else
+#define QM_SCSS_PMUX_BASE (0xB0800900)
+#define QM_SCSS_PMUX ((qm_scss_pmux_reg_t *)QM_SCSS_PMUX_BASE)
+#endif
+
+/* Pin MUX slew rate registers and settings */
+#define QM_PMUX_SLEW_4MA_DRIVER (0xFFFFFFFF)
+#define QM_PMUX_SLEW0 (REG_VAL(0xB0800910))
+#define QM_PMUX_SLEW1 (REG_VAL(0xB0800914))
+#define QM_PMUX_SLEW2 (REG_VAL(0xB0800918))
+#define QM_PMUX_SLEW3 (REG_VAL(0xB080091C))
+
+/** @} */
+
+/**
+ * @name ID
+ * @{
+ */
+
+/** Information register map. */
+typedef struct {
+ QM_RW uint32_t id;
+} qm_scss_info_reg_t;
+
+#if (UNIT_TEST)
+qm_scss_info_reg_t test_scss_info;
+#define QM_SCSS_INFO ((qm_scss_info_reg_t *)(&test_scss_info))
+
+#else
+#define QM_SCSS_INFO_BASE (0xB0801000)
+#define QM_SCSS_INFO ((qm_scss_info_reg_t *)QM_SCSS_INFO_BASE)
+#endif
+
+/** @} */
+
+/**
+ * @name Mailbox
+ * @{
+ */
+
+#define HAS_MAILBOX (1)
+#define NUM_MAILBOXES (8)
+
+#define HAS_MAILBOX_LAKEMONT_DEST (1)
+#define HAS_MAILBOX_SENSOR_SUB_SYSTEM_DEST (1)
+
+/**
+ * Mailbox MBOX_CH_CTRL_N Mailbox Channel Control Word Register
+ *
+ * 31 RW/1S/V MBOX_CH_CTRL_INT Mailbox Channel Control Word interrupt
+ * 30:0 RW MBOX_CH_CTRL Mailbox Channel Control Word
+ */
+#define QM_MBOX_CH_CTRL_INT BIT(31)
+#define QM_MBOX_CH_CTRL_MASK (0x7FFFFFFF)
+#define QM_MBOX_CH_CTRL_SHIFT (0)
+
+/*
+ * Mailbox Channel Status MBOX_CH_STS_N
+ *
+ * 31:2 RO reserved
+ * 1 RW/1C/V MBOX_CH_STS_CTRL_INT Mailbox Channel Interrupt Status
+ * - Bit set when message sent, indicates pending interrupt
+ * - Bit set when a mailbox channel interrupt is pending..
+ * - Bit cleared by writing 1
+ * - Bit should be cleared by the receivers isr
+ * 0 RW/1C/V MBOX_CH_STS Mailbox Channel Status
+ * - Bit set when message sent, indicates pending data
+ * - Bit cleared by writing 1
+ * - Bit should be cleared by the receiver after
+ * consuming the message.
+ */
+#define QM_MBOX_CH_STS_CTRL_INT BIT(1)
+#define QM_MBOX_CH_STS BIT(0)
+
+#define QM_MBOX_STATUS_MASK (QM_MBOX_CH_STS | QM_MBOX_CH_STS_CTRL_INT)
+
+/**
+ * Mailbox MBOX_CHALL_STS Channel Status Bits Register
+ *
+ * 31:16 RO reserved
+ * 15:0 RO/V MBOX_CHALL_STS Channel Status Bits
+ */
+#define QM_MBOX_CHALL_STS(N) BIT((N * 2))
+#define QM_MBOX_CHALL_INT_STS(N) BIT((N * 2) + 1)
+
+/**
+ * Mailbox interrupt routing mask register INT_MAILBOX_MASK
+ *
+ * There is only 1 Mailbox interrupt mask register.
+ * The register contains masks for all 8 mailbox channels.
+ *
+ * Note that the Mailbox interrupt mask register does not follow
+ * the same layout as most other interrupt mask registers in the SCSS.
+ *
+ * Mask bit positions for INT_MAILBOX_MASK are listed here:
+ *
+ * 31:24 RW/P/L INT_MAILBOX_SS_HALT_MASK Mailbox SS Halt interrupt mask
+ * 23:16 RW/P/L INT_MAILBOX_HOST_HALT_MASK Mailbox Host Halt interrupt mask
+ * 15:8 RW/P/L INT_MAILBOX_SS_MASK Mailbox SS interrupt mask
+ * 7:0 RW/P/L INT_MAILBOX_HOST_MASK Mailbox Host interrupt mask
+ */
+#define QM_MBOX_SS_HALT_MASK_OFFSET (24)
+#define QM_MBOX_SS_HALT_MASK_MASK (0xFF000000)
+#define QM_MBOX_HOST_HALT_MASK_OFFSET (16)
+#define QM_MBOX_HOST_HALT_MASK_MASK (0x00FF0000)
+#define QM_MBOX_SS_MASK_OFFSET (8)
+#define QM_MBOX_SS_MASK_MASK (0x0000FF00)
+#define QM_MBOX_HOST_MASK_OFFSET (0)
+#define QM_MBOX_HOST_MASK_MASK (0x000000FF)
+
+/**
+ * Mailbox Interrupt Mask enable/disable definitions
+ *
+ * \#defines use the channel number to determine the register and bit shift to
+ * use.
+ * The interrupt destination adds an offset to the bit shift.
+ */
+#define QM_MBOX_ENABLE_LMT_INT_MASK(N) \
+ QM_INTERRUPT_ROUTER->mailbox_0_int_mask &= \
+ ~(BIT(N + QM_MBOX_HOST_MASK_OFFSET))
+#define QM_MBOX_DISABLE_LMT_INT_MASK(N) \
+ QM_INTERRUPT_ROUTER->mailbox_0_int_mask |= \
+ (BIT(N + QM_MBOX_HOST_MASK_OFFSET))
+#define QM_MBOX_ENABLE_SS_INT_MASK(N) \
+ QM_INTERRUPT_ROUTER->mailbox_0_int_mask &= \
+ ~(BIT(N + QM_MBOX_SS_MASK_OFFSET))
+#define QM_MBOX_DISABLE_SS_INT_MASK(N) \
+ QM_INTERRUPT_ROUTER->mailbox_0_int_mask |= \
+ (BIT(N + QM_MBOX_SS_MASK_OFFSET))
+
+/**
+ * Mailbox Interrupt Halt Mask enable/disable definitions
+ *
+ * \#defines use the channel number to determine the register and bit shift to
+ * use.
+ * The interrupt destination adds an offset to the bit shift,
+ * see above for the bit position layout
+ */
+#define QM_MBOX_ENABLE_LMT_INT_HALT_MASK(N) \
+ QM_INTERRUPT_ROUTER->mailbox_0_int_mask &= \
+ ~(BIT(N + QM_MBOX_HOST_HALT_MASK_OFFSET))
+#define QM_MBOX_DISABLE_LMT_INT_HALT_MASK(N) \
+ QM_INTERRUPT_ROUTER->mailbox_0_int_mask |= \
+ (BIT(N + QM_MBOX_HOST_HALT_MASK_OFFSET))
+#define QM_MBOX_ENABLE_SS_INT_HALT_MASK(N) \
+ QM_INTERRUPT_ROUTER->mailbox_0_int_mask &= \
+ ~(BIT(N + QM_MBOX_SS_HALT_MASK_OFFSET))
+#define QM_MBOX_DISABLE_SS_INT_HALT_MASK(N) \
+ QM_INTERRUPT_ROUTER->mailbox_0_int_mask |= \
+ (BIT(N + QM_MBOX_SS_HALT_MASK_OFFSET))
+
+/**
+ * Mailbox interrupt mask definitions to return the current mask values
+ */
+#define QM_MBOX_SS_INT_HALT_MASK \
+ ((QM_MBOX_SS_HALT_MASK_MASK & \
+ QM_INTERRUPT_ROUTER->mailbox_0_int_mask) >> \
+ QM_MBOX_SS_HALT_MASK_OFFSET)
+#define QM_MBOX_LMT_INT_HALT_MASK \
+ ((QM_MBOX_HOST_HALT_MASK_MASK & \
+ QM_INTERRUPT_ROUTER->mailbox_0_int_mask) >> \
+ QM_MBOX_SS_HALT_MASK_OFFSET)
+#define QM_MBOX_SS_INT_MASK \
+ ((QM_MBOX_SS_MASK_MASK & QM_INTERRUPT_ROUTER->mailbox_0_int_mask) >> \
+ QM_MBOX_SS_MASK_OFFSET)
+#define QM_MBOX_LMT_INT_MASK \
+ (QM_MBOX_HOST_MASK_MASK & QM_INTERRUPT_ROUTER->mailbox_0_int_mask)
+
+/**
+ * Mailbox interrupt macros to determine if the specified mailbox interrupt mask
+ * has been locked.
+ */
+#define QM_MBOX_SS_INT_LOCK_HALT_MASK(N) \
+ (QM_INTERRUPT_ROUTER->lock_int_mask_reg & BIT(3))
+#define QM_MBOX_LMT_INT_LOCK_HALT_MASK(N) \
+ (QM_INTERRUPT_ROUTER->lock_int_mask_reg & BIT(2))
+#define QM_MBOX_SS_INT_LOCK_MASK(N) \
+ (QM_INTERRUPT_ROUTER->lock_int_mask_reg & BIT(1))
+#define QM_MBOX_LMT_INT_LOCK_MASK(N) \
+ (QM_INTERRUPT_ROUTER->lock_int_mask_reg & BIT(0))
+
+/** Mailbox register structure. */
+typedef struct {
+ QM_RW uint32_t ch_ctrl; /**< Channel Control Word */
+ QM_RW uint32_t ch_data[4]; /**< Channel Payload Data Word 0 */
+ QM_RW uint32_t ch_sts; /**< Channel status */
+} qm_mailbox_t;
+
+/** Mailbox register map. */
+typedef struct {
+ qm_mailbox_t mbox[NUM_MAILBOXES]; /**< 8 Mailboxes */
+ QM_RW uint32_t mbox_chall_sts; /**< All channel status */
+} qm_mailbox_reg_t;
+
+#if (UNIT_TEST)
+qm_mailbox_reg_t test_mailbox;
+#define QM_MAILBOX ((qm_mailbox_reg_t *)(&test_mailbox))
+
+#else
+#define QM_MAILBOX_BASE (0xB0800A00)
+#define QM_MAILBOX ((qm_mailbox_reg_t *)QM_MAILBOX_BASE)
+#endif
+
+/** @} */
+
+/**
+ * @name PWM / Timer
+ * @{
+ */
+
+/** Number of PWM / Timer controllers. */
+typedef enum { QM_PWM_0 = 0, QM_PWM_NUM } qm_pwm_t;
+
+/** PWM ID type. */
+typedef enum {
+ QM_PWM_ID_0 = 0,
+ QM_PWM_ID_1,
+ QM_PWM_ID_2,
+ QM_PWM_ID_3,
+ QM_PWM_ID_NUM
+} qm_pwm_id_t;
+
+/** PWM / Timer channel register map. */
+typedef struct {
+ 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]; /**< 4 Timers */
+ QM_RW uint32_t reserved[20];
+ QM_RW uint32_t timersintstatus; /**< Timers Interrupt Status */
+ QM_RW uint32_t timerseoi; /**< Timers End Of Interrupt */
+ QM_RW uint32_t timersrawintstatus; /**< Timers Raw Interrupt Status */
+ QM_RW uint32_t timerscompversion; /**< Timers Component Version */
+ QM_RW uint32_t
+ timer_loadcount2[QM_PWM_ID_NUM]; /**< Timer Load Count 2 */
+} qm_pwm_reg_t;
+
+/**
+ * PWM context type.
+ *
+ * Applications should not modify the content.
+ * This structure is only intended to be used by
+ * the qm_pwm_save_context and qm_pwm_restore_context functions.
+ */
+typedef struct {
+ struct {
+ uint32_t loadcount; /**< Load Count 1. */
+ uint32_t loadcount2; /**< Load Count 2. */
+ uint32_t controlreg; /**< Control Register. */
+ } channel[QM_PWM_ID_NUM];
+} qm_pwm_context_t;
+
+#if (UNIT_TEST)
+qm_pwm_reg_t test_pwm_t;
+#define QM_PWM ((qm_pwm_reg_t *)(&test_pwm_t))
+
+#else
+/* PWM register base address. */
+#define QM_PWM_BASE (0xB0000800)
+/* PWM register block. */
+#define QM_PWM ((qm_pwm_reg_t *)QM_PWM_BASE)
+#endif
+
+#define PWM_START (1)
+
+#define QM_PWM_CONF_MODE_MASK (0xA)
+#define QM_PWM_CONF_INT_EN_MASK (0x4)
+
+#define QM_PWM_INTERRUPT_MASK_OFFSET (0x2)
+
+/**
+ * Timer N Control (TimerNControlReg)
+ *
+ * 31:4 RO reserved
+ * 3 RW Timer PWM
+ * 1 - PWM Mode
+ * 0 - Timer Mode
+ * 2 RW Timer Interrupt Mask, set to 1b to mask interrupt.
+ * 1 RW Timer Mode
+ * 1 - user-defined count mode
+ * 0 - free-running mode
+ * 0 RW Timer Enable
+ * 0 - Disable PWM/Timer
+ * 1 - Enable PWM/Timer
+ */
+
+#define QM_PWM_TIMERNCONTROLREG_TIMER_ENABLE (BIT(0))
+#define QM_PWM_TIMERNCONTROLREG_TIMER_MODE (BIT(1))
+#define QM_PWM_TIMERNCONTROLREG_TIMER_INTERRUPT_MASK (BIT(2))
+#define QM_PWM_TIMERNCONTROLREG_TIMER_PWM (BIT(3))
+
+#define QM_PWM_MODE_TIMER_FREE_RUNNING_VALUE (0)
+#define QM_PWM_MODE_TIMER_COUNT_VALUE (QM_PWM_TIMERNCONTROLREG_TIMER_MODE)
+#define QM_PWM_MODE_PWM_VALUE \
+ (QM_PWM_TIMERNCONTROLREG_TIMER_PWM | QM_PWM_TIMERNCONTROLREG_TIMER_MODE)
+
+/** @} */
+
+/**
+ * @name WDT
+ * @{
+ */
+
+/** Number of WDT controllers. */
+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_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;
+
+/*
+ * WDT context type.
+ *
+ * Application should not modify the content.
+ * This structure is only intended to be used by the qm_wdt_save_context and
+ * qm_wdt_restore_context functions.
+ */
+typedef struct {
+ uint32_t wdt_cr; /**< Control Register. */
+ uint32_t wdt_torr; /**< Timeout Range Register. */
+} qm_wdt_context_t;
+
+#if (UNIT_TEST)
+qm_wdt_reg_t test_wdt;
+#define QM_WDT ((qm_wdt_reg_t *)(&test_wdt))
+
+#else
+/* WDT register base address. */
+#define QM_WDT_BASE (0xB0000000)
+
+/* WDT register block. */
+#define QM_WDT ((qm_wdt_reg_t *)QM_WDT_BASE)
+#endif
+
+/* Watchdog enable. */
+#define QM_WDT_CR_WDT_ENABLE (BIT(0))
+/* Watchdog mode. */
+#define QM_WDT_CR_RMOD (BIT(1))
+/* Watchdog mode offset. */
+#define QM_WDT_CR_RMOD_OFFSET (1)
+/* Watchdog Timeout Mask. */
+#define QM_WDT_TORR_TOP_MASK (0xF)
+
+/**
+ * WDT timeout table (in clock cycles):
+ * Each table entry corresponds with the value loaded
+ * into the WDT at the time of a WDT reload for the
+ * corresponding timeout range register value.
+ *
+ * TORR | Timeout (Clock Cycles)
+ * 0. | 2^16 (65536)
+ * 1. | 2^17 (131072)
+ * 2. | 2^18 (262144)
+ * 3. | 2^19 (524288)
+ * 4. | 2^20 (1048576)
+ * 5. | 2^21 (2097152)
+ * 6. | 2^22 (4194304)
+ * 7. | 2^23 (8388608)
+ * 8. | 2^24 (16777216)
+ * 9. | 2^25 (33554432)
+ * 10. | 2^26 (67108864)
+ * 11. | 2^27 (134217728)
+ * 12. | 2^28 (268435456)
+ * 13. | 2^29 (536870912)
+ * 14. | 2^30 (1073741824)
+ * 15. | 2^31 (2147483648)
+ */
+
+/** @} */
+
+/**
+ * @name UART
+ * @{
+ */
+
+/* Break character Bit. */
+#define QM_UART_LCR_BREAK BIT(6)
+/* Divisor Latch Access Bit. */
+#define QM_UART_LCR_DLAB BIT(7)
+
+/* Request to Send Bit. */
+#define QM_UART_MCR_RTS BIT(1)
+/* Loopback Enable Bit. */
+#define QM_UART_MCR_LOOPBACK BIT(4)
+/* Auto Flow Control Enable Bit. */
+#define QM_UART_MCR_AFCE BIT(5)
+
+/* FIFO Enable Bit. */
+#define QM_UART_FCR_FIFOE BIT(0)
+/* Reset Receive FIFO. */
+#define QM_UART_FCR_RFIFOR BIT(1)
+/* Reset Transmit FIFO. */
+#define QM_UART_FCR_XFIFOR BIT(2)
+
+/* Default FIFO RX & TX Thresholds, half full for both. */
+#define QM_UART_FCR_DEFAULT_TX_RX_THRESHOLD (0xB0)
+/* Change TX Threshold to empty, keep RX Threshold to default. */
+#define QM_UART_FCR_TX_0_RX_1_2_THRESHOLD (0x80)
+
+/* Transmit Holding Register Empty. */
+#define QM_UART_IIR_THR_EMPTY (0x02)
+/* Received Data Available. */
+#define QM_UART_IIR_RECV_DATA_AVAIL (0x04)
+/* Receiver Line Status. */
+#define QM_UART_IIR_RECV_LINE_STATUS (0x06)
+/* Character Timeout. */
+#define QM_UART_IIR_CHAR_TIMEOUT (0x0C)
+/* Interrupt ID Mask. */
+#define QM_UART_IIR_IID_MASK (0x0F)
+
+/* Data Ready Bit. */
+#define QM_UART_LSR_DR BIT(0)
+/* Overflow Error Bit. */
+#define QM_UART_LSR_OE BIT(1)
+/* Parity Error Bit. */
+#define QM_UART_LSR_PE BIT(2)
+/* Framing Error Bit. */
+#define QM_UART_LSR_FE BIT(3)
+/* Break Interrupt Bit. */
+#define QM_UART_LSR_BI BIT(4)
+/* Transmit Holding Register Empty Bit. */
+#define QM_UART_LSR_THRE BIT(5)
+/* Transmitter Empty Bit. */
+#define QM_UART_LSR_TEMT BIT(6)
+/* Receiver FIFO Error Bit. */
+#define QM_UART_LSR_RFE BIT(7)
+
+/* Enable Received Data Available Interrupt. */
+#define QM_UART_IER_ERBFI BIT(0)
+/* Enable Transmit Holding Register Empty Interrupt. */
+#define QM_UART_IER_ETBEI BIT(1)
+/* Enable Receiver Line Status Interrupt. */
+#define QM_UART_IER_ELSI BIT(2)
+/* Programmable THRE Interrupt Mode. */
+#define QM_UART_IER_PTIME BIT(7)
+
+/* Line Status Errors. */
+#define QM_UART_LSR_ERROR_BITS \
+ (QM_UART_LSR_OE | QM_UART_LSR_PE | QM_UART_LSR_FE | QM_UART_LSR_BI)
+
+/* FIFO Depth. */
+#define QM_UART_FIFO_DEPTH (16)
+/* FIFO Half Depth. */
+#define QM_UART_FIFO_HALF_DEPTH (QM_UART_FIFO_DEPTH / 2)
+
+/* Divisor Latch High Offset. */
+#define QM_UART_CFG_BAUD_DLH_OFFS 16
+/* Divisor Latch Low Offset. */
+#define QM_UART_CFG_BAUD_DLL_OFFS 8
+/* Divisor Latch Fraction Offset. */
+#define QM_UART_CFG_BAUD_DLF_OFFS 0
+/* Divisor Latch High Mask. */
+#define QM_UART_CFG_BAUD_DLH_MASK (0xFF << QM_UART_CFG_BAUD_DLH_OFFS)
+/* Divisor Latch Low Mask. */
+#define QM_UART_CFG_BAUD_DLL_MASK (0xFF << QM_UART_CFG_BAUD_DLL_OFFS)
+/* Divisor Latch Fraction Mask. */
+#define QM_UART_CFG_BAUD_DLF_MASK (0xFF << QM_UART_CFG_BAUD_DLF_OFFS)
+
+/* Divisor Latch Packing Helper. */
+#define QM_UART_CFG_BAUD_DL_PACK(dlh, dll, dlf) \
+ (dlh << QM_UART_CFG_BAUD_DLH_OFFS | dll << QM_UART_CFG_BAUD_DLL_OFFS | \
+ dlf << QM_UART_CFG_BAUD_DLF_OFFS)
+
+/* Divisor Latch High Unpacking Helper. */
+#define QM_UART_CFG_BAUD_DLH_UNPACK(packed) \
+ ((packed & QM_UART_CFG_BAUD_DLH_MASK) >> QM_UART_CFG_BAUD_DLH_OFFS)
+/* Divisor Latch Low Unpacking Helper. */
+#define QM_UART_CFG_BAUD_DLL_UNPACK(packed) \
+ ((packed & QM_UART_CFG_BAUD_DLL_MASK) >> QM_UART_CFG_BAUD_DLL_OFFS)
+/* Divisor Latch Fraction Unpacking Helper. */
+#define QM_UART_CFG_BAUD_DLF_UNPACK(packed) \
+ ((packed & QM_UART_CFG_BAUD_DLF_MASK) >> QM_UART_CFG_BAUD_DLF_OFFS)
+
+/** Number of UART controllers. */
+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 reserved[23];
+ 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 reserved2[5];
+ QM_RW uint32_t dlf; /**< Divisor Latch Fraction */
+ QM_RW uint32_t padding[0xCF]; /* (0x400 - 0xC4) / 4 */
+} qm_uart_reg_t;
+
+/**
+ * UART context to be saved between sleep/resume.
+ *
+ * Application should not modify the content.
+ * This structure is only intended to be used by the qm_uart_save_context and
+ * qm_uart_restore_context functions.
+ */
+typedef struct {
+ uint32_t ier; /**< Interrupt Enable Register. */
+ uint32_t dlh; /**< Divisor Latch High. */
+ uint32_t dll; /**< Divisor Latch Low. */
+ uint32_t lcr; /**< Line Control. */
+ uint32_t mcr; /**< Modem Control. */
+ uint32_t scr; /**< Scratchpad. */
+ uint32_t htx; /**< Halt Transmission. */
+ uint32_t dlf; /**< Divisor Latch Fraction. */
+} qm_uart_context_t;
+
+#if (UNIT_TEST)
+qm_uart_reg_t test_uart_instance;
+qm_uart_reg_t *test_uart[QM_UART_NUM];
+#define QM_UART test_uart
+
+#else
+/* UART register base address. */
+#define QM_UART_0_BASE (0xB0002000)
+#define QM_UART_1_BASE (0xB0002400)
+/* UART register block. */
+extern qm_uart_reg_t *qm_uart[QM_UART_NUM];
+#define QM_UART qm_uart
+#endif
+
+/** @} */
+
+/**
+ * @name SPI
+ * @{
+ */
+
+/** Number of SPI controllers (only master driver available). */
+typedef enum { QM_SPI_MST_0 = 0, QM_SPI_MST_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 padding[0xC4]; /* (0x400 - 0xF0) / 4 */
+} qm_spi_reg_t;
+
+/**
+ * SPI context type.
+ *
+ * Applications should not modify the content.
+ * This structure is only intended to be used by
+ * the qm_spi_save_context and qm_spi_restore_context functions.
+ */
+typedef struct {
+ uint32_t ctrlr0; /**< Control Register 0. */
+ uint32_t ser; /**< Slave Enable Register. */
+ uint32_t baudr; /**< Baud Rate Select. */
+} qm_spi_context_t;
+
+#if (UNIT_TEST)
+qm_spi_reg_t test_spi;
+qm_spi_reg_t *test_spi_controllers[QM_SPI_NUM];
+
+#define QM_SPI test_spi_controllers
+
+#else
+/* 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. */
+#define QM_SPI_SLV_BASE (0xB0001800)
+#endif
+
+/* 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)
+#define QM_SPI_CTRLR0_FRF_MASK (0x00000030)
+#define QM_SPI_CTRLR0_DFS_32_OFFSET (16)
+#define QM_SPI_CTRLR0_TMOD_OFFSET (8)
+#define QM_SPI_CTRLR0_SCPOL_SCPH_OFFSET (6)
+#define QM_SPI_CTRLR0_FRF_OFFSET (4)
+
+/* SPI SSI Enable register. */
+#define QM_SPI_SSIENR_SSIENR BIT(0)
+
+/* 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. */
+#define QM_SPI_IMR_MASK_ALL (0x00)
+#define QM_SPI_IMR_TXEIM BIT(0)
+#define QM_SPI_IMR_TXOIM BIT(1)
+#define QM_SPI_IMR_RXUIM BIT(2)
+#define QM_SPI_IMR_RXOIM BIT(3)
+#define QM_SPI_IMR_RXFIM BIT(4)
+
+/* 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. */
+#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. */
+#define QM_SPI_DMACR_RDMAE BIT(0)
+#define QM_SPI_DMACR_TDMAE BIT(1)
+
+/** @} */
+
+/**
+ * @name RTC
+ * @{
+ */
+
+/** Number of RTC controllers. */
+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_rtc_reg_t;
+
+#define QM_RTC_CCR_INTERRUPT_ENABLE BIT(0)
+#define QM_RTC_CCR_INTERRUPT_MASK BIT(1)
+#define QM_RTC_CCR_ENABLE BIT(2)
+
+#if (UNIT_TEST)
+qm_rtc_reg_t test_rtc;
+#define QM_RTC ((qm_rtc_reg_t *)(&test_rtc))
+
+#else
+/* RTC register base address. */
+#define QM_RTC_BASE (0xB0000400)
+
+/* RTC register block. */
+#define QM_RTC ((qm_rtc_reg_t *)QM_RTC_BASE)
+#endif
+
+/** @} */
+
+/**
+ * @name I2C
+ * @{
+ */
+
+/** Number of I2C controllers. */
+typedef enum { QM_I2C_0 = 0, QM_I2C_1, 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_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 */
+ QM_RW uint32_t
+ 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 */
+ 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 */
+ 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 */
+ 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 reserved1[19];
+ 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 padding[0xC0]; /* Padding (0x400-0xFC)/4 */
+} qm_i2c_reg_t;
+
+/**
+ * I2C context to be saved between sleep/resume.
+ *
+ * Application should not modify the content.
+ * This structure is only intended to be used by the qm_i2c_save_context and
+ * qm_i2c_restore_context functions.
+ */
+typedef struct {
+ uint32_t con; /**< Control Register. */
+ uint32_t sar; /**< Slave Address. */
+ uint32_t ss_scl_hcnt; /**< Standard Speed Clock SCL High Count. */
+ uint32_t ss_scl_lcnt; /**< Standard Speed Clock SCL Low Count. */
+ uint32_t fs_scl_hcnt; /**< Fast Speed Clock SCL High Count. */
+ uint32_t fs_scl_lcnt; /**< Fast Speed I2C Clock SCL Low Count. */
+ uint32_t enable; /**< Enable. */
+ uint32_t fs_spklen; /**< SS and FS Spike Suppression Limit. */
+ uint32_t ic_intr_mask; /**< I2C Interrupt Mask. */
+} qm_i2c_context_t;
+
+#if (UNIT_TEST)
+qm_i2c_reg_t test_i2c_instance[QM_I2C_NUM];
+qm_i2c_reg_t *test_i2c[QM_I2C_NUM];
+
+#define QM_I2C test_i2c
+
+#else
+/* I2C Master register base address. */
+#define QM_I2C_0_BASE (0xB0002800)
+#define QM_I2C_1_BASE (0xB0002C00)
+
+/** I2C register block. */
+extern qm_i2c_reg_t *qm_i2c[QM_I2C_NUM];
+#define QM_I2C qm_i2c
+#endif
+
+#define QM_I2C_IC_ENABLE_CONTROLLER_EN BIT(0)
+#define QM_I2C_IC_ENABLE_CONTROLLER_ABORT BIT(1)
+#define QM_I2C_IC_ENABLE_STATUS_IC_EN BIT(0)
+#define QM_I2C_IC_CON_MASTER_MODE BIT(0)
+#define QM_I2C_IC_CON_SLAVE_DISABLE BIT(6)
+#define QM_I2C_IC_CON_10BITADDR_MASTER BIT(4)
+#define QM_I2C_IC_CON_10BITADDR_MASTER_OFFSET (4)
+#define QM_I2C_IC_CON_10BITADDR_SLAVE BIT(3)
+#define QM_I2C_IC_CON_10BITADDR_SLAVE_OFFSET (3)
+#define QM_I2C_IC_CON_SPEED_OFFSET (1)
+#define QM_I2C_IC_CON_SPEED_SS BIT(1)
+#define QM_I2C_IC_CON_SPEED_FS_FSP BIT(2)
+#define QM_I2C_IC_CON_SPEED_MASK (0x06)
+#define QM_I2C_IC_CON_RESTART_EN BIT(5)
+#define QM_I2C_IC_CON_STOP_DET_IFADDRESSED BIT(7)
+#define QM_I2C_IC_DATA_CMD_READ BIT(8)
+#define QM_I2C_IC_DATA_CMD_STOP_BIT_CTRL BIT(9)
+#define QM_I2C_IC_DATA_CMD_LSB_MASK (0x000000FF)
+#define QM_I2C_IC_RAW_INTR_STAT_RX_FULL BIT(2)
+#define QM_I2C_IC_RAW_INTR_STAT_TX_ABRT BIT(6)
+#define QM_I2C_IC_RAW_INTR_STAT_GEN_CALL BIT(11)
+#define QM_I2C_IC_RAW_INTR_STAT_RESTART_DETECTED BIT(12)
+#define QM_I2C_IC_TX_ABRT_SOURCE_NAK_MASK (0x1F)
+#define QM_I2C_IC_TX_ABRT_SOURCE_ARB_LOST BIT(12)
+#define QM_I2C_IC_TX_ABRT_SOURCE_ABRT_SBYTE_NORSTRT BIT(9)
+#define QM_I2C_IC_TX_ABRT_SOURCE_ALL_MASK (0x1FFFF)
+#define QM_I2C_IC_STATUS_BUSY_MASK (0x00000060)
+#define QM_I2C_IC_STATUS_RFF BIT(4)
+#define QM_I2C_IC_STATUS_RFNE BIT(3)
+#define QM_I2C_IC_STATUS_TFE BIT(2)
+#define QM_I2C_IC_STATUS_TNF BIT(1)
+#define QM_I2C_IC_INTR_MASK_ALL (0x00)
+#define QM_I2C_IC_INTR_MASK_RX_UNDER BIT(0)
+#define QM_I2C_IC_INTR_MASK_RX_OVER BIT(1)
+#define QM_I2C_IC_INTR_MASK_RX_FULL BIT(2)
+#define QM_I2C_IC_INTR_MASK_TX_OVER BIT(3)
+#define QM_I2C_IC_INTR_MASK_TX_EMPTY BIT(4)
+#define QM_I2C_IC_INTR_MASK_RD_REQ BIT(5)
+#define QM_I2C_IC_INTR_MASK_TX_ABORT BIT(6)
+#define QM_I2C_IC_INTR_MASK_RX_DONE BIT(7)
+#define QM_I2C_IC_INTR_MASK_ACTIVITY BIT(8)
+#define QM_I2C_IC_INTR_MASK_STOP_DETECTED BIT(9)
+#define QM_I2C_IC_INTR_MASK_START_DETECTED BIT(10)
+#define QM_I2C_IC_INTR_MASK_GEN_CALL_DETECTED BIT(11)
+#define QM_I2C_IC_INTR_MASK_RESTART_DETECTED BIT(12)
+#define QM_I2C_IC_INTR_STAT_RX_UNDER BIT(0)
+#define QM_I2C_IC_INTR_STAT_RX_OVER BIT(1)
+#define QM_I2C_IC_INTR_STAT_RX_FULL BIT(2)
+#define QM_I2C_IC_INTR_STAT_TX_OVER BIT(3)
+#define QM_I2C_IC_INTR_STAT_TX_EMPTY BIT(4)
+#define QM_I2C_IC_INTR_STAT_RD_REQ BIT(5)
+#define QM_I2C_IC_INTR_STAT_TX_ABRT BIT(6)
+#define QM_I2C_IC_INTR_STAT_RX_DONE BIT(7)
+#define QM_I2C_IC_INTR_STAT_STOP_DETECTED BIT(9)
+#define QM_I2C_IC_INTR_STAT_START_DETECTED BIT(10)
+#define QM_I2C_IC_INTR_STAT_GEN_CALL_DETECTED BIT(11)
+#define QM_I2C_IC_LCNT_MAX (65525)
+#define QM_I2C_IC_LCNT_MIN (8)
+#define QM_I2C_IC_HCNT_MAX (65525)
+#define QM_I2C_IC_HCNT_MIN (6)
+
+#define QM_I2C_FIFO_SIZE (16)
+
+/* I2C DMA */
+#define QM_I2C_IC_DMA_CR_RX_ENABLE BIT(0)
+#define QM_I2C_IC_DMA_CR_TX_ENABLE BIT(1)
+
+/** @} */
+
+/**
+ * @name GPIO
+ * @{
+ */
+
+/** Number of GPIO controllers. */
+typedef enum { QM_GPIO_0 = 0, QM_AON_GPIO_0 = 1, 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_ctl; /**< Port A Data Source */
+ QM_RW uint32_t reserved[9];
+ 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 reserved2;
+ QM_RW uint32_t gpio_int_bothedge; /**< Interrupt both edge type */
+ QM_RW uint32_t reserved3;
+ 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;
+
+/**
+ * GPIO context type.
+ *
+ * Application should not modify the content.
+ * This structure is only intended to be used by the qm_gpio_save_context and
+ * qm_gpio_restore_context functions.
+ */
+typedef struct {
+ uint32_t gpio_swporta_dr; /**< Port A Data. */
+ uint32_t gpio_swporta_ddr; /**< Port A Data Direction. */
+ uint32_t gpio_swporta_ctl; /**< Port A Data Source. */
+ uint32_t gpio_inten; /**< Interrupt Enable. */
+ uint32_t gpio_intmask; /**< Interrupt Mask. */
+ uint32_t gpio_inttype_level; /**< Interrupt Type. */
+ uint32_t gpio_int_polarity; /**< Interrupt Polarity. */
+ uint32_t gpio_debounce; /**< Debounce Enable. */
+ uint32_t gpio_ls_sync; /**< Synchronization Level. */
+ uint32_t gpio_int_bothedge; /**< Interrupt both edge type. */
+} qm_gpio_context_t;
+
+#define QM_NUM_GPIO_PINS (32)
+#define QM_NUM_AON_GPIO_PINS (6)
+
+#if (UNIT_TEST)
+qm_gpio_reg_t test_gpio_instance;
+qm_gpio_reg_t *test_gpio[QM_GPIO_NUM];
+
+#define QM_GPIO test_gpio
+#else
+
+/* GPIO register base address */
+#define QM_GPIO_BASE (0xB0000C00)
+#define QM_AON_GPIO_BASE (QM_SCSS_CCU_BASE + 0xB00)
+
+/** GPIO register block */
+extern qm_gpio_reg_t *qm_gpio[QM_GPIO_NUM];
+#define QM_GPIO qm_gpio
+#endif
+
+/** @} */
+
+/**
+ * @name Flash
+ * @{
+ */
+
+/** Number of Flash controllers. */
+typedef enum { QM_FLASH_0 = 0, QM_FLASH_1, QM_FLASH_NUM } qm_flash_t;
+
+/** Flash register map. */
+typedef struct {
+ QM_RW uint32_t tmg_ctrl; /**< TMG_CTRL. */
+ QM_RW uint32_t rom_wr_ctrl; /**< ROM_WR_CTRL. */
+ QM_RW uint32_t rom_wr_data; /**< ROM_WR_DATA. */
+ QM_RW uint32_t flash_wr_ctrl; /**< FLASH_WR_CTRL. */
+ QM_RW uint32_t flash_wr_data; /**< FLASH_WR_DATA. */
+ QM_RW uint32_t flash_stts; /**< FLASH_STTS. */
+ QM_RW uint32_t ctrl; /**< CTRL. */
+ QM_RW uint32_t fpr_rd_cfg[4]; /**< 4 FPR_RD_CFG registers. */
+ QM_RW uint32_t
+ mpr_wr_cfg; /**< Flash Write Protection Control Register. */
+ QM_RW uint32_t mpr_vsts; /**< Protection Status Register. */
+} qm_flash_reg_t;
+
+/**
+ * Flash context type.
+ *
+ * Applications should not modify the content.
+ * This structure is only intended to be used by the
+ * qm_flash_save_context and qm_flash_restore_context functions.
+ */
+typedef struct {
+ /** Flash Timing Control Register. */
+ uint32_t tmg_ctrl;
+ /** Control Register. */
+ uint32_t ctrl;
+} qm_flash_context_t;
+
+#if (UNIT_TEST)
+qm_flash_reg_t test_flash_instance;
+qm_flash_reg_t *test_flash[QM_FLASH_NUM];
+uint8_t test_flash_page[0x800];
+
+#define QM_FLASH test_flash
+
+#define QM_FLASH_REGION_SYS_1_BASE (test_flash_page)
+#define QM_FLASH_REGION_SYS_0_BASE (test_flash_page)
+#define QM_FLASH_REGION_OTP_0_BASE (test_flash_page)
+
+#define QM_FLASH_PAGE_MASK (0xCFF)
+#define QM_FLASH_MAX_ADDR (0xFFFFFFFF)
+#else
+
+/* Flash physical address mappings */
+
+#define QM_FLASH_REGION_SYS_1_BASE (0x40030000)
+#define QM_FLASH_REGION_SYS_0_BASE (0x40000000)
+#define QM_FLASH_REGION_OTP_0_BASE (0xFFFFE000)
+
+#define QM_FLASH_PAGE_MASK (0x3F800)
+#define QM_FLASH_MAX_ADDR (0x30000)
+
+/* Flash controller register base address. */
+#define QM_FLASH_BASE_0 (0xB0100000)
+#define QM_FLASH_BASE_1 (0xB0200000)
+
+/* Flash controller register block. */
+extern qm_flash_reg_t *qm_flash[QM_FLASH_NUM];
+#define QM_FLASH qm_flash
+
+#endif
+
+#define QM_FLASH_REGION_DATA_BASE_OFFSET (0x00)
+#define QM_FLASH_MAX_WAIT_STATES (0xF)
+#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)
+
+/* Flash mask to clear timing. */
+#define QM_FLASH_TMG_DEF_MASK (0xFFFFFC00)
+/* Flash mask to clear micro seconds. */
+#define QM_FLASH_MICRO_SEC_COUNT_MASK (0x3F)
+/* Flash mask to clear wait state. */
+#define QM_FLASH_WAIT_STATE_MASK (0x3C0)
+/* Flash wait state offset bit. */
+#define QM_FLASH_WAIT_STATE_OFFSET (6)
+/* Flash write disable offset bit. */
+#define QM_FLASH_WRITE_DISABLE_OFFSET (4)
+/* Flash write disable value. */
+#define QM_FLASH_WRITE_DISABLE_VAL BIT(4)
+
+/* Flash page erase request. */
+#define ER_REQ BIT(1)
+/* Flash page erase done. */
+#define ER_DONE (1)
+/* Flash page write request. */
+#define WR_REQ (1)
+/* Flash page write done. */
+#define WR_DONE BIT(1)
+
+/* Flash write address offset. */
+#define WR_ADDR_OFFSET (2)
+/* Flash perform mass erase includes OTP region. */
+#define MASS_ERASE_INFO BIT(6)
+/* Flash perform mass erase. */
+#define MASS_ERASE BIT(7)
+
+#define QM_FLASH_ADDRESS_MASK (0x7FF)
+/* Increment by 4 bytes each time, but there is an offset of 2, so 0x10. */
+#define QM_FLASH_ADDR_INC (0x10)
+
+/* Flash page size in dwords. */
+#define QM_FLASH_PAGE_SIZE_DWORDS (0x200)
+/* Flash page size in bytes. */
+#define QM_FLASH_PAGE_SIZE_BYTES (0x800)
+/* Flash page size in bits. */
+#define QM_FLASH_PAGE_SIZE_BITS (11)
+
+/** @} */
+
+/**
+ * @name Flash Protection Region
+ * @{
+ */
+
+/**
+ * FPR register map.
+ */
+typedef enum {
+ QM_FPR_0, /**< FPR 0. */
+ QM_FPR_1, /**< FPR 1. */
+ QM_FPR_2, /**< FPR 2. */
+ QM_FPR_3, /**< FPR 3. */
+ QM_FPR_NUM
+} qm_fpr_id_t;
+
+/**
+ * FPR context type.
+ *
+ * Applications should not modify the content.
+ * This structure is only intended to be used by the
+ * qm_fpr_save_context and qm_fpr_restore_context functions.
+ */
+typedef struct {
+ /** Flash Protection Region Read Control Register. */
+ uint32_t fpr_rd_cfg[QM_FPR_NUM];
+} qm_fpr_context_t;
+
+/** @} */
+
+/**
+ * @name Memory Protection Region
+ * @{
+ */
+
+/* MPR identifier */
+typedef enum {
+ QM_MPR_0 = 0, /**< Memory Protection Region 0. */
+ QM_MPR_1, /**< Memory Protection Region 1. */
+ QM_MPR_2, /**< Memory Protection Region 2. */
+ QM_MPR_3, /**< Memory Protection Region 3. */
+ QM_MPR_NUM /**< Number of Memory Protection Regions. */
+} qm_mpr_id_t;
+
+/** Memory Protection Region register map. */
+typedef struct {
+ QM_RW uint32_t mpr_cfg[4]; /**< MPR CFG */
+ QM_RW uint32_t mpr_vdata; /**< MPR_VDATA */
+ QM_RW uint32_t mpr_vsts; /**< MPR_VSTS */
+} qm_mpr_reg_t;
+
+/**
+ * MPR context type.
+ *
+ * Application should not modify the content.
+ * This structure is only intended to be used by the qm_mpr_save_context and
+ * qm_mpr_restore_context functions.
+ */
+typedef struct {
+ uint32_t mpr_cfg[QM_MPR_NUM]; /**< MPR Configuration Register. */
+} qm_mpr_context_t;
+
+#if (UNIT_TEST)
+qm_mpr_reg_t test_mpr;
+
+#define QM_MPR ((qm_mpr_reg_t *)(&test_mpr))
+
+#else
+
+#define QM_MPR_BASE (0xB0400000)
+#define QM_MPR ((qm_mpr_reg_t *)QM_MPR_BASE)
+
+#endif
+
+#define QM_MPR_RD_EN_OFFSET (20)
+#define QM_MPR_RD_EN_MASK 0x700000
+#define QM_MPR_WR_EN_OFFSET (24)
+#define QM_MPR_WR_EN_MASK 0x7000000
+#define QM_MPR_EN_LOCK_OFFSET (30)
+#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)
+
+#define QM_CCU_EXTERN_DIV_OFFSET (3)
+#define QM_CCU_EXT_CLK_DIV_EN BIT(2)
+
+/**
+ * @name Peripheral Clock
+ * @{
+ */
+
+/** Peripheral clock type. */
+typedef enum {
+ CLK_PERIPH_REGISTER = BIT(0), /**< Peripheral Clock Gate Enable. */
+ CLK_PERIPH_CLK = BIT(1), /**< Peripheral Clock Enable. */
+ CLK_PERIPH_I2C_M0 = BIT(2), /**< I2C Master 0 Clock Enable. */
+ CLK_PERIPH_I2C_M1 = BIT(3), /**< I2C Master 1 Clock Enable. */
+ CLK_PERIPH_SPI_S = BIT(4), /**< SPI Slave Clock Enable. */
+ CLK_PERIPH_SPI_M0 = BIT(5), /**< SPI Master 0 Clock Enable. */
+ CLK_PERIPH_SPI_M1 = BIT(6), /**< SPI Master 1 Clock Enable. */
+ CLK_PERIPH_GPIO_INTERRUPT = BIT(7), /**< GPIO Interrupt Clock Enable. */
+ CLK_PERIPH_GPIO_DB = BIT(8), /**< GPIO Debounce Clock Enable. */
+ CLK_PERIPH_I2S = BIT(9), /**< I2S Clock Enable. */
+ CLK_PERIPH_WDT_REGISTER = BIT(10), /**< Watchdog Clock Enable. */
+ CLK_PERIPH_RTC_REGISTER = BIT(11), /**< RTC Clock Gate Enable. */
+ CLK_PERIPH_PWM_REGISTER = BIT(12), /**< PWM Clock Gate Enable. */
+ CLK_PERIPH_GPIO_REGISTER = BIT(13), /**< GPIO Clock Gate Enable. */
+ CLK_PERIPH_SPI_M0_REGISTER =
+ BIT(14), /**< SPI Master 0 Clock Gate Enable. */
+ CLK_PERIPH_SPI_M1_REGISTER =
+ BIT(15), /**< SPI Master 1 Clock Gate Enable. */
+ CLK_PERIPH_SPI_S_REGISTER =
+ BIT(16), /**< SPI Slave Clock Gate Enable. */
+ CLK_PERIPH_UARTA_REGISTER = BIT(17), /**< UARTA Clock Gate Enable. */
+ CLK_PERIPH_UARTB_REGISTER = BIT(18), /**< UARTB Clock Gate Enable. */
+ CLK_PERIPH_I2C_M0_REGISTER =
+ BIT(19), /**< I2C Master 0 Clock Gate Enable. */
+ CLK_PERIPH_I2C_M1_REGISTER =
+ BIT(20), /**< I2C Master 1 Clock Gate Enable. */
+ CLK_PERIPH_I2S_REGISTER = BIT(21), /**< I2S Clock Gate Enable. */
+ CLK_PERIPH_ALL = 0x3FFFFF /**< Quark SE peripherals Mask. */
+} clk_periph_t;
+
+/* Default mask values */
+#define CLK_EXTERN_DIV_DEF_MASK (0xFFFFFFE3)
+#define CLK_SYS_CLK_DIV_DEF_MASK (0xFFFFFC7F)
+#define CLK_RTC_DIV_DEF_MASK (0xFFFFFF83)
+#define CLK_GPIO_DB_DIV_DEF_MASK (0xFFFFFFE1)
+#define CLK_PERIPH_DIV_DEF_MASK (0xFFFFFFF9)
+
+/** @} */
+
+/**
+ * @name DMA
+ * @{
+ */
+
+/** DMA instances. */
+typedef enum {
+ QM_DMA_0, /**< DMA controller id. */
+ QM_DMA_NUM /**< Number of DMA controllers. */
+} qm_dma_t;
+
+/** DMA channel IDs. */
+typedef enum {
+ QM_DMA_CHANNEL_0 = 0, /**< DMA channel id for channel 0 */
+ QM_DMA_CHANNEL_1, /**< DMA channel id for channel 1 */
+ QM_DMA_CHANNEL_2, /**< DMA channel id for channel 2 */
+ QM_DMA_CHANNEL_3, /**< DMA channel id for channel 3 */
+ QM_DMA_CHANNEL_4, /**< DMA channel id for channel 4 */
+ QM_DMA_CHANNEL_5, /**< DMA channel id for channel 5 */
+ QM_DMA_CHANNEL_6, /**< DMA channel id for channel 6 */
+ QM_DMA_CHANNEL_7, /**< DMA channel id for channel 7 */
+ QM_DMA_CHANNEL_NUM /**< Number of DMA channels */
+} qm_dma_channel_id_t;
+
+/** DMA hardware handshake interfaces. */
+typedef enum {
+ DMA_HW_IF_UART_A_TX = 0x0, /**< UART_A_TX */
+ DMA_HW_IF_UART_A_RX = 0x1, /**< UART_A_RX */
+ DMA_HW_IF_UART_B_TX = 0x2, /**< UART_B_TX*/
+ DMA_HW_IF_UART_B_RX = 0x3, /**< UART_B_RX */
+ DMA_HW_IF_SPI_MASTER_0_TX = 0x4, /**< SPI_Master_0_TX */
+ DMA_HW_IF_SPI_MASTER_0_RX = 0x5, /**< SPI_Master_0_RX */
+ DMA_HW_IF_SPI_MASTER_1_TX = 0x6, /**< SPI_Master_1_TX */
+ DMA_HW_IF_SPI_MASTER_1_RX = 0x7, /**< SPI_Master_1_RX */
+ DMA_HW_IF_SPI_SLAVE_TX = 0x8, /**< SPI_Slave_TX */
+ DMA_HW_IF_SPI_SLAVE_RX = 0x9, /**< SPI_Slave_RX */
+ DMA_HW_IF_I2S_PLAYBACK = 0xa, /**< I2S_Playback channel */
+ DMA_HW_IF_I2S_CAPTURE = 0xb, /**< I2S_Capture channel */
+ DMA_HW_IF_I2C_MASTER_0_TX = 0xc, /**< I2C_Master_0_TX */
+ DMA_HW_IF_I2C_MASTER_0_RX = 0xd, /**< I2C_Master_0_RX */
+ DMA_HW_IF_I2C_MASTER_1_TX = 0xe, /**< I2C_Master_1_TX */
+ DMA_HW_IF_I2C_MASTER_1_RX = 0xf, /**< I2C_Master_1_RX */
+} qm_dma_handshake_interface_t;
+
+/** DMA channel register map. */
+typedef struct {
+ QM_RW uint32_t sar_low; /**< SAR */
+ QM_RW uint32_t sar_high; /**< SAR */
+ QM_RW uint32_t dar_low; /**< DAR */
+ QM_RW uint32_t dar_high; /**< DAR */
+ QM_RW uint32_t llp_low; /**< LLP */
+ QM_RW uint32_t llp_high; /**< LLP */
+ QM_RW uint32_t ctrl_low; /**< CTL */
+ QM_RW uint32_t ctrl_high; /**< CTL */
+ QM_RW uint32_t src_stat_low; /**< SSTAT */
+ QM_RW uint32_t src_stat_high; /**< SSTAT */
+ QM_RW uint32_t dst_stat_low; /**< DSTAT */
+ QM_RW uint32_t dst_stat_high; /**< DSTAT */
+ QM_RW uint32_t src_stat_addr_low; /**< SSTATAR */
+ QM_RW uint32_t src_stat_addr_high; /**< SSTATAR */
+ QM_RW uint32_t dst_stat_addr_low; /**< DSTATAR */
+ QM_RW uint32_t dst_stat_addr_high; /**< DSTATAR */
+ QM_RW uint32_t cfg_low; /**< CFG */
+ QM_RW uint32_t cfg_high; /**< CFG */
+ QM_RW uint32_t src_sg_low; /**< SGR */
+ QM_RW uint32_t src_sg_high; /**< SGR */
+ QM_RW uint32_t dst_sg_low; /**< DSR */
+ QM_RW uint32_t dst_sg_high; /**< DSR */
+} qm_dma_chan_reg_t;
+
+/* DMA channel control register offsets and masks. */
+#define QM_DMA_CTL_L_INT_EN_MASK BIT(0)
+#define QM_DMA_CTL_L_DST_TR_WIDTH_OFFSET (1)
+#define QM_DMA_CTL_L_DST_TR_WIDTH_MASK (0x7 << QM_DMA_CTL_L_DST_TR_WIDTH_OFFSET)
+#define QM_DMA_CTL_L_SRC_TR_WIDTH_OFFSET (4)
+#define QM_DMA_CTL_L_SRC_TR_WIDTH_MASK (0x7 << QM_DMA_CTL_L_SRC_TR_WIDTH_OFFSET)
+#define QM_DMA_CTL_L_DINC_OFFSET (7)
+#define QM_DMA_CTL_L_DINC_MASK (0x3 << QM_DMA_CTL_L_DINC_OFFSET)
+#define QM_DMA_CTL_L_SINC_OFFSET (9)
+#define QM_DMA_CTL_L_SINC_MASK (0x3 << QM_DMA_CTL_L_SINC_OFFSET)
+#define QM_DMA_CTL_L_DEST_MSIZE_OFFSET (11)
+#define QM_DMA_CTL_L_DEST_MSIZE_MASK (0x7 << QM_DMA_CTL_L_DEST_MSIZE_OFFSET)
+#define QM_DMA_CTL_L_SRC_MSIZE_OFFSET (14)
+#define QM_DMA_CTL_L_SRC_MSIZE_MASK (0x7 << QM_DMA_CTL_L_SRC_MSIZE_OFFSET)
+#define QM_DMA_CTL_L_TT_FC_OFFSET (20)
+#define QM_DMA_CTL_L_TT_FC_MASK (0x7 << QM_DMA_CTL_L_TT_FC_OFFSET)
+#define QM_DMA_CTL_L_LLP_DST_EN_MASK BIT(27)
+#define QM_DMA_CTL_L_LLP_SRC_EN_MASK BIT(28)
+#define QM_DMA_CTL_H_BLOCK_TS_OFFSET (0)
+#define QM_DMA_CTL_H_BLOCK_TS_MASK (0xfff << QM_DMA_CTL_H_BLOCK_TS_OFFSET)
+#define QM_DMA_CTL_H_BLOCK_TS_MAX 4095
+#define QM_DMA_CTL_H_BLOCK_TS_MIN 1
+
+/* DMA channel config register offsets and masks. */
+#define QM_DMA_CFG_L_CH_SUSP_MASK BIT(8)
+#define QM_DMA_CFG_L_FIFO_EMPTY_MASK BIT(9)
+#define QM_DMA_CFG_L_HS_SEL_DST_OFFSET 10
+#define QM_DMA_CFG_L_HS_SEL_DST_MASK BIT(QM_DMA_CFG_L_HS_SEL_DST_OFFSET)
+#define QM_DMA_CFG_L_HS_SEL_SRC_OFFSET 11
+#define QM_DMA_CFG_L_HS_SEL_SRC_MASK BIT(QM_DMA_CFG_L_HS_SEL_SRC_OFFSET)
+#define QM_DMA_CFG_L_DST_HS_POL_OFFSET 18
+#define QM_DMA_CFG_L_DST_HS_POL_MASK BIT(QM_DMA_CFG_L_DST_HS_POL_OFFSET)
+#define QM_DMA_CFG_L_SRC_HS_POL_OFFSET 19
+#define QM_DMA_CFG_L_SRC_HS_POL_MASK BIT(QM_DMA_CFG_L_SRC_HS_POL_OFFSET)
+#define QM_DMA_CFG_L_RELOAD_SRC_MASK BIT(30)
+#define QM_DMA_CFG_L_RELOAD_DST_MASK BIT(31)
+#define QM_DMA_CFG_H_DS_UPD_EN_OFFSET (5)
+#define QM_DMA_CFG_H_DS_UPD_EN_MASK BIT(QM_DMA_CFG_H_DS_UPD_EN_OFFSET)
+#define QM_DMA_CFG_H_SS_UPD_EN_OFFSET (6)
+#define QM_DMA_CFG_H_SS_UPD_EN_MASK BIT(QM_DMA_CFG_H_SS_UPD_EN_OFFSET)
+#define QM_DMA_CFG_H_SRC_PER_OFFSET (7)
+#define QM_DMA_CFG_H_SRC_PER_MASK (0xf << QM_DMA_CFG_H_SRC_PER_OFFSET)
+#define QM_DMA_CFG_H_DEST_PER_OFFSET (11)
+#define QM_DMA_CFG_H_DEST_PER_MASK (0xf << QM_DMA_CFG_H_DEST_PER_OFFSET)
+
+/** DMA interrupt register map. */
+typedef struct {
+ QM_RW uint32_t raw_tfr_low; /**< RawTfr */
+ QM_RW uint32_t raw_tfr_high; /**< RawTfr */
+ QM_RW uint32_t raw_block_low; /**< RawBlock */
+ QM_RW uint32_t raw_block_high; /**< RawBlock */
+ QM_RW uint32_t raw_src_trans_low; /**< RawSrcTran */
+ QM_RW uint32_t raw_src_trans_high; /**< RawSrcTran */
+ QM_RW uint32_t raw_dst_trans_low; /**< RawDstTran */
+ QM_RW uint32_t raw_dst_trans_high; /**< RawDstTran */
+ QM_RW uint32_t raw_err_low; /**< RawErr */
+ QM_RW uint32_t raw_err_high; /**< RawErr */
+ QM_RW uint32_t status_tfr_low; /**< StatusTfr */
+ QM_RW uint32_t status_tfr_high; /**< StatusTfr */
+ QM_RW uint32_t status_block_low; /**< StatusBlock */
+ QM_RW uint32_t status_block_high; /**< StatusBlock */
+ QM_RW uint32_t status_src_trans_low; /**< StatusSrcTran */
+ QM_RW uint32_t status_src_trans_high; /**< StatusSrcTran */
+ QM_RW uint32_t status_dst_trans_low; /**< StatusDstTran */
+ QM_RW uint32_t status_dst_trans_high; /**< StatusDstTran */
+ QM_RW uint32_t status_err_low; /**< StatusErr */
+ QM_RW uint32_t status_err_high; /**< StatusErr */
+ QM_RW uint32_t mask_tfr_low; /**< MaskTfr */
+ QM_RW uint32_t mask_tfr_high; /**< MaskTfr */
+ QM_RW uint32_t mask_block_low; /**< MaskBlock */
+ QM_RW uint32_t mask_block_high; /**< MaskBlock */
+ QM_RW uint32_t mask_src_trans_low; /**< MaskSrcTran */
+ QM_RW uint32_t mask_src_trans_high; /**< MaskSrcTran */
+ QM_RW uint32_t mask_dst_trans_low; /**< MaskDstTran */
+ QM_RW uint32_t mask_dst_trans_high; /**< MaskDstTran */
+ QM_RW uint32_t mask_err_low; /**< MaskErr */
+ QM_RW uint32_t mask_err_high; /**< MaskErr */
+ QM_RW uint32_t clear_tfr_low; /**< ClearTfr */
+ QM_RW uint32_t clear_tfr_high; /**< ClearTfr */
+ QM_RW uint32_t clear_block_low; /**< ClearBlock */
+ QM_RW uint32_t clear_block_high; /**< ClearBlock */
+ QM_RW uint32_t clear_src_trans_low; /**< ClearSrcTran */
+ QM_RW uint32_t clear_src_trans_high; /**< ClearSrcTran */
+ QM_RW uint32_t clear_dst_trans_low; /**< ClearDstTran */
+ QM_RW uint32_t clear_dst_trans_high; /**< ClearDstTran */
+ QM_RW uint32_t clear_err_low; /**< ClearErr */
+ QM_RW uint32_t clear_err_high; /**< ClearErr */
+ QM_RW uint32_t status_int_low; /**< StatusInt */
+ QM_RW uint32_t status_int_high; /**< StatusInt */
+} qm_dma_int_reg_t;
+
+/* DMA interrupt status register bits. */
+#define QM_DMA_INT_STATUS_TFR BIT(0)
+#define QM_DMA_INT_STATUS_BLOCK BIT(1)
+#define QM_DMA_INT_STATUS_ERR BIT(4)
+
+/** DMA miscellaneous register map. */
+typedef struct {
+ QM_RW uint32_t cfg_low; /**< DmaCfgReg */
+ QM_RW uint32_t cfg_high; /**< DmaCfgReg */
+ QM_RW uint32_t chan_en_low; /**< ChEnReg */
+ QM_RW uint32_t chan_en_high; /**< ChEnReg */
+ QM_RW uint32_t id_low; /**< DmaIdReg */
+ QM_RW uint32_t id_high; /**< DmaIdReg */
+ QM_RW uint32_t test_low; /**< DmaTestReg */
+ QM_RW uint32_t test_high; /**< DmaTestReg */
+ QM_RW uint32_t reserved[4]; /**< Reserved */
+} qm_dma_misc_reg_t;
+
+/* 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. */
+#define QM_DMA_MISC_CFG_DMA_EN BIT(0)
+
+typedef struct {
+ QM_RW qm_dma_chan_reg_t chan_reg[8]; /**< Channel Register */
+ QM_RW qm_dma_int_reg_t int_reg; /**< Interrupt Register */
+ QM_RW uint32_t reserved[12]; /**< Reserved (SW HS) */
+ QM_RW qm_dma_misc_reg_t misc_reg; /**< Miscellaneous Register */
+} qm_dma_reg_t;
+
+/**
+ * DMA context type.
+ *
+ * Applications should not modify the content.
+ * This structure is only intended to be used by
+ * the qm_dma_save_context and qm_dma_restore_context functions.
+ */
+typedef struct {
+ struct {
+ uint32_t ctrl_low; /**< Channel Control Lower. */
+ uint32_t cfg_low; /**< Channel Configuration Lower. */
+ uint32_t cfg_high; /**< Channel Configuration Upper. */
+ uint32_t llp_low; /**< Channel Linked List Pointer. */
+ } channel[QM_DMA_CHANNEL_NUM];
+ uint32_t misc_cfg_low; /**< DMA Configuration. */
+} qm_dma_context_t;
+
+#if (UNIT_TEST)
+qm_dma_reg_t test_dma_instance[QM_DMA_NUM];
+qm_dma_reg_t *test_dma[QM_DMA_NUM];
+#define QM_DMA test_dma
+#else
+#define QM_DMA_BASE (0xB0700000)
+extern qm_dma_reg_t *qm_dma[QM_DMA_NUM];
+#define QM_DMA qm_dma
+#endif
+
+/** @} */
+
+/**
+ * @name USB
+ * @{
+ */
+
+#define QM_USB_EP_DIR_IN_MASK (0x80)
+#define QM_USB_IN_EP_NUM (6)
+#define QM_USB_OUT_EP_NUM (4)
+#define QM_USB_MAX_PACKET_SIZE (64)
+
+/** Number of USB controllers. */
+typedef enum { QM_USB_0 = 0, QM_USB_NUM } qm_usb_t;
+
+typedef enum {
+ QM_USB_IN_EP_0 = 0,
+ QM_USB_IN_EP_1 = 1,
+ QM_USB_IN_EP_2 = 2,
+ QM_USB_IN_EP_3 = 3,
+ QM_USB_IN_EP_4 = 4,
+ QM_USB_IN_EP_5 = 5,
+ QM_USB_OUT_EP_0 = 6,
+ QM_USB_OUT_EP_1 = 7,
+ QM_USB_OUT_EP_2 = 8,
+ QM_USB_OUT_EP_3 = 9
+} qm_usb_ep_idx_t;
+
+/** USB register map. */
+
+/** IN Endpoint Registers. */
+typedef struct {
+ QM_RW uint32_t diepctl;
+ QM_R uint32_t reserved;
+ QM_RW uint32_t diepint;
+ QM_R uint32_t reserved1;
+ QM_RW uint32_t dieptsiz;
+ QM_RW uint32_t diepdma;
+ QM_RW uint32_t dtxfsts;
+ QM_R uint32_t reserved2;
+} qm_usb_in_ep_reg_t;
+
+/** OUT Endpoint Registers. */
+typedef struct {
+ QM_RW uint32_t doepctl;
+ QM_R uint32_t reserved;
+ QM_RW uint32_t doepint;
+ QM_R uint32_t reserved1;
+ QM_RW uint32_t doeptsiz;
+ QM_RW uint32_t doepdma;
+ QM_R uint32_t reserved2[2];
+} qm_usb_out_ep_reg_t;
+
+/**
+ * USB Register block type.
+ */
+typedef struct {
+ QM_RW uint32_t gotgctl; /**< OTG Control. */
+ QM_RW uint32_t gotgint; /**< OTG Interrupt. */
+ QM_RW uint32_t gahbcfg; /**< AHB Configuration. */
+ QM_RW uint32_t gusbcfg; /**< USB Configuration. */
+ QM_RW uint32_t grstctl; /**< Reset Register. */
+ QM_RW uint32_t gintsts; /**< Interrupt Status. */
+ QM_RW uint32_t gintmsk; /**< Interrupt Mask. */
+ QM_R uint32_t grxstsr; /**< Receive Status Read/Pop. */
+ QM_R uint32_t grxstsp; /**< Receive Status Read/Pop. */
+ QM_R uint32_t grxfsiz; /**< Receive FIFO Size. */
+ QM_R uint32_t gnptxfsiz; /**< Non-periodic Transmit FIFO Size. */
+ QM_R uint32_t reserved[5];
+ QM_R uint32_t gsnpsid; /**< Synopsys ID. */
+ QM_R uint32_t ghwcfg1; /**< HW config - Endpoint direction. */
+ QM_R uint32_t ghwcfg2; /**< HW config 2. */
+ QM_R uint32_t ghwcfg3; /**< HW config 3. */
+ QM_R uint32_t ghwcfg4; /**< HW config 4. */
+ QM_RW uint32_t gdfifocfg; /**< Global DFIFO Configuration. */
+ QM_R uint32_t reserved1[43];
+ QM_RW uint32_t dieptxf1;
+ QM_RW uint32_t dieptxf2;
+ QM_RW uint32_t dieptxf3;
+ QM_RW uint32_t dieptxf4;
+ QM_RW uint32_t dieptxf5;
+ QM_R uint32_t reserved2[442];
+ QM_RW uint32_t dcfg; /**< Device config. */
+ QM_RW uint32_t dctl; /**< Device control. */
+ QM_RW uint32_t dsts; /**< Device Status. */
+ QM_R uint32_t reserved3;
+ QM_RW uint32_t diepmsk; /**< IN EP Common Interrupt Mask. */
+ QM_RW uint32_t doepmsk; /**< OUT EP Common Interrupt Mask. */
+ QM_R uint32_t daint; /**< Device Interrupt Register. */
+ QM_RW uint32_t daintmsk; /**< Device Interrupt Mask Register. */
+ QM_R uint32_t reserved4[2];
+ QM_RW uint32_t dvbusdis; /**< VBUS discharge time register. */
+ QM_RW uint32_t dvbuspulse; /**< Device VBUS discharge time. */
+ QM_RW uint32_t dthrctl; /**< Device Threshold Ctrl. */
+ QM_RW uint32_t diepempmsk; /**< IN EP FIFO Empty Intr Mask. */
+ QM_R uint32_t reserved5[50];
+ qm_usb_in_ep_reg_t in_ep_reg[QM_USB_IN_EP_NUM];
+ QM_R uint32_t reserved6[80];
+ qm_usb_out_ep_reg_t out_ep_reg[QM_USB_OUT_EP_NUM];
+} qm_usb_reg_t;
+
+#if (UNIT_TEST)
+qm_usb_reg_t test_usb;
+#define QM_USB ((qm_usb_reg_t *)(&test_usb))
+#else
+#define QM_USB_0_BASE (0xB0500000)
+/* USB controller base address */
+#define QM_USB ((qm_usb_reg_t *)QM_USB_0_BASE)
+#endif
+
+/* 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)
+
+/* USB PLL register */
+#if (UNIT_TEST)
+uint32_t test_usb_pll;
+#define QM_USB_PLL_CFG0 (test_usb_pll)
+#else
+#define QM_USB_PLL_CFG0 (REG_VAL(0xB0800014))
+#endif
+
+/* USB clock enable bit */
+#define QM_CCU_USB_CLK_EN BIT(1)
+
+/** @} */
+
+/**
+ * @name Hardware Fixes
+ * @{
+ */
+
+/* Refer to "HARDWARE_ISSUES.rst" for fix description. */
+#define FIX_1 (1)
+
+/** @} */
+
+/**
+ * @name Versioning
+ * @{
+ */
+
+#if (UNIT_TEST)
+uint32_t test_rom_version;
+#define ROM_VERSION_ADDRESS &test_rom_version;
+#else
+#define ROM_VERSION_ADDRESS (0xFFFFFFEC);
+#endif
+
+/** @} */
+
+/** @} */
+
+#endif /* __REGISTERS_H__ */
diff --git a/src/include/arc32/ss_power_states.h b/src/include/arc32/ss_power_states.h
new file mode 100644
index 0000000..f4dd80b
--- /dev/null
+++ b/src/include/arc32/ss_power_states.h
@@ -0,0 +1,295 @@
+/*
+ * Copyright (c) 2016, Intel Corporation
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of the Intel Corporation nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE INTEL CORPORATION OR CONTRIBUTORS BE
+ * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __QM_SS_POWER_STATES_H__
+#define __QM_SS_POWER_STATES_H__
+
+#include "qm_sensor_regs.h"
+
+/**
+ * SS Power mode control for Quark SE Microcontrollers.
+ *
+ * @defgroup groupSSPower SS Power states
+ * @{
+ */
+
+/**
+ * Sensor Subsystem SS1 Timers mode type.
+ */
+typedef enum {
+ SS_POWER_CPU_SS1_TIMER_OFF = 0, /**< Disable SS Timers in SS1. */
+ SS_POWER_CPU_SS1_TIMER_ON /**< Keep SS Timers enabled in SS1. */
+} ss_power_cpu_ss1_mode_t;
+
+/**
+ * Enable LPSS state entry.
+ *
+ * Put the SoC into LPSS on next C2/C2LP and SS2 state combination.
+ * This function needs to be called on the Sensor Core to
+ * Clock Gate ADC, I2C0, I2C1, SPI0 and SPI1 sensor peripherals.
+ * Clock Gating sensor peripherals is a requirement to enter LPSS state.
+ * After LPSS, ss_power_soc_lpss_disable needs to be called to
+ * restore clock gating.
+ *
+ * This needs to be called before any transition to C2/C2LP and SS2
+ * in order to enter LPSS.
+ * SoC Hybrid Clock is gated in this state.
+ * Core Well Clocks are gated.
+ * 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);
+
+/**
+ * Enter SoC sleep state and restore after wake up.
+ *
+ * Put the ARC core into sleep state until next SoC wake event
+ * and continue execution after wake up where the application stopped.
+ *
+ * If the library is built with ENABLE_RESTORE_CONTEXT=1, then this function
+ * will use the arc_restore_addr to save restore trap address which brings back
+ * the ARC CPU to the point where this function was called.
+ * This means that applications should refrain from using them.
+ *
+ * This function calls qm_ss_save_context and qm_ss_restore_context
+ * in order to restore execution where it stopped.
+ * All power management transitions are done by power_soc_sleep().
+ */
+//void ss_power_soc_sleep_restore(void);
+/**
+ * Enter SoC sleep state and restore after wake up.
+ *
+ * Put the ARC core into sleep state until next SoC wake event
+ * and continue execution after wake up where the application stopped.
+ *
+ * If the library is built with ENABLE_RESTORE_CONTEXT=1, then this function
+ * will use the arc_restore_addr to save restore trap address which brings back
+ * the ARC CPU to the point where this function was called.
+ * This means that applications should refrain from using them.
+ *
+ * This function calls qm_ss_save_context and qm_ss_restore_context
+ * in order to restore execution where it stopped.
+ * All power management transitions are done by power_soc_deep_sleep().
+ */
+//void ss_power_soc_deep_sleep_restore(void);
+
+/**
+ * Save context, enter ARC SS1 power save state and restore after wake up.
+ *
+ * This routine is same as ss_power_soc_sleep_restore(), just instead of
+ * going to sleep it will go to SS1 power save state.
+ * Note: this function has a while(1) which will spin until we enter
+ * (and exit) sleep and the power state change will be managed by the other
+ * core.
+ */
+//void ss_power_sleep_wait(void);
+
+/**
+ * Enable the SENSOR startup restore flag.
+ */
+//void power_soc_set_ss_restore_flag(void);
+
+/**
+ * Disable LPSS state entry.
+ *
+ * Clear LPSS enable flag.
+ * Disable Clock Gating of ADC, I2C0, I2C1, SPI0 and SPI1 sensor
+ * peripherals.
+ * 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.
+ *
+ * Put the Sensor Subsystem into SS1.
+ * Processor Clock is gated in this state.
+ *
+ * A wake event causes the Sensor Subsystem to transition to SS0.
+ * A wake event is a sensor subsystem interrupt.
+ *
+ * According to the mode selected, Sensor Subsystem Timers can be disabled.
+ *
+ * @param[in] mode Mode selection for SS1 state.
+ */
+//void ss_power_cpu_ss1(const ss_power_cpu_ss1_mode_t mode);
+
+/**
+ * Enter Sensor SS2 state or SoC LPSS state.
+ *
+ * Put the Sensor Subsystem into SS2.
+ * Sensor Complex Clock is gated in this state.
+ * Sensor Peripherals are gated in this state.
+ *
+ * This enables entry in LPSS if:
+ * - Sensor Subsystem is in SS2
+ * - Lakemont is in C2 or C2LP
+ * - LPSS entry is enabled
+ *
+ * A wake event causes the Sensor Subsystem to transition to SS0.
+ * There are two kinds of wake event depending on the Sensor Subsystem
+ * and SoC state:
+ * - SS2: a wake event is a Sensor Subsystem interrupt
+ * - LPSS: a wake event is a Sensor Subsystem interrupt or a Lakemont interrupt
+ *
+ * LPSS wake events apply if LPSS is entered.
+ * If Host wakes the SoC from LPSS,
+ * Sensor also transitions back to SS0.
+ */
+//void ss_power_cpu_ss2(void);
+
+/**
+ * Save resume vector.
+ *
+ * Saves the resume vector in the global "arc_restore_addr" location.
+ * The ARC will jump to the resume vector once a wake up event is
+ * triggered and x86 resumes the ARC.
+ */
+#define qm_ss_set_resume_vector(_restore_label, arc_restore_addr) \
+ __asm__ __volatile__("mov r0, @arc_restore_addr\n\t" \
+ "st " #_restore_label ", [r0]\n\t" \
+ : /* Output operands. */ \
+ : /* Input operands. */ \
+ : /* Clobbered registers list. */ \
+ "r0")
+
+/* Save execution context.
+ *
+ * This routine saves CPU registers onto cpu_context,
+ * array.
+ *
+ */
+#define qm_ss_save_context(cpu_context) \
+ __asm__ __volatile__("push_s r0\n\t" \
+ "mov r0, @cpu_context\n\t" \
+ "st r1, [r0, 4]\n\t" \
+ "st r2, [r0, 8]\n\t" \
+ "st r3, [r0, 12]\n\t" \
+ "st r4, [r0, 16]\n\t" \
+ "st r5, [r0, 20]\n\t" \
+ "st r6, [r0, 24]\n\t" \
+ "st r7, [r0, 28]\n\t" \
+ "st r8, [r0, 32]\n\t" \
+ "st r9, [r0, 36]\n\t" \
+ "st r10, [r0, 40]\n\t" \
+ "st r11, [r0, 44]\n\t" \
+ "st r12, [r0, 48]\n\t" \
+ "st r13, [r0, 52]\n\t" \
+ "st r14, [r0, 56]\n\t" \
+ "st r15, [r0, 60]\n\t" \
+ "st r16, [r0, 64]\n\t" \
+ "st r17, [r0, 68]\n\t" \
+ "st r18, [r0, 72]\n\t" \
+ "st r19, [r0, 76]\n\t" \
+ "st r20, [r0, 80]\n\t" \
+ "st r21, [r0, 84]\n\t" \
+ "st r22, [r0, 88]\n\t" \
+ "st r23, [r0, 92]\n\t" \
+ "st r24, [r0, 96]\n\t" \
+ "st r25, [r0, 100]\n\t" \
+ "st r26, [r0, 104]\n\t" \
+ "st r27, [r0, 108]\n\t" \
+ "st r28, [r0, 112]\n\t" \
+ "st r29, [r0, 116]\n\t" \
+ "st r30, [r0, 120]\n\t" \
+ "st r31, [r0, 124]\n\t" \
+ "lr r31, [ic_ctrl]\n\t" \
+ "st r31, [r0, 128]\n\t" \
+ : /* Output operands. */ \
+ : /* Input operands. */ \
+ [ic_ctrl] "i"(QM_SS_AUX_IC_CTRL) \
+ : /* Clobbered registers list. */ \
+ "r0")
+
+/* Restore execution context.
+ *
+ * This routine restores CPU registers from cpu_context,
+ * array.
+ *
+ * This routine is called from the bootloader to restore the execution context
+ * from before entering in sleep mode.
+ */
+#define qm_ss_restore_context(_restore_label, cpu_context) \
+ __asm__ __volatile__( \
+ #_restore_label \
+ ":\n\t" \
+ "mov r0, @cpu_context\n\t" \
+ "ld r1, [r0, 4]\n\t" \
+ "ld r2, [r0, 8]\n\t" \
+ "ld r3, [r0, 12]\n\t" \
+ "ld r4, [r0, 16]\n\t" \
+ "ld r5, [r0, 20]\n\t" \
+ "ld r6, [r0, 24]\n\t" \
+ "ld r7, [r0, 28]\n\t" \
+ "ld r8, [r0, 32]\n\t" \
+ "ld r9, [r0, 36]\n\t" \
+ "ld r10, [r0, 40]\n\t" \
+ "ld r11, [r0, 44]\n\t" \
+ "ld r12, [r0, 48]\n\t" \
+ "ld r13, [r0, 52]\n\t" \
+ "ld r14, [r0, 56]\n\t" \
+ "ld r15, [r0, 60]\n\t" \
+ "ld r16, [r0, 64]\n\t" \
+ "ld r17, [r0, 68]\n\t" \
+ "ld r18, [r0, 72]\n\t" \
+ "ld r19, [r0, 76]\n\t" \
+ "ld r20, [r0, 80]\n\t" \
+ "ld r21, [r0, 84]\n\t" \
+ "ld r22, [r0, 88]\n\t" \
+ "ld r23, [r0, 92]\n\t" \
+ "ld r24, [r0, 96]\n\t" \
+ "ld r25, [r0, 100]\n\t" \
+ "ld r26, [r0, 104]\n\t" \
+ "ld r27, [r0, 108]\n\t" \
+ "ld r28, [r0, 112]\n\t" \
+ "ld r29, [r0, 116]\n\t" \
+ "ld r30, [r0, 120]\n\t" \
+ "ld r31, [r0, 124]\n\t" \
+ "ld r0, [r0, 128]\n\t" \
+ "sr r0, [ic_ctrl]\n\t" \
+ "pop_s r0\n\t" \
+ "sr 0,[0x101]\n\t" /* Setup Sensor Subsystem TimeStamp Counter */ \
+ "sr 0,[0x100]\n\t" \
+ "sr -1,[0x102]\n\t" \
+ : /* Output operands. */ \
+ : /* Input operands. */ \
+ [ic_ctrl] "i"(QM_SS_AUX_IC_CTRL) \
+ : /* Clobbered registers list. */ \
+ "r0")
+
+/**
+ * @}
+ */
+
+#endif /* __QM_SS_POWER_STATES_H__ */