Merged in alinjerpelea/nuttx (pull request #881)

updates for arch: arm: cxd56xx:

* arch: arm: cxd56xx: add pinconfig

    Add the HW pin configuration for cxd56xx

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* arch: arm: cxd56xx: add GPIO support

    Add GPIO support for cxd56xx

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* arch: arm: cxd56xx: add support for GPIO interrupts

    add support for GPIO interrupts

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* arch: arm: cxd56xx: add clock support

    Add clock support for cxd56xx

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* arch: arm: cxd56xx: add PMIC support

    Add support for PMIC (Power management integrated circuit)
    for cxd56xx chip

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* arch: arm: cxd56xx: add FIFO CPU schedulier

    add a simple FIFO schedulier that minimizes overhead

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* arch: arm: cxd56xx: add ICC support

    add Inter Core Communication for cxd56xx

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
Alin Jerpelea 2019-06-05 11:29:51 +00:00 committed by Gregory Nutt
parent fe0ab650bb
commit eeedce32c4
25 changed files with 10595 additions and 2 deletions

View File

@ -0,0 +1,151 @@
/****************************************************************************
* arch/arm/include/cxd56xx/pin.h
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_INCLUDE_CXD56XX_PIN_H
#define __ARCH_ARM_INCLUDE_CXD56XX_PIN_H
/****************************************************************************
* Included Files
***************************************************************************/
#include <nuttx/config.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Pin number Definitions */
#define PIN_RTC_CLK_IN (0)
/* SYS GPIO: system power domain GPIOs */
#define PIN_I2C4_BCK (1)
#define PIN_I2C4_BDT (2)
#define PIN_PMIC_INT (3)
#define PIN_RTC_IRQ_OUT (4)
#define PIN_AP_CLK (5)
#define PIN_GNSS_1PPS_OUT (6)
#define PIN_SPI0_CS_X (17)
#define PIN_SPI0_SCK (18)
#define PIN_SPI0_MOSI (19)
#define PIN_SPI0_MISO (20)
#define PIN_SPI1_CS_X (21)
#define PIN_SPI1_SCK (22)
#define PIN_SPI1_IO0 (23)
#define PIN_SPI1_IO1 (24)
#define PIN_SPI1_IO2 (25)
#define PIN_SPI1_IO3 (26)
#define PIN_SPI2_CS_X (27)
#define PIN_SPI2_SCK (28)
#define PIN_SPI2_MOSI (29)
#define PIN_SPI2_MISO (30)
#define PIN_HIF_IRQ_OUT (31)
#define PIN_HIF_GPIO0 (32)
#define PIN_SEN_IRQ_IN (37)
#define PIN_SPI3_CS0_X (38)
#define PIN_SPI3_CS1_X (39)
#define PIN_SPI3_CS2_X (40)
#define PIN_SPI3_SCK (41)
#define PIN_SPI3_MOSI (42)
#define PIN_SPI3_MISO (43)
#define PIN_I2C0_BCK (44)
#define PIN_I2C0_BDT (45)
#define PIN_PWM0 (46)
#define PIN_PWM1 (47)
#define PIN_PWM2 (48)
#define PIN_PWM3 (49)
/* APP GPIO: application power domain GPIOs */
#define PIN_IS_CLK (56)
#define PIN_IS_VSYNC (57)
#define PIN_IS_HSYNC (58)
#define PIN_IS_DATA0 (59)
#define PIN_IS_DATA1 (60)
#define PIN_IS_DATA2 (61)
#define PIN_IS_DATA3 (62)
#define PIN_IS_DATA4 (63)
#define PIN_IS_DATA5 (64)
#define PIN_IS_DATA6 (65)
#define PIN_IS_DATA7 (66)
#define PIN_UART2_TXD (67)
#define PIN_UART2_RXD (68)
#define PIN_UART2_CTS (69)
#define PIN_UART2_RTS (70)
#define PIN_SPI4_CS_X (71)
#define PIN_SPI4_SCK (72)
#define PIN_SPI4_MOSI (73)
#define PIN_SPI4_MISO (74)
#define PIN_EMMC_CLK (75)
#define PIN_SPI5_SCK (PIN_EMMC_CLK)
#define PIN_EMMC_CMD (76)
#define PIN_SPI5_CS_X (PIN_EMMC_CMD)
#define PIN_EMMC_DATA0 (77)
#define PIN_SPI5_MOSI (PIN_EMMC_DATA0)
#define PIN_EMMC_DATA1 (78)
#define PIN_SPI5_MISO (PIN_EMMC_DATA1)
#define PIN_EMMC_DATA2 (79)
#define PIN_EMMC_DATA3 (80)
#define PIN_SDIO_CLK (81)
#define PIN_SDIO_CMD (82)
#define PIN_SDIO_DATA0 (83)
#define PIN_SDIO_DATA1 (84)
#define PIN_SDIO_DATA2 (85)
#define PIN_SDIO_DATA3 (86)
#define PIN_SDIO_CD (87)
#define PIN_SDIO_WP (88)
#define PIN_SDIO_CMDDIR (89)
#define PIN_SDIO_DIR0 (90)
#define PIN_SDIO_DIR1_3 (91)
#define PIN_SDIO_CLKI (92)
#define PIN_I2S0_BCK (93)
#define PIN_I2S0_LRCK (94)
#define PIN_I2S0_DATA_IN (95)
#define PIN_I2S0_DATA_OUT (96)
#define PIN_I2S1_BCK (97)
#define PIN_I2S1_LRCK (98)
#define PIN_I2S1_DATA_IN (99)
#define PIN_I2S1_DATA_OUT (100)
#define PIN_MCLK (101)
#define PIN_PDM_CLK (102)
#define PIN_PDM_IN (103)
#define PIN_PDM_OUT (104)
#define PIN_USB_VBUSINT (105)
#endif /* __ARCH_ARM_INCLUDE_CXD56XX_PIN_H */

View File

@ -0,0 +1,391 @@
/****************************************************************************
* arch/arm/include/cxd56xx/pm.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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.
*
****************************************************************************/
/**
* @file pm.h
*/
#ifndef __ARCH_ARM_INCLUDE_CXD56XX_PM_H
#define __ARCH_ARM_INCLUDE_CXD56XX_PM_H
/*-----------------------------------------------------------------------------
* include files
*---------------------------------------------------------------------------*/
#include <queue.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Boot Cause definitions */
#define PM_BOOT_POR_NORMAL (0x00000000ul) /** Power On Reset like as battery attached */
#define PM_BOOT_POR_DEADBATT (0x00000001ul) /** Battery charged from DeadBattery state */
#define PM_BOOT_WDT_REBOOT (0x00000002ul) /** System WDT expired or Explicitly Self Reboot */
#define PM_BOOT_WDT_RESET (0x00000004ul) /** Chip WDT expired (might be used in HV-only system) */
#define PM_BOOT_DEEP_WKUPL (0x00000008ul) /** In DeepSleep state, Detected WKUPL signal */
#define PM_BOOT_DEEP_WKUPS (0x00000010ul) /** In DeepSleep state, Detected WKUPS signal */
#define PM_BOOT_DEEP_RTC (0x00000020ul) /** In DeepSleep state, RTC Alarm expired */
#define PM_BOOT_DEEP_USB_ATTACH (0x00000040ul) /** In DeepSleep state, USB Connected */
#define PM_BOOT_DEEP_OTHERS (0x00000080ul) /** In DeepSleep state, Reserved others cause occurred */
#define PM_BOOT_COLD_SCU_INT (0x00000100ul) /** In ColdSleep state, Detected SCU Interrupt */
#define PM_BOOT_COLD_RTC (0x00001e00ul) /** In ColdSleep state, RTC Alarm Interrupt */
#define PM_BOOT_COLD_RTC_ALM0 (0x00000200ul) /** In ColdSleep state, RTC Alarm0 expired */
#define PM_BOOT_COLD_RTC_ALM1 (0x00000400ul) /** In ColdSleep state, RTC Alarm1 expired */
#define PM_BOOT_COLD_RTC_ALM2 (0x00000800ul) /** In ColdSleep state, RTC Alarm2 expired */
#define PM_BOOT_COLD_RTC_ALMERR (0x00001000ul) /** In ColdSleep state, RTC Alarm Error occurred */
#define PM_BOOT_COLD_GPIO (0x0fff0000ul) /** In ColdSleep state, Detected GPIO interrupt */
#define PM_BOOT_COLD_SEN_INT (0x10000000ul) /** In ColdSleep state, Detected SEN_INT Interrupt */
#define PM_BOOT_COLD_PMIC_INT (0x20000000ul) /** In ColdSleep state, Detected PMIC Interrupt */
#define PM_BOOT_COLD_USB_DETACH (0x40000000ul) /** In ColdSleep state, USB Disconnected */
#define PM_BOOT_COLD_USB_ATTACH (0x80000000ul) /** In ColdSleep state, USB Connected */
/* SRAM power status definitions */
#define PMCMD_RAM_OFF 0 /* Power off */
#define PMCMD_RAM_RET 1 /* Retention */
#define PMCMD_RAM_ON 3 /* Power on */
/* FrequencyLock request flag definitions */
#define PM_CPUFREQLOCK_FLAG_HV (0x0001) /* request HV */
#define PM_CPUFREQLOCK_FLAG_LV (0x4000) /* request LV */
/* FrequencyLock identifier tag helper macro function */
#define PM_CPUFREQLOCK_TAG(prefix1, prefix2, num) \
(((prefix1) << 24) + ((prefix2) << 16) + (num))
/* FrequencyLock initializer macro function */
# define PM_CPUFREQLOCK_INIT(_tag, _flag) \
{ \
.count = 0, \
.info = _tag, \
.flag = _flag, \
}
/* WakeLock identifier tag helper macro function */
#define PM_CPUWAKELOCK_TAG(prefix1, prefix2, num) \
(((prefix1) << 24) + ((prefix2) << 16) + (num))
/* WakeLock initializer macro function */
#define PM_CPUWAKELOCK_INIT(_tag) \
{ \
.count = 0, \
.info = _tag, \
}
/****************************************************************************
* Public Types
****************************************************************************/
/* slee mode definitions */
enum pm_sleepmode_e
{
PM_SLEEP_DEEP,
PM_SLEEP_COLD,
};
/* FreqLock structure */
struct pm_cpu_freqlock_s
{
struct sq_entry_s sq_entry;
int count;
uint32_t info;
int flag;
};
/* WakeLock structure */
struct pm_cpu_wakelock_s
{
struct sq_entry_s sq_entry;
int count;
uint32_t info;
};
/* Definitions for pmic notify */
enum pmic_notify_e
{
PMIC_NOTIFY_ALARM = 0,
PMIC_NOTIFY_WKUPS,
PMIC_NOTIFY_WKUPL,
PMIC_NOTIFY_LOWBATT,
PMIC_NOTIFY_MAX
};
/* callback function for pmic notify */
typedef void (*pmic_notify_t)(void *arg);
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Name: up_pmstatdump
*
* Description:
* Print architecture specific power status
*
****************************************************************************/
int up_pmramctrl(int cmd, uintptr_t addr, size_t size);
#ifdef CONFIG_DEBUG_PM
/****************************************************************************
* Name: up_pmstatdump
*
* Description:
* Print architecture specific power status
*
****************************************************************************/
void up_pmstatdump(void);
#else
# define up_pmstatdump()
#endif
/****************************************************************************
* Name: up_pm_acquire_freqlock
*
* Description:
* Acquire the specified freqlock. If the higher freqlock is acquired, the
* system can clockup until it is released.
*
* Parameter:
* lock - the pointer of a wakelock variable
*
****************************************************************************/
void up_pm_acquire_freqlock(struct pm_cpu_freqlock_s *lock);
/****************************************************************************
* Name: up_pm_release_freqlock
*
* Description:
* Release the specified freqlock. If the freqlock are released, the system
* can drop to the lower clock mode for power saving.
*
* Parameter:
* lock - the pointer of a freqlock variable
*
****************************************************************************/
void up_pm_release_freqlock(struct pm_cpu_freqlock_s *lock);
/****************************************************************************
* Name: up_pm_get_freqlock_count
*
* Description:
* Get the locked count of the specified freqlock
*
* Parameter:
* lock - the pointer of a freqlock variable
*
* Return:
* the locked count of the specified freqlock
*
****************************************************************************/
int up_pm_get_freqlock_count(struct pm_cpu_freqlock_s *lock);
/****************************************************************************
* Name: up_pm_acquire_wakelock
*
* Description:
* Acquire the specified wakelock. If any wakelock is acquired, CPU can't
* enter to the hot sleep state.
*
* Parameter:
* lock - the pointer of a wakelock variable
*
****************************************************************************/
void up_pm_acquire_wakelock(struct pm_cpu_wakelock_s *lock);
/****************************************************************************
* Name: up_pm_release_wakelock
*
* Description:
* Release the specified wakelock. If all of the wakelock are released,
* CPU can enter to the hot sleep state.
*
* Parameter:
* lock - the pointer of a wakelock variable
*
****************************************************************************/
void up_pm_release_wakelock(struct pm_cpu_wakelock_s *lock);
/****************************************************************************
* Name: up_pm_count_acquire_wakelock
*
* Description:
* Count the total number of wakelock
*
* Return:
* the total number of wakelock
*
****************************************************************************/
int up_pm_count_acquire_wakelock(void);
/****************************************************************************
* Name: up_pm_get_bootcause
*
* Description:
* Get the system boot cause. This boot cause indicates the cause why the
* system is launched from the state of power-off, deep sleep or cold sleep.
* Each boot cause is defined as PM_BOOT_XXX.
*
* Return:
* Boot cause
*
****************************************************************************/
uint32_t up_pm_get_bootcause(void);
/****************************************************************************
* Name: up_pm_get_bootmask
*
* Description:
* Get the system boot mask. This boot mask indicates whether the specified
* bit is enabled or not as the boot cause. If a bit of boot mask is set,
* the boot cause is enabled. Each boot mask is defined as PM_BOOT_XXX.
*
* Return:
* Boot mask
*
****************************************************************************/
uint32_t up_pm_get_bootmask(void);
/****************************************************************************
* Name: up_pm_set_bootmask
*
* Description:
* Enable the boot cause of the specified bit.
*
* Parameter:
* mask - OR of Boot mask definied as PM_BOOT_XXX
*
* Return:
* Updated boot mask
*
****************************************************************************/
uint32_t up_pm_set_bootmask(uint32_t mask);
/****************************************************************************
* Name: up_pm_clr_bootmask
*
* Description:
* Disable the boot cause of the specified bit.
*
* Parameter:
* mask - OR of Boot mask definied as PM_BOOT_XXX
*
* Return:
* Updated boot mask
*
****************************************************************************/
uint32_t up_pm_clr_bootmask(uint32_t mask);
/****************************************************************************
* Name: up_pm_sleep
*
* Description:
* Enter sleep mode. This function never returns.
*
* Parameter:
* mode - PM_SLEEP_DEEP or PM_SLEEP_COLD
*
****************************************************************************/
int up_pm_sleep(enum pm_sleepmode_e mode);
/****************************************************************************
* Name: up_pm_reboot
*
* Description:
* System reboot. This function never returns.
*
****************************************************************************/
int up_pm_reboot(void);
/****************************************************************************
* Name: up_pmic_set_notify
*
* Description:
* Register a callback for pmic interrupt
*
* Input Parameter:
* kind - A kind of pmic interrupt defined as pmic_notify_e
* cb - A callback function for a kind of pmic interrupt
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
#ifdef CONFIG_CXD56_PMIC_INT
int up_pmic_set_notify(int kind, pmic_notify_t cb);
#else
# define up_pmic_set_notify(kind, cb)
#endif
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* __ARCH_ARM_INCLUDE_CXD56XX_PM_H */

View File

@ -11,8 +11,31 @@ config CXD56_ARCH_OPTS
select ARCH_DMA
select SDIO_DMA if MMCSD
comment "Basic Options"
config CXD56_XOSC_CLOCK
int
default 26000000
config CXD56_PMIC
bool
default y
config CXD56_CPUFIFO
bool
config CXD56_ICC
bool
default y
menu "CXD56xx Peripheral Support"
config CXD56_GPIO_IRQ
bool "GPIO interrupt"
default y
---help---
Enable support for GPIO interrupts
config CXD56_UART1
bool "UART1"
default y

View File

@ -87,3 +87,13 @@ CHIP_CSRCS = cxd56_allocateheap.c cxd56_idle.c
CHIP_CSRCS += cxd56_serial.c cxd56_uart.c cxd56_irq.c
CHIP_CSRCS += cxd56_start.c
CHIP_CSRCS += cxd56_timerisr.c
CHIP_CSRCS += cxd56_pinconfig.c
CHIP_CSRCS += cxd56_clock.c
CHIP_CSRCS += cxd56_gpio.c
CHIP_CSRCS += cxd56_pmic.c
CHIP_CSRCS += cxd56_cpufifo.c
CHIP_CSRCS += cxd56_icc.c
ifeq ($(CONFIG_CXD56_GPIO_IRQ),y)
CHIP_CSRCS += cxd56_gpioint.c
endif

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,711 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_clock.h
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CXD56_CLOCK_H
#define __ARCH_ARM_SRC_CXD56XX_CXD56_CLOCK_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "hardware/cxd5602_topreg.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: cxd56_spif_clock_enable
*
* Description:
*
****************************************************************************/
void cxd56_spif_clock_enable(void);
/****************************************************************************
* Name: cxd56_spif_clock_disable
*
* Description:
*
****************************************************************************/
void cxd56_spif_clock_disable(void);
/****************************************************************************
* Name: cxd56_get_cpu_baseclk
*
* Description:
* Get CPU clock.
*
****************************************************************************/
uint32_t cxd56_get_cpu_baseclk(void);
/****************************************************************************
* Name: cxd56_cpu_clock_enable
*
* Description:
*
****************************************************************************/
void cxd56_cpu_clock_enable(int cpu);
/****************************************************************************
* Name: cxd56_cpulist_clock_enable
*
* Description:
*
****************************************************************************/
void cxd56_cpulist_clock_enable(uint32_t cpus);
/****************************************************************************
* Name: cxd56_cpu_clock_disable
*
* Description:
*
****************************************************************************/
void cxd56_cpu_clock_disable(int cpu);
/****************************************************************************
* Name: cxd56_cpulist_clock_disable
*
* Description:
*
****************************************************************************/
void cxd56_cpulist_clock_disable(uint32_t cpus);
/****************************************************************************
* Name: cxd56_cpu_reset
*
* Description:
*
****************************************************************************/
void cxd56_cpu_reset(int cpu);
/****************************************************************************
* Name: cxd56_cpulist_reset
*
* Description:
*
****************************************************************************/
void cxd56_cpulist_reset(uint32_t cpus);
/****************************************************************************
* Name: cxd56_usb_clock_enable
*
* Description:
*
****************************************************************************/
void cxd56_usb_clock_enable(void);
/****************************************************************************
* Name: cxd56_usb_clock_disable
*
* Description:
*
****************************************************************************/
void cxd56_usb_clock_disable(void);
/****************************************************************************
* Name: cxd56_emmc_clock_enable
*
* Description:
*
****************************************************************************/
void cxd56_emmc_clock_enable(uint32_t div, uint32_t driver, uint32_t sample);
/****************************************************************************
* Name: cxd56_emmc_clock_disable
*
* Description:
*
****************************************************************************/
void cxd56_emmc_clock_disable(void);
/****************************************************************************
* Name: cxd56_sdio_clock_enable
*
* Description:
*
****************************************************************************/
void cxd56_sdio_clock_enable(void);
/****************************************************************************
* Name: cxd56_sdio_clock_disable
*
* Description:
*
****************************************************************************/
void cxd56_sdio_clock_disable(void);
/****************************************************************************
* Name: cxd56_audio_clock_enable
*
* Description:
*
****************************************************************************/
void cxd56_audio_clock_enable(uint32_t clk, uint32_t div);
/****************************************************************************
* Name: cxd56_audio_clock_disable
*
* Description:
*
****************************************************************************/
void cxd56_audio_clock_disable(void);
/****************************************************************************
* Name: cxd56_audio_clock_is_enabled
*
* Description:
*
****************************************************************************/
bool cxd56_audio_clock_is_enabled(void);
/****************************************************************************
* Name: cxd56_spi_clock_enable
*
* Description:
* Enable SPI device clock.
*
****************************************************************************/
void cxd56_spi_clock_enable(int port);
/****************************************************************************
* Name: cxd56_spi_clock_disable
*
* Description:
* Disable SPI device clock.
*
****************************************************************************/
void cxd56_spi_clock_disable(int port);
/****************************************************************************
* Name: cxd56_spi_clock_gate_enable
*
* Description:
*
****************************************************************************/
void cxd56_spi_clock_gate_enable(int port);
/****************************************************************************
* Name: cxd56_spi_clock_gate_disable
*
* Description:
*
****************************************************************************/
void cxd56_spi_clock_gate_disable(int port);
/****************************************************************************
* Name: cxd56_spi_clock_gear_adjust
*
* Description:
*
****************************************************************************/
void cxd56_spi_clock_gear_adjust(int port, uint32_t maxfreq);
/****************************************************************************
* Name: cxd56_i2c0_clock_enable
*
* Description:
* Enable I2C device clock.
*
****************************************************************************/
void cxd56_i2c_clock_enable(int port);
/****************************************************************************
* Name: cxd56_i2c_clock_dsiable
*
* Description:
* Disable I2C device clock.
*
****************************************************************************/
void cxd56_i2c_clock_disable(int port);
/****************************************************************************
* Name: cxd56_i2c_clock_gate_enable
*
* Description:
*
****************************************************************************/
void cxd56_i2c_clock_gate_enable(int port);
/****************************************************************************
* Name: cxd56_i2c_clock_gate_disable
*
* Description:
*
****************************************************************************/
void cxd56_i2c_clock_gate_disable(int port);
/****************************************************************************
* Name: cxd56_scuseq_is_clock_enabled
*
* Description:
* Get whether Sensor Control Unit Sequencer clock is enabled or not
*
****************************************************************************/
bool cxd56_scuseq_clock_is_enabled(void);
/****************************************************************************
* Name: cxd56_scuseq_clock_enable
*
* Description:
* Enable Sensor Control Unit Sequencer clock.
*
****************************************************************************/
int cxd56_scuseq_clock_enable(void);
/****************************************************************************
* Name: cxd56_scuseq_release_reset
*
* Description:
* Release sequencer reset. This function must be call after
* cxd56_scuseq_clock_enable() and copy sequencer firmware.
*
****************************************************************************/
void cxd56_scuseq_release_reset(void);
/****************************************************************************
* Name: cxd56_scuseq_clock_dsiable
*
* Description:
* Disable Sensor Control Unit Sequencer clock.
*
****************************************************************************/
void cxd56_scuseq_clock_disable(void);
/****************************************************************************
* Name: cxd56_img_uart_clock_enable
*
* Description:
* Enable img uart clock.
*
****************************************************************************/
void cxd56_img_uart_clock_enable(void);
/****************************************************************************
* Name: cxd56_img_uart_clock_dsiable
*
* Description:
* Disable img uart clock.
*
****************************************************************************/
void cxd56_img_uart_clock_disable(void);
/****************************************************************************
* Name: cxd56_get_img_uart_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_img_uart_baseclock(void);
/****************************************************************************
* Name: cxd56_img_cisif_clock_enable
*
* Description:
* Enable cisif clock.
*
****************************************************************************/
void cxd56_img_cisif_clock_enable(void);
/****************************************************************************
* Name: cxd56_img_cisif_clock_dsiable
*
* Description:
* Disable cisif clock.
*
****************************************************************************/
void cxd56_img_cisif_clock_disable(void);
/****************************************************************************
* Name: cxd56_img_ge2d_clock_enable
*
* Description:
* Enable ge2d clock.
*
****************************************************************************/
void cxd56_img_ge2d_clock_enable(void);
/****************************************************************************
* Name: cxd56_img_ge2d_clock_dsiable
*
* Description:
* Disable ge2d clock.
*
****************************************************************************/
void cxd56_img_ge2d_clock_disable(void);
/****************************************************************************
* Name: cxd56_get_com_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_com_baseclock(void);
/****************************************************************************
* Name: cxd56_get_sdio_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_sdio_baseclock(void);
/****************************************************************************
* Name: cxd56_get_spi_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_spi_baseclock(int port);
/****************************************************************************
* Name: cxd56_get_i2c_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_i2c_baseclock(int port);
/****************************************************************************
* Name: cxd56_get_pwm_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_pwm_baseclock(void);
/****************************************************************************
* Name: cxd56_udmac_clock_enable
*
* Description:
*
****************************************************************************/
void cxd56_udmac_clock_enable(void);
/****************************************************************************
* Name: cxd56_udmac_clock_disable
*
* Description:
*
****************************************************************************/
void cxd56_udmac_clock_disable(void);
/****************************************************************************
* Name: cxd56_lpadc_clock_enable
*
* Description:
*
****************************************************************************/
void cxd56_lpadc_clock_enable(uint32_t div);
/****************************************************************************
* Name: cxd56_lpadc_clock_disable
*
* Description:
*
****************************************************************************/
void cxd56_lpadc_clock_disable(void);
/****************************************************************************
* Name: cxd56_hpadc_clock_enable
*
* Description:
*
****************************************************************************/
void cxd56_hpadc_clock_enable(uint32_t div);
/****************************************************************************
* Name: cxd56_hpadc_clock_disable
*
* Description:
*
****************************************************************************/
void cxd56_hpadc_clock_disable(void);
/****************************************************************************
* Name: cxd56_get_xosc_clock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_xosc_clock(void);
/****************************************************************************
* Name: cxd56_get_rcosc_clock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_rcosc_clock(void);
/****************************************************************************
* Name: cxd56_get_rtc_clock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_rtc_clock(void);
/****************************************************************************
* Name: cxd56_get_syspll_clock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_syspll_clock(void);
/****************************************************************************
* Name: cxd56_get_sys_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_sys_baseclock(void);
/****************************************************************************
* Name: cxd56_get_sys_ahb_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_sys_ahb_baseclock(void);
/****************************************************************************
* Name: cxd56_get_sys_apb_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_sys_apb_baseclock(void);
/****************************************************************************
* Name: cxd56_get_sys_sfc_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_sys_sfc_baseclock(void);
/****************************************************************************
* Name: cxd56_get_scu_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_scu_baseclock(void);
/****************************************************************************
* Name: cxd56_get_hpadc_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_hpadc_baseclock(void);
/****************************************************************************
* Name: cxd56_get_lpadc_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_lpadc_baseclock(void);
/****************************************************************************
* Name: cxd56_get_pmui2c_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_pmui2c_baseclock(void);
/****************************************************************************
* Name: cxd56_get_gps_cpu_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_gps_cpu_baseclock(void);
/****************************************************************************
* Name: cxd56_get_gps_ahb_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_gps_ahb_baseclock(void);
/****************************************************************************
* Name: cxd56_get_img_spi_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_img_spi_baseclock(void);
/****************************************************************************
* Name: cxd56_get_img_wspi_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_img_wspi_baseclock(void);
/****************************************************************************
* Name: cxd56_get_usb_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_usb_baseclock(void);
/****************************************************************************
* Name: cxd56_get_img_vsync_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_img_vsync_baseclock(void);
/****************************************************************************
* Name: cxd56_get_appsmp_baseclock
*
* Description:
*
****************************************************************************/
uint32_t cxd56_get_appsmp_baseclock(void);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_CLOCK_H */

View File

@ -0,0 +1,262 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_cpufifo.c
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <queue.h>
#include <debug.h>
#include <errno.h>
#include "up_arch.h"
#include "chip.h"
#include "hardware/cxd56_cpufifo.h"
#include "cxd56_cpufifo.h"
/****************************************************************************
* Private Definitions
****************************************************************************/
#ifdef CONFIG_CXD56_CPUFIFO_ENTRIES
#define NR_PUSHBUFENTRIES CONFIG_CXD56_CPUFIFO_ENTRIES
#else
#define NR_PUSHBUFENTRIES 8
#endif
#define MSGFROM(x) (((x)[0] >> 28) & 0xf)
/****************************************************************************
* Private Types
****************************************************************************/
struct cfpushdata_s
{
FAR sq_entry_t entry;
uint32_t data[2];
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static int cpufifo_txhandler(int irq, FAR void *context, FAR void *arg);
static int cpufifo_rxhandler(int irq, FAR void *context, FAR void *arg);
static int cpufifo_trypush(uint32_t data[2]);
static void cpufifo_reserve(uint32_t data[2]);
/****************************************************************************
* Private Data
****************************************************************************/
/* Only for SYS, GNSS CPUs */
static sq_queue_t g_pushqueue;
static sq_queue_t g_emptyqueue;
static struct cfpushdata_s g_pushbuffer[NR_PUSHBUFENTRIES];
static cpufifo_handler_t g_cfrxhandler;
/****************************************************************************
* Private Functions
****************************************************************************/
static int cpufifo_txhandler(int irq, FAR void *context, FAR void *arg)
{
FAR struct cfpushdata_s *pd;
pd = (FAR struct cfpushdata_s *)sq_remfirst(&g_pushqueue);
if (pd)
{
/* Ignore error because always FIFO is not full at here */
cpufifo_trypush(pd->data);
sq_addlast(&pd->entry, &g_emptyqueue);
}
if (sq_empty(&g_pushqueue))
{
up_disable_irq(CXD56_IRQ_FIFO_TO);
}
return OK;
}
static int cpufifo_rxhandler(int irq, FAR void *context, FAR void *arg)
{
uint32_t word[2] = {0};
int cpuid;
/* Drain from PULL FIFO. But not all data because this handler
* will be re-entered when data remaining in PULL FIFO.
*/
cxd56_cfpull(word);
cpuid = MSGFROM(word);
DEBUGASSERT(cpuid >= 0 && cpuid < 8);
if (g_cfrxhandler)
{
g_cfrxhandler(cpuid, word);
}
return OK;
}
static int cpufifo_trypush(uint32_t data[2])
{
if (getreg32(CXD56_FIF_PUSH_FULL))
{
return -1;
}
putreg32(data[0], CXD56_FIF_PUSH_WRD0);
putreg32(data[1], CXD56_FIF_PUSH_WRD1);
putreg32(1, CXD56_FIF_PUSH_CMP);
return OK;
}
static void cpufifo_reserve(uint32_t data[2])
{
FAR struct cfpushdata_s *pd;
pd = (FAR struct cfpushdata_s *)sq_remfirst(&g_emptyqueue);
/* This assertion indicate that need more sending buffer, it can be
* configured by CONFIG_CXD56_CPUFIFO_ENTRIES.
*/
ASSERT(pd);
pd->data[0] = data[0];
pd->data[1] = data[1];
sq_addlast(&pd->entry, &g_pushqueue);
}
/****************************************************************************
* Public Functions
****************************************************************************/
int cxd56_cfpush(uint32_t data[2])
{
irqstate_t flags;
int ret;
flags = enter_critical_section();
if (!sq_empty(&g_pushqueue))
{
cpufifo_reserve(data);
return OK;
}
ret = cpufifo_trypush(data);
if (ret < 0)
{
cpufifo_reserve(data);
up_enable_irq(CXD56_IRQ_FIFO_TO);
}
leave_critical_section(flags);
return OK;
}
int cxd56_cfpull(uint32_t data[2])
{
if (getreg32(CXD56_FIF_PULL_EMP))
{
return -1;
}
data[0] = getreg32(CXD56_FIF_PULL_WRD0);
data[1] = getreg32(CXD56_FIF_PULL_WRD1);
putreg32(1, CXD56_FIF_PULL_CMP);
return 0;
}
int cxd56_cfregrxhandler(cpufifo_handler_t handler)
{
irqstate_t flags;
int ret = OK;
flags = enter_critical_section();
if (g_cfrxhandler)
{
ret = -1;
}
else
{
g_cfrxhandler = handler;
}
leave_critical_section(flags);
return ret;
}
void cxd56_cfunregrxhandler(void)
{
irqstate_t flags;
flags = enter_critical_section();
g_cfrxhandler = NULL;
leave_critical_section(flags);
}
int cxd56_cfinitialize(void)
{
int i;
/* Setup IRQ handlers. Enable only FROM (RX) interrupt because TO (TX)
* interrupt for retry sending when FIFO is full.
*/
irq_attach(CXD56_IRQ_FIFO_FROM, cpufifo_rxhandler, NULL);
irq_attach(CXD56_IRQ_FIFO_TO, cpufifo_txhandler, NULL);
up_enable_irq(CXD56_IRQ_FIFO_FROM);
/* Initialize push buffer. */
sq_init(&g_pushqueue);
sq_init(&g_emptyqueue);
for (i = 0; i < NR_PUSHBUFENTRIES; i++)
{
sq_addlast((FAR sq_entry_t *)&g_pushbuffer[i], &g_emptyqueue);
}
/* Clear user defined receive handler. */
g_cfrxhandler = NULL;
return OK;
}

View File

@ -0,0 +1,62 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_cpufifo.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CXD56_CPUFIFO_H
#define __ARCH_ARM_SRC_CXD56XX_CXD56_CPUFIFO_H
#ifndef __ASSEMBLY__
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
typedef int (*cpufifo_handler_t)(int cpuid, uint32_t data[2]);
int cxd56_cfinitialize(void);
int cxd56_cfpush(uint32_t data[2]);
int cxd56_cfpull(uint32_t data[2]);
int cxd56_cfregrxhandler(cpufifo_handler_t handler);
void cxd56_cfunregrxhandler(void);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif
#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_CPUFIFO_H */

View File

@ -0,0 +1,299 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_gpio.c
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <errno.h>
#include <assert.h>
#include <debug.h>
#include "chip.h"
#include "up_arch.h"
#include "cxd56_pinconfig.h"
#include "cxd56_gpio.h"
#include "hardware/cxd5602_topreg.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* GPIO register Definitions */
#define GPIO_OUTPUT_EN_SHIFT (16)
#define GPIO_OUTPUT_EN_MASK (1u << GPIO_OUTPUT_EN_SHIFT)
#define GPIO_OUTPUT_ENABLE (0u << GPIO_OUTPUT_EN_SHIFT)
#define GPIO_OUTPUT_DISABLE (1u << GPIO_OUTPUT_EN_SHIFT)
#define GPIO_OUTPUT_ENABLED(v) (((v) & GPIO_OUTPUT_EN_MASK) == GPIO_OUTPUT_ENABLE)
#define GPIO_OUTPUT_SHIFT (8)
#define GPIO_OUTPUT_MASK (1u << GPIO_OUTPUT_SHIFT)
#define GPIO_OUTPUT_HIGH (1u << GPIO_OUTPUT_SHIFT)
#define GPIO_OUTPUT_LOW (0u << GPIO_OUTPUT_SHIFT)
#define GPIO_INPUT_SHIFT (0)
#define GPIO_INPUT_MASK (1u << GPIO_INPUT_SHIFT)
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
static uint32_t get_gpio_regaddr(uint32_t pin)
{
uint32_t base;
base = (pin < PIN_IS_CLK) ? 1 : 7;
return CXD56_TOPREG_GP_I2C4_BCK + ((pin - base) * 4);
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: cxd56_gpio_config
*
* Description:
* Configure a GPIO which input is enabled or not.
* Output is enabled when cxd56_gpio_write() is called.
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
****************************************************************************/
int cxd56_gpio_config(uint32_t pin, bool input_enable)
{
int ret = 0;
uint32_t pinconf;
uint32_t regaddr;
uint32_t ioreg;
uint32_t ioval;
DEBUGASSERT((PIN_I2C4_BCK <= pin) && (pin <= PIN_USB_VBUSINT));
DEBUGASSERT((pin <= PIN_GNSS_1PPS_OUT) || (PIN_SPI0_CS_X <= pin));
DEBUGASSERT((pin <= PIN_HIF_GPIO0) || (PIN_SEN_IRQ_IN <= pin));
DEBUGASSERT((pin <= PIN_PWM3) || (PIN_IS_CLK <= pin));
ioreg = CXD56_TOPREG_IO_RTC_CLK_IN + (pin * 4);
ioval = getreg32(ioreg);
if (input_enable)
{
pinconf = PINCONF_SET(pin, PINCONF_MODE0, PINCONF_INPUT_ENABLE,
ioval & PINCONF_DRIVE_MASK,
ioval & PINCONF_PULL_MASK);
}
else
{
pinconf = PINCONF_SET(pin, PINCONF_MODE0, PINCONF_INPUT_DISABLE,
ioval & PINCONF_DRIVE_MASK,
ioval & PINCONF_PULL_MASK);
}
ret = cxd56_pin_config(pinconf);
/* output disabled */
regaddr = get_gpio_regaddr(pin);
putreg32(GPIO_OUTPUT_DISABLE, regaddr);
return ret;
}
/****************************************************************************
* Name: cxd56_gpio_write
*
* Description:
* Write one or zero to the selected GPIO pin
*
* Returned Value:
* None
*
****************************************************************************/
void cxd56_gpio_write(uint32_t pin, bool value)
{
uint32_t regaddr;
uint32_t regval;
DEBUGASSERT((PIN_I2C4_BCK <= pin) && (pin <= PIN_USB_VBUSINT));
DEBUGASSERT((pin <= PIN_GNSS_1PPS_OUT) || (PIN_SPI0_CS_X <= pin));
DEBUGASSERT((pin <= PIN_HIF_GPIO0) || (PIN_SEN_IRQ_IN <= pin));
DEBUGASSERT((pin <= PIN_PWM3) || (PIN_IS_CLK <= pin));
regaddr = get_gpio_regaddr(pin);
if (value)
{
regval = GPIO_OUTPUT_ENABLE | GPIO_OUTPUT_HIGH;
}
else
{
regval = GPIO_OUTPUT_ENABLE | GPIO_OUTPUT_LOW;
}
putreg32(regval, regaddr);
}
/****************************************************************************
* Name: cxd56_gpio_write_hiz
*
* Description:
* Write HiZ to the selected opendrain GPIO pin
*
* Returned Value:
* None
*
****************************************************************************/
void cxd56_gpio_write_hiz(uint32_t pin)
{
uint32_t regaddr;
uint32_t regval;
DEBUGASSERT((PIN_I2C4_BCK <= pin) && (pin <= PIN_USB_VBUSINT));
DEBUGASSERT((pin <= PIN_GNSS_1PPS_OUT) || (PIN_SPI0_CS_X <= pin));
DEBUGASSERT((pin <= PIN_HIF_GPIO0) || (PIN_SEN_IRQ_IN <= pin));
DEBUGASSERT((pin <= PIN_PWM3) || (PIN_IS_CLK <= pin));
regaddr = get_gpio_regaddr(pin);
regval = GPIO_OUTPUT_DISABLE;
putreg32(regval, regaddr);
}
/****************************************************************************
* Name: cxd56_gpio_read
*
* Description:
* Read one or zero from the selected GPIO pin
*
* Returned Value:
* The boolean state of the input pin
*
****************************************************************************/
bool cxd56_gpio_read(uint32_t pin)
{
uint32_t regaddr;
uint32_t regval;
uint32_t shift;
uint32_t ioreg;
uint32_t ioval;
DEBUGASSERT((PIN_I2C4_BCK <= pin) && (pin <= PIN_USB_VBUSINT));
DEBUGASSERT((pin <= PIN_GNSS_1PPS_OUT) || (PIN_SPI0_CS_X <= pin));
DEBUGASSERT((pin <= PIN_HIF_GPIO0) || (PIN_SEN_IRQ_IN <= pin));
DEBUGASSERT((pin <= PIN_PWM3) || (PIN_IS_CLK <= pin));
regaddr = get_gpio_regaddr(pin);
regval = getreg32(regaddr);
ioreg = CXD56_TOPREG_IO_RTC_CLK_IN + (pin * 4);
ioval = getreg32(ioreg);
if (PINCONF_INPUT_ENABLED(ioval))
{
shift = GPIO_INPUT_SHIFT;
}
else if (GPIO_OUTPUT_ENABLED(regval))
{
shift = GPIO_OUTPUT_SHIFT;
}
else
{
shift = GPIO_INPUT_SHIFT;
}
return ((regval & (1 << shift)) != 0);
}
/********************************************************************************************
* Name: cxd56_gpio_status
*
* Description:
* Get a gpio status which input/output is enabled or not.
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
********************************************************************************************/
int cxd56_gpio_status(uint32_t pin, cxd56_gpio_status_t *stat)
{
uint32_t regaddr;
uint32_t regval;
uint32_t ioreg;
uint32_t ioval;
if ((pin < PIN_I2C4_BCK) ||
((PIN_GNSS_1PPS_OUT < pin) && (pin < PIN_SPI0_CS_X)) ||
((PIN_HIF_GPIO0 < pin) && (pin < PIN_SEN_IRQ_IN)) ||
((PIN_PWM3 < pin) && (pin < PIN_IS_CLK)) ||
(PIN_USB_VBUSINT < pin))
{
return -EINVAL;
}
ioreg = CXD56_TOPREG_IO_RTC_CLK_IN + (pin * 4);
ioval = getreg32(ioreg);
regaddr = get_gpio_regaddr(pin);
regval = getreg32(regaddr);
stat->input_en = PINCONF_INPUT_ENABLED(ioval);
stat->output_en = GPIO_OUTPUT_ENABLED(regval);
return 0;
}

View File

@ -0,0 +1,158 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_gpio.h
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CXD56_GPIO_H
#define __ARCH_ARM_SRC_CXD56XX_CXD56_GPIO_H
/********************************************************************************************
* Included Files
********************************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include "cxd56_pinconfig.h"
/********************************************************************************************
* Pre-processor Definitions
********************************************************************************************/
/********************************************************************************************
* Public Types
********************************************************************************************/
struct cxd56_gpio_status_s
{
bool input_en;
bool output_en;
};
typedef struct cxd56_gpio_status_s cxd56_gpio_status_t;
/********************************************************************************************
* Public Data
********************************************************************************************/
#ifndef __ASSEMBLY__
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/********************************************************************************************
* Public Functions
********************************************************************************************/
/********************************************************************************************
* Name: cxd56_gpio_config
*
* Description:
* Configure a GPIO which input is enabled or not.
* Output is enabled when cxd56_gpio_write() is called.
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
********************************************************************************************/
int cxd56_gpio_config(uint32_t pin, bool input_enable);
/********************************************************************************************
* Name: cxd56_gpio_write
*
* Description:
* Write one or zero to the selected GPIO pin
*
* Returned Value:
* None
*
********************************************************************************************/
void cxd56_gpio_write(uint32_t pin, bool value);
/********************************************************************************************
* Name: cxd56_gpio_write_hiz
*
* Description:
* Output HiZ to the selected opendrain GPIO pin
*
* Returned Value:
* None
*
********************************************************************************************/
void cxd56_gpio_write_hiz(uint32_t pin);
/********************************************************************************************
* Name: cxd56_gpio_read
*
* Description:
* Read one or zero from the selected GPIO pin
*
* Returned Value:
* The boolean state of the input pin
*
********************************************************************************************/
bool cxd56_gpio_read(uint32_t pin);
/********************************************************************************************
* Name: cxd56_gpio_status
*
* Description:
* Get a gpio status which input/output is enabled or not.
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
********************************************************************************************/
int cxd56_gpio_status(uint32_t pin, cxd56_gpio_status_t *stat);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_GPIO_H */

View File

@ -0,0 +1,657 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_gpioint.c
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <arch/board/board.h>
#include <nuttx/config.h>
#include <errno.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include "up_arch.h"
#include "chip.h"
#include "cxd56_pinconfig.h"
#include "cxd56_gpio.h"
#include "cxd56_gpioint.h"
#include "hardware/cxd5602_topreg.h"
#ifdef CONFIG_CXD56_GPIO_IRQ
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* GPIO Interrupt Polarity Definitions */
#define GPIOINT_POLARITY_SHIFT (0)
#define GPIOINT_POLARITY_MASK (7)
#define GPIOINT_GET_POLARITY(v) (((v) & GPIOINT_POLARITY_MASK) >> GPIOINT_POLARITY_SHIFT)
#define GPIOINT_SET_POLARITY(v) (((v) << GPIOINT_POLARITY_SHIFT) & GPIOINT_POLARITY_MASK)
#define GPIOINT_IS_LEVEL(v) (GPIOINT_GET_POLARITY(v) <= GPIOINT_LEVEL_LOW)
#define GPIOINT_IS_EDGE(v) (GPIOINT_EDGE_RISE <= GPIOINT_GET_POLARITY(v))
#define GPIOINT_IS_HIGH(v) ((GPIOINT_LEVEL_HIGH == GPIOINT_GET_POLARITY(v)) || \
(GPIOINT_EDGE_RISE == GPIOINT_GET_POLARITY(v)))
#define GPIOINT_IS_LOW(v) ((GPIOINT_LEVEL_LOW == GPIOINT_GET_POLARITY(v)) || \
(GPIOINT_EDGE_FALL == GPIOINT_GET_POLARITY(v)))
/* GPIO Interrupt Noise Filter Definitions */
#define GPIOINT_NOISE_FILTER_SHIFT (3)
#define GPIOINT_NOISE_FILTER_MASK (1u << GPIOINT_NOISE_FILTER_SHIFT)
#define GPIOINT_NOISE_FILTER_ENABLED(v) (((v) & GPIOINT_NOISE_FILTER_MASK) \
== GPIOINT_NOISE_FILTER_ENABLE)
/* Use Pseudo Edge Interrupt */
#define GPIOINT_TOGGLE_MODE_SHIFT (16)
/* GPIO Interrupt Index Number Definitions */
#define MAX_SLOT (12)
#define MAX_SYS_SLOT (6)
#define INTSEL_DEFAULT_VAL (63)
#define GET_SLOT2IRQ(slot) (CXD56_IRQ_EXDEVICE_0 + (slot))
#define GET_IRQ2SLOT(irq) ((irq) - CXD56_IRQ_EXDEVICE_0)
/* PMU_WAKE_TRIG_CPUINTSELx */
#define INT_ROUTE_THROUGH (0)
#define INT_ROUTE_INVERTER (1)
#define INT_ROUTE_PMU (2)
#define INT_ROUTE_PMU_LATCH (3)
#define CXD56_INTC_ENABLE (CXD56_INTC_BASE + 0x10)
#define CXD56_INTC_INVERT (CXD56_INTC_BASE + 0x20)
/****************************************************************************
* Private Data
****************************************************************************/
static xcpt_t g_isr[MAX_SLOT];
static uint32_t g_bothedge = 0;
/****************************************************************************
* Private Functions
****************************************************************************/
/* allocate/deallocate/get slot number (SYS: 0~5, APP: 6~11) */
static int alloc_slot(int pin, bool isalloc)
{
irqstate_t flags;
int alloc = -1;
int slot;
uint8_t val;
uint32_t base = (pin < PIN_IS_CLK) ? CXD56_TOPREG_IOCSYS_INTSEL0
: CXD56_TOPREG_IOCAPP_INTSEL0;
int offset = (pin < PIN_IS_CLK) ? 1 : 56;
flags = enter_critical_section();
for (slot = 0; slot < MAX_SYS_SLOT; slot++)
{
val = getreg8(base + slot);
if ((pin - offset) == val)
{
if (isalloc == false)
{
putreg8(INTSEL_DEFAULT_VAL, base + slot);
}
break; /* already used */
}
if ((-1 == alloc) && (INTSEL_DEFAULT_VAL == val))
{
alloc = slot;
}
}
if (slot == MAX_SYS_SLOT)
{
if (isalloc && (-1 != alloc))
{
slot = alloc;
putreg8(pin - offset, base + slot);
}
else
{
leave_critical_section(flags);
return -ENXIO; /* no space */
}
}
leave_critical_section(flags);
if (PIN_IS_CLK <= pin)
{
slot += MAX_SYS_SLOT;
}
return slot;
}
/* convert from slot to pin */
static int get_slot2pin(int slot)
{
uint32_t base = (slot < MAX_SYS_SLOT) ? CXD56_TOPREG_IOCSYS_INTSEL0
: CXD56_TOPREG_IOCAPP_INTSEL0;
int offset = 1;
if (MAX_SYS_SLOT <= slot)
{
slot -= MAX_SYS_SLOT;
offset = 56;
}
return (int)getreg8(base + slot) + offset;
}
/* convert from pin to slot number (SYS: 0~5, APP: 6~11) */
static int get_pin2slot(int pin)
{
int slot;
uint32_t base = (pin < PIN_IS_CLK) ? CXD56_TOPREG_IOCSYS_INTSEL0
: CXD56_TOPREG_IOCAPP_INTSEL0;
int offset = (pin < PIN_IS_CLK) ? 1 : 56;
for (slot = 0; slot < MAX_SYS_SLOT; slot++)
{
if ((pin - offset) == getreg8(base + slot)) /* byte access */
{
break;
}
}
if (slot == MAX_SYS_SLOT)
{
return -1;
}
if (PIN_IS_CLK <= pin)
{
slot += MAX_SYS_SLOT;
}
return slot;
}
/* convert from pin to irq number */
static int get_pin2irq(int pin)
{
int slot = get_pin2slot(pin);
if ((0 <= slot) && (slot < MAX_SLOT))
{
return GET_SLOT2IRQ(slot);
}
else
{
return -1;
}
}
/* set GPIO interrupt configuration registers */
static int set_gpioint_config(int slot, uint32_t gpiocfg)
{
uint32_t val;
uint32_t shift;
uint32_t polreg = CXD56_TOPREG_PMU_WAKE_TRIG_INTDET0;
uint32_t selreg = CXD56_TOPREG_PMU_WAKE_TRIG_CPUINTSEL0;
/* Configure the noise filter */
val = getreg32(CXD56_TOPREG_PMU_WAKE_TRIG_NOISECUTEN0);
if (GPIOINT_NOISE_FILTER_ENABLED(gpiocfg))
{
val |= (1 << (slot + 16));
}
else
{
val &= ~(1 << (slot + 16));
}
putreg32(val, CXD56_TOPREG_PMU_WAKE_TRIG_NOISECUTEN0);
/* Configure the polarity */
shift = 16 + (slot * 4);
if (32 <= shift)
{
polreg = CXD56_TOPREG_PMU_WAKE_TRIG_INTDET1;
selreg = CXD56_TOPREG_PMU_WAKE_TRIG_CPUINTSEL1;
shift -= 32;
}
val = getreg32(polreg);
val &= ~(0x7 << shift);
val |= (GPIOINT_GET_POLARITY(gpiocfg) << shift);
putreg32(val, polreg);
/* Configure the interrupt route */
val = getreg32(selreg);
val &= ~(0x7 << shift);
switch (GPIOINT_GET_POLARITY(gpiocfg))
{
case GPIOINT_LEVEL_HIGH:
if (GPIOINT_NOISE_FILTER_ENABLED(gpiocfg))
{
val |= (INT_ROUTE_PMU << shift);
}
else
{
val |= (INT_ROUTE_THROUGH << shift);
}
break;
case GPIOINT_LEVEL_LOW:
if (GPIOINT_NOISE_FILTER_ENABLED(gpiocfg))
{
val |= (INT_ROUTE_PMU << shift);
}
else
{
val |= (INT_ROUTE_INVERTER << shift);
}
break;
case GPIOINT_EDGE_RISE:
case GPIOINT_EDGE_FALL:
case GPIOINT_EDGE_BOTH:
val |= (INT_ROUTE_PMU_LATCH << shift);
break;
default:
DEBUGASSERT(0);
break;
}
putreg32(val, selreg);
return 0;
}
/* Invert interrupt polarity in INTC */
static void invert_irq(int irq)
{
irqstate_t flags;
uint32_t val;
flags = enter_critical_section();
val = getreg32(CXD56_INTC_INVERT);
val ^= (1 << (irq - CXD56_IRQ_EXTINT));
putreg32(val, CXD56_INTC_INVERT);
leave_critical_section(flags);
}
static bool inverted_irq(int irq)
{
uint32_t val;
val = getreg32(CXD56_INTC_INVERT);
return ((val & (1 << (irq - CXD56_IRQ_EXTINT))) != 0);
}
static bool enabled_irq(int irq)
{
uint32_t val;
val = getreg32(CXD56_INTC_ENABLE);
return ((val & (1 << (irq - CXD56_IRQ_EXTINT))) != 0);
}
static int gpioint_handler(int irq, FAR void *context, FAR void *arg)
{
uint32_t val;
uint32_t shift;
uint32_t polreg = CXD56_TOPREG_PMU_WAKE_TRIG_INTDET0;
int slot = GET_IRQ2SLOT(irq);
/* Invert mask of interrupt to be disable temporarily */
invert_irq(irq);
if (g_bothedge & (1 << slot))
{
g_isr[slot](irq, context, arg);
return 0;
}
/* Get the polarity */
shift = 16 + (slot * 4);
if (32 <= shift)
{
polreg = CXD56_TOPREG_PMU_WAKE_TRIG_INTDET1;
shift -= 32;
}
val = getreg32(polreg);
val = (val >> shift) & 0x7;
if (inverted_irq(irq))
{
/* Clear edge interrupt */
if (GPIOINT_IS_EDGE(val))
{
/* TBD: ignore access protection */
putreg32(1 << (slot + 16), CXD56_TOPREG_PMU_WAKE_TRIG0_CLR);
}
g_isr[slot](irq, context, arg);
}
return 0;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: cxd56_gpioint_config
*
* Description:
* Configure a GPIO pin as an GPIO pin interrupt source
*
* Input Parameters:
* pin - Pin number defined in cxd56_pinconfig.h
* gpiocfg - GPIO Interrupt Polarity and Noise Filter Configuration Value
* isr - Interrupt handler. If isr is NULL, then free an allocated handler.
*
* Returned Value:
* IRQ number on success; a negated errno value on failure.
*
* Assumptions:
* The interrupt are disabled so that read-modify-write operations are safe.
*
****************************************************************************/
int cxd56_gpioint_config(uint32_t pin, uint32_t gpiocfg, xcpt_t isr)
{
int slot;
int irq;
irqstate_t flags;
slot = alloc_slot(pin, (isr != NULL));
if (slot < 0)
{
return -ENXIO;
}
irq = GET_SLOT2IRQ(slot);
if (isr == NULL)
{
/* disable GPIO input */
cxd56_gpio_config(pin, false);
/* disable interrupt */
irq_attach(irq, NULL, NULL);
g_isr[slot] = NULL;
flags = enter_critical_section();
g_bothedge &= ~(1 << slot);
leave_critical_section(flags);
return irq;
}
/* enable GPIO input */
cxd56_gpio_config(pin, true);
/* set GPIO interrupt configuration */
if (gpiocfg & GPIOINT_TOGGLE_BOTH_MASK) {
/* set GPIO pseudo both edge interrupt */
flags = enter_critical_section();
g_bothedge |= (1 << slot);
leave_critical_section(flags);
/* detect the change from the current signal */
if (true == cxd56_gpio_read(pin)) {
gpiocfg |= GPIOINT_SET_POLARITY(GPIOINT_LEVEL_LOW);
} else {
gpiocfg |= GPIOINT_SET_POLARITY(GPIOINT_LEVEL_HIGH);
}
}
set_gpioint_config(slot, gpiocfg);
if ((gpiocfg & GPIOINT_TOGGLE_MODE_MASK) || GPIOINT_IS_EDGE(gpiocfg))
{
irq_attach(irq, gpioint_handler, (void *)pin); /* call intermediate handler */
g_isr[slot] = isr;
}
else
{
irq_attach(irq, isr, (void *)pin); /* call user handler directly */
g_isr[slot] = NULL;
}
return irq;
}
/****************************************************************************
* Name: cxd56_gpioint_irq
*
* Description:
* Get a GPIO interrupt number for specified pin number
*
* Returned Value:
* IRQ number on success; a negated errno value on failure.
*
****************************************************************************/
int cxd56_gpioint_irq(uint32_t pin)
{
return get_pin2irq(pin);
}
/****************************************************************************
* Name: cxd56_gpioint_pin
*
* Description:
* Get a pin number for specified IRQ number
*
* Returned Value:
* Pin number on success; a negated errno value on failure.
*
****************************************************************************/
int cxd56_gpioint_pin(int irq)
{
int slot;
if ((irq < CXD56_IRQ_EXDEVICE_0) || (CXD56_IRQ_EXDEVICE_11 < irq))
{
return -1;
}
slot = GET_IRQ2SLOT(irq);
return get_slot2pin(slot);
}
/****************************************************************************
* Name: cxd56_gpioint_enable
*
* Description:
* Enable a GPIO interrupt for specified pin number
*
* Returned Value:
* None
*
****************************************************************************/
void cxd56_gpioint_enable(uint32_t pin)
{
int irq = get_pin2irq(pin);
if (irq > 0)
{
up_enable_irq(irq);
}
}
/****************************************************************************
* Name: cxd56_gpioint_disable
*
* Description:
* Disable a GPIO interrupt for specified pin number
*
* Returned Value:
* None
*
****************************************************************************/
void cxd56_gpioint_disable(uint32_t pin)
{
int irq = get_pin2irq(pin);
if (irq > 0)
{
up_disable_irq(irq);
}
}
/****************************************************************************
* Name: cxd56_gpioint_invert
*
* Description:
* Invert polarity of a GPIO interrupt for specified pin number
*
* Returned Value:
* None
*
****************************************************************************/
void cxd56_gpioint_invert(uint32_t pin)
{
int irq = get_pin2irq(pin);
if (irq > 0)
{
invert_irq(irq);
}
}
/****************************************************************************
* Name: cxd56_gpioint_status
*
* Description:
* Get a gpio interrupt status
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
****************************************************************************/
int cxd56_gpioint_status(uint32_t pin, cxd56_gpioint_status_t *stat)
{
uint32_t val;
uint32_t shift;
uint32_t polreg = CXD56_TOPREG_PMU_WAKE_TRIG_INTDET0;
int slot;
DEBUGASSERT(stat);
/* Get IRQ number */
stat->irq = cxd56_gpioint_irq(pin);
if (stat->irq < 0)
{
return -EINVAL;
}
/* Get polarity */
slot = GET_IRQ2SLOT(stat->irq);
shift = 16 + (slot * 4);
if (32 <= shift)
{
polreg = CXD56_TOPREG_PMU_WAKE_TRIG_INTDET1;
shift -= 32;
}
val = getreg32(polreg);
stat->polarity = GPIOINT_GET_POLARITY(val >> shift);
/* Replace for pseudo edge */
if ((g_isr[slot]) && (stat->polarity == GPIOINT_LEVEL_HIGH))
{
stat->polarity = GPIOINT_EDGE_RISE;
}
if ((g_isr[slot]) && (stat->polarity == GPIOINT_LEVEL_LOW))
{
stat->polarity = GPIOINT_EDGE_FALL;
}
if ((g_isr[slot]) && (g_bothedge & (1 << slot)))
{
stat->polarity = GPIOINT_EDGE_BOTH;
}
/* Get noise filter enabled or not */
val = getreg32(CXD56_TOPREG_PMU_WAKE_TRIG_NOISECUTEN0);
stat->filter = ((val >> (slot + 16)) & 1) ? true : false;
/* Get interrupt enabled or not */
stat->enable = enabled_irq(stat->irq);
return OK;
}
#endif /* CONFIG_CXD56_GPIO_IRQ */

View File

@ -0,0 +1,233 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_gpioint.h
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CXD56_GPIOINT_H
#define __ARCH_ARM_SRC_CXD56XX_CXD56_GPIOINT_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
#ifdef CONFIG_CXD56_GPIO_IRQ
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* 32-bit encoded gpioconf value
*
* 3322 2222 2222 1111 1111 1100 0000 0000
* 1098 7654 3210 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ---- ---- ---- ----
* .... .... .... ..B. .... .... .... .... Both detect mode
* .... .... .... ...T .... .... .... .... Toggle detect mode
* .... .... .... .... .... .... .... N... Noise Filter
* .... .... .... .... .... .... .... .YYY Polarity
*/
/* GPIO Interrupt Polarity Definitions */
//#define GPIOINT_INSTANT_HIGH (0) /* Not supported */
//#define GPIOINT_INSTANT_LOW (1) /* Not supported */
#define GPIOINT_LEVEL_HIGH (2) /* High Level */
#define GPIOINT_LEVEL_LOW (3) /* Low Level */
#define GPIOINT_EDGE_RISE (4) /* Rising Edge */
#define GPIOINT_EDGE_FALL (5) /* Falling Edge */
#define GPIOINT_EDGE_BOTH (7) /* Both Edge */
#define GPIOINT_PSEUDO_EDGE_RISE (GPIOINT_LEVEL_HIGH | \
GPIOINT_TOGGLE_MODE_MASK)
/* Rising Edge without clear */
#define GPIOINT_PSEUDO_EDGE_FALL (GPIOINT_LEVEL_LOW | \
GPIOINT_TOGGLE_MODE_MASK)
/* Falling Edge without clear */
#define GPIOINT_PSEUDO_EDGE_BOTH (GPIOINT_TOGGLE_MODE_MASK | \
GPIOINT_TOGGLE_BOTH_MASK)
/* Both Edge without clear */
/* GPIO Interrupt Noise Filter Definitions */
#define GPIOINT_NOISE_FILTER_ENABLE (1u << 3)
#define GPIOINT_NOISE_FILTER_DISABLE (0u << 3)
/* Use Pseudo Edge Interrupt */
#define GPIOINT_TOGGLE_MODE_MASK (1u << 16)
#define GPIOINT_TOGGLE_BOTH_MASK (1u << 17)
/****************************************************************************
* Public Types
****************************************************************************/
struct cxd56_gpioint_status_s
{
int irq;
uint32_t polarity;
bool filter;
bool enable;
};
typedef struct cxd56_gpioint_status_s cxd56_gpioint_status_t;
/****************************************************************************
* Public Data
****************************************************************************/
#ifndef __ASSEMBLY__
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: cxd56_gpioint_config
*
* Description:
* Configure a GPIO pin as an GPIO pin interrupt source
*
* Input Parameters:
* pin - Pin number defined in cxd56_pinconfig.h
* gpiocfg - GPIO Interrupt Polarity and Noise Filter Configuration Value
* isr - Interrupt handler
*
* Returned Value:
* IRQ number on success; a negated errno value on failure.
*
* Assumptions:
* The interrupt are disabled so that read-modify-write operations are safe.
*
****************************************************************************/
int cxd56_gpioint_config(uint32_t pin, uint32_t gpiocfg, xcpt_t isr);
/****************************************************************************
* Name: cxd56_gpioint_irq
*
* Description:
* Get a GPIO interrupt number for specified pin number
*
* Returned Value:
* IRQ number on success; a negated errno value on failure.
*
****************************************************************************/
int cxd56_gpioint_irq(uint32_t pin);
/****************************************************************************
* Name: cxd56_gpioint_pin
*
* Description:
* Get a pin number for specified IRQ number
*
* Returned Value:
* Pin number on success; a negated errno value on failure.
*
****************************************************************************/
int cxd56_gpioint_pin(int irq);
/****************************************************************************
* Name: cxd56_gpioint_enable
*
* Description:
* Enable a GPIO interrupt for specified pin number
*
* Returned Value:
* None
*
****************************************************************************/
void cxd56_gpioint_enable(uint32_t pin);
/****************************************************************************
* Name: cxd56_gpioint_disable
*
* Description:
* Disable a GPIO interrupt for specified pin number
*
* Returned Value:
* None
*
****************************************************************************/
void cxd56_gpioint_disable(uint32_t pin);
/****************************************************************************
* Name: cxd56_gpioint_invert
*
* Description:
* Invert polarity of a GPIO interrupt for specified pin number
*
* Returned Value:
* None
*
****************************************************************************/
void cxd56_gpioint_invert(uint32_t pin);
/********************************************************************************************
* Name: cxd56_gpioint_status
*
* Description:
* Get a gpio interrupt status
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
********************************************************************************************/
int cxd56_gpioint_status(uint32_t pin, cxd56_gpioint_status_t *stat);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* CONFIG_CXD56_GPIO_IRQ */
#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_GPIOINT_H */

View File

@ -0,0 +1,653 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_icc.c
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
#include <nuttx/irq.h>
#include <queue.h>
#include <semaphore.h>
#include <stdio.h>
#include <stdint.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include "up_arch.h"
#include "chip.h"
#include "cxd56_cpufifo.h"
#include "cxd56_icc.h"
#ifdef CONFIG_CXD56_ICC
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifndef CONFIG_CXD56_CPUFIFO_NBUFFERS
# define NBUFFERS 4
#else
# define NBUFFERS CONFIG_CXD56_CPUFIFO_NBUFFERS
#endif
#define NPROTOCOLS 16
#define GET_PROTOCOLID(w) (((w)[0] >> 24) & 0xf)
#define NCPUS 8
#define FLAG_TIMEOUT (1 << 0)
#define IS_SIGNAL(w) (((((w)[0]) >> 24) & 0xf) == CXD56_PROTO_SIG)
#ifdef CONFIG_CXD56_ICC_DEBUG
# define iccerr(fmt, ...) _err(fmt, ##__VA_ARGS__)
# define iccinfo(fmt, ...) _info(fmt, ##__VA_ARGS__)
#else
# define iccerr(fmt, ...)
# define iccinfo(fmt, ...)
#endif
/****************************************************************************
* Private Types
****************************************************************************/
struct iccmsg_msg_s
{
/* Little endian */
uint16_t pdata;
uint8_t msgid;
uint8_t proto: 4;
uint8_t cpuid: 4;
uint32_t data;
};
struct iccreq_s
{
sq_entry_t entry;
union
{
uint32_t word[2];
struct iccmsg_msg_s msg;
};
};
struct iccdev_s
{
union
{
cxd56_icchandler_t handler;
cxd56_iccsighandler_t sighandler;
} u;
FAR void *userdata;
sem_t rxwait;
WDOG_ID rxtimeout;
int flags;
/* for POSIX signal */
int signo;
int pid;
FAR void *sigdata;
struct sq_queue_s recvq;
struct sq_queue_s freelist;
struct iccreq_s pool[NBUFFERS];
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static int icc_sighandler(int cpuid, int protoid, uint32_t pdata,
uint32_t data, FAR void *userdata);
static int icc_msghandler(int cpuid, int protoid, uint32_t pdata,
uint32_t data, FAR void *userdata);
static int icc_irqhandler(int cpuid, uint32_t word[2]);
/****************************************************************************
* Private Data
****************************************************************************/
static struct iccdev_s *g_protocol[NPROTOCOLS];
static struct iccdev_s *g_cpumsg[NCPUS];
/****************************************************************************
* Private Functions
****************************************************************************/
static void icc_semtake(sem_t *semid)
{
while (sem_wait(semid) != 0)
{
ASSERT(errno == EINTR);
}
}
static void icc_semgive(sem_t *semid)
{
sem_post(semid);
}
static FAR struct iccdev_s *icc_getprotocol(int protoid)
{
if (protoid < 0 || protoid >= NPROTOCOLS)
{
return NULL;
}
return g_protocol[protoid];
}
static FAR struct iccdev_s *icc_getcpu(int cpuid)
{
if (cpuid < 0 || cpuid >= NCPUS)
{
return NULL;
}
return g_cpumsg[cpuid];
}
static int icc_irqhandler(int cpuid, uint32_t word[2])
{
FAR struct iccdev_s *priv;
FAR struct iccreq_s *req;
int protoid;
protoid = GET_PROTOCOLID(word);
priv = icc_getprotocol(protoid);
if (!priv)
{
/* Nobody waits this message... */
iccerr("nobody waits %08x %08x\n", word[0], word[1]);
return OK;
}
/* If handler has been registered, then call it. */
if (priv->u.handler)
{
int ret;
ret = priv->u.handler(cpuid, protoid, word[0] & 0xffffff, word[1],
priv->userdata);
if (ret == OK)
{
return OK;
}
}
/* If MSG protocol, then replace priv to cpu ones. */
if (protoid == CXD56_PROTO_MSG)
{
priv = icc_getcpu(cpuid);
if (!priv)
{
iccerr("nobody waits from CPU %d\n", cpuid);
return OK;
}
}
req = (FAR struct iccreq_s *)sq_remfirst(&priv->freelist);
if (!req)
{
iccerr("Receive buffer is full.\n");
return -ENOMEM;
}
req->word[0] = word[0];
req->word[1] = word[1];
sq_addlast((FAR sq_entry_t *)req, &priv->recvq);
icc_semgive(&priv->rxwait);
/* If signal registered by cxd56_iccnotify(), then send POSIX signal to
* process.
*/
#ifndef CONFIG_DISABLE_SIGNAL
if (priv->pid != INVALID_PROCESS_ID)
{
# ifdef CONFIG_CAN_PASS_STRUCTS
union sigval value;
value.sival_ptr = priv->sigdata;
(void)sigqueue(priv->pid, priv->signo, value);
# else
(void)sigqueue(priv->pid, priv->signo, priv->sigdata);
# endif
}
#endif
return OK;
}
static int icc_sighandler(int cpuid, int protoid, uint32_t pdata,
uint32_t data, FAR void *userdata)
{
FAR struct iccdev_s *priv = icc_getcpu(cpuid);
if (!priv)
{
/* Nobody waits this message... */
iccerr("nobody waits %08x %08x\n", word[0], word[1]);
return OK;
}
iccinfo("Caught signal\n");
if (priv->u.sighandler)
{
int8_t signo;
uint16_t sigdata;
signo = (int8_t)((pdata >> 16) & 0xff);
sigdata = pdata & 0xffff;
iccinfo("Call signal handler with No %d.\n", signo);
priv->u.sighandler(signo, sigdata, data, priv->userdata);
}
return OK;
}
static int icc_msghandler(int cpuid, int protoid, uint32_t pdata,
uint32_t data, FAR void *userdata)
{
/* Do nothing. This handler used for reserve MSG protocol handler.
* This handler returns -1 to indicate not consumed the passed
* message.
*/
return -1;
}
static void icc_rxtimeout(int argc, uint32_t arg, ...)
{
FAR struct iccdev_s *priv = (FAR struct iccdev_s *)arg;
icc_semgive(&priv->rxwait);
}
static int icc_recv(FAR struct iccdev_s *priv, FAR iccmsg_t *msg, int32_t ms)
{
FAR struct iccreq_s *req;
irqstate_t flags;
int ret = OK;
if (ms)
{
int32_t timo;
timo = ms * 1000 / CONFIG_USEC_PER_TICK;
wd_start(priv->rxtimeout, timo, icc_rxtimeout, 1, (uint32_t)priv);
}
icc_semtake(&priv->rxwait);
wd_cancel(priv->rxtimeout);
flags = enter_critical_section();
req = (FAR struct iccreq_s *)sq_remfirst(&priv->recvq);
if (req)
{
msg->msgid = req->msg.msgid;
msg->data = req->msg.data;
msg->cpuid = req->msg.cpuid;
msg->protodata = req->msg.pdata;
sq_addlast((FAR sq_entry_t *)req, &priv->freelist);
}
else
{
ret = -ETIMEDOUT;
}
leave_critical_section(flags);
return ret;
}
static FAR struct iccdev_s *icc_devnew(void)
{
FAR struct iccdev_s *priv;
int i;
priv = (struct iccdev_s *)kmm_malloc(sizeof(struct iccdev_s));
if (!priv)
{
return NULL;
}
memset(priv, 0, sizeof(struct iccdev_s));
priv->rxtimeout = wd_create();
sem_init(&priv->rxwait, 0, 0);
/* Initialize receive queue and free list */
sq_init(&priv->recvq);
sq_init(&priv->freelist);
for (i = 0; i < NBUFFERS; i++)
{
sq_addlast((FAR sq_entry_t *)&priv->pool[i], &priv->freelist);
}
priv->pid = INVALID_PROCESS_ID;
return priv;
}
static void icc_devfree(FAR struct iccdev_s *priv)
{
wd_delete(priv->rxtimeout);
kmm_free(priv);
}
/****************************************************************************
* Public Functions
****************************************************************************/
int cxd56_iccregisterhandler(int protoid, cxd56_icchandler_t handler,
FAR void *data)
{
FAR struct iccdev_s *priv;
irqstate_t flags;
int ret = OK;
flags = enter_critical_section();
priv = icc_getprotocol(protoid);
if (priv)
{
priv->u.handler = handler;
priv->userdata = data;
}
else
{
ret = -EINVAL;
}
leave_critical_section(flags);
return ret;
}
int cxd56_iccregistersighandler(int cpuid, cxd56_iccsighandler_t handler,
FAR void *data)
{
FAR struct iccdev_s *priv;
irqstate_t flags;
int ret = OK;
flags = enter_critical_section();
priv = icc_getcpu(cpuid);
if (priv)
{
priv->u.sighandler = handler;
priv->userdata = data;
}
else
{
ret = -EINVAL;
}
leave_critical_section(flags);
return ret;
}
int cxd56_iccsend(int protoid, FAR iccmsg_t *msg, int32_t ms)
{
FAR struct iccdev_s *priv;
struct iccreq_s req;
if (!msg)
{
return -EINVAL;
}
priv = icc_getprotocol(protoid);
if (!priv)
{
return -EINVAL;
}
req.msg.cpuid = msg->cpuid;
req.msg.msgid = msg->msgid;
req.msg.data = msg->data;
req.msg.pdata = msg->protodata;
req.msg.proto = protoid;
priv->flags = 0;
return cxd56_cfpush(req.word);
}
int cxd56_iccsendmsg(FAR iccmsg_t *msg, int32_t ms)
{
return cxd56_iccsend(CXD56_PROTO_MSG, msg, ms);
}
int cxd56_iccrecv(int protoid, FAR iccmsg_t *msg, int32_t ms)
{
FAR struct iccdev_s *priv;
if (!msg)
{
return -EINVAL;
}
priv = icc_getprotocol(protoid);
if (!priv)
{
return -EINVAL;
}
return icc_recv(priv, msg, ms);
}
int cxd56_iccrecvmsg(FAR iccmsg_t *msg, int32_t ms)
{
FAR struct iccdev_s *priv;
if (!msg)
{
return -EINVAL;
}
priv = icc_getcpu(msg->cpuid);
if (!priv)
{
return -EINVAL;
}
return icc_recv(priv, msg, ms);
}
int cxd56_iccsignal(int8_t cpuid, int8_t signo, int16_t sigdata, uint32_t data)
{
struct iccreq_s req;
if (cpuid <= 2 && cpuid >= 7)
{
return -EINVAL;
}
req.msg.cpuid = cpuid;
req.msg.proto = CXD56_PROTO_SIG;
req.msg.msgid = signo;
req.msg.pdata = sigdata;
req.msg.data = data;
return cxd56_cfpush(req.word);
}
int cxd56_iccnotify(int cpuid, int signo, FAR void *sigdata)
{
FAR struct iccdev_s *priv;
priv = icc_getcpu(cpuid);
if (!priv)
{
return -ESRCH;
}
priv->pid = getpid();
priv->signo = signo;
priv->sigdata = sigdata;
return OK;
}
int cxd56_iccinit(int protoid)
{
FAR struct iccdev_s *priv;
if (protoid < 0 || protoid >= NPROTOCOLS)
{
return -EINVAL;
}
if (g_protocol[protoid])
{
return OK;
}
priv = icc_devnew();
if (!priv)
{
return -ENOMEM;
}
g_protocol[protoid] = priv;
return OK;
}
int cxd56_iccinitmsg(int cpuid)
{
FAR struct iccdev_s *priv;
if (cpuid < 0 || cpuid >= NCPUS)
{
return -EINVAL;
}
if (g_cpumsg[cpuid])
{
return OK;
}
priv = icc_devnew();
if (!priv)
{
return -ENOMEM;
}
g_cpumsg[cpuid] = priv;
return OK;
}
void cxd56_iccuninit(int protoid)
{
FAR struct iccdev_s *priv;
irqstate_t flags;
if (protoid < 0 || protoid >= NPROTOCOLS)
{
return;
}
flags = enter_critical_section();
priv = g_protocol[protoid];
if (priv)
{
icc_devfree(priv);
g_protocol[protoid] = NULL;
}
leave_critical_section(flags);
}
void cxd56_iccuninitmsg(int cpuid)
{
FAR struct iccdev_s *priv;
irqstate_t flags;
if (cpuid < 0 || cpuid >= NCPUS)
{
return;
}
flags = enter_critical_section();
priv = g_cpumsg[cpuid];
if (priv)
{
icc_devfree(priv);
g_cpumsg[cpuid] = NULL;
}
leave_critical_section(flags);
}
void cxd56_iccinitialize(void)
{
int i;
for (i = 0; i < NPROTOCOLS; i++)
{
g_protocol[i] = NULL;
}
for (i = 0; i < NCPUS; i++)
{
g_cpumsg[i] = NULL;
}
/* Protocol MSG and SIG is special, reserved by ICC driver. */
cxd56_iccinit(CXD56_PROTO_MSG);
cxd56_iccregisterhandler(CXD56_PROTO_MSG, icc_msghandler, NULL);
cxd56_iccinit(CXD56_PROTO_SIG);
cxd56_iccregisterhandler(CXD56_PROTO_SIG, icc_sighandler, NULL);
cxd56_cfregrxhandler(icc_irqhandler);
}
#endif

View File

@ -0,0 +1,101 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_icc.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CXD56_ICC_H
#define __ARCH_ARM_SRC_CXD56XX_CXD56_ICC_H
#define CXD56_PROTO_MSG 0 /* Generic message */
#define CXD56_PROTO_MBX 1
#define CXD56_PROTO_SEM 2
#define CXD56_PROTO_FLG 3
#define CXD56_PROTO_MPF 4
#define CXD56_PROTO_DBG 5
#define CXD56_PROTO_AUDIO 6
#define CXD56_PROTO_CALLBACK 7
#define CXD56_PROTO_HOTSLEEP 8
#define CXD56_PROTO_IMAGE 9
#define CXD56_PROTO_PM 10 /* Power manager */
#define CXD56_PROTO_SYSCTL 12
#define CXD56_PROTO_GNSS 13
#define CXD56_PROTO_SIG 15 /* Inter-CPU Comm signal */
typedef int (*cxd56_icchandler_t)(int cpuid, int protoid, uint32_t pdata,
uint32_t data, FAR void *userdata);
typedef int (*cxd56_iccsighandler_t)(int8_t signo, uint16_t sigdata,
uint32_t data, FAR void *userdata);
struct cxd56_iccmsg_s
{
int8_t cpuid;
int8_t msgid;
uint16_t protodata;
uint32_t data;
};
typedef struct cxd56_iccmsg_s iccmsg_t;
#ifndef __ASSEMBLY__
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
int cxd56_iccinit(int protoid);
int cxd56_iccinitmsg(int cpuid);
void cxd56_iccuninit(int protoid);
void cxd56_iccuninitmsg(int cpuid);
int cxd56_iccregisterhandler(int protoid, cxd56_icchandler_t handler,
FAR void *data);
int cxd56_iccregistersighandler(int cpuid, cxd56_iccsighandler_t handler,
FAR void *data);
int cxd56_iccsend(int protoid, FAR iccmsg_t *msg, int32_t ms);
int cxd56_iccrecv(int protoid, FAR iccmsg_t *msg, int32_t ms);
int cxd56_iccsendmsg(FAR iccmsg_t *msg, int32_t ms);
int cxd56_iccrecvmsg(FAR iccmsg_t *msg, int32_t ms);
int cxd56_iccsignal(int8_t cpuid, int8_t signo, int16_t sigdata,
uint32_t data);
int cxd56_iccnotify(int cpuid, int signo, FAR void *sigdata);
void cxd56_iccinitialize(void);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif
#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_ICC_H */

View File

@ -0,0 +1,462 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_pinconfig.c
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <errno.h>
#include <assert.h>
#include <debug.h>
#include "chip.h"
#include "up_arch.h"
#include "cxd56_pinconfig.h"
#include "hardware/cxd5602_topreg.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define GET_IOVAL_MASK(p) \
((p) & (PINCONF_DRIVE_MASK | PINCONF_PULL_MASK | PINCONF_IN_EN_MASK))
/* IOCSYS_IOMD0 */
#define GROUP_I2C4 (0)
#define GROUP_PMIC_INT (2)
#define GROUP_RTC_IRQ_OUT (4)
#define GROUP_AP_CLK (6)
#define GROUP_GNSS_1PPS_OUT (8)
#define GROUP_SPI0A (12)
#define GROUP_SPI0B (14)
#define GROUP_SPI1A (16)
#define GROUP_SPI1B (18)
#define GROUP_SPI2A (20)
#define GROUP_SPI2B (22)
#define GROUP_HIFIRQ (24)
#define GROUP_HIFEXT (26)
/* IOCSYS_IOMD1 */
#define GROUP_SEN_IRQ_IN (8)
#define GROUP_SPI3_CS0_X (10)
#define GROUP_SPI3_CS1_X (12)
#define GROUP_SPI3_CS2_X (14)
#define GROUP_SPI3 (16)
#define GROUP_I2C0 (18)
#define GROUP_PWMA (20)
#define GROUP_PWMB (22)
/* IOCAPP_IOMD */
#define GROUP_IS (0)
#define GROUP_UART2 (2)
#define GROUP_SPI4 (4)
#define GROUP_EMMCA (6)
#define GROUP_EMMCB (8)
#define GROUP_SDIOA (10)
#define GROUP_SDIOB (12)
#define GROUP_SDIOC (14)
#define GROUP_SDIOD (16)
#define GROUP_I2S0 (18)
#define GROUP_I2S1 (20)
#define GROUP_MCLK (22)
#define GROUP_PDM (24)
#define GROUP_USBVBUS (26)
/* DBG_HOSTIF_SEL */
#define LATCH_OFF (1ul << 0)
#define LATCH_OFF_MASK (1ul << 0)
/* SYSTEM_CONFIG */
#define SYSTEM_CONFIG_I2C (0)
#define SYSTEM_CONFIG_UART (1)
#define SYSTEM_CONFIG_SPI (2)
#define SYSTEM_CONFIG_MON (3)
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
static int get_mode_regaddr(uint32_t pin, uint32_t *addr, uint32_t *shift)
{
DEBUGASSERT(addr && shift);
if ((pin < PIN_I2C4_BCK) || (PIN_USB_VBUSINT < pin))
return -EINVAL;
if (pin <= PIN_HIF_GPIO0)
{
if (pin <= PIN_I2C4_BDT)
{
*shift = GROUP_I2C4;
}
else if (pin <= PIN_PMIC_INT)
{
*shift = GROUP_PMIC_INT;
}
else if (pin <= PIN_RTC_IRQ_OUT)
{
*shift = GROUP_RTC_IRQ_OUT;
}
else if (pin <= PIN_AP_CLK)
{
*shift = GROUP_AP_CLK;
}
else if (pin <= PIN_GNSS_1PPS_OUT)
{
*shift = GROUP_GNSS_1PPS_OUT;
}
else if (pin <= PIN_SPI0_SCK)
{
*shift = GROUP_SPI0A;
}
else if (pin <= PIN_SPI0_MISO)
{
*shift = GROUP_SPI0B;
}
else if (pin <= PIN_SPI1_IO1)
{
*shift = GROUP_SPI1A;
}
else if (pin <= PIN_SPI1_IO3)
{
*shift = GROUP_SPI1B;
}
else if (pin <= PIN_SPI2_SCK)
{
*shift = GROUP_SPI2A;
}
else if (pin <= PIN_SPI2_MISO)
{
*shift = GROUP_SPI2B;
}
else if (pin <= PIN_HIF_IRQ_OUT)
{
*shift = GROUP_HIFIRQ;
}
else
{
*shift = GROUP_HIFEXT;
}
*addr = CXD56_TOPREG_IOCSYS_IOMD0;
}
else if (pin <= PIN_PWM3)
{
if (pin <= PIN_SEN_IRQ_IN)
{
*shift = GROUP_SEN_IRQ_IN;
}
else if (pin <= PIN_SPI3_CS0_X)
{
*shift = GROUP_SPI3_CS0_X;
}
else if (pin <= PIN_SPI3_CS1_X)
{
*shift = GROUP_SPI3_CS1_X;
}
else if (pin <= PIN_SPI3_CS2_X)
{
*shift = GROUP_SPI3_CS2_X;
}
else if (pin <= PIN_SPI3_MISO)
{
*shift = GROUP_SPI3;
}
else if (pin <= PIN_I2C0_BDT)
{
*shift = GROUP_I2C0;
}
else if (pin <= PIN_PWM1)
{
*shift = GROUP_PWMA;
}
else
{
*shift = GROUP_PWMB;
}
*addr = CXD56_TOPREG_IOCSYS_IOMD1;
}
else
{
if (pin <= PIN_IS_DATA7)
{
*shift = GROUP_IS;
}
else if (pin <= PIN_UART2_RTS)
{
*shift = GROUP_UART2;
}
else if (pin <= PIN_SPI4_MISO)
{
*shift = GROUP_SPI4;
}
else if (pin <= PIN_EMMC_DATA1)
{
*shift = GROUP_EMMCA;
}
else if (pin <= PIN_EMMC_DATA3)
{
*shift = GROUP_EMMCB;
}
else if (pin <= PIN_SDIO_DATA3)
{
*shift = GROUP_SDIOA;
}
else if (pin <= PIN_SDIO_WP)
{
*shift = GROUP_SDIOB;
}
else if (pin <= PIN_SDIO_DIR1_3)
{
*shift = GROUP_SDIOC;
}
else if (pin <= PIN_SDIO_CLKI)
{
*shift = GROUP_SDIOD;
}
else if (pin <= PIN_I2S0_DATA_OUT)
{
*shift = GROUP_I2S0;
}
else if (pin <= PIN_I2S1_DATA_OUT)
{
*shift = GROUP_I2S1;
}
else if (pin <= PIN_MCLK)
{
*shift = GROUP_MCLK;
}
else if (pin <= PIN_PDM_OUT)
{
*shift = GROUP_PDM;
}
else
{
*shift = GROUP_USBVBUS;
}
*addr = CXD56_TOPREG_IOCAPP_IOMD;
}
return 0;
}
static void set_i2s_output_config(uint32_t pin, uint32_t mode, bool is_slave)
{
uint32_t mask =
(PIN_I2S0_BCK == pin) ? (I2S0_BCK | I2S0_LRCK) : (I2S1_BCK | I2S1_LRCK);
if (is_slave)
{
modifyreg32(CXD56_TOPREG_IOOEN_APP, 0, mask);
}
else
{
modifyreg32(CXD56_TOPREG_IOOEN_APP, mask, 0);
}
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: cxd56_pin_config
*
* Description:
* Configure a pin based on bit-encoded description of the pin.
*
* Input Value:
* 32-bit encoded value describing the pin.
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
****************************************************************************/
int cxd56_pin_config(uint32_t pinconf)
{
return cxd56_pin_configs(&pinconf, 1);
}
/****************************************************************************
* Name: cxd56_pin_configs
*
* Description:
* Configure multiple pins based on bit-encoded description of the pin.
*
* Input Value:
* pinconfs[] - Array of 32-bit encoded value describing the pin.
* n - The number of elements in the array.
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
****************************************************************************/
int cxd56_pin_configs(uint32_t pinconfs[], size_t n)
{
int ret = 0;
int i;
uint32_t pin;
uint32_t mode;
uint32_t ioreg;
uint32_t ioval;
uint32_t modereg;
uint32_t shift;
uint32_t oldreg = 0;
uint32_t oldshift = 0;
uint32_t latch_endpin = PIN_SPI2_SCK;
if (SYSTEM_CONFIG_SPI == getreg8(CXD56_TOPREG_SYSTEM_CONFIG))
{
latch_endpin = PIN_SPI2_MISO;
}
for (i = 0; i < n; i++)
{
pin = PINCONF_GET_PIN(pinconfs[i]);
mode = PINCONF_GET_MODE(pinconfs[i]);
ioval = GET_IOVAL_MASK(pinconfs[i]);
DEBUGASSERT((PIN_RTC_CLK_IN <= pin) && (pin <= PIN_USB_VBUSINT));
DEBUGASSERT((pin <= PIN_GNSS_1PPS_OUT) || (PIN_SPI0_CS_X <= pin));
DEBUGASSERT((pin <= PIN_HIF_GPIO0) || (PIN_SEN_IRQ_IN <= pin));
DEBUGASSERT((pin <= PIN_PWM3) || (PIN_IS_CLK <= pin));
/* Set HostIF latch off */
if (((PIN_SPI2_CS_X <= pin) && (pin <= latch_endpin)) &&
(PINCONF_MODE0 == mode))
{
modifyreg32(CXD56_TOPREG_DBG_HOSTIF_SEL, LATCH_OFF_MASK, LATCH_OFF);
}
/* Set IO cell register */
ioreg = CXD56_TOPREG_IO_RTC_CLK_IN + (pin * 4);
putreg32(ioval, ioreg);
/* Set i2s output register */
if (((PIN_I2S0_BCK == pin) || (PIN_I2S1_BCK == pin)) &&
(PINCONF_MODE1 == mode))
{
set_i2s_output_config(pin, mode, PINCONF_INPUT_ENABLED(pinconfs[i]));
}
ret = get_mode_regaddr(pin, &modereg, &shift);
if ((!ret) && ((oldreg != modereg) || (oldshift != shift)))
{
oldreg = modereg;
oldshift = shift;
/* Set alternative mode register */
modifyreg32(modereg, (0x3 << shift), (mode << shift));
}
}
return 0;
}
/********************************************************************************************
* Name: cxd56_pin_status
*
* Description:
* Get a pin status.
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
********************************************************************************************/
int cxd56_pin_status(uint32_t pin, cxd56_pin_status_t *stat)
{
int ret = 0;
uint32_t ioreg;
uint32_t ioval;
uint32_t modereg;
uint32_t modeval;
uint32_t shift;
DEBUGASSERT(stat);
stat->mode = -1;
stat->input_en = -1;
stat->drive = -1;
stat->pull = -1;
if (((PIN_GNSS_1PPS_OUT < pin) && (pin < PIN_SPI0_CS_X)) ||
((PIN_HIF_GPIO0 < pin) && (pin < PIN_SEN_IRQ_IN)) ||
((PIN_PWM3 < pin) && (pin < PIN_IS_CLK)) || (PIN_USB_VBUSINT < pin))
{
return -EINVAL;
}
ioreg = CXD56_TOPREG_IO_RTC_CLK_IN + (pin * 4);
ioval = getreg32(ioreg);
ret = get_mode_regaddr(pin, &modereg, &shift);
if (!ret)
{
modeval = getreg32(modereg);
modeval = (modeval >> shift) & 0x3;
stat->mode = modeval;
stat->input_en = (ioval & PINCONF_IN_EN_MASK);
stat->drive = (ioval & PINCONF_DRIVE_MASK);
stat->pull = (ioval & PINCONF_PULL_MASK);
}
return ret;
}

View File

@ -0,0 +1,226 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_pinconfig.h
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CXD56_PINCONFIG_H
#define __ARCH_ARM_SRC_CXD56XX_CXD56_PINCONFIG_H
/********************************************************************************************
* Included Files
********************************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <arch/chip/pin.h>
#include "hardware/cxd5602_pinconfig.h"
/********************************************************************************************
* Pre-processor Definitions
********************************************************************************************/
/* 32-bit encoded pinconf value
*
* 3322 2222 2222 1111 1111 1100 0000 0000
* 1098 7654 3210 9876 5432 1098 7654 3210
* ---- ---- ---- ---- ---- ---- ---- ----
* PPPP PPP. .... .... .... .... .... .... Pin number
* .... ...D .... .... .... .... .... .... Drive strength
* .... .... .... ...U .... ...U .... .... Pull-up/down/off
* .... .... .... .... .... .... .... ...I Input enable
* .... .... .... .... .... .... .... .MM. Alternate mode number
*/
/* Pin number Definitions */
#define PINCONF_PIN_SHIFT (25)
#define PINCONF_PIN_MASK (0x7Fu << PINCONF_PIN_SHIFT)
#define PINCONF_GET_PIN(p) (((p) & PINCONF_PIN_MASK) >> PINCONF_PIN_SHIFT)
#define PINCONF_SET_PIN(p) (((p) << PINCONF_PIN_SHIFT) & PINCONF_PIN_MASK)
/* Drive strength Definitions */
#define PINCONF_DRIVE_SHIFT (24)
#define PINCONF_DRIVE_MASK (1u << PINCONF_DRIVE_SHIFT)
#define PINCONF_DRIVE_NORMAL (1u << PINCONF_DRIVE_SHIFT) /* 2mA */
#define PINCONF_DRIVE_HIGH (0u << PINCONF_DRIVE_SHIFT) /* 4mA */
#define PINCONF_IS_DRIVE_NORM(p) (((p) & PINCONF_DRIVE_MASK) == PINCONF_DRIVE_NORMAL)
#define PINCONF_IS_DRIVE_HIGH(p) (((p) & PINCONF_DRIVE_MASK) == PINCONF_DRIVE_HIGH)
/* Pull-up/down/off Definitions */
#define PINCONF_PULL_MASK ((1u << 16) | (1u << 8))
#define PINCONF_FLOAT ((1u << 16) | (1u << 8))
#define PINCONF_PULLUP ((1u << 16) | (0u << 8))
#define PINCONF_PULLDOWN ((0u << 16) | (1u << 8))
#define PINCONF_BUSKEEPER ((0u << 16) | (0u << 8))
#define PINCONF_IS_FLOAT(p) (((p) & PINCONF_PULL_MASK) == PINCONF_FLOAT)
#define PINCONF_IS_PULLUP(p) (((p) & PINCONF_PULL_MASK) == PINCONF_PULLUP)
#define PINCONF_IS_PULLDOWN(p) (((p) & PINCONF_PULL_MASK) == PINCONF_PULLDOWN)
#define PINCONF_IS_BUSKEEPER(p) (((p) & PINCONF_PULL_MASK) == PINCONF_BUSKEEPER)
/* Input enable Definitions */
#define PINCONF_IN_EN_SHIFT (0)
#define PINCONF_IN_EN_MASK (1u << PINCONF_IN_EN_SHIFT)
#define PINCONF_INPUT_ENABLE (1u << PINCONF_IN_EN_SHIFT)
#define PINCONF_INPUT_DISABLE (0u << PINCONF_IN_EN_SHIFT)
#define PINCONF_INPUT_ENABLED(p) (((p) & PINCONF_IN_EN_MASK) == PINCONF_INPUT_ENABLE)
/* Alternate mode number Definitions */
#define PINCONF_MODE_SHIFT (1)
#define PINCONF_MODE_MASK (3u << PINCONF_MODE_SHIFT)
#define PINCONF_GET_MODE(p) (((p) & PINCONF_MODE_MASK) >> PINCONF_MODE_SHIFT)
#define PINCONF_SET_MODE(p) (((p) << PINCONF_MODE_SHIFT) & PINCONF_MODE_MASK)
#define PINCONF_MODE0 (0) /* GPIO */
#define PINCONF_MODE1 (1) /* Function */
#define PINCONF_MODE2 (2) /* Function */
#define PINCONF_MODE3 (3) /* Function */
/* Set pinconf macro Definitions */
#define PINCONF_SET(pin, mode, input, drive, pull) \
( \
(PINCONF_SET_PIN(pin)) | \
(PINCONF_SET_MODE(mode)) | \
(input) | (drive) | (pull) \
)
#define PINCONF_SET_GPIO(pin, input) \
PINCONF_SET((pin), PINCONF_MODE0, (input), PINCONF_DRIVE_NORMAL, PINCONF_FLOAT)
#define CXD56_PIN_CONFIGS(pin) do { \
uint32_t p[] = pin; \
cxd56_pin_configs((p), sizeof(p) / sizeof((p)[0])); \
} while (0)
/********************************************************************************************
* Public Types
********************************************************************************************/
struct cxd56_pin_status_s
{
uint32_t mode; /* alternate pin function mode */
uint32_t input_en; /* input enable or disable */
uint32_t drive; /* strength of drive current */
uint32_t pull; /* internal pull-up, pull-down, floating or buskeeper */
};
typedef struct cxd56_pin_status_s cxd56_pin_status_t;
/********************************************************************************************
* Public Data
********************************************************************************************/
#ifndef __ASSEMBLY__
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/********************************************************************************************
* Public Functions
********************************************************************************************/
/********************************************************************************************
* Name: cxd56_pin_config
*
* Description:
* Configure a pin based on bit-encoded description of the pin.
*
* Input Value:
* 32-bit encoded value describing the pin.
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
********************************************************************************************/
int cxd56_pin_config(uint32_t pinconf);
/********************************************************************************************
* Name: cxd56_pin_configs
*
* Description:
* Configure multiple pins based on bit-encoded description of the pin.
*
* Input Value:
* Array of 32-bit encoded value describing the pin.
* Number of elements in the array.
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
********************************************************************************************/
int cxd56_pin_configs(uint32_t pinconfs[], size_t n);
/********************************************************************************************
* Name: cxd56_pin_status
*
* Description:
* Get a pin status.
*
* Returned Value:
* OK on success; A negated errno value on failure.
*
********************************************************************************************/
int cxd56_pin_status(uint32_t pin, cxd56_pin_status_t *stat);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_PINCONFIG_H */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,761 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_pmic.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CXD56_PMIC_H
#define __ARCH_ARM_SRC_CXD56XX_CXD56_PMIC_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#ifdef CONFIG_CXD56_PMIC
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* PMIC Register Definitions */
#define PMIC_REG_DDC_ANA1 (0x26)
#define PMIC_REG_CNT_USB2 (0x81)
/* PMIC DDC_ANA1 Definitions */
#define PMIC_PM_HIZ (2u << 4)
#define PMIC_PM_DEF (0u << 4)
#define PMIC_IOST_DEF (2u << 2)
#define PMIC_IOMAX_DEF (2u << 0)
/* PMIC CNT_USB2 Definitions */
#define PMIC_SET_CHGOFF (1u << 2)
/* PMIC Interrupt Status Definitions */
#define PMIC_INT_ALARM (1u << 0)
#define PMIC_INT_WKUPS (1u << 1)
#define PMIC_INT_WKUPL (1u << 2)
#define PMIC_INT_VSYS (1u << 3)
/* PMIC GPO Channel Definitions */
#define PMIC_GPO0 (1u << 0)
#define PMIC_GPO1 (1u << 1)
#define PMIC_GPO2 (1u << 2)
#define PMIC_GPO3 (1u << 3)
#define PMIC_GPO4 (1u << 4)
#define PMIC_GPO5 (1u << 5)
#define PMIC_GPO6 (1u << 6)
#define PMIC_GPO7 (1u << 7)
/* PMIC LoadSwitch Channel Definitions */
#define PMIC_LOADSW2 (1u << 2)
#define PMIC_LOADSW3 (1u << 3)
#define PMIC_LOADSW4 (1u << 4)
/* PMIC DDC/LDO Channel Definitions */
#define PMIC_DDC_IO (1u << 0)
#define PMIC_LDO_EMMC (1u << 1)
#define PMIC_DDC_ANA (1u << 2)
#define PMIC_LDO_ANA (1u << 3)
#define PMIC_DDC_CORE (1u << 4)
#define PMIC_LDO_PERI (1u << 5)
/* Charge mode for both of low/high temperature */
#define PMIC_CHGMODE_ON 0x00
#define PMIC_CHGMODE_OFF 0x01
#define PMIC_CHGMODE_WEAK 0x02
/* Charge status */
#define PMIC_STAT_INIT_RST 0
#define PMIC_STAT_INIT_WAIT 1
#define PMIC_STAT_INIT_CHK 2
#define PMIC_STAT_DBP_START 3
#define PMIC_STAT_DB_INICHARGE 4
#define PMIC_STAT_DB_PRECHARGE 5
#define PMIC_STAT_DCON_WAIT 6
#define PMIC_STAT_PD_START 7
#define PMIC_STAT_DM_COMPARE 8
#define PMIC_STAT_PD_END 9
#define PMIC_STAT_BAT_WAIT 10
#define PMIC_STAT_CHG_STOP 11
#define PMIC_STAT_GB_PRECHARGE 12
#define PMIC_STAT_GB_QCKCHARGE 13
#define PMIC_STAT_GB_LOWCHARGE 14
#define PMIC_STAT_GB_HIGHCHARGE 15
#define PMIC_STAT_CHG_JUDGE 16
#define PMIC_STAT_CHG_COMPLETE 17
#define PMIC_STAT_GB_CONWAIT 18
#define PMIC_STAT_GB_CPTEMPWAIT1 19
#define PMIC_STAT_GB_CPTEMPWAIT2 20
#define PMIC_STAT_GB_TEMPWAIT 21
#define PMIC_STAT_DB_TEMPWAIT 22
#define PMIC_STAT_DB_CONWAIT 23
#define PMIC_STAT_BAT_UNUSUAL 24
#define PMIC_STAT_BAT_DISCON 25
/****************************************************************************
* Public Types
****************************************************************************/
struct pmic_gauge_s
{
int voltage;
int current;
int temp;
};
struct pmic_temp_table_s
{
int T60;
int T45;
int T10;
int T00;
};
struct pmic_mon_s
{
int on;
int interval;
int threshold_volt;
int threshold_current;
};
struct pmic_mon_status_s
{
int bRun;
int index;
int latest;
int total_watt;
int total_time;
};
struct pmic_mon_set_s
{
int clearBuf;
int clearSum;
};
struct pmic_mon_rec_s
{
uint16_t index;
uint16_t timestamp;
uint16_t voltage;
int16_t current;
};
struct pmic_mon_log_s
{
FAR struct pmic_monitor_rec_s *rec;
int index;
int size;
};
/****************************************************************************
* Public Data
****************************************************************************/
#ifndef __ASSEMBLY__
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: cxd56_pmic_get_interrupt_status
*
* Description:
* Get Raw Interrupt Status register. And furthermore, if status is set,
* then clear the interrupt. Register's decription is below:
*
* 7 6 5 4 3 2 1 0
* +---------------+-----+-----+-----+-----+
* | x x x x |VSYS |WKUPL|WKUPS|ALARM| target of status
* +---------------+-----+-----+-----+-----+
*
* Input Parameter:
* status - a pointer to the polled value of interrupt status
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
* status - return the value of interrupt status register
*
****************************************************************************/
int cxd56_pmic_get_interrupt_status(FAR uint8_t *status);
/****************************************************************************
* Name: cxd56_pmic_set_gpo_reg
*
* Description:
* Set GPO register. Register's decription is below:
*
* 7 6 5 4 3 2 1 0
* +---+---+---+---+---+---+---+---+
* |CH3|CH2|CH1|CH0|CH3|CH2|CH1|CH0| target of setbit0/clrbit0
* +---+---+---+---+---+---+---+---+
* +---+---+---+---+---+---+---+---+
* |CH7|CH6|CH5|CH4|CH7|CH6|CH5|CH4| target of setbit1/clrbit1
* +---+---+---+---+---+---+---+---+
* |<- 0: Hi-Z ->|<- 0: Low ->|
* |<- 1: Output ->|<- 1: High ->|
*
* Input Parameter:
* setbitX - set bit that 1 is set
* clrbitX - clear bit that 1 is set
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
* setbitX - return the current value of register
*
****************************************************************************/
int cxd56_pmic_set_gpo_reg(FAR uint8_t *setbit0, FAR uint8_t *clrbit0,
FAR uint8_t *setbit1, FAR uint8_t *clrbit1);
/****************************************************************************
* Name: cxd56_pmic_set_gpo
*
* Description:
* Set High/Low to the specified GPO channel(s)
*
* Input Parameter:
* chset - GPO Channel number(s)
* value - true if output high, false if output low.
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_set_gpo(uint8_t chset, bool value);
/****************************************************************************
* Name: cxd56_pmic_set_gpo_hiz
*
* Description:
* Set Hi-Z to the specified GPO channel(s)
*
* Input Parameter:
* chset - GPO Channel number(s)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_set_gpo_hiz(uint8_t chset);
/****************************************************************************
* Name: cxd56_pmic_get_gpo
*
* Description:
* Get the value from the specified GPO channel(s)
*
* Input Parameter:
* chset : GPO Channel number(s)
*
* Returned Value:
* Return true if all of the specified chset are high. Otherwise, return false
*
****************************************************************************/
bool cxd56_pmic_get_gpo(uint8_t chset);
/****************************************************************************
* Name: cxd56_pmic_set_loadswitch_reg
*
* Description:
* Set LoadSwitch register. Register's decription is below:
*
* 7 6 5 4 3 2 1 0
* +---+---+---+---+---+---+---+---+
* | - | - | - |CH4|CH3|CH2| 1 | 1 | target of setbit/clrbit
* +---+---+---+---+---+---+---+---+
* |<- 0: Off->|
* |<- 1: On ->|
*
* Input Parameter:
* setbit - set bit that 1 is set
* clrbit - clear bit that 1 is set
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
* setbit - return the current value of register
*
****************************************************************************/
int cxd56_pmic_set_loadswitch_reg(FAR uint8_t *setbit, FAR uint8_t *clrbit);
/****************************************************************************
* Name: cxd56_pmic_set_loadswitch
*
* Description:
* Set On/Off to the specified LoadSwitch channel(s)
*
* Input Parameter:
* chset - LoadSwitch Channel number(s)
* value - true if set on, false if set off.
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_set_loadswitch(uint8_t chset, bool value);
/****************************************************************************
* Name: cxd56_pmic_get_loadswitch
*
* Description:
* Get the value from the specified LoadSwitch channel(s)
*
* Input Parameter:
* chset - LoadSwitch Channel number(s)
*
* Returned Value:
* Return true if all of the specified chset are on. Otherwise, return false
*
****************************************************************************/
bool cxd56_pmic_get_loadswitch(uint8_t chset);
/****************************************************************************
* Name: cxd56_pmic_set_ddc_ldo_reg
*
* Description:
* Set DDC/LDO register. Register's decription is below:
*
* 7 6 5 4 3 2 1 0
* +----+----+----+----+----+----+----+----+
* | | |LDO |DDC |LDO |DDC |LDO |DDC | target of setbit/clrbit
* | - | - |PERI|CORE|ANA |ANA |EMMC|IO |
* +----+----+----+----+----+----+----+----+
* |<- 0: Off ->|
* |<- 1: On ->|
*
* Input Parameter:
* setbit - set bit that 1 is set
* clrbit - clear bit that 1 is set
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
* setbit - return the current value of register
*
****************************************************************************/
int cxd56_pmic_set_ddc_ldo_reg(FAR uint8_t *setbit, FAR uint8_t *clrbit);
/****************************************************************************
* Name: cxd56_pmic_set_ddc_ldo
*
* Description:
* Set On/Off to the specified DDC/LDO channel(s)
*
* Input Parameter:
* chset - DDC/LO Channel number(s)
* value - true if set on, false if set off.
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_set_ddc_ldo(uint8_t chset, bool value);
/****************************************************************************
* Name: cxd56_pmic_get_ddc_ldo
*
* Description:
* Get the value from the specified DDC/LDO channel(s)
*
* Input Parameter:
* chset - DDC/LDO Channel number(s)
*
* Returned Value:
* Return true if all of the specified chset are on. Otherwise, return false
*
****************************************************************************/
bool cxd56_pmic_get_ddc_ldo(uint8_t chset);
/****************************************************************************
* Name: cxd56_pmic_get_gauge
*
* Description:
* Get the set of values (gauge, voltage, current and temperature) from
* PMIC.
*
* Input Parameter:
* gauge - Set of gauge values
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_get_gauge(FAR struct pmic_gauge_s *gauge);
/****************************************************************************
* Name: cxd56_pmic_getlowervol
*
* Description:
* Get lower limit of voltage for system to be running.
*
* Input Parameter:
* voltage - Lower limit voltage (mV)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_getlowervol(FAR int *vol);
/****************************************************************************
* Name: cxd56_pmic_getchargevol
*
* Description:
* Get charge voltage
*
* Input Parameter:
* voltage - Possible values are every 50 between 4000 to 4400 (mV)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_getchargevol(FAR int *voltage);
/****************************************************************************
* Name: cxd56_pmic_setchargevol
*
* Description:
* Set charge voltage
*
* Input Parameter:
* voltage - Avalable values are every 50 between 4000 to 4400 (mV)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_setchargevol(int voltage);
/****************************************************************************
* Name: cxd56_pmic_getchargecurrent
*
* Description:
* Get charge current value
*
* Input Parameter:
* current - Possible values are 2, 100 and 500 (mA). However,
* 2 means 2.5 mA actually.
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_getchargecurrent(FAR int *current);
/****************************************************************************
* Name: cxd56_pmic_setchargecurrent
*
* Description:
* Set charge current value
*
* Input Parameter:
* current - Available values are 2, 100 and 500 (mA). However, 2 means
* 2.5 mA actually.
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_setchargecurrent(int current);
/****************************************************************************
* Name: cxd56_pmic_getporttype
*
* Description:
* Get USB port type
*
* Input Parameter:
* porttype - PMIC_PORTTYPE_SDP or PMIC_PORTTYPE_DCPCDP
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_getporttype(FAR int *porttype);
/****************************************************************************
* Name: cxd56_pmic_getchargestate
*
* Description:
* Read charging status
*
* Input Parameter:
* state - Charging status (see PMIC_STAT_* definitions)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_getchargestate(FAR uint8_t *state);
/****************************************************************************
* Name: cxd56_pmic_setrechargevol
*
* Description:
* Set threshold voltage against full charge for automatic restart charging.
*
* Input Parameter:
* mV - Available values are -400, -350, -300 and -250 (mV)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_setrechargevol(int mV);
/****************************************************************************
* Name: cxd56_pmic_getrechargevol
*
* Description:
* Get threshold voltage against full charge for automatic restart charging.
*
* Input Parameter:
* mV - Possible values are -400, -350, -300 and -250 (mV)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_getrechargevol(FAR int *mV);
/****************************************************************************
* Name: cxd56_pmic_setchargecompcurrent
*
* Description:
* Set current value setting for determine fully charged.
*
* Input Parameter:
* current - Possible values are 50, 40, 30, 20 and 10 (mA)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_setchargecompcurrent(int current);
/****************************************************************************
* Name: cxd56_pmic_getchargecompcurrent
*
* Description:
* Get current value setting for determine fully charged.
*
* Input Parameter:
* current - Available values are 50, 40, 30, 20 and 10 (mA)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_getchargecompcurrent(FAR int *current);
/****************************************************************************
* Name: cxd56_pmic_gettemptable
*
* Description:
* Get temperature detect resistance table
*
* Input Parameter:
* table - Settings values for temperature detecting (see CXD5247GF
* specification for more detail)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_gettemptable(FAR struct pmic_temp_table_s *table);
/****************************************************************************
* Name: cxd56_pmic_settemptable
*
* Description:
* Set temperature detect resistance table
*
* Input Parameter:
* table - Settings values for temperature detecting (see CXD5247GF
* specification for more detail)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_settemptable(FAR struct pmic_temp_table_s *table);
/****************************************************************************
* Name: cxd56_pmic_setchargemode
*
* Description:
* Set charging mode in each low/high temperatures.
* In lower than 10 degrees Celsius, charging mode will be changed on/off
* and weak (half of charge current) according to setting.
* In higher than 45 degrees Celsius, charging mode will be charged on/off
* and weak (-0.15V from charge voltage) according to setting.
*
* Input Parameter:
* low - Charging mode in low temperature (see PMIC_CHGMODE_*)
* high - Charging mode in high temperature (see PMIC_CHGMODE_*)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_setchargemode(int low, int high);
/****************************************************************************
* Name: cxd56_pmic_getchargemode
*
* Description:
* Get charging mode in each low/high temperatures.
* In lower than 10 degrees Celsius, charging mode will be changed on/off
* and weak (half of charge current) according to setting.
* In higher than 45 degrees Celsius, charging mode will be charged on/off
* and weak (-0.15V from charge voltage) according to setting.
*
* Input Parameter:
* low - Charging mode in low temperature (see PMIC_CHG_*)
* high - Charging mode in high temperature (see PMIC_CHG_*)
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_getchargemode(FAR int *low, FAR int *high);
/****************************************************************************
* Name: cxd56_pmic_read
*
* Description:
* Read the value from the specified sub address
*
* Input Parameter:
* addr - sub address
* buf - pointer to read buffer
* size - byte count of read
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_read(uint8_t addr, FAR void *buf, uint32_t size);
/****************************************************************************
* Name: cxd56_pmic_write
*
* Description:
* Write the value to the specified sub address
*
* Input Parameter:
* addr - sub address
* buf - pointer to write buffer
* size - byte count of write
*
* Returned Value:
* Return 0 on success. Otherwise, return a negated errno.
*
****************************************************************************/
int cxd56_pmic_write(uint8_t addr, FAR void *buf, uint32_t size);
/****************************************************************************
* Battery monitor for debug
****************************************************************************/
#ifdef CONFIG_CXD56_PMIC_BATMONITOR
int cxd56_pmic_monitor_enable(FAR struct pmic_mon_s *ptr);
int cxd56_pmic_monitor_status(FAR struct pmic_mon_status_s *ptr);
int cxd56_pmic_monitor_set(FAR struct pmic_mon_set_s *ptr);
int cxd56_pmic_monitor_get(FAR struct pmic_mon_log_s *ptr);
#else
#define cxd56_pmic_monitor_enable(ptr)
#define cxd56_pmic_monitor_status(ptr)
#define cxd56_pmic_monitor_set(ptr)
#define cxd56_pmic_monitor_get(ptr)
#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* CONFIG_CXD56_PMIC */
#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_PMIC_H */

View File

@ -0,0 +1,87 @@
/****************************************************************************
* arch/arm/src/cxd56xx/hardware/cxd5602_backupmem.h
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_BACKUPMEM_H
#define __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_BACKUPMEM_H
/********************************************************************************************
* Included Files
********************************************************************************************/
/********************************************************************************************
* Pre-processor Definitions
********************************************************************************************/
#define CXD56_BKUP_SRAM_BASE (0x04400000)
#define BKUP ((backup_info_t*)CXD56_BKUP_SRAM_BASE)
/********************************************************************************************
* Public Types
********************************************************************************************/
typedef struct {
uint32_t rcosc_clock; /* 0x04400000 ~ 0x04400003 */
uint32_t chip_revision; /* 0x04400004 ~ 0x04400007 */
uint32_t sbl_version; /* 0x04400008 ~ 0x0440000b */
uint32_t sysfw_version; /* 0x0440000c ~ 0x0440000f */
uint32_t reserved_version[4]; /* 0x04400010 ~ 0x0440001f */
uint32_t bootcause; /* 0x04400020 ~ 0x04400023 */
uint32_t bootmask; /* 0x04400024 ~ 0x04400027 */
uint32_t bootreserve; /* 0x04400028 ~ 0x0440002b */
uint32_t systemconfig; /* 0x0440002c ~ 0x0440002f */
uint8_t rtc_saved_data[32]; /* 0x04400030 ~ 0x0440004f */
uint32_t irq_wake_map[4]; /* 0x04400050 ~ 0x0440005f */
uint32_t irq_inv_map[4]; /* 0x04400060 ~ 0x0440006f */
uint8_t reserved0[0x100 - 0x70]; /* 0x04400070 ~ 0x044000ff */
uint8_t power_monitor_data[0x420]; /* 0x04400100 ~ 0x0440051f */
uint8_t reserved1[2 * 1024 - 0x520]; /* 0x04400520 ~ 0x044007ff (2KB-0x520)*/
uint8_t gnss_backup_data[24 * 1024]; /* 0x04400800 ~ 0x044067ff (24KB) */
uint8_t gnss_pvtlog_data[ 4 * 1024]; /* 0x04406800 ~ 0x044077ff (4KB) */
uint8_t reserved_romcode[ 2 * 1024]; /* 0x04407800 ~ 0x04407fff (2KB) */
uint8_t log[32 * 1024]; /* 0x04408000 ~ 0x0440ffff (32KB) */
} backup_info_t;
/********************************************************************************************
* Public Data
********************************************************************************************/
/********************************************************************************************
* Public Functions
********************************************************************************************/
#endif /* __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_BACKUPMEM_H */

View File

@ -121,4 +121,3 @@
#define CXD56_SDIO_BASE (CXD56_ADSP_BASE + 0x02202000)
#endif /* __ARCH_ARM_SRC_CXD56XX_HARDWARE_CXD5602_MEMORYMAP_H */

View File

@ -0,0 +1,659 @@
/****************************************************************************
* arch/arm/src/cxd56xx/hardware/cxd5602_pinconfig.h
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_PINCONFIG_H
#define __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_PINCONFIG_H
/********************************************************************************************
* Included Files
********************************************************************************************/
#include <nuttx/config.h>
/********************************************************************************************
* Pre-processor Definitions
********************************************************************************************/
/* Set the standard pinconf macro Definitions
* - If it's used as input pin, then set 1. Otherwise set 0 (default).
* - If it's drived in 4mA, then set 1. Otherwise set 0 (default 2mA).
* - If it's used as weak pull-up/down, then set PINCONF_PULLUP/PINCONF_PULLDOWN.
* Otherwise set 0 (default).
*
*/
#define PINCONF(pin, mode, input, drive, pull) \
( \
(PINCONF_SET_PIN(pin)) | \
(PINCONF_SET_MODE(mode)) | \
((input) ? PINCONF_INPUT_ENABLE : PINCONF_INPUT_DISABLE) | \
((drive) ? PINCONF_DRIVE_HIGH : PINCONF_DRIVE_NORMAL) | \
((pull) ? (pull) : PINCONF_FLOAT) \
)
/* CXD5602 Pin Configuration Table
*
* Group Pin 100 185 Mode0 Mode1 Mode2 Mode3
* ================ =============== === === ======= =============== =============== ===============
* I2C4 I2C4_BCK o o GPIO I2C4(PMIC) - -
* I2C4_BDT o o GPIO I2C4(PMIC) - -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* PMIC_INT PMIC_INT o o GPIO PMIC_INT PMIC_INT(OD) -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* RTC_IRQ_OUT RTC_IRQ_OUT - o GPIO RTC_IRQ_OUT RTC_IRQ_OUT(OD) -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* AP_CLK AP_CLK o o GPIO AP_CLK PMU_WDT PMU_WDT(OD)
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* GNSS_1PPS_OUT GNSS_1PPS_OUT - o GPIO GNSS_1PPS_OUT CPU_WDT CPU_WDT(OD)
* ---------------- --------------- --- --- --------------- ------- --------------- ---------------
* SPI0A SPI0_CS_X o o GPIO UART1(DBG) SPI0(CFG) SYS_MONOUT0
* SPI0_SCK o o GPIO UART1(DBG) SPI0(CFG) SYS_MONOUT1
* ---------------- --------------- --- --- ------- --------------- ---------------
* SPI0B SPI0_MOSI - o GPIO I2C2(CFG) SPI0(CFG) SYS_MONOUT2
* SPI0_MISO - o GPIO I2C2(CFG) SPI0(CFG) SYS_MONOUT3
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SPI1A SPI1_CS_X o o GPIO SPI1(Flash) SPI0(CFG) SYS_MONOUT4
* SPI1_SCK o o GPIO SPI1(Flash) SPI0(CFG) SYS_MONOUT5
* SPI1_IO0 o o GPIO SPI1(Flash) SPI0(CFG) SYS_MONOUT6
* SPI1_IO1 o o GPIO SPI1(Flash) SPI0(CFG) SYS_MONOUT7
* ---------------- --------------- --- --- ------- --------------- ---------------
* SPI1B SPI1_IO2 o o GPIO SPI1(Flash) - SYS_MONOUT8
* SPI1_IO3 o o GPIO SPI1(Flash) - SYS_MONOUT9
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SPI2A SPI2_CS_X o o GPIO SPI2(HostIF) UART0(HostIF) I2C3(HostIF)
* SPI2_SCK o o GPIO SPI2(HostIF) UART0(HostIF) I2C3(HostIF)
* ---------------- --------------- --- --- ------- --------------- ---------------
* SPI2B SPI2_MOSI o o GPIO SPI2(HostIF) UART0(HostIF) -
* SPI2_MISO o o GPIO SPI2(HostIF) UART0(HostIF) -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* HIFIRQ HIF_IRQ_OUT o o GPIO HIF_IRQ_OUT HIF_IRQ_OUT(OD) GNSS_1PPS_OUT
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* HIFEXT HIF_GPIO0 - o GPIO - - GPS_EXTLD
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SEN_IRQ_IN SEN_IRQ_IN o o GPIO SEN_IRQ_IN SYS_MONOUT0 DBG_LOGGER
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SPI3_CS0_X SPI3_CS0_X o o GPIO SPI3_CS0_X SYS_MONOUT1 DBG_LOGGER
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SPI3_CS1_X SPI3_CS1_X o o GPIO SPI3_CS1_X SYS_MONOUT2 DBG_LOGGER
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SPI3_CS2_X SPI3_CS2_X o o GPIO SPI3_CS2_X SYS_MONOUT3 DBG_LOGGER
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SPI3 SPI3_SCK o o GPIO SPI3(Sensor) SYS_MONOUT4 DBG_LOGGER
* SPI3_MOSI o o GPIO SPI3(Sensor) SYS_MONOUT5 DBG_LOGGER
* SPI3_MISO o o GPIO SPI3(Sensor) SYS_MONOUT6 DBG_LOGGER
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* I2C0 I2C0_BCK o o GPIO I2C0(Sensor) SYS_MONOUT7 DBG_LOGGER
* I2C0_BDT o o GPIO I2C0(Sensor) SYS_MONOUT8 DBG_LOGGER
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* PWMA PWM0 o o GPIO PWMA SYS_MONOUT9 DBG_LOGGER
* PWM1 o o GPIO PWMA GPIO DBG_LOGGER
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* PWMB PWM2 o o GPIO PWMB I2C1(Sensor) DBG_LOGGER
* PWM3 o o GPIO PWMB I2C1(Sensor) DBG_LOGGER
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* IS IS_CLK - o GPIO IS - -
* IS_VSYNC - o GPIO IS - -
* IS_HSYNC - o GPIO IS - -
* IS_DATA0 - o GPIO IS - -
* IS_DATA1 - o GPIO IS - -
* IS_DATA2 - o GPIO IS - -
* IS_DATA3 - o GPIO IS - -
* IS_DATA4 - o GPIO IS - -
* IS_DATA5 - o GPIO IS - -
* IS_DATA6 - o GPIO IS - -
* IS_DATA7 - o GPIO IS - -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* UART2 UART2_TXD o o GPIO UART2(APP) APP_MONOUT0 -
* UART2_RXD o o GPIO UART2(APP) APP_MONOUT1 -
* UART2_CTS o o GPIO UART2(APP) APP_MONOUT2 -
* UART2_RTS o o GPIO UART2(APP) APP_MONOUT3 -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SPI4 SPI4_CS_X o o GPIO SPI4(APP) APP_MONOUT4 -
* SPI4_SCK o o GPIO SPI4(APP) APP_MONOUT5 -
* SPI4_MOSI o o GPIO SPI4(APP) APP_MONOUT6 -
* SPI4_MISO o o GPIO SPI4(APP) APP_MONOUT7 -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* EMMCA EMMC_CLK o o GPIO EMMC SPI5(APP) -
* EMMC_CMD o o GPIO EMMC SPI5(APP) -
* EMMC_DATA0 o o GPIO EMMC SPI5(APP) -
* EMMC_DATA1 o o GPIO EMMC SPI5(APP) -
* ---------------- --------------- --- --- ------- --------------- ---------------
* EMMCB EMMC_DATA2 o o GPIO EMMC APP_MONOUT8 -
* EMMC_DATA3 o o GPIO EMMC APP_MONOUT9 -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SDIOA SDIO_CLK - o GPIO SDIO SPI5(APP) -
* SDIO_CMD - o GPIO SDIO SPI5(APP) -
* SDIO_DATA0 - o GPIO SDIO SPI5(APP) -
* SDIO_DATA1 - o GPIO SDIO SPI5(APP) -
* SDIO_DATA2 - o GPIO SDIO GPIO -
* SDIO_DATA3 - o GPIO SDIO GPIO -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SDIOB SDIO_CD - o GPIO SDIO - -
* SDIO_WP - o GPIO SDIO - -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SDIOC SDIO_CMDDIR - o GPIO SDIO - -
* SDIO_DIR0 - o GPIO SDIO - -
* SDIO_DIR1_3 - o GPIO SDIO - -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* SDIOD SDIO_CLKI - o GPIO SDIO - -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* I2S0 I2S0_BCK o o GPIO I2S0 APP_MONOUT0 -
* I2S0_LRCK o o GPIO I2S0 APP_MONOUT1 -
* I2S0_DATA_IN o o GPIO I2S0 APP_MONOUT2 -
* I2S0_DATA_OUT o o GPIO I2S0 APP_MONOUT3 -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* I2S1 I2S1_BCK - o GPIO I2S1 APP_MONOUT4 -
* I2S1_LRCK - o GPIO I2S1 APP_MONOUT5 -
* I2S1_DATA_IN - o GPIO I2S1 APP_MONOUT6 -
* I2S1_DATA_OUT - o GPIO I2S1 APP_MONOUT7 -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* MCLK MCLK o o GPIO MCLK APP_MONOUT8 -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* PDM PDM_CLK o o GPIO PDM APP_MONOUT9 -
* PDM_IN o o GPIO PDM GPIO -
* PDM_OUT o o GPIO PDM GPIO -
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
* USBVBUS USB_VBUSINT o o GPIO USB_VBUSINT - DBG_LOGGER
* ---------------- --------------- --- --- ------- --------------- --------------- ---------------
*/
/* Default pin configurations
* Mode: shared pin function mode
* ENZI: 1=Input Enable, 0=Input Disable
* 4mA : Drive Current 1=4mA, 0=2mA
* Pull: 0=HiZ floating, PINCONF_PULLUP, PINCONF_PULLDOWN
* M E P
* P o N 4 u
* i d Z m l
* n e I A l
*/
#define PINCONF_I2C4_BCK_GPIO PINCONF(PIN_I2C4_BCK, 0, 0, 0, 0)
#define PINCONF_I2C4_BCK PINCONF(PIN_I2C4_BCK, 1, 1, 0, 0)
#define PINCONF_I2C4_BDT_GPIO PINCONF(PIN_I2C4_BDT, 0, 0, 0, 0)
#define PINCONF_I2C4_BDT PINCONF(PIN_I2C4_BDT, 1, 1, 0, 0)
#define PINCONF_PMIC_INT_GPIO PINCONF(PIN_PMIC_INT, 0, 0, 0, 0)
#define PINCONF_PMIC_INT PINCONF(PIN_PMIC_INT, 1, 1, 0, 0)
#define PINCONF_PMIC_INT_OD PINCONF(PIN_PMIC_INT, 2, 1, 0, 0)
#ifdef CONFIG_CXD56_FCBGA
#define PINCONF_RTC_IRQ_OUT_GPIO PINCONF(PIN_RTC_IRQ_OUT, 0, 0, 0, 0)
#define PINCONF_RTC_IRQ_OUT PINCONF(PIN_RTC_IRQ_OUT, 1, 0, 0, 0)
#define PINCONF_RTC_IRQ_OUT_OD PINCONF(PIN_RTC_IRQ_OUT, 2, 0, 0, 0)
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONF_AP_CLK_GPIO PINCONF(PIN_AP_CLK, 0, 0, 0, 0)
#define PINCONF_AP_CLK PINCONF(PIN_AP_CLK, 1, 1, 0, 0)
#define PINCONF_AP_CLK_PMU_WDT PINCONF(PIN_AP_CLK, 2, 0, 0, 0)
#define PINCONF_AP_CLK_PMU_WDT_OD PINCONF(PIN_AP_CLK, 3, 0, 0, 0)
#ifdef CONFIG_CXD56_FCBGA
#define PINCONF_GNSS_1PPS_OUT_GPIO PINCONF(PIN_GNSS_1PPS_OUT, 0, 0, 0, 0)
#define PINCONF_GNSS_1PPS_OUT PINCONF(PIN_GNSS_1PPS_OUT, 1, 0, 0, 0)
#define PINCONF_GNSS_1PPS_OUT_CPU_WDT PINCONF(PIN_GNSS_1PPS_OUT, 2, 0, 0, 0)
#define PINCONF_GNSS_1PPS_OUT_CPU_WDT_OD PINCONF(PIN_GNSS_1PPS_OUT, 3, 0, 0, 0)
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONF_SPI0_CS_X_GPIO PINCONF(PIN_SPI0_CS_X, 0, 0, 0, 0)
#define PINCONF_SPI0_CS_X_UART1_TXD PINCONF(PIN_SPI0_CS_X, 1, 0, 0, 0)
#define PINCONF_SPI0_CS_X PINCONF(PIN_SPI0_CS_X, 2, 0, 0, 0)
#define PINCONF_SPI0_CS_X_SYS_MONOUT0 PINCONF(PIN_SPI0_CS_X, 3, 0, 0, 0)
#define PINCONF_SPI0_SCK_GPIO PINCONF(PIN_SPI0_SCK, 0, 0, 0, 0)
#define PINCONF_SPI0_SCK_UART1_RXD PINCONF(PIN_SPI0_SCK, 1, 1, 0, 0)
#define PINCONF_SPI0_SCK PINCONF(PIN_SPI0_SCK, 2, 0, 0, 0)
#define PINCONF_SPI0_SCK_SYS_MONOUT1 PINCONF(PIN_SPI0_SCK, 3, 0, 0, 0)
#ifdef CONFIG_CXD56_FCBGA
#define PINCONF_SPI0_MOSI_GPIO PINCONF(PIN_SPI0_MOSI, 0, 0, 0, 0)
#define PINCONF_SPI0_MOSI_I2C2_BCK PINCONF(PIN_SPI0_MOSI, 1, 1, 0, 0)
#define PINCONF_SPI0_MOSI PINCONF(PIN_SPI0_MOSI, 2, 0, 0, 0)
#define PINCONF_SPI0_MOSI_SYS_MONOUT2 PINCONF(PIN_SPI0_MOSI, 3, 0, 0, 0)
#define PINCONF_SPI0_MISO_GPIO PINCONF(PIN_SPI0_MISO, 0, 0, 0, 0)
#define PINCONF_SPI0_MISO_I2C2_BDT PINCONF(PIN_SPI0_MISO, 1, 1, 0, 0)
#define PINCONF_SPI0_MISO PINCONF(PIN_SPI0_MISO, 2, 1, 0, 0)
#define PINCONF_SPI0_MISO_SYS_MONOUT3 PINCONF(PIN_SPI0_MISO, 3, 0, 0, 0)
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONF_SPI1_CS_X_GPIO PINCONF(PIN_SPI1_CS_X, 0, 0, 0, 0)
#define PINCONF_SPI1_CS_X PINCONF(PIN_SPI1_CS_X, 1, 0, 1, 0)
#define PINCONF_SPI1_CS_X_SPI0_CS_X PINCONF(PIN_SPI1_CS_X, 2, 0, 0, 0)
#define PINCONF_SPI1_CS_X_SYS_MONOUT4 PINCONF(PIN_SPI1_CS_X, 3, 0, 0, 0)
#define PINCONF_SPI1_SCK_GPIO PINCONF(PIN_SPI1_SCK, 0, 0, 0, 0)
#define PINCONF_SPI1_SCK PINCONF(PIN_SPI1_SCK, 1, 0, 1, 0)
#define PINCONF_SPI1_SCK_SPI0_SCK PINCONF(PIN_SPI1_SCK, 2, 0, 0, 0)
#define PINCONF_SPI1_SCK_SYS_MONOUT5 PINCONF(PIN_SPI1_SCK, 3, 0, 0, 0)
#define PINCONF_SPI1_IO0_GPIO PINCONF(PIN_SPI1_IO0, 0, 0, 0, 0)
#define PINCONF_SPI1_IO0 PINCONF(PIN_SPI1_IO0, 1, 1, 1, 0)
#define PINCONF_SPI1_IO0_SPI0_MOSI PINCONF(PIN_SPI1_IO0, 2, 0, 0, 0)
#define PINCONF_SPI1_IO0_SYS_MONOUT6 PINCONF(PIN_SPI1_IO0, 3, 0, 0, 0)
#define PINCONF_SPI1_IO1_GPIO PINCONF(PIN_SPI1_IO1, 0, 0, 0, 0)
#define PINCONF_SPI1_IO1 PINCONF(PIN_SPI1_IO1, 1, 1, 1, 0)
#define PINCONF_SPI1_IO1_SPI0_MISO PINCONF(PIN_SPI1_IO1, 2, 1, 0, 0)
#define PINCONF_SPI1_IO1_SYS_MONOUT7 PINCONF(PIN_SPI1_IO1, 3, 0, 0, 0)
#define PINCONF_SPI1_IO2_GPIO PINCONF(PIN_SPI1_IO2, 0, 0, 0, 0)
#define PINCONF_SPI1_IO2 PINCONF(PIN_SPI1_IO2, 1, 1, 1, 0)
#define PINCONF_SPI1_IO2_SYS_MONOUT8 PINCONF(PIN_SPI1_IO2, 3, 0, 0, 0)
#define PINCONF_SPI1_IO3_GPIO PINCONF(PIN_SPI1_IO3, 0, 0, 0, 0)
#define PINCONF_SPI1_IO3 PINCONF(PIN_SPI1_IO3, 1, 1, 1, 0)
#define PINCONF_SPI1_IO3_SYS_MONOUT9 PINCONF(PIN_SPI1_IO3, 3, 0, 0, 0)
#define PINCONF_SPI2_CS_X_GPIO PINCONF(PIN_SPI2_CS_X, 0, 0, 0, 0)
#define PINCONF_SPI2_CS_X PINCONF(PIN_SPI2_CS_X, 1, 1, 0, 0)
#define PINCONF_SPI2_CS_X_UART0_TXD PINCONF(PIN_SPI2_CS_X, 2, 0, 0, 0)
#define PINCONF_SPI2_CS_X_I2C3_BCK PINCONF(PIN_SPI2_CS_X, 3, 1, 0, 0)
#define PINCONF_SPI2_SCK_GPIO PINCONF(PIN_SPI2_SCK, 0, 0, 0, 0)
#define PINCONF_SPI2_SCK PINCONF(PIN_SPI2_SCK, 1, 1, 0, 0)
#define PINCONF_SPI2_SCK_UART0_RXD PINCONF(PIN_SPI2_SCK, 2, 1, 0, 0)
#define PINCONF_SPI2_SCK_I2C3_BDT PINCONF(PIN_SPI2_SCK, 3, 1, 0, 0)
#define PINCONF_SPI2_MOSI_GPIO PINCONF(PIN_SPI2_MOSI, 0, 0, 0, 0)
#define PINCONF_SPI2_MOSI PINCONF(PIN_SPI2_MOSI, 1, 1, 0, 0)
#define PINCONF_SPI2_MOSI_UART0_CTS PINCONF(PIN_SPI2_MOSI, 2, 1, 0, 0)
#define PINCONF_SPI2_MISO_GPIO PINCONF(PIN_SPI2_MISO, 0, 0, 0, 0)
#define PINCONF_SPI2_MISO PINCONF(PIN_SPI2_MISO, 1, 0, 0, 0)
#define PINCONF_SPI2_MISO_UART0_RTS PINCONF(PIN_SPI2_MISO, 2, 0, 0, 0)
#define PINCONF_HIF_IRQ_OUT_GPIO PINCONF(PIN_HIF_IRQ_OUT, 0, 0, 0, 0)
#define PINCONF_HIF_IRQ_OUT PINCONF(PIN_HIF_IRQ_OUT, 1, 0, 0, 0)
#define PINCONF_HIF_IRQ_OUT_OD PINCONF(PIN_HIF_IRQ_OUT, 2, 0, 0, 0)
#define PINCONF_HIF_IRQ_OUT_GNSS_1PPS_OUT PINCONF(PIN_HIF_IRQ_OUT, 3, 0, 0, 0)
#ifdef CONFIG_CXD56_FCBGA
#define PINCONF_HIF_GPIO0_GPIO PINCONF(PIN_HIF_GPIO0, 0, 0, 0, 0)
#define PINCONF_HIF_GPIO0_GPS_EXTLD PINCONF(PIN_HIF_GPIO0, 3, 0, 0, 0)
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONF_SEN_IRQ_IN_GPIO PINCONF(PIN_SEN_IRQ_IN, 0, 0, 0, 0)
#define PINCONF_SEN_IRQ_IN PINCONF(PIN_SEN_IRQ_IN, 1, 1, 0, 0)
#define PINCONF_SEN_IRQ_IN_SYS_MONOUT0 PINCONF(PIN_SEN_IRQ_IN, 2, 0, 0, 0)
#define PINCONF_SEN_IRQ_IN_DBG_LOGGERI3 PINCONF(PIN_SEN_IRQ_IN, 3, 0, 0, 0)
#define PINCONF_SPI3_CS0_X_GPIO PINCONF(PIN_SPI3_CS0_X, 0, 0, 0, 0)
#define PINCONF_SPI3_CS0_X PINCONF(PIN_SPI3_CS0_X, 1, 0, 0, 0)
#define PINCONF_SPI3_CS0_X_SYS_MONOUT1 PINCONF(PIN_SPI3_CS0_X, 2, 0, 0, 0)
#define PINCONF_SPI3_CS0_X_DBG_LOGGERI2 PINCONF(PIN_SPI3_CS0_X, 3, 0, 0, 0)
#define PINCONF_SPI3_CS1_X_GPIO PINCONF(PIN_SPI3_CS1_X, 0, 0, 0, 0)
#define PINCONF_SPI3_CS1_X PINCONF(PIN_SPI3_CS1_X, 1, 0, 0, 0)
#define PINCONF_SPI3_CS1_X_SYS_MONOUT2 PINCONF(PIN_SPI3_CS1_X, 2, 0, 0, 0)
#define PINCONF_SPI3_CS1_X_DBG_LOGGERI1 PINCONF(PIN_SPI3_CS1_X, 3, 0, 0, 0)
#define PINCONF_SPI3_CS2_X_GPIO PINCONF(PIN_SPI3_CS2_X, 0, 0, 0, 0)
#define PINCONF_SPI3_CS2_X PINCONF(PIN_SPI3_CS2_X, 1, 0, 0, 0)
#define PINCONF_SPI3_CS2_X_SYS_MONOUT3 PINCONF(PIN_SPI3_CS2_X, 2, 0, 0, 0)
#define PINCONF_SPI3_CS2_X_DBG_LOGGERI0 PINCONF(PIN_SPI3_CS2_X, 3, 0, 0, 0)
#define PINCONF_SPI3_SCK_GPIO PINCONF(PIN_SPI3_SCK, 0, 0, 0, 0)
#define PINCONF_SPI3_SCK PINCONF(PIN_SPI3_SCK, 1, 0, 0, 0)
#define PINCONF_SPI3_SCK_SYS_MONOUT4 PINCONF(PIN_SPI3_SCK, 2, 0, 0, 0)
#define PINCONF_SPI3_SCK_DBG_LOGGERQ5 PINCONF(PIN_SPI3_SCK, 3, 0, 0, 0)
#define PINCONF_SPI3_MOSI_GPIO PINCONF(PIN_SPI3_MOSI, 0, 0, 0, 0)
#define PINCONF_SPI3_MOSI PINCONF(PIN_SPI3_MOSI, 1, 0, 0, 0)
#define PINCONF_SPI3_MOSI_SYS_MONOUT5 PINCONF(PIN_SPI3_MOSI, 2, 0, 0, 0)
#define PINCONF_SPI3_MOSI_DBG_LOGGERQ4 PINCONF(PIN_SPI3_MOSI, 3, 0, 0, 0)
#define PINCONF_SPI3_MISO_GPIO PINCONF(PIN_SPI3_MISO, 0, 0, 0, 0)
#define PINCONF_SPI3_MISO PINCONF(PIN_SPI3_MISO, 1, 1, 0, 0)
#define PINCONF_SPI3_MISO_SYS_MONOUT6 PINCONF(PIN_SPI3_MISO, 2, 0, 0, 0)
#define PINCONF_SPI3_MISO_DBG_LOGGERQ3 PINCONF(PIN_SPI3_MISO, 3, 0, 0, 0)
#define PINCONF_I2C0_BCK_GPIO PINCONF(PIN_I2C0_BCK, 0, 0, 0, 0)
#define PINCONF_I2C0_BCK PINCONF(PIN_I2C0_BCK, 1, 1, 0, 0)
#define PINCONF_I2C0_BCK_SYS_MONOUT7 PINCONF(PIN_I2C0_BCK, 2, 0, 0, 0)
#define PINCONF_I2C0_BCK_DBG_LOGGERQ2 PINCONF(PIN_I2C0_BCK, 3, 0, 0, 0)
#define PINCONF_I2C0_BDT_GPIO PINCONF(PIN_I2C0_BDT, 0, 0, 0, 0)
#define PINCONF_I2C0_BDT PINCONF(PIN_I2C0_BDT, 1, 1, 0, 0)
#define PINCONF_I2C0_BDT_SYS_MONOUT8 PINCONF(PIN_I2C0_BDT, 2, 0, 0, 0)
#define PINCONF_I2C0_BDT_DBG_LOGGERQ1 PINCONF(PIN_I2C0_BDT, 3, 0, 0, 0)
#define PINCONF_PWM0_GPIO PINCONF(PIN_PWM0, 0, 0, 0, 0)
#define PINCONF_PWM0 PINCONF(PIN_PWM0, 1, 0, 0, 0)
#define PINCONF_PWM0_SYS_MONOUT9 PINCONF(PIN_PWM0, 2, 0, 0, 0)
#define PINCONF_PWM0_DBG_LOGGERQ0 PINCONF(PIN_PWM0, 3, 0, 0, 0)
#define PINCONF_PWM1_GPIO PINCONF(PIN_PWM1, 0, 0, 0, 0)
#define PINCONF_PWM1 PINCONF(PIN_PWM1, 1, 0, 0, 0)
#define PINCONF_PWM1_SYS_MONOUT_GPIO PINCONF(PIN_PWM1, 2, 0, 0, 0)
#define PINCONF_PWM1_DBG_LOGGERSEL PINCONF(PIN_PWM1, 3, 0, 0, 0)
#define PINCONF_PWM2_GPIO PINCONF(PIN_PWM2, 0, 0, 0, 0)
#define PINCONF_PWM2 PINCONF(PIN_PWM2, 1, 0, 0, 0)
#define PINCONF_PWM2_I2C1_BCK PINCONF(PIN_PWM2, 2, 1, 0, 0)
#define PINCONF_PWM2_DBG_LOGGERI5 PINCONF(PIN_PWM2, 3, 0, 0, 0)
#define PINCONF_PWM3_GPIO PINCONF(PIN_PWM3, 0, 0, 0, 0)
#define PINCONF_PWM3 PINCONF(PIN_PWM3, 1, 0, 0, 0)
#define PINCONF_PWM3_I2C1_BDT PINCONF(PIN_PWM3, 2, 1, 0, 0)
#define PINCONF_PWM3_DBG_LOGGERI4 PINCONF(PIN_PWM3, 3, 0, 0, 0)
#ifdef CONFIG_CXD56_FCBGA
#define PINCONF_IS_CLK_GPIO PINCONF(PIN_IS_CLK, 0, 0, 0, 0)
#define PINCONF_IS_CLK PINCONF(PIN_IS_CLK, 1, 1, 0, 0)
#define PINCONF_IS_VSYNC_GPIO PINCONF(PIN_IS_VSYNC, 0, 0, 0, 0)
#define PINCONF_IS_VSYNC PINCONF(PIN_IS_VSYNC, 1, 1, 0, 0)
#define PINCONF_IS_HSYNC_GPIO PINCONF(PIN_IS_HSYNC, 0, 0, 0, 0)
#define PINCONF_IS_HSYNC PINCONF(PIN_IS_HSYNC, 1, 1, 0, 0)
#define PINCONF_IS_DATA0_GPIO PINCONF(PIN_IS_DATA0, 0, 0, 0, 0)
#define PINCONF_IS_DATA0 PINCONF(PIN_IS_DATA0, 1, 1, 0, 0)
#define PINCONF_IS_DATA1_GPIO PINCONF(PIN_IS_DATA1, 0, 0, 0, 0)
#define PINCONF_IS_DATA1 PINCONF(PIN_IS_DATA1, 1, 1, 0, 0)
#define PINCONF_IS_DATA2_GPIO PINCONF(PIN_IS_DATA2, 0, 0, 0, 0)
#define PINCONF_IS_DATA2 PINCONF(PIN_IS_DATA2, 1, 1, 0, 0)
#define PINCONF_IS_DATA3_GPIO PINCONF(PIN_IS_DATA3, 0, 0, 0, 0)
#define PINCONF_IS_DATA3 PINCONF(PIN_IS_DATA3, 1, 1, 0, 0)
#define PINCONF_IS_DATA4_GPIO PINCONF(PIN_IS_DATA4, 0, 0, 0, 0)
#define PINCONF_IS_DATA4 PINCONF(PIN_IS_DATA4, 1, 1, 0, 0)
#define PINCONF_IS_DATA5_GPIO PINCONF(PIN_IS_DATA5, 0, 0, 0, 0)
#define PINCONF_IS_DATA5 PINCONF(PIN_IS_DATA5, 1, 1, 0, 0)
#define PINCONF_IS_DATA6_GPIO PINCONF(PIN_IS_DATA6, 0, 0, 0, 0)
#define PINCONF_IS_DATA6 PINCONF(PIN_IS_DATA6, 1, 1, 0, 0)
#define PINCONF_IS_DATA7_GPIO PINCONF(PIN_IS_DATA7, 0, 0, 0, 0)
#define PINCONF_IS_DATA7 PINCONF(PIN_IS_DATA7, 1, 1, 0, 0)
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONF_UART2_TXD_GPIO PINCONF(PIN_UART2_TXD, 0, 0, 0, 0)
#define PINCONF_UART2_TXD PINCONF(PIN_UART2_TXD, 1, 0, 0, 0)
#define PINCONF_UART2_TXD_APP_MONOUT0 PINCONF(PIN_UART2_TXD, 2, 0, 0, 0)
#define PINCONF_UART2_RXD_GPIO PINCONF(PIN_UART2_RXD, 0, 0, 0, 0)
#define PINCONF_UART2_RXD PINCONF(PIN_UART2_RXD, 1, 1, 0, 0)
#define PINCONF_UART2_RXD_APP_MONOUT1 PINCONF(PIN_UART2_RXD, 2, 0, 0, 0)
#define PINCONF_UART2_CTS_GPIO PINCONF(PIN_UART2_CTS, 0, 0, 0, 0)
#define PINCONF_UART2_CTS PINCONF(PIN_UART2_CTS, 1, 1, 0, 0)
#define PINCONF_UART2_CTS_APP_MONOUT2 PINCONF(PIN_UART2_CTS, 2, 0, 0, 0)
#define PINCONF_UART2_RTS_GPIO PINCONF(PIN_UART2_RTS, 0, 0, 0, 0)
#define PINCONF_UART2_RTS PINCONF(PIN_UART2_RTS, 1, 0, 0, 0)
#define PINCONF_UART2_RTS_APP_MONOUT3 PINCONF(PIN_UART2_RTS, 2, 0, 0, 0)
#define PINCONF_SPI4_CS_X_GPIO PINCONF(PIN_SPI4_CS_X, 0, 0, 0, 0)
#define PINCONF_SPI4_CS_X PINCONF(PIN_SPI4_CS_X, 1, 0, 0, 0)
#define PINCONF_SPI4_CS_X_APP_MONOUT4 PINCONF(PIN_SPI4_CS_X, 2, 0, 0, 0)
#define PINCONF_SPI4_SCK_GPIO PINCONF(PIN_SPI4_SCK, 0, 0, 0, 0)
#define PINCONF_SPI4_SCK PINCONF(PIN_SPI4_SCK, 1, 0, 0, 0)
#define PINCONF_SPI4_SCK_APP_MONOUT5 PINCONF(PIN_SPI4_SCK, 2, 0, 0, 0)
#define PINCONF_SPI4_MOSI_GPIO PINCONF(PIN_SPI4_MOSI, 0, 0, 0, 0)
#define PINCONF_SPI4_MOSI PINCONF(PIN_SPI4_MOSI, 1, 0, 0, 0)
#define PINCONF_SPI4_MOSI_APP_MONOUT6 PINCONF(PIN_SPI4_MOSI, 2, 0, 0, 0)
#define PINCONF_SPI4_MISO_GPIO PINCONF(PIN_SPI4_MISO, 0, 0, 0, 0)
#define PINCONF_SPI4_MISO PINCONF(PIN_SPI4_MISO, 1, 1, 0, 0)
#define PINCONF_SPI4_MISO_APP_MONOUT7 PINCONF(PIN_SPI4_MISO, 2, 0, 0, 0)
#define PINCONF_EMMC_CLK_GPIO PINCONF(PIN_EMMC_CLK, 0, 0, 0, 0)
#define PINCONF_EMMC_CLK PINCONF(PIN_EMMC_CLK, 1, 0, 0, 0)
#define PINCONF_EMMC_CLK_SPI5_SCK PINCONF(PIN_EMMC_CLK, 2, 0, 0, 0)
#define PINCONF_EMMC_CMD_GPIO PINCONF(PIN_EMMC_CMD, 0, 0, 0, 0)
#define PINCONF_EMMC_CMD PINCONF(PIN_EMMC_CMD, 1, 1, 0, 0)
#define PINCONF_EMMC_CMD_SPI5_CS_X PINCONF(PIN_EMMC_CMD, 2, 0, 0, 0)
#define PINCONF_EMMC_DATA0_GPIO PINCONF(PIN_EMMC_DATA0, 0, 0, 0, 0)
#define PINCONF_EMMC_DATA0 PINCONF(PIN_EMMC_DATA0, 1, 1, 0, 0)
#define PINCONF_EMMC_DATA0_SPI5_MOSI PINCONF(PIN_EMMC_DATA0, 2, 0, 0, 0)
#define PINCONF_EMMC_DATA1_GPIO PINCONF(PIN_EMMC_DATA1, 0, 0, 0, 0)
#define PINCONF_EMMC_DATA1 PINCONF(PIN_EMMC_DATA1, 1, 1, 0, 0)
#define PINCONF_EMMC_DATA1_SPI5_MISO PINCONF(PIN_EMMC_DATA1, 2, 1, 0, 0)
#define PINCONF_EMMC_DATA2_GPIO PINCONF(PIN_EMMC_DATA2, 0, 0, 0, 0)
#define PINCONF_EMMC_DATA2 PINCONF(PIN_EMMC_DATA2, 1, 1, 0, 0)
#define PINCONF_EMMC_DATA2_APP_MONOUT8 PINCONF(PIN_EMMC_DATA2, 2, 0, 0, 0)
#define PINCONF_EMMC_DATA3_GPIO PINCONF(PIN_EMMC_DATA3, 0, 0, 0, 0)
#define PINCONF_EMMC_DATA3 PINCONF(PIN_EMMC_DATA3, 1, 1, 0, 0)
#define PINCONF_EMMC_DATA3_APP_MONOUT9 PINCONF(PIN_EMMC_DATA3, 2, 0, 0, 0)
#ifdef CONFIG_CXD56_FCBGA
#define PINCONF_SDIO_CLK_GPIO PINCONF(PIN_SDIO_CLK, 0, 0, 0, 0)
#define PINCONF_SDIO_CLK PINCONF(PIN_SDIO_CLK, 1, 1, 1, 0)
#define PINCONF_SDIO_CLK_SDCARD PINCONF(PIN_SDIO_CLK, 1, 0, 1, 0)
#define PINCONF_SDIO_CLK_SPI5_SCK PINCONF(PIN_SDIO_CLK, 2, 0, 0, 0)
#define PINCONF_SDIO_CMD_GPIO PINCONF(PIN_SDIO_CMD, 0, 0, 0, 0)
#define PINCONF_SDIO_CMD PINCONF(PIN_SDIO_CMD, 1, 1, 1, 0)
#define PINCONF_SDIO_CMD_SPI5_CS_X PINCONF(PIN_SDIO_CMD, 2, 0, 0, 0)
#define PINCONF_SDIO_DATA0_GPIO PINCONF(PIN_SDIO_DATA0, 0, 0, 0, 0)
#define PINCONF_SDIO_DATA0 PINCONF(PIN_SDIO_DATA0, 1, 1, 1, 0)
#define PINCONF_SDIO_DATA0_SPI5_MOSI PINCONF(PIN_SDIO_DATA0, 2, 0, 0, 0)
#define PINCONF_SDIO_DATA1_GPIO PINCONF(PIN_SDIO_DATA1, 0, 0, 0, 0)
#define PINCONF_SDIO_DATA1 PINCONF(PIN_SDIO_DATA1, 1, 1, 1, 0)
#define PINCONF_SDIO_DATA1_SPI5_MISO PINCONF(PIN_SDIO_DATA1, 2, 1, 0, 0)
#define PINCONF_SDIO_DATA2_GPIO PINCONF(PIN_SDIO_DATA2, 0, 0, 0, 0)
#define PINCONF_SDIO_DATA2 PINCONF(PIN_SDIO_DATA2, 1, 1, 1, 0)
#define PINCONF_SDIO_DATA2_SPI5_GPIO PINCONF(PIN_SDIO_DATA2, 2, 0, 0, 0)
#define PINCONF_SDIO_DATA3_GPIO PINCONF(PIN_SDIO_DATA3, 0, 0, 0, 0)
#define PINCONF_SDIO_DATA3 PINCONF(PIN_SDIO_DATA3, 1, 1, 1, 0)
#define PINCONF_SDIO_DATA3_SPI5_GPIO PINCONF(PIN_SDIO_DATA3, 2, 0, 0, 0)
#define PINCONF_SDIO_CD_GPIO PINCONF(PIN_SDIO_CD, 0, 0, 0, 0)
#define PINCONF_SDIO_CD PINCONF(PIN_SDIO_CD, 1, 1, 0, 0)
#define PINCONF_SDIO_WP_GPIO PINCONF(PIN_SDIO_WP, 0, 0, 0, 0)
#define PINCONF_SDIO_WP PINCONF(PIN_SDIO_WP, 1, 1, 0, 0)
#define PINCONF_SDIO_CMDDIR_GPIO PINCONF(PIN_SDIO_CMDDIR, 0, 0, 0, 0)
#define PINCONF_SDIO_CMDDIR PINCONF(PIN_SDIO_CMDDIR, 1, 0, 1, 0)
#define PINCONF_SDIO_DIR0_GPIO PINCONF(PIN_SDIO_DIR0, 0, 0, 0, 0)
#define PINCONF_SDIO_DIR0 PINCONF(PIN_SDIO_DIR0, 1, 0, 1, 0)
#define PINCONF_SDIO_DIR1_3_GPIO PINCONF(PIN_SDIO_DIR1_3, 0, 0, 0, 0)
#define PINCONF_SDIO_DIR1_3 PINCONF(PIN_SDIO_DIR1_3, 1, 0, 1, 0)
#define PINCONF_SDIO_CLKI_GPIO PINCONF(PIN_SDIO_CLKI, 0, 0, 0, 0)
#define PINCONF_SDIO_CLKI PINCONF(PIN_SDIO_CLKI, 1, 1, 0, 0) /* only for SD Card */
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONF_I2S0_BCK_GPIO PINCONF(PIN_I2S0_BCK, 0, 0, 0, 0)
#define PINCONF_I2S0_BCK_M_HIGH PINCONF(PIN_I2S0_BCK, 1, 0, 1, 0)
#define PINCONF_I2S0_BCK_M_NORM PINCONF(PIN_I2S0_BCK, 1, 0, 0, 0)
#define PINCONF_I2S0_BCK_S PINCONF(PIN_I2S0_BCK, 1, 1, 0, 0)
#define PINCONF_I2S0_BCK_APP_MONOUT0 PINCONF(PIN_I2S0_BCK, 2, 0, 0, 0)
#define PINCONF_I2S0_LRCK_GPIO PINCONF(PIN_I2S0_LRCK, 0, 0, 0, 0)
#define PINCONF_I2S0_LRCK_M_HIGH PINCONF(PIN_I2S0_LRCK, 1, 0, 1, 0)
#define PINCONF_I2S0_LRCK_M_NORM PINCONF(PIN_I2S0_LRCK, 1, 0, 0, 0)
#define PINCONF_I2S0_LRCK_S PINCONF(PIN_I2S0_LRCK, 1, 1, 0, 0)
#define PINCONF_I2S0_LRCK_APP_MONOUT1 PINCONF(PIN_I2S0_LRCK, 2, 0, 0, 0)
#define PINCONF_I2S0_DATA_IN_GPIO PINCONF(PIN_I2S0_DATA_IN, 0, 0, 0, 0)
#define PINCONF_I2S0_DATA_IN PINCONF(PIN_I2S0_DATA_IN, 1, 1, 0, 0)
#define PINCONF_I2S0_DATA_IN_APP_MONOUT2 PINCONF(PIN_I2S0_DATA_IN, 2, 0, 0, 0)
#define PINCONF_I2S0_DATA_OUT_GPIO PINCONF(PIN_I2S0_DATA_OUT, 0, 0, 0, 0)
#define PINCONF_I2S0_DATA_OUT_HIGH PINCONF(PIN_I2S0_DATA_OUT, 1, 0, 1, 0)
#define PINCONF_I2S0_DATA_OUT_NORM PINCONF(PIN_I2S0_DATA_OUT, 1, 0, 0, 0)
#define PINCONF_I2S0_DATA_OUT_APP_MONOUT3 PINCONF(PIN_I2S0_DATA_OUT, 2, 0, 0, 0)
#ifdef CONFIG_CXD56_FCBGA
#define PINCONF_I2S1_BCK_GPIO PINCONF(PIN_I2S1_BCK, 0, 0, 0, 0)
#define PINCONF_I2S1_BCK_M_HIGH PINCONF(PIN_I2S1_BCK, 1, 0, 1, 0)
#define PINCONF_I2S1_BCK_M_NORM PINCONF(PIN_I2S1_BCK, 1, 0, 0, 0)
#define PINCONF_I2S1_BCK_S PINCONF(PIN_I2S1_BCK, 1, 1, 0, 0)
#define PINCONF_I2S1_BCK_APP_MONOUT4 PINCONF(PIN_I2S1_BCK, 2, 0, 0, 0)
#define PINCONF_I2S1_LRCK_GPIO PINCONF(PIN_I2S1_LRCK, 0, 0, 0, 0)
#define PINCONF_I2S1_LRCK_M_HIGH PINCONF(PIN_I2S1_LRCK, 1, 0, 1, 0)
#define PINCONF_I2S1_LRCK_M_NORM PINCONF(PIN_I2S1_LRCK, 1, 0, 0, 0)
#define PINCONF_I2S1_LRCK_S PINCONF(PIN_I2S1_LRCK, 1, 1, 0, 0)
#define PINCONF_I2S1_LRCK_APP_MONOUT5 PINCONF(PIN_I2S1_LRCK, 2, 0, 0, 0)
#define PINCONF_I2S1_DATA_IN_GPIO PINCONF(PIN_I2S1_DATA_IN, 0, 0, 0, 0)
#define PINCONF_I2S1_DATA_IN PINCONF(PIN_I2S1_DATA_IN, 1, 1, 0, 0)
#define PINCONF_I2S1_DATA_IN_APP_MONOUT6 PINCONF(PIN_I2S1_DATA_IN, 2, 0, 0, 0)
#define PINCONF_I2S1_DATA_OUT_GPIO PINCONF(PIN_I2S1_DATA_OUT, 0, 0, 0, 0)
#define PINCONF_I2S1_DATA_OUT_HIGH PINCONF(PIN_I2S1_DATA_OUT, 1, 0, 1, 0)
#define PINCONF_I2S1_DATA_OUT_NORM PINCONF(PIN_I2S1_DATA_OUT, 1, 0, 0, 0)
#define PINCONF_I2S1_DATA_OUT_APP_MONOUT7 PINCONF(PIN_I2S1_DATA_OUT, 2, 0, 0, 0)
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONF_MCLK_GPIO PINCONF(PIN_MCLK, 0, 0, 0, 0)
#define PINCONF_MCLK PINCONF(PIN_MCLK, 1, 1, 0, 0)
#define PINCONF_MCLK_APP_MONOUT8 PINCONF(PIN_MCLK, 2, 0, 0, 0)
#define PINCONF_PDM_CLK_GPIO PINCONF(PIN_PDM_CLK, 0, 0, 0, 0)
#define PINCONF_PDM_CLK_HIGH PINCONF(PIN_PDM_CLK, 1, 0, 1, 0)
#define PINCONF_PDM_CLK_NORM PINCONF(PIN_PDM_CLK, 1, 0, 0, 0)
#define PINCONF_PDM_CLK_APP_MONOUT9 PINCONF(PIN_PDM_CLK, 2, 0, 0, 0)
#define PINCONF_PDM_IN_GPIO PINCONF(PIN_PDM_IN, 0, 0, 0, 0)
#define PINCONF_PDM_IN PINCONF(PIN_PDM_IN, 1, 1, 0, 0)
#define PINCONF_PDM_OUT_GPIO PINCONF(PIN_PDM_OUT, 0, 0, 0, 0)
#define PINCONF_PDM_OUT_HIGH PINCONF(PIN_PDM_OUT, 1, 0, 1, 0)
#define PINCONF_PDM_OUT_NORM PINCONF(PIN_PDM_OUT, 1, 0, 0, 0)
#define PINCONF_USB_VBUSINT_GPIO PINCONF(PIN_USB_VBUSINT, 0, 0, 0, 0)
#define PINCONF_USB_VBUSINT PINCONF(PIN_USB_VBUSINT, 1, 1, 0, 0)
#define PINCONF_USB_VBUSINT_DBG_LOGGERCLK PINCONF(PIN_USB_VBUSINT, 3, 0, 0, 0)
/* Reference set of multiple pinconfigs
*
*/
#define PINCONFS_I2C4_GPIO { PINCONF_I2C4_BCK_GPIO, PINCONF_I2C4_BDT_GPIO }
#define PINCONFS_I2C4 { PINCONF_I2C4_BCK, PINCONF_I2C4_BDT }
#define PINCONFS_PMIC_INT_GPIO { PINCONF_PMIC_INT_GPIO }
#define PINCONFS_PMIC_INT { PINCONF_PMIC_INT }
#define PINCONFS_PMIC_INT_OD { PINCONF_PMIC_INT_OD }
#ifdef CONFIG_CXD56_FCBGA
#define PINCONFS_RTC_IRQ_OUT_GPIO { PINCONF_RTC_IRQ_OUT_GPIO }
#define PINCONFS_RTC_IRQ_OUT { PINCONF_RTC_IRQ_OUT }
#define PINCONFS_RTC_IRQ_OUT_OD { PINCONF_RTC_IRQ_OUT_OD }
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONFS_AP_CLK_GPIO { PINCONF_AP_CLK_GPIO }
#define PINCONFS_AP_CLK { PINCONF_AP_CLK }
#define PINCONFS_AP_CLK_PMU_WDT { PINCONF_AP_CLK_PMU_WDT }
#define PINCONFS_AP_CLK_PMU_WDT_OD { PINCONF_AP_CLK_PMU_WDT_OD }
#ifdef CONFIG_CXD56_FCBGA
#define PINCONFS_GNSS_1PPS_OUT_GPIO { PINCONF_GNSS_1PPS_OUT_GPIO }
#define PINCONFS_GNSS_1PPS_OUT { PINCONF_GNSS_1PPS_OUT }
#define PINCONFS_GNSS_1PPS_OUT_CPU_WDT { PINCONF_GNSS_1PPS_OUT_CPU_WDT }
#define PINCONFS_GNSS_1PPS_OUT_CPU_WDT_OD { PINCONF_GNSS_1PPS_OUT_CPU_WDT_OD }
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONFS_SPI0A_GPIO { PINCONF_SPI0_CS_X_GPIO, PINCONF_SPI0_SCK_GPIO }
#ifdef CONFIG_CXD56_FCBGA
#define PINCONFS_SPI0B_GPIO { PINCONF_SPI0_MOSI_GPIO, PINCONF_SPI0_MISO_GPIO }
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONFS_SPI0A_UART1 { PINCONF_SPI0_CS_X_UART1_TXD, PINCONF_SPI0_SCK_UART1_RXD }
#ifdef CONFIG_CXD56_FCBGA
#define PINCONFS_SPI0B_I2C2 { PINCONF_SPI0_MOSI_I2C2_BCK, PINCONF_SPI0_MISO_I2C2_BDT }
#define PINCONFS_SPI0_GPIO { PINCONF_SPI0_CS_X_GPIO, PINCONF_SPI0_SCK_GPIO, \
PINCONF_SPI0_MOSI_GPIO, PINCONF_SPI0_MISO_GPIO }
#define PINCONFS_SPI0 { PINCONF_SPI0_CS_X, PINCONF_SPI0_SCK, \
PINCONF_SPI0_MOSI, PINCONF_SPI0_MISO }
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONFS_SPI1A_GPIO { PINCONF_SPI1_CS_X_GPIO, PINCONF_SPI1_SCK_GPIO, \
PINCONF_SPI1_IO0_GPIO, PINCONF_SPI1_IO1_GPIO }
#define PINCONFS_SPI1B_GPIO { PINCONF_SPI1_IO2_GPIO, PINCONF_SPI1_IO3_GPIO }
#define PINCONFS_SPI1A_SPI0 { PINCONF_SPI1_CS_X_SPI0_CS_X, PINCONF_SPI1_SCK_SPI0_SCK, \
PINCONF_SPI1_IO0_SPI0_MOSI, PINCONF_SPI1_IO1_SPI0_MISO }
#define PINCONFS_SPI1_GPIO { PINCONF_SPI1_CS_X_GPIO, PINCONF_SPI1_SCK_GPIO, PINCONF_SPI1_IO0_GPIO, \
PINCONF_SPI1_IO1_GPIO, PINCONF_SPI1_IO2_GPIO, PINCONF_SPI1_IO3_GPIO }
#define PINCONFS_SPI1 { PINCONF_SPI1_CS_X, PINCONF_SPI1_SCK, PINCONF_SPI1_IO0, \
PINCONF_SPI1_IO1, PINCONF_SPI1_IO2, PINCONF_SPI1_IO3 }
#define PINCONFS_SPI2A_GPIO { PINCONF_SPI2_CS_X_GPIO, PINCONF_SPI2_SCK_GPIO }
#define PINCONFS_SPI2B_GPIO { PINCONF_SPI2_MOSI_GPIO, PINCONF_SPI2_MISO_GPIO }
#define PINCONFS_SPI2A_UART0 { PINCONF_SPI2_CS_X_UART0_TXD, PINCONF_SPI2_SCK_UART0_RXD }
#define PINCONFS_SPI2B_UART0 { PINCONF_SPI2_MOSI_UART0_CTS, PINCONF_SPI2_MISO_UART0_RTS }
#define PINCONFS_SPI2A_I2C3 { PINCONF_SPI2_CS_X_I2C3_BCK, PINCONF_SPI2_SCK_I2C3_BDT }
#define PINCONFS_SPI2_GPIO { PINCONF_SPI2_CS_X_GPIO, PINCONF_SPI2_SCK_GPIO, \
PINCONF_SPI2_MOSI_GPIO, PINCONF_SPI2_MISO_GPIO }
#define PINCONFS_SPI2 { PINCONF_SPI2_CS_X, PINCONF_SPI2_SCK, \
PINCONF_SPI2_MOSI, PINCONF_SPI2_MISO }
#define PINCONFS_SPI2_UART0 { PINCONF_SPI2_CS_X_UART0_TXD, PINCONF_SPI2_SCK_UART0_RXD, \
PINCONF_SPI2_MOSI_UART0_CTS, PINCONF_SPI2_MISO_UART0_RTS }
#define PINCONFS_HIF_IRQ_OUT_GPIO { PINCONF_HIF_IRQ_OUT_GPIO }
#define PINCONFS_HIF_IRQ_OUT { PINCONF_HIF_IRQ_OUT }
#define PINCONFS_HIF_IRQ_OUT_OD { PINCONF_HIF_IRQ_OUT_OD }
#define PINCONFS_HIF_IRQ_OUT_GNSS_1PPS_OUT { PINCONF_HIF_IRQ_OUT_GNSS_1PPS_OUT }
#ifdef CONFIG_CXD56_FCBGA
#define PINCONFS_HIF_GPIO0_GPIO { PINCONF_HIF_GPIO0_GPIO }
#define PINCONFS_HIF_GPIO0_GPS_EXTLD { PINCONF_HIF_GPIO0_GPS_EXTLD }
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONFS_SEN_IRQ_IN_GPIO { PINCONF_SEN_IRQ_IN_GPIO }
#define PINCONFS_SEN_IRQ_IN { PINCONF_SEN_IRQ_IN }
#define PINCONFS_SPI3_CS0_X_GPIO { PINCONF_SPI3_CS0_X_GPIO }
#define PINCONFS_SPI3_CS0_X { PINCONF_SPI3_CS0_X }
#define PINCONFS_SPI3_CS1_X_GPIO { PINCONF_SPI3_CS1_X_GPIO }
#define PINCONFS_SPI3_CS1_X { PINCONF_SPI3_CS1_X }
#define PINCONFS_SPI3_CS2_X_GPIO { PINCONF_SPI3_CS2_X_GPIO }
#define PINCONFS_SPI3_CS2_X { PINCONF_SPI3_CS2_X }
#define PINCONFS_SPI3_GPIO { PINCONF_SPI3_SCK_GPIO, \
PINCONF_SPI3_MOSI_GPIO, PINCONF_SPI3_MISO_GPIO }
#define PINCONFS_SPI3 { PINCONF_SPI3_SCK, \
PINCONF_SPI3_MOSI, PINCONF_SPI3_MISO }
#define PINCONFS_I2C0_GPIO { PINCONF_I2C0_BCK_GPIO, PINCONF_I2C0_BDT_GPIO }
#define PINCONFS_I2C0 { PINCONF_I2C0_BCK, PINCONF_I2C0_BDT }
#define PINCONFS_PWMA_GPIO { PINCONF_PWM0_GPIO, PINCONF_PWM1_GPIO }
#define PINCONFS_PWMA { PINCONF_PWM0, PINCONF_PWM1 }
#define PINCONFS_PWMB_GPIO { PINCONF_PWM2_GPIO, PINCONF_PWM3_GPIO }
#define PINCONFS_PWMB { PINCONF_PWM2, PINCONF_PWM3 }
#define PINCONFS_PWMB_I2C1 { PINCONF_PWM2_I2C1_BCK, PINCONF_PWM3_I2C1_BDT }
#ifdef CONFIG_CXD56_FCBGA
#define PINCONFS_IS_GPIO { PINCONF_IS_CLK_GPIO, PINCONF_IS_VSYNC_GPIO, PINCONF_IS_HSYNC_GPIO, \
PINCONF_IS_DATA0_GPIO, PINCONF_IS_DATA1_GPIO, PINCONF_IS_DATA2_GPIO, \
PINCONF_IS_DATA3_GPIO, PINCONF_IS_DATA4_GPIO, PINCONF_IS_DATA5_GPIO, \
PINCONF_IS_DATA6_GPIO, PINCONF_IS_DATA7_GPIO }
#define PINCONFS_IS { PINCONF_IS_CLK, PINCONF_IS_VSYNC, PINCONF_IS_HSYNC, \
PINCONF_IS_DATA0, PINCONF_IS_DATA1, PINCONF_IS_DATA2, \
PINCONF_IS_DATA3, PINCONF_IS_DATA4, PINCONF_IS_DATA5, \
PINCONF_IS_DATA6, PINCONF_IS_DATA7 }
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONFS_UART2_GPIO { PINCONF_UART2_TXD_GPIO, PINCONF_UART2_RXD_GPIO, \
PINCONF_UART2_CTS_GPIO, PINCONF_UART2_RTS_GPIO }
#define PINCONFS_UART2 { PINCONF_UART2_TXD, PINCONF_UART2_RXD, \
PINCONF_UART2_CTS, PINCONF_UART2_RTS }
#define PINCONFS_SPI4_GPIO { PINCONF_SPI4_CS_X_GPIO, PINCONF_SPI4_SCK_GPIO, \
PINCONF_SPI4_MOSI_GPIO, PINCONF_SPI4_MISO_GPIO }
#define PINCONFS_SPI4 { PINCONF_SPI4_CS_X, PINCONF_SPI4_SCK, \
PINCONF_SPI4_MOSI, PINCONF_SPI4_MISO }
#define PINCONFS_EMMCA_GPIO { PINCONF_EMMC_CLK_GPIO, PINCONF_EMMC_CMD_GPIO, \
PINCONF_EMMC_DATA0_GPIO, PINCONF_EMMC_DATA1_GPIO }
#define PINCONFS_EMMCB_GPIO { PINCONF_EMMC_DATA2_GPIO, PINCONF_EMMC_DATA3_GPIO }
#define PINCONFS_EMMCA_SPI5 { PINCONF_EMMC_CLK_SPI5_SCK, PINCONF_EMMC_CMD_SPI5_CS_X, \
PINCONF_EMMC_DATA0_SPI5_MOSI, PINCONF_EMMC_DATA1_SPI5_MISO }
#define PINCONFS_EMMC_GPIO { PINCONF_EMMC_CLK_GPIO, PINCONF_EMMC_CMD_GPIO, \
PINCONF_EMMC_DATA0_GPIO, PINCONF_EMMC_DATA1_GPIO, \
PINCONF_EMMC_DATA2_GPIO, PINCONF_EMMC_DATA3_GPIO }
#define PINCONFS_EMMC { PINCONF_EMMC_CLK, PINCONF_EMMC_CMD, \
PINCONF_EMMC_DATA0, PINCONF_EMMC_DATA1, \
PINCONF_EMMC_DATA2, PINCONF_EMMC_DATA3 }
#ifdef CONFIG_CXD56_FCBGA
#define PINCONFS_SDIOA_GPIO { PINCONF_SDIO_CLK_GPIO, PINCONF_SDIO_CMD_GPIO, \
PINCONF_SDIO_DATA0_GPIO, PINCONF_SDIO_DATA1_GPIO, \
PINCONF_SDIO_DATA2_GPIO, PINCONF_SDIO_DATA3_GPIO }
#define PINCONFS_SDIOA_SDIO { PINCONF_SDIO_CLK, PINCONF_SDIO_CMD, \
PINCONF_SDIO_DATA0, PINCONF_SDIO_DATA1, \
PINCONF_SDIO_DATA2, PINCONF_SDIO_DATA3 }
#define PINCONFS_SDIOA_SDCARD { PINCONF_SDIO_CLK_SDCARD, PINCONF_SDIO_CMD, \
PINCONF_SDIO_DATA0, PINCONF_SDIO_DATA1, \
PINCONF_SDIO_DATA2, PINCONF_SDIO_DATA3 }
#define PINCONFS_SDIOA_SPI5 { PINCONF_SDIO_CLK_SPI5_SCK, PINCONF_SDIO_CMD_SPI5_CS_X, \
PINCONF_SDIO_DATA0_SPI5_MOSI, PINCONF_SDIO_DATA1_SPI5_MISO, \
PINCONF_SDIO_DATA2_SPI5_GPIO, PINCONF_SDIO_DATA3_SPI5_GPIO }
#define PINCONFS_SDIOB_GPIO { PINCONF_SDIO_CD_GPIO, PINCONF_SDIO_WP_GPIO }
#define PINCONFS_SDIOB_SDCARD { PINCONF_SDIO_CD, PINCONF_SDIO_WP }
#define PINCONFS_SDIOC_GPIO { PINCONF_SDIO_CMDDIR_GPIO, PINCONF_SDIO_DIR0_GPIO, PINCONF_SDIO_DIR1_3_GPIO }
#define PINCONFS_SDIOC_SDIO { PINCONF_SDIO_CMDDIR, PINCONF_SDIO_DIR0, PINCONF_SDIO_DIR1_3 }
#define PINCONFS_SDIOD_GPIO { PINCONF_SDIO_CLKI_GPIO }
#define PINCONFS_SDIOD_SDIO { PINCONF_SDIO_CLKI }
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONFS_I2S0_GPIO { PINCONF_I2S0_BCK_GPIO, PINCONF_I2S0_LRCK_GPIO, \
PINCONF_I2S0_DATA_IN_GPIO, PINCONF_I2S0_DATA_OUT_GPIO }
#define PINCONFS_I2S0_M_HIGH { PINCONF_I2S0_BCK_M_HIGH, PINCONF_I2S0_LRCK_M_HIGH, \
PINCONF_I2S0_DATA_IN, PINCONF_I2S0_DATA_OUT_HIGH }
#define PINCONFS_I2S0_M_NORM { PINCONF_I2S0_BCK_M_NORM, PINCONF_I2S0_LRCK_M_NORM, \
PINCONF_I2S0_DATA_IN, PINCONF_I2S0_DATA_OUT_NORM }
#define PINCONFS_I2S0_S_HIGH { PINCONF_I2S0_BCK_S, PINCONF_I2S0_LRCK_S, \
PINCONF_I2S0_DATA_IN, PINCONF_I2S0_DATA_OUT_HIGH }
#define PINCONFS_I2S0_S_NORM { PINCONF_I2S0_BCK_S, PINCONF_I2S0_LRCK_S, \
PINCONF_I2S0_DATA_IN, PINCONF_I2S0_DATA_OUT_NORM }
#ifdef CONFIG_CXD56_FCBGA
#define PINCONFS_I2S1_GPIO { PINCONF_I2S1_BCK_GPIO, PINCONF_I2S1_LRCK_GPIO, \
PINCONF_I2S1_DATA_IN_GPIO, PINCONF_I2S1_DATA_OUT_GPIO }
#define PINCONFS_I2S1_M_HIGH { PINCONF_I2S1_BCK_M_HIGH, PINCONF_I2S1_LRCK_M_HIGH, \
PINCONF_I2S1_DATA_IN, PINCONF_I2S1_DATA_OUT_HIGH }
#define PINCONFS_I2S1_M_NORM { PINCONF_I2S1_BCK_M_NORM, PINCONF_I2S1_LRCK_M_NORM, \
PINCONF_I2S1_DATA_IN, PINCONF_I2S1_DATA_OUT_NORM }
#define PINCONFS_I2S1_S_HIGH { PINCONF_I2S1_BCK_S, PINCONF_I2S1_LRCK_S, \
PINCONF_I2S1_DATA_IN, PINCONF_I2S1_DATA_OUT_HIGH }
#define PINCONFS_I2S1_S_NORM { PINCONF_I2S1_BCK_S, PINCONF_I2S1_LRCK_S, \
PINCONF_I2S1_DATA_IN, PINCONF_I2S1_DATA_OUT_NORM }
#endif /* CONFIG_CXD56_FCBGA */
#define PINCONFS_MCLK_GPIO { PINCONF_MCLK_GPIO }
#define PINCONFS_MCLK { PINCONF_MCLK }
#define PINCONFS_PDM_GPIO { PINCONF_PDM_CLK_GPIO, PINCONF_PDM_IN_GPIO, PINCONF_PDM_OUT_GPIO }
#define PINCONFS_PDM_HIGH { PINCONF_PDM_CLK_HIGH, PINCONF_PDM_IN, PINCONF_PDM_OUT_HIGH }
#define PINCONFS_PDM_NORM { PINCONF_PDM_CLK_NORM, PINCONF_PDM_IN, PINCONF_PDM_OUT_NORM }
#define PINCONFS_USB_VBUSINT_GPIO { PINCONF_USB_VBUSINT_GPIO }
#define PINCONFS_USB_VBUSINT { PINCONF_USB_VBUSINT }
#ifdef CONFIG_BOARD_CUSTOM_PINCONFIG
/* Change the pin configuration depending on each board */
# include <arch/board/board_pinconfig.h>
#endif /* CONFIG_BOARD_CUSTOM_PINCONFIG */
#endif /* __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_PINCONFIG_H */

View File

@ -0,0 +1,718 @@
/****************************************************************************
* arch/arm/src/cxd56xx/hardware/cxd5602_topreg.h
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_TOPREG_H
#define __ARCH_ARM_SRC_CXD56XX_CHIP_CXD5602_TOPREG_H
/********************************************************************************************
* Included Files
********************************************************************************************/
#include <nuttx/config.h>
/********************************************************************************************
* Pre-processor Definitions
********************************************************************************************/
#define CXD56_TOPREG_PWD_CTL (CXD56_TOPREG_BASE + 0x0)
#define CXD56_TOPREG_ANA_PW_CTL (CXD56_TOPREG_BASE + 0x4)
#define CXD56_TOPREG_ANA_EN_CTL (CXD56_TOPREG_BASE + 0x8)
#define CXD56_TOPREG_SYSCPU_RAMMODE_SEL (CXD56_TOPREG_BASE + 0x10)
#define CXD56_TOPREG_TOP_SCU_RAMMODE_SEL (CXD56_TOPREG_BASE + 0x18)
#define CXD56_TOPREG_HOSTIFC_RAMMODE_SEL (CXD56_TOPREG_BASE + 0x1c)
#define CXD56_TOPREG_PMU_FAST (CXD56_TOPREG_BASE + 0x20)
#define CXD56_TOPREG_PMU_PW_CTL (CXD56_TOPREG_BASE + 0x30)
#define CXD56_TOPREG_PMU_INT_STAT (CXD56_TOPREG_BASE + 0x40)
#define CXD56_TOPREG_PMU_RAW_INT_STAT (CXD56_TOPREG_BASE + 0x44)
#define CXD56_TOPREG_PMU_INT_CLR (CXD56_TOPREG_BASE + 0x48)
#define CXD56_TOPREG_PMU_INT_MASK (CXD56_TOPREG_BASE + 0x4c)
#define CXD56_TOPREG_PWD_RESET0 (CXD56_TOPREG_BASE + 0x60)
#define CXD56_TOPREG_PMU_DBG (CXD56_TOPREG_BASE + 0x70)
#define CXD56_TOPREG_PMU_TIMEOUT_CTL0 (CXD56_TOPREG_BASE + 0x74)
#define CXD56_TOPREG_PMU_TIMEOUT_CTL1 (CXD56_TOPREG_BASE + 0x78)
#define CXD56_TOPREG_PMU_TIMEOUT_CTL2 (CXD56_TOPREG_BASE + 0x7c)
#define CXD56_TOPREG_PMU_FSM (CXD56_TOPREG_BASE + 0x80)
#define CXD56_TOPREG_PMU_PW_STAT (CXD56_TOPREG_BASE + 0x84)
#define CXD56_TOPREG_PMU_WAIT0 (CXD56_TOPREG_BASE + 0x88)
#define CXD56_TOPREG_PMU_WAIT1 (CXD56_TOPREG_BASE + 0x8c)
#define CXD56_TOPREG_PMU_WAIT2 (CXD56_TOPREG_BASE + 0x90)
#define CXD56_TOPREG_PMU_WAIT3 (CXD56_TOPREG_BASE + 0x94)
#define CXD56_TOPREG_PMU_WAIT4 (CXD56_TOPREG_BASE + 0x98)
#define CXD56_TOPREG_PMU_WAIT5 (CXD56_TOPREG_BASE + 0x9c)
#define CXD56_TOPREG_PMU_WAIT6 (CXD56_TOPREG_BASE + 0xa0)
#define CXD56_TOPREG_PMU_WAIT7 (CXD56_TOPREG_BASE + 0xa4)
#define CXD56_TOPREG_PMU_WAIT8 (CXD56_TOPREG_BASE + 0xa8)
#define CXD56_TOPREG_PMU_WAIT9 (CXD56_TOPREG_BASE + 0xac)
#define CXD56_TOPREG_PMU_DBG_INITEN (CXD56_TOPREG_BASE + 0xb0)
#define CXD56_TOPREG_PMU_DBG_ON_ORDER0 (CXD56_TOPREG_BASE + 0xb4)
#define CXD56_TOPREG_PMU_DBG_ON_ORDER1 (CXD56_TOPREG_BASE + 0xb8)
#define CXD56_TOPREG_PMU_DBG_ON_ORDER2 (CXD56_TOPREG_BASE + 0xbc)
#define CXD56_TOPREG_PMU_DBG_ON_ORDER3 (CXD56_TOPREG_BASE + 0xc0)
#define CXD56_TOPREG_PMU_DBG_ON_ORDER4 (CXD56_TOPREG_BASE + 0xc4)
#define CXD56_TOPREG_PMU_DBG_ON_ORDER5 (CXD56_TOPREG_BASE + 0xc8)
#define CXD56_TOPREG_PMU_DBG_ON_ORDER6 (CXD56_TOPREG_BASE + 0xcc)
#define CXD56_TOPREG_PMU_DBG_ON_ORDER7 (CXD56_TOPREG_BASE + 0xd0)
#define CXD56_TOPREG_PMU_DBG_OFF_ORDER0 (CXD56_TOPREG_BASE + 0xd4)
#define CXD56_TOPREG_PMU_DBG_OFF_ORDER1 (CXD56_TOPREG_BASE + 0xd8)
#define CXD56_TOPREG_PMU_DBG_OFF_ORDER2 (CXD56_TOPREG_BASE + 0xdc)
#define CXD56_TOPREG_PMU_DBG_OFF_ORDER3 (CXD56_TOPREG_BASE + 0xe0)
#define CXD56_TOPREG_PMU_DBG_OFF_ORDER4 (CXD56_TOPREG_BASE + 0xe4)
#define CXD56_TOPREG_PMU_DBG_OFF_ORDER5 (CXD56_TOPREG_BASE + 0xe8)
#define CXD56_TOPREG_PMU_DBG_OFF_ORDER6 (CXD56_TOPREG_BASE + 0xec)
#define CXD56_TOPREG_PMU_DBG_OFF_ORDER7 (CXD56_TOPREG_BASE + 0xf0)
#define CXD56_TOPREG_PMU_DBG_LUMPEN (CXD56_TOPREG_BASE + 0xf4)
#define CXD56_TOPREG_PMU_DBG_ADD (CXD56_TOPREG_BASE + 0xfc)
#define CXD56_TOPREG_PMU_DBG_ADD_WAIT0 (CXD56_TOPREG_BASE + 0x100)
#define CXD56_TOPREG_PMU_DBG_ADD_WAIT1 (CXD56_TOPREG_BASE + 0x104)
#define CXD56_TOPREG_PWD_STAT (CXD56_TOPREG_BASE + 0x200)
#define CXD56_TOPREG_PWD_PGACK_STAT (CXD56_TOPREG_BASE + 0x204)
#define CXD56_TOPREG_ANA_PW_STAT (CXD56_TOPREG_BASE + 0x208)
#define CXD56_TOPREG_SYSCPU_RAMMODE_STAT (CXD56_TOPREG_BASE + 0x20c)
#define CXD56_TOPREG_TOP_SCU_RAMMODE_STAT (CXD56_TOPREG_BASE + 0x214)
#define CXD56_TOPREG_HOSTIFC_RAMMODE_STAT (CXD56_TOPREG_BASE + 0x218)
#define CXD56_TOPREG_PMU_HW_STAT (CXD56_TOPREG_BASE + 0x21c)
#define CXD56_TOPREG_YOBI2_0 (CXD56_TOPREG_BASE + 0x230)
#define CXD56_TOPREG_ANA_PW_CTL_SEL_WAKE (CXD56_TOPREG_BASE + 0x400)
#define CXD56_TOPREG_SYSCPU_RAMMODE_SEL_WAKE (CXD56_TOPREG_BASE + 0x404)
#define CXD56_TOPREG_TOP_SCU_RAMMODE_SEL_WAKE (CXD56_TOPREG_BASE + 0x410)
#define CXD56_TOPREG_CLSELDIV_WAKE (CXD56_TOPREG_BASE + 0x414)
#define CXD56_TOPREG_CKDIV_CPU_DSP_BUS_WAKE (CXD56_TOPREG_BASE + 0x418)
#define CXD56_TOPREG_CKSEL_ROOT_WAKE (CXD56_TOPREG_BASE + 0x41c)
#define CXD56_TOPREG_PMIC_SLEEP_I2C0 (CXD56_TOPREG_BASE + 0x420)
#define CXD56_TOPREG_PMIC_SLEEP_I2C1 (CXD56_TOPREG_BASE + 0x424)
#define CXD56_TOPREG_PMIC_SLEEP_I2C2 (CXD56_TOPREG_BASE + 0x428)
#define CXD56_TOPREG_PMIC_SLEEP_I2C3 (CXD56_TOPREG_BASE + 0x42c)
#define CXD56_TOPREG_PMIC_WAKE_I2C0 (CXD56_TOPREG_BASE + 0x430)
#define CXD56_TOPREG_PMIC_WAKE_I2C1 (CXD56_TOPREG_BASE + 0x434)
#define CXD56_TOPREG_PMIC_WAKE_I2C2 (CXD56_TOPREG_BASE + 0x438)
#define CXD56_TOPREG_PMIC_WAKE_I2C3 (CXD56_TOPREG_BASE + 0x43c)
#define CXD56_TOPREG_PMIC_UNEXP_I2C0 (CXD56_TOPREG_BASE + 0x440)
#define CXD56_TOPREG_PMIC_UNEXP_I2C1 (CXD56_TOPREG_BASE + 0x444)
#define CXD56_TOPREG_PMIC_UNEXP_I2C2 (CXD56_TOPREG_BASE + 0x448)
#define CXD56_TOPREG_PMIC_UNEXP_I2C3 (CXD56_TOPREG_BASE + 0x44c)
#define CXD56_TOPREG_PMIC_UNEXP_I2C (CXD56_TOPREG_BASE + 0x450)
#define CXD56_TOPREG_PMU_WAKE_TRIG_EN0 (CXD56_TOPREG_BASE + 0x454)
#define CXD56_TOPREG_PMU_WAKE_TRIG_EN1 (CXD56_TOPREG_BASE + 0x458)
#define CXD56_TOPREG_PMU_WAKE_TRIG_NEGEN0 (CXD56_TOPREG_BASE + 0x45c)
#define CXD56_TOPREG_PMU_WAKE_TRIG_NEGEN1 (CXD56_TOPREG_BASE + 0x460)
#define CXD56_TOPREG_PMU_WAKE_TRIG_NOISECUTEN0 (CXD56_TOPREG_BASE + 0x464)
#define CXD56_TOPREG_PMU_WAKE_TRIG_CPUINTSEL0 (CXD56_TOPREG_BASE + 0x468)
#define CXD56_TOPREG_PMU_WAKE_TRIG_CPUINTSEL1 (CXD56_TOPREG_BASE + 0x46c)
#define CXD56_TOPREG_PMU_WAKE_TRIG_CPUINTSEL2 (CXD56_TOPREG_BASE + 0x470)
#define CXD56_TOPREG_PMU_WAKE_TRIG_INTDET0 (CXD56_TOPREG_BASE + 0x474)
#define CXD56_TOPREG_PMU_WAKE_TRIG_INTDET1 (CXD56_TOPREG_BASE + 0x478)
#define CXD56_TOPREG_PMU_WAKE_TRIG_INTDET2 (CXD56_TOPREG_BASE + 0x47c)
#define CXD56_TOPREG_PMU_WAKE_PMIC_I2C (CXD56_TOPREG_BASE + 0x480)
#define CXD56_TOPREG_BOOT_CAUSE (CXD56_TOPREG_BASE + 0x484)
#define CXD56_TOPREG_PMU_CORE_CKEN (CXD56_TOPREG_BASE + 0x4c0)
#define CXD56_TOPREG_CKSEL_ROOT (CXD56_TOPREG_BASE + 0x4c4)
#define CXD56_TOPREG_CKSEL_PMU (CXD56_TOPREG_BASE + 0x4c8)
#define CXD56_TOPREG_CKSEL_SYSIOP (CXD56_TOPREG_BASE + 0x4cc)
#define CXD56_TOPREG_CKSEL_SYSIOP_SUB (CXD56_TOPREG_BASE + 0x4d0)
#define CXD56_TOPREG_CKSEL_SCU (CXD56_TOPREG_BASE + 0x4d4)
#define CXD56_TOPREG_CKDIV_CPU_DSP_BUS (CXD56_TOPREG_BASE + 0x4d8)
#define CXD56_TOPREG_CKDIV_COM (CXD56_TOPREG_BASE + 0x4dc)
#define CXD56_TOPREG_CKDIV_HOSTIFC (CXD56_TOPREG_BASE + 0x4e0)
#define CXD56_TOPREG_CKDIV_SCU (CXD56_TOPREG_BASE + 0x4e4)
#define CXD56_TOPREG_CKDIV_PMU (CXD56_TOPREG_BASE + 0x4e8)
#define CXD56_TOPREG_CRG_INT_CLR0 (CXD56_TOPREG_BASE + 0x4ec)
#define CXD56_TOPREG_CRG_INT_MASK0 (CXD56_TOPREG_BASE + 0x4f0)
#define CXD56_TOPREG_CRG_INT_STAT_MSK0 (CXD56_TOPREG_BASE + 0x4f4)
#define CXD56_TOPREG_CRG_INT_STAT_RAW0 (CXD56_TOPREG_BASE + 0x4f8)
#define CXD56_TOPREG_CRG_INT_CLR1 (CXD56_TOPREG_BASE + 0x4fc)
#define CXD56_TOPREG_CRG_INT_MASK1 (CXD56_TOPREG_BASE + 0x500)
#define CXD56_TOPREG_CRG_INT_STAT_MSK1 (CXD56_TOPREG_BASE + 0x504)
#define CXD56_TOPREG_CRG_INT_STAT_RAW1 (CXD56_TOPREG_BASE + 0x508)
#define CXD56_TOPREG_CPU_GATECLK (CXD56_TOPREG_BASE + 0x50c)
#define CXD56_TOPREG_USBPHY_CKEN (CXD56_TOPREG_BASE + 0x510)
#define CXD56_TOPREG_CRG_MON (CXD56_TOPREG_BASE + 0x514)
#define CXD56_TOPREG_GEAR_STAT (CXD56_TOPREG_BASE + 0x518)
#define CXD56_TOPREG_XOSC_CTRL (CXD56_TOPREG_BASE + 0x580)
#define CXD56_TOPREG_XOSC_CTRL2 (CXD56_TOPREG_BASE + 0x584)
#define CXD56_TOPREG_SYS_PLL_CTRL1 (CXD56_TOPREG_BASE + 0x588)
#define CXD56_TOPREG_SYS_PLL_CTRL2 (CXD56_TOPREG_BASE + 0x58c)
#define CXD56_TOPREG_RCOSC_CTRL1 (CXD56_TOPREG_BASE + 0x590)
#define CXD56_TOPREG_RCOSC_CTRL2 (CXD56_TOPREG_BASE + 0x594)
#define CXD56_TOPREG_RF_GPMBI_EN (CXD56_TOPREG_BASE + 0x598)
#define CXD56_TOPREG_BUSPROT_SDMAC (CXD56_TOPREG_BASE + 0x5c0)
#define CXD56_TOPREG_BUSPROT_HDMAC (CXD56_TOPREG_BASE + 0x5c4)
#define CXD56_TOPREG_BUSPROT_SYDMAC (CXD56_TOPREG_BASE + 0x5c8)
#define CXD56_TOPREG_BUSPROT_SYSUBDMAC (CXD56_TOPREG_BASE + 0x5cc)
#define CXD56_TOPREG_BUSPROT_SAKE (CXD56_TOPREG_BASE + 0x5d0)
#define CXD56_TOPREG_BUSPROT_KAKI (CXD56_TOPREG_BASE + 0x5d4)
#define CXD56_TOPREG_BUSPROT_BKUPSRAM (CXD56_TOPREG_BASE + 0x5d8)
#define CXD56_TOPREG_BUSPROT_SPIFLAIF (CXD56_TOPREG_BASE + 0x5dc)
#define CXD56_TOPREG_BUSPROT_TOPREG_0 (CXD56_TOPREG_BASE + 0x5e0)
#define CXD56_TOPREG_BUSPROT_TOPREG_1 (CXD56_TOPREG_BASE + 0x5e4)
#define CXD56_TOPREG_BUSPROT_TOPREG_2 (CXD56_TOPREG_BASE + 0x5e8)
#define CXD56_TOPREG_BUSPROT_TOPREG_3 (CXD56_TOPREG_BASE + 0x5ec)
#define CXD56_TOPREG_BUSPROT_TOPREG_4 (CXD56_TOPREG_BASE + 0x5f0)
#define CXD56_TOPREG_GPIO_PROT_0 (CXD56_TOPREG_BASE + 0x5f4)
#define CXD56_TOPREG_GPIO_PROT_1 (CXD56_TOPREG_BASE + 0x5f8)
#define CXD56_TOPREG_GPIO_PROT_2 (CXD56_TOPREG_BASE + 0x5fc)
#define CXD56_TOPREG_GPIO_PROT_3 (CXD56_TOPREG_BASE + 0x600)
#define CXD56_TOPREG_BUSPROT_CHECKER (CXD56_TOPREG_BASE + 0x610)
#define CXD56_TOPREG_WDT_SRST_EN (CXD56_TOPREG_BASE + 0x640)
#define CXD56_TOPREG_FORCE_CKEN (CXD56_TOPREG_BASE + 0x644)
#define CXD56_TOPREG_SDEBUG_PASS_BYPASS (CXD56_TOPREG_BASE + 0x648)
#define CXD56_TOPREG_SDEBUG_CTRL (CXD56_TOPREG_BASE + 0x64c)
#define CXD56_TOPREG_DBG_HOSTIF_SEL (CXD56_TOPREG_BASE + 0x650)
#define CXD56_TOPREG_WDT_MASK (CXD56_TOPREG_BASE + 0x654)
#define CXD56_TOPREG_CKGATE_CTL (CXD56_TOPREG_BASE + 0x660)
#define CXD56_TOPREG_M0_BOOT_MODE (CXD56_TOPREG_BASE + 0x680)
#define CXD56_TOPREG_M0_BOOT_MODE_EN (CXD56_TOPREG_BASE + 0x684)
#define CXD56_TOPREG_M0_BOOT_ENTRY_POINT (CXD56_TOPREG_BASE + 0x688)
#define CXD56_TOPREG_M0_BOOT_MODE_EXT (CXD56_TOPREG_BASE + 0x690)
#define CXD56_TOPREG_M0_BOOT_REC (CXD56_TOPREG_BASE + 0x694)
#define CXD56_TOPREG_I2CRPT_SADR (CXD56_TOPREG_BASE + 0x6c0)
#define CXD56_TOPREG_I2CRPT_REP (CXD56_TOPREG_BASE + 0x6c4)
#define CXD56_TOPREG_PMIC_I2C (CXD56_TOPREG_BASE + 0x6d0)
#define CXD56_TOPREG_RAMMODE (CXD56_TOPREG_BASE + 0x6e4)
#define CXD56_TOPREG_SWRESET_BUS (CXD56_TOPREG_BASE + 0x700)
#define CXD56_TOPREG_SWRESET_SCU (CXD56_TOPREG_BASE + 0x704)
#define CXD56_TOPREG_BUSROM_CKEN (CXD56_TOPREG_BASE + 0x710)
#define CXD56_TOPREG_SYSIOP_CKEN (CXD56_TOPREG_BASE + 0x714)
#define CXD56_TOPREG_SCU_CKEN (CXD56_TOPREG_BASE + 0x71c)
#define CXD56_TOPREG_RTC0_CTL (CXD56_TOPREG_BASE + 0x730)
#define CXD56_TOPREG_FUSERDCFG0 (CXD56_TOPREG_BASE + 0x740)
#define CXD56_TOPREG_FUSERDCFG1 (CXD56_TOPREG_BASE + 0x744)
#define CXD56_TOPREG_FUSERDCFG2 (CXD56_TOPREG_BASE + 0x748)
#define CXD56_TOPREG_VID0 (CXD56_TOPREG_BASE + 0x750)
#define CXD56_TOPREG_VID1 (CXD56_TOPREG_BASE + 0x754)
#define CXD56_TOPREG_M0_BOOT_FLASH_DIS (CXD56_TOPREG_BASE + 0x758)
#define CXD56_TOPREG_LDOADJ0 (CXD56_TOPREG_BASE + 0x760)
#define CXD56_TOPREG_LDOADJ1 (CXD56_TOPREG_BASE + 0x764)
#define CXD56_TOPREG_FQFIX_CTL0 (CXD56_TOPREG_BASE + 0x770)
#define CXD56_TOPREG_FQFIX_AUTO (CXD56_TOPREG_BASE + 0x774)
#define CXD56_TOPREG_FQFIX_SINGLE (CXD56_TOPREG_BASE + 0x778)
#define CXD56_TOPREG_FQFIX_STATUS (CXD56_TOPREG_BASE + 0x77c)
#define CXD56_TOPREG_SYSTEM_CONFIG (CXD56_TOPREG_BASE + 0x790)
#define CXD56_TOPREG_MON_SEL (CXD56_TOPREG_BASE + 0x7a0)
#define CXD56_TOPREG_IOCSYS_MONSEL0 (CXD56_TOPREG_BASE + 0x7a4)
#define CXD56_TOPREG_IOCSYS_MONSEL1 (CXD56_TOPREG_BASE + 0x7a8)
#define CXD56_TOPREG_IOCSYS_INTSEL0 (CXD56_TOPREG_BASE + 0x7b0)
#define CXD56_TOPREG_IOCSYS_INTSEL1 (CXD56_TOPREG_BASE + 0x7b4)
#define CXD56_TOPREG_IOCSYS_IOMD0 (CXD56_TOPREG_BASE + 0x7c0)
#define CXD56_TOPREG_IOCSYS_IOMD1 (CXD56_TOPREG_BASE + 0x7c4)
#define CXD56_TOPREG_IOOEN_SYS (CXD56_TOPREG_BASE + 0x7e0)
#define CXD56_TOPREG_IO_RTC_CLK_IN (CXD56_TOPREG_BASE + 0x800)
#define CXD56_TOPREG_IO_I2C4_BCK (CXD56_TOPREG_BASE + 0x804)
#define CXD56_TOPREG_IO_I2C4_BDT (CXD56_TOPREG_BASE + 0x808)
#define CXD56_TOPREG_IO_PMIC_INT (CXD56_TOPREG_BASE + 0x80c)
#define CXD56_TOPREG_IO_RTC_IRQ_OUT (CXD56_TOPREG_BASE + 0x810)
#define CXD56_TOPREG_IO_AP_CLK (CXD56_TOPREG_BASE + 0x814)
#define CXD56_TOPREG_IO_GNSS_1PPS_OUT (CXD56_TOPREG_BASE + 0x818)
#define CXD56_TOPREG_IO_SPI0_CS_X (CXD56_TOPREG_BASE + 0x844)
#define CXD56_TOPREG_IO_SPI0_SCK (CXD56_TOPREG_BASE + 0x848)
#define CXD56_TOPREG_IO_SPI0_MOSI (CXD56_TOPREG_BASE + 0x84c)
#define CXD56_TOPREG_IO_SPI0_MISO (CXD56_TOPREG_BASE + 0x850)
#define CXD56_TOPREG_IO_SPI1_CS_X (CXD56_TOPREG_BASE + 0x854)
#define CXD56_TOPREG_IO_SPI1_SCK (CXD56_TOPREG_BASE + 0x858)
#define CXD56_TOPREG_IO_SPI1_IO0 (CXD56_TOPREG_BASE + 0x85c)
#define CXD56_TOPREG_IO_SPI1_IO1 (CXD56_TOPREG_BASE + 0x860)
#define CXD56_TOPREG_IO_SPI1_IO2 (CXD56_TOPREG_BASE + 0x864)
#define CXD56_TOPREG_IO_SPI1_IO3 (CXD56_TOPREG_BASE + 0x868)
#define CXD56_TOPREG_IO_SPI2_CS_X (CXD56_TOPREG_BASE + 0x86c)
#define CXD56_TOPREG_IO_SPI2_SCK (CXD56_TOPREG_BASE + 0x870)
#define CXD56_TOPREG_IO_SPI2_MOSI (CXD56_TOPREG_BASE + 0x874)
#define CXD56_TOPREG_IO_SPI2_MISO (CXD56_TOPREG_BASE + 0x878)
#define CXD56_TOPREG_IO_HIF_IRQ_OUT (CXD56_TOPREG_BASE + 0x87c)
#define CXD56_TOPREG_IO_HIF_GPIO0 (CXD56_TOPREG_BASE + 0x880)
#define CXD56_TOPREG_IO_SEN_IRQ_IN (CXD56_TOPREG_BASE + 0x894)
#define CXD56_TOPREG_IO_SPI3_CS0_X (CXD56_TOPREG_BASE + 0x898)
#define CXD56_TOPREG_IO_SPI3_CS1_X (CXD56_TOPREG_BASE + 0x89c)
#define CXD56_TOPREG_IO_SPI3_CS2_X (CXD56_TOPREG_BASE + 0x8a0)
#define CXD56_TOPREG_IO_SPI3_SCK (CXD56_TOPREG_BASE + 0x8a4)
#define CXD56_TOPREG_IO_SPI3_MOSI (CXD56_TOPREG_BASE + 0x8a8)
#define CXD56_TOPREG_IO_SPI3_MISO (CXD56_TOPREG_BASE + 0x8ac)
#define CXD56_TOPREG_IO_I2C0_BCK (CXD56_TOPREG_BASE + 0x8b0)
#define CXD56_TOPREG_IO_I2C0_BDT (CXD56_TOPREG_BASE + 0x8b4)
#define CXD56_TOPREG_IO_PWM0 (CXD56_TOPREG_BASE + 0x8b8)
#define CXD56_TOPREG_IO_PWM1 (CXD56_TOPREG_BASE + 0x8bc)
#define CXD56_TOPREG_IO_PWM2 (CXD56_TOPREG_BASE + 0x8c0)
#define CXD56_TOPREG_IO_PWM3 (CXD56_TOPREG_BASE + 0x8c4)
#define CXD56_TOPREG_IO_DBG_SWOCLK (CXD56_TOPREG_BASE + 0x8d4)
#define CXD56_TOPREG_IO_DBG_SWO (CXD56_TOPREG_BASE + 0x8d8)
#define CXD56_TOPREG_IO_IS_CLK (CXD56_TOPREG_BASE + 0x8e0)
#define CXD56_TOPREG_IO_IS_VSYNC (CXD56_TOPREG_BASE + 0x8e4)
#define CXD56_TOPREG_IO_IS_HSYNC (CXD56_TOPREG_BASE + 0x8e8)
#define CXD56_TOPREG_IO_IS_DATA0 (CXD56_TOPREG_BASE + 0x8ec)
#define CXD56_TOPREG_IO_IS_DATA1 (CXD56_TOPREG_BASE + 0x8f0)
#define CXD56_TOPREG_IO_IS_DATA2 (CXD56_TOPREG_BASE + 0x8f4)
#define CXD56_TOPREG_IO_IS_DATA3 (CXD56_TOPREG_BASE + 0x8f8)
#define CXD56_TOPREG_IO_IS_DATA4 (CXD56_TOPREG_BASE + 0x8fc)
#define CXD56_TOPREG_IO_IS_DATA5 (CXD56_TOPREG_BASE + 0x900)
#define CXD56_TOPREG_IO_IS_DATA6 (CXD56_TOPREG_BASE + 0x904)
#define CXD56_TOPREG_IO_IS_DATA7 (CXD56_TOPREG_BASE + 0x908)
#define CXD56_TOPREG_IO_UART2_TXD (CXD56_TOPREG_BASE + 0x90c)
#define CXD56_TOPREG_IO_UART2_RXD (CXD56_TOPREG_BASE + 0x910)
#define CXD56_TOPREG_IO_UART2_CTS (CXD56_TOPREG_BASE + 0x914)
#define CXD56_TOPREG_IO_UART2_RTS (CXD56_TOPREG_BASE + 0x918)
#define CXD56_TOPREG_IO_SPI4_CS_X (CXD56_TOPREG_BASE + 0x91c)
#define CXD56_TOPREG_IO_SPI4_SCK (CXD56_TOPREG_BASE + 0x920)
#define CXD56_TOPREG_IO_SPI4_MOSI (CXD56_TOPREG_BASE + 0x924)
#define CXD56_TOPREG_IO_SPI4_MISO (CXD56_TOPREG_BASE + 0x928)
#define CXD56_TOPREG_IO_EMMC_CLK (CXD56_TOPREG_BASE + 0x92c)
#define CXD56_TOPREG_IO_EMMC_CMD (CXD56_TOPREG_BASE + 0x930)
#define CXD56_TOPREG_IO_EMMC_DATA0 (CXD56_TOPREG_BASE + 0x934)
#define CXD56_TOPREG_IO_EMMC_DATA1 (CXD56_TOPREG_BASE + 0x938)
#define CXD56_TOPREG_IO_EMMC_DATA2 (CXD56_TOPREG_BASE + 0x93c)
#define CXD56_TOPREG_IO_EMMC_DATA3 (CXD56_TOPREG_BASE + 0x940)
#define CXD56_TOPREG_IO_SDIO_CLK (CXD56_TOPREG_BASE + 0x944)
#define CXD56_TOPREG_IO_SDIO_CMD (CXD56_TOPREG_BASE + 0x948)
#define CXD56_TOPREG_IO_SDIO_DATA0 (CXD56_TOPREG_BASE + 0x94c)
#define CXD56_TOPREG_IO_SDIO_DATA1 (CXD56_TOPREG_BASE + 0x950)
#define CXD56_TOPREG_IO_SDIO_DATA2 (CXD56_TOPREG_BASE + 0x954)
#define CXD56_TOPREG_IO_SDIO_DATA3 (CXD56_TOPREG_BASE + 0x958)
#define CXD56_TOPREG_IO_SDIO_CD (CXD56_TOPREG_BASE + 0x95c)
#define CXD56_TOPREG_IO_SDIO_WP (CXD56_TOPREG_BASE + 0x960)
#define CXD56_TOPREG_IO_SDIO_CMDDIR (CXD56_TOPREG_BASE + 0x964)
#define CXD56_TOPREG_IO_SDIO_DIR0 (CXD56_TOPREG_BASE + 0x968)
#define CXD56_TOPREG_IO_SDIO_DIR1_3 (CXD56_TOPREG_BASE + 0x96c)
#define CXD56_TOPREG_IO_SDIO_CLKI (CXD56_TOPREG_BASE + 0x970)
#define CXD56_TOPREG_IO_I2S0_BCK (CXD56_TOPREG_BASE + 0x974)
#define CXD56_TOPREG_IO_I2S0_LRCK (CXD56_TOPREG_BASE + 0x978)
#define CXD56_TOPREG_IO_I2S0_DATA_IN (CXD56_TOPREG_BASE + 0x97c)
#define CXD56_TOPREG_IO_I2S0_DATA_OUT (CXD56_TOPREG_BASE + 0x980)
#define CXD56_TOPREG_IO_I2S1_BCK (CXD56_TOPREG_BASE + 0x984)
#define CXD56_TOPREG_IO_I2S1_LRCK (CXD56_TOPREG_BASE + 0x988)
#define CXD56_TOPREG_IO_I2S1_DATA_IN (CXD56_TOPREG_BASE + 0x98c)
#define CXD56_TOPREG_IO_I2S1_DATA_OUT (CXD56_TOPREG_BASE + 0x990)
#define CXD56_TOPREG_IO_MCLK (CXD56_TOPREG_BASE + 0x994)
#define CXD56_TOPREG_IO_PDM_CLK (CXD56_TOPREG_BASE + 0x998)
#define CXD56_TOPREG_IO_PDM_IN (CXD56_TOPREG_BASE + 0x99c)
#define CXD56_TOPREG_IO_PDM_OUT (CXD56_TOPREG_BASE + 0x9a0)
#define CXD56_TOPREG_IO_USB_VBUSINT (CXD56_TOPREG_BASE + 0x9a4)
#define CXD56_TOPREG_FUSEWRST (CXD56_TOPREG_BASE + 0xa00)
#define CXD56_TOPREG_FUSEWRAD (CXD56_TOPREG_BASE + 0xa04)
#define CXD56_TOPREG_FUSEWRDT (CXD56_TOPREG_BASE + 0xa08)
#define CXD56_TOPREG_FUSEWRPG (CXD56_TOPREG_BASE + 0xa0c)
#define CXD56_TOPREG_YOBI2_1 (CXD56_TOPREG_BASE + 0xb00)
#define CXD56_TOPREG_GNSSDSP_RAMMODE_SEL (CXD56_TOPREG_BASE + 0xc00)
#define CXD56_TOPREG_CKSEL_GNSS_BB (CXD56_TOPREG_BASE + 0xc04)
#define CXD56_TOPREG_CKDIV_ITP (CXD56_TOPREG_BASE + 0xc0c)
#define CXD56_TOPREG_GNS_ITP_CKEN (CXD56_TOPREG_BASE + 0xc10)
#define CXD56_TOPREG_RF_CTRL (CXD56_TOPREG_BASE + 0xc20)
#define CXD56_TOPREG_GDSP_BOOT_ENTRY_POINT (CXD56_TOPREG_BASE + 0xc30)
#define CXD56_TOPREG_GNSSDSP_RAMMODE_STAT (CXD56_TOPREG_BASE + 0xc40)
#define CXD56_TOPREG_LOGGERIF (CXD56_TOPREG_BASE + 0xc50)
#define CXD56_TOPREG_YOBI2_2 (CXD56_TOPREG_BASE + 0xc60)
#define CXD56_TOPREG_ADSP1_BOOT_ENTRY_POINT (CXD56_TOPREG_BASE + 0x1010)
#define CXD56_TOPREG_ADSP2_BOOT_ENTRY_POINT (CXD56_TOPREG_BASE + 0x1014)
#define CXD56_TOPREG_ADSP3_BOOT_ENTRY_POINT (CXD56_TOPREG_BASE + 0x1018)
#define CXD56_TOPREG_ADSP4_BOOT_ENTRY_POINT (CXD56_TOPREG_BASE + 0x101c)
#define CXD56_TOPREG_ADSP5_BOOT_ENTRY_POINT (CXD56_TOPREG_BASE + 0x1020)
#define CXD56_TOPREG_YOBI2_3 (CXD56_TOPREG_BASE + 0x1040)
#define CXD56_TOPREG_ADSP0_BOOT_ENTRY_POINT (CXD56_TOPREG_BASE + 0x1400)
#define CXD56_TOPREG_USB_VBUS (CXD56_TOPREG_BASE + 0x1410)
#define CXD56_TOPREG_FUSERD00 (CXD56_TOPREG_BASE + 0x1420)
#define CXD56_TOPREG_FUSERD01 (CXD56_TOPREG_BASE + 0x1424)
#define CXD56_TOPREG_FUSERD02 (CXD56_TOPREG_BASE + 0x1428)
#define CXD56_TOPREG_FUSERD03 (CXD56_TOPREG_BASE + 0x142c)
#define CXD56_TOPREG_FUSERD04 (CXD56_TOPREG_BASE + 0x1430)
#define CXD56_TOPREG_FUSERD05 (CXD56_TOPREG_BASE + 0x1434)
#define CXD56_TOPREG_FUSERD06 (CXD56_TOPREG_BASE + 0x1438)
#define CXD56_TOPREG_FUSERD07 (CXD56_TOPREG_BASE + 0x143c)
#define CXD56_TOPREG_FUSERD08 (CXD56_TOPREG_BASE + 0x1440)
#define CXD56_TOPREG_FUSERD09 (CXD56_TOPREG_BASE + 0x1444)
#define CXD56_TOPREG_FUSERD10 (CXD56_TOPREG_BASE + 0x1448)
#define CXD56_TOPREG_FUSERD11 (CXD56_TOPREG_BASE + 0x144c)
#define CXD56_TOPREG_FUSERD12 (CXD56_TOPREG_BASE + 0x1450)
#define CXD56_TOPREG_FUSERD13 (CXD56_TOPREG_BASE + 0x1454)
#define CXD56_TOPREG_FUSERD14 (CXD56_TOPREG_BASE + 0x1458)
#define CXD56_TOPREG_FUSERD15 (CXD56_TOPREG_BASE + 0x145c)
#define CXD56_TOPREG_AUDIO_IF_SEL (CXD56_TOPREG_BASE + 0x1470)
#define CXD56_TOPREG_IOOEN_APP (CXD56_TOPREG_BASE + 0x1474)
#define CXD56_TOPREG_IOFIX_APP (CXD56_TOPREG_BASE + 0x1478)
#define CXD56_TOPREG_IOCAPP_MONSEL0 (CXD56_TOPREG_BASE + 0x1480)
#define CXD56_TOPREG_IOCAPP_MONSEL1 (CXD56_TOPREG_BASE + 0x1484)
#define CXD56_TOPREG_IOCAPP_INTSEL0 (CXD56_TOPREG_BASE + 0x1490)
#define CXD56_TOPREG_IOCAPP_INTSEL1 (CXD56_TOPREG_BASE + 0x1494)
#define CXD56_TOPREG_IOCAPP_IOMD (CXD56_TOPREG_BASE + 0x14a0)
#define CXD56_TOPREG_YOBI2_4 (CXD56_TOPREG_BASE + 0x14c0)
#define CXD56_TOPREG_GP_I2C4_BCK (CXD56_TOPREG_BASE + 0x2000)
#define CXD56_TOPREG_GP_I2C4_BDT (CXD56_TOPREG_BASE + 0x2004)
#define CXD56_TOPREG_GP_PMIC_INT (CXD56_TOPREG_BASE + 0x2008)
#define CXD56_TOPREG_GP_RTC_IRQ_OUT (CXD56_TOPREG_BASE + 0x200c)
#define CXD56_TOPREG_GP_AP_CLK (CXD56_TOPREG_BASE + 0x2010)
#define CXD56_TOPREG_GP_GNSS_1PPS_OUT (CXD56_TOPREG_BASE + 0x2014)
#define CXD56_TOPREG_GP_SPI0_CS_X (CXD56_TOPREG_BASE + 0x2040)
#define CXD56_TOPREG_GP_SPI0_SCK (CXD56_TOPREG_BASE + 0x2044)
#define CXD56_TOPREG_GP_SPI0_MOSI (CXD56_TOPREG_BASE + 0x2048)
#define CXD56_TOPREG_GP_SPI0_MISO (CXD56_TOPREG_BASE + 0x204c)
#define CXD56_TOPREG_GP_SPI1_CS_X (CXD56_TOPREG_BASE + 0x2050)
#define CXD56_TOPREG_GP_SPI1_SCK (CXD56_TOPREG_BASE + 0x2054)
#define CXD56_TOPREG_GP_SPI1_IO0 (CXD56_TOPREG_BASE + 0x2058)
#define CXD56_TOPREG_GP_SPI1_IO1 (CXD56_TOPREG_BASE + 0x205c)
#define CXD56_TOPREG_GP_SPI1_IO2 (CXD56_TOPREG_BASE + 0x2060)
#define CXD56_TOPREG_GP_SPI1_IO3 (CXD56_TOPREG_BASE + 0x2064)
#define CXD56_TOPREG_GP_SPI2_CS_X (CXD56_TOPREG_BASE + 0x2068)
#define CXD56_TOPREG_GP_SPI2_SCK (CXD56_TOPREG_BASE + 0x206c)
#define CXD56_TOPREG_GP_SPI2_MOSI (CXD56_TOPREG_BASE + 0x2070)
#define CXD56_TOPREG_GP_SPI2_MISO (CXD56_TOPREG_BASE + 0x2074)
#define CXD56_TOPREG_GP_HIF_IRQ_OUT (CXD56_TOPREG_BASE + 0x2078)
#define CXD56_TOPREG_GP_HIF_GPIO0 (CXD56_TOPREG_BASE + 0x207c)
#define CXD56_TOPREG_GP_SEN_IRQ_IN (CXD56_TOPREG_BASE + 0x2090)
#define CXD56_TOPREG_GP_SPI3_CS0_X (CXD56_TOPREG_BASE + 0x2094)
#define CXD56_TOPREG_GP_SPI3_CS1_X (CXD56_TOPREG_BASE + 0x2098)
#define CXD56_TOPREG_GP_SPI3_CS2_X (CXD56_TOPREG_BASE + 0x209c)
#define CXD56_TOPREG_GP_SPI3_SCK (CXD56_TOPREG_BASE + 0x20a0)
#define CXD56_TOPREG_GP_SPI3_MOSI (CXD56_TOPREG_BASE + 0x20a4)
#define CXD56_TOPREG_GP_SPI3_MISO (CXD56_TOPREG_BASE + 0x20a8)
#define CXD56_TOPREG_GP_I2C0_BCK (CXD56_TOPREG_BASE + 0x20ac)
#define CXD56_TOPREG_GP_I2C0_BDT (CXD56_TOPREG_BASE + 0x20b0)
#define CXD56_TOPREG_GP_PWM0 (CXD56_TOPREG_BASE + 0x20b4)
#define CXD56_TOPREG_GP_PWM1 (CXD56_TOPREG_BASE + 0x20b8)
#define CXD56_TOPREG_GP_PWM2 (CXD56_TOPREG_BASE + 0x20bc)
#define CXD56_TOPREG_GP_PWM3 (CXD56_TOPREG_BASE + 0x20c0)
#define CXD56_TOPREG_GP_IS_CLK (CXD56_TOPREG_BASE + 0x20c4)
#define CXD56_TOPREG_GP_IS_VSYNC (CXD56_TOPREG_BASE + 0x20c8)
#define CXD56_TOPREG_GP_IS_HSYNC (CXD56_TOPREG_BASE + 0x20cc)
#define CXD56_TOPREG_GP_IS_DATA0 (CXD56_TOPREG_BASE + 0x20d0)
#define CXD56_TOPREG_GP_IS_DATA1 (CXD56_TOPREG_BASE + 0x20d4)
#define CXD56_TOPREG_GP_IS_DATA2 (CXD56_TOPREG_BASE + 0x20d8)
#define CXD56_TOPREG_GP_IS_DATA3 (CXD56_TOPREG_BASE + 0x20dc)
#define CXD56_TOPREG_GP_IS_DATA4 (CXD56_TOPREG_BASE + 0x20e0)
#define CXD56_TOPREG_GP_IS_DATA5 (CXD56_TOPREG_BASE + 0x20e4)
#define CXD56_TOPREG_GP_IS_DATA6 (CXD56_TOPREG_BASE + 0x20e8)
#define CXD56_TOPREG_GP_IS_DATA7 (CXD56_TOPREG_BASE + 0x20ec)
#define CXD56_TOPREG_GP_UART2_TXD (CXD56_TOPREG_BASE + 0x20f0)
#define CXD56_TOPREG_GP_UART2_RXD (CXD56_TOPREG_BASE + 0x20f4)
#define CXD56_TOPREG_GP_UART2_CTS (CXD56_TOPREG_BASE + 0x20f8)
#define CXD56_TOPREG_GP_UART2_RTS (CXD56_TOPREG_BASE + 0x20fc)
#define CXD56_TOPREG_GP_SPI4_CS_X (CXD56_TOPREG_BASE + 0x2100)
#define CXD56_TOPREG_GP_SPI4_SCK (CXD56_TOPREG_BASE + 0x2104)
#define CXD56_TOPREG_GP_SPI4_MOSI (CXD56_TOPREG_BASE + 0x2108)
#define CXD56_TOPREG_GP_SPI4_MISO (CXD56_TOPREG_BASE + 0x210c)
#define CXD56_TOPREG_GP_EMMC_CLK (CXD56_TOPREG_BASE + 0x2110)
#define CXD56_TOPREG_GP_EMMC_CMD (CXD56_TOPREG_BASE + 0x2114)
#define CXD56_TOPREG_GP_EMMC_DATA0 (CXD56_TOPREG_BASE + 0x2118)
#define CXD56_TOPREG_GP_EMMC_DATA1 (CXD56_TOPREG_BASE + 0x211c)
#define CXD56_TOPREG_GP_EMMC_DATA2 (CXD56_TOPREG_BASE + 0x2120)
#define CXD56_TOPREG_GP_EMMC_DATA3 (CXD56_TOPREG_BASE + 0x2124)
#define CXD56_TOPREG_GP_SDIO_CLK (CXD56_TOPREG_BASE + 0x2128)
#define CXD56_TOPREG_GP_SDIO_CMD (CXD56_TOPREG_BASE + 0x212c)
#define CXD56_TOPREG_GP_SDIO_DATA0 (CXD56_TOPREG_BASE + 0x2130)
#define CXD56_TOPREG_GP_SDIO_DATA1 (CXD56_TOPREG_BASE + 0x2134)
#define CXD56_TOPREG_GP_SDIO_DATA2 (CXD56_TOPREG_BASE + 0x2138)
#define CXD56_TOPREG_GP_SDIO_DATA3 (CXD56_TOPREG_BASE + 0x213c)
#define CXD56_TOPREG_GP_SDIO_CD (CXD56_TOPREG_BASE + 0x2140)
#define CXD56_TOPREG_GP_SDIO_WP (CXD56_TOPREG_BASE + 0x2144)
#define CXD56_TOPREG_GP_SDIO_CMDDIR (CXD56_TOPREG_BASE + 0x2148)
#define CXD56_TOPREG_GP_SDIO_DIR0 (CXD56_TOPREG_BASE + 0x214c)
#define CXD56_TOPREG_GP_SDIO_DIR1_3 (CXD56_TOPREG_BASE + 0x2150)
#define CXD56_TOPREG_GP_SDIO_CLKI (CXD56_TOPREG_BASE + 0x2154)
#define CXD56_TOPREG_GP_I2S0_BCK (CXD56_TOPREG_BASE + 0x2158)
#define CXD56_TOPREG_GP_I2S0_LRCK (CXD56_TOPREG_BASE + 0x215c)
#define CXD56_TOPREG_GP_I2S0_DATA_IN (CXD56_TOPREG_BASE + 0x2160)
#define CXD56_TOPREG_GP_I2S0_DATA_OUT (CXD56_TOPREG_BASE + 0x2164)
#define CXD56_TOPREG_GP_I2S1_BCK (CXD56_TOPREG_BASE + 0x2168)
#define CXD56_TOPREG_GP_I2S1_LRCK (CXD56_TOPREG_BASE + 0x216c)
#define CXD56_TOPREG_GP_I2S1_DATA_IN (CXD56_TOPREG_BASE + 0x2170)
#define CXD56_TOPREG_GP_I2S1_DATA_OUT (CXD56_TOPREG_BASE + 0x2174)
#define CXD56_TOPREG_GP_MCLK (CXD56_TOPREG_BASE + 0x2178)
#define CXD56_TOPREG_GP_PDM_CLK (CXD56_TOPREG_BASE + 0x217c)
#define CXD56_TOPREG_GP_PDM_IN (CXD56_TOPREG_BASE + 0x2180)
#define CXD56_TOPREG_GP_PDM_OUT (CXD56_TOPREG_BASE + 0x2184)
#define CXD56_TOPREG_GP_USB_VBUSINT (CXD56_TOPREG_BASE + 0x2188)
#define CXD56_TOPREG_YOBI3 (CXD56_TOPREG_BASE + 0x21fc)
/* Topreg sub */
#define CXD56_TOPREG_PSW_CHECK (CXD56_TOPREG_SUB_BASE + 0x0000)
#define CXD56_TOPREG_UNEXP_PSW_DIG (CXD56_TOPREG_SUB_BASE + 0x0004)
#define CXD56_TOPREG_UNEXP_PSW_ANA (CXD56_TOPREG_SUB_BASE + 0x0008)
#define CXD56_TOPREG_UNEXP_OTHER (CXD56_TOPREG_SUB_BASE + 0x000c)
#define CXD56_TOPREG_UNEXP_CLR (CXD56_TOPREG_SUB_BASE + 0x0010)
#define CXD56_TOPREG_PMU_WAIT10 (CXD56_TOPREG_SUB_BASE + 0x0020)
#define CXD56_TOPREG_PMU_WAIT11 (CXD56_TOPREG_SUB_BASE + 0x0024)
#if 0
#define CXD56_TOPREG_PMU_DBG_INITEN (CXD56_TOPREG_SUB_BASE + 0x0030)
#define CXD56_TOPREG_PMU_DBG_LUMPEN (CXD56_TOPREG_SUB_BASE + 0x0034)
#endif
#define CXD56_TOPREG_SWRESET_DBG (CXD56_TOPREG_SUB_BASE + 0x0400)
#define CXD56_TOPREG_SWRESET_GNSDSP (CXD56_TOPREG_SUB_BASE + 0x0404)
#define CXD56_TOPREG_SWRESET_APP (CXD56_TOPREG_SUB_BASE + 0x0408)
#define CXD56_TOPREG_SYSCPU_CKEN (CXD56_TOPREG_SUB_BASE + 0x0410)
#define CXD56_TOPREG_APP_CKEN (CXD56_TOPREG_SUB_BASE + 0x0414)
#define CXD56_TOPREG_APP_CKSEL (CXD56_TOPREG_SUB_BASE + 0x0418)
#define CXD56_TOPREG_APP_DIV (CXD56_TOPREG_SUB_BASE + 0x041c)
#define CXD56_TOPREG_SYSIOP_SUB_CKEN (CXD56_TOPREG_SUB_BASE + 0x0420)
#define CXD56_TOPREG_ROSC_MON (CXD56_TOPREG_SUB_BASE + 0x0428)
#define CXD56_TOPREG_TDC_MON (CXD56_TOPREG_SUB_BASE + 0x042c)
#define CXD56_TOPREG_PMU_WAKE_TRIG0_CLR (CXD56_TOPREG_SUB_BASE + 0x0430)
#define CXD56_TOPREG_PMU_WAKE_TRIG1_CLR (CXD56_TOPREG_SUB_BASE + 0x0434)
#define CXD56_TOPREG_PMU_WAKE_TRIG0_RAW (CXD56_TOPREG_SUB_BASE + 0x0438)
#define CXD56_TOPREG_PMU_WAKE_TRIG1_RAW (CXD56_TOPREG_SUB_BASE + 0x043c)
#define CXD56_TOPREG_PMU_WAKE_TRIG0 (CXD56_TOPREG_SUB_BASE + 0x0440)
#define CXD56_TOPREG_PMU_WAKE_TRIG1 (CXD56_TOPREG_SUB_BASE + 0x0444)
#define CXD56_TOPREG_RTC1_CTL (CXD56_TOPREG_SUB_BASE + 0x0470)
#define CXD56_TOPREG_GNSS_RAMMODE_SEL (CXD56_TOPREG_SUB_BASE + 0x0c00)
#define CXD56_TOPREG_SWRESET_GNSDSP2 (CXD56_TOPREG_SUB_BASE + 0x0c10)
#define CXD56_TOPREG_SWRESET_BB (CXD56_TOPREG_SUB_BASE + 0x0c14)
#define CXD56_TOPREG_GNSDSP_CKEN (CXD56_TOPREG_SUB_BASE + 0x0c20)
#define CXD56_TOPREG_GNSS_BB_CKEN (CXD56_TOPREG_SUB_BASE + 0x0c24)
#define CXD56_TOPREG_GNSS_DIV (CXD56_TOPREG_SUB_BASE + 0x0c28)
#define CXD56_TOPREG_GNSS_RAMMODE_STAT (CXD56_TOPREG_SUB_BASE + 0x0c30)
#define CXD56_TOPREG_APPDSP_RAMMODE_SEL0 (CXD56_TOPREG_SUB_BASE + 0x1400)
#define CXD56_TOPREG_APPDSP_RAMMODE_SEL1 (CXD56_TOPREG_SUB_BASE + 0x1404)
#define CXD56_TOPREG_APPDSP_RAMMODE_STAT0 (CXD56_TOPREG_SUB_BASE + 0x1420)
#define CXD56_TOPREG_APPDSP_RAMMODE_STAT1 (CXD56_TOPREG_SUB_BASE + 0x1424)
#define CXD56_TOPREG_BUSERR0 (CXD56_TOPREG_SUB_BASE + 0x1470)
#define CXD56_TOPREG_BUSERR1 (CXD56_TOPREG_SUB_BASE + 0x1474)
#define CXD56_TOPREG_BUSERR2 (CXD56_TOPREG_SUB_BASE + 0x1478)
#define CXD56_TOPREG_CHIP_ID (CXD56_TOPREG_SUB_BASE + 0x1490)
#define CXD56_TOPREG_CUID0 (CXD56_TOPREG_SUB_BASE + 0x1494)
#define CXD56_TOPREG_CUID1 (CXD56_TOPREG_SUB_BASE + 0x1498)
#define CXD56_TOPREG_UDID0 (CXD56_TOPREG_SUB_BASE + 0x149c)
#define CXD56_TOPREG_UDID1 (CXD56_TOPREG_SUB_BASE + 0x14a0)
#define CXD56_TOPREG_FUSE_STATUS (CXD56_TOPREG_SUB_BASE + 0x14a4)
#define CXD56_TOPREG_SDBG_ENB (CXD56_TOPREG_SUB_BASE + 0x14a8)
#define CXD56_TOPREG_DBG_MONSEL (CXD56_TOPREG_SUB_BASE + 0x14c0)
/* PWD_CTL, PWD_STAT */
#define PWD_APP_AUDIO (1u<<14)
#define PWD_GNSS (1u<<13)
#define PWD_GNSS_ITP (1u<<12)
#define PWD_APP_SUB (1u<<10)
#define PWD_APP_DSP (1u<<9)
#define PWD_APP (1u<<8)
#define PWD_SYSIOP_SUB (1u<<6)
#define PWD_SYSIOP (1u<<5)
#define PWD_CORE (1u<<4)
#define PWD_SCU (1u<<0)
/* ANA_PW_CTL */
#define ANA_PW_LPADC (1u<<13)
#define ANA_PW_HPADC (1u<<12)
#define ANA_PW_RF_PLL (1u<<9)
#define ANA_PW_RF_LO (1u<<8)
#define ANA_PW_RF_ADC (1u<<7)
#define ANA_PW_RF_IF (1u<<6)
#define ANA_PW_RF_MIX (1u<<5)
#define ANA_PW_RF_LNA (1u<<4)
#define ANA_PW_SYSPLL (1u<<2)
#define ANA_PW_XOSC (1u<<1)
#define ANA_PW_RCOSC (1u<<0)
/* ANA_EN_CTL */
#define ON_GP_MBI_EN_SET (1u<<27)
#define OFF_GP_MBI_EN_CLR (1u<<26)
#define ON_XO_OSC_EN_SET (1u<<25)
#define OFF_XO_OSC_EN_CLR (1u<<24)
#define ON_XO_OSCOUT_EN_SET (1u<<20)
#define OFF_XO_OSCOUT_EN_CLR (1u<<19)
#define ON_XO_EXT_EN_SET (1u<<18)
#define OFF_XO_EXT_EN_CLR (1u<<17)
#define OFF_XO_CLK_EN_CLR (1u<<16)
#define ON_SP_ENPLL_SET (1u<<8)
#define OFF_SP_ENCLK_CLR (1u<<7)
#define ON_SP_ENOTHER_SET (1u<<6)
#define OFF_SP_ENOTHER_CLR (1u<<5)
#define OFF_SP_ENPLL_CLR (1u<<4)
#define ON_RO_XEN_CLR (1u<<2)
#define OFF_RO_XEN_SET (1u<<1)
#define OFF_RO_CLK_XEN_SET (1u<<0)
/* PMU_INT_STAT */
#define PMU_INT_BOOTEN (1u<<4)
#define PMU_INT_UNEXP_I2C_PMIC (1u<<3)
#define PMU_INT_UNEXP_TIMEOUT (1u<<2)
#define PMU_INT_NOGO (1u<<1)
#define PMU_INT_DONE (1u<<0)
/* CKSEL_ROOT */
#define STATUS_RTC_MASK (3u<<30)
#define STATUS_RTC_SEL (2u<<30)
#define ENABLE_RF_PLL1 (1u<<4)
#define ENABLE_SOURCE_SEL (1u<<16)
/* CRG_INT_CLR0 */
#define CRG_CK_PCLK_UART0 (1u<<0)
#define CRG_CK_UART0 (1u<<1)
#define CRG_CK_BRG_HOST (1u<<2)
#define CRG_CK_PCLK_HOSTIFC (1u<<3)
#define CRG_CK_HOSTIFC_SEQ (1u<<4)
#define CRG_CK_I2CS (1u<<5)
#define CRG_CK_RTC_ORG (1u<<6)
#define CRG_CK_SYSIOP_RTC (1u<<7)
#define CRG_CK_BRG_SCU (1u<<8)
#define CRG_CK_SCU (1u<<9)
#define CRG_CK_SCU_SPI (1u<<10)
#define CRG_CK_SCU_I2C0 (1u<<11)
#define CRG_CK_SCU_I2C1 (1u<<12)
#define CRG_CK_SCU_SEQ (1u<<13)
#define CRG_CK_SCU_SC (1u<<14)
#define CRG_CK_32K (1u<<15)
#define CRG_CK_U32KH (1u<<16)
#define CRG_CK_U32KL (1u<<17)
#define CRG_CK_TADC (1u<<18)
#define CRG_CK_RTC_PCLK (1u<<19)
#define CRG_CK_PMU_RTC_PCLK (1u<<20)
#define CRG_CK_APP (1u<<21)
/* CRG_INT_CLR1 */
#define CRG_CK_CPU_BUS (1u<<0)
#define CRG_CK_CPU_BUS_TO (1u<<1)
#define CRG_CK_RFPLL1 (1u<<2)
#define CRG_CK_RFPLL1_TO (1u<<3)
#define CRG_CK_RTC_PRE (1u<<4)
#define CRG_CK_RTC_PRE_TO (1u<<5)
#define CRG_CK_APP_PRE (1u<<6)
#define CRG_CK_APP_PRE_TO (1u<<7)
#define CRG_CK_SEL_SP (1u<<8)
#define CRG_CK_SEL_SP_TO (1u<<9)
#define CRG_CK_SEL_RO_RTC (1u<<10)
#define CRG_FREQFIX_ERR (1u<<11)
/* SYS_PLL_CTRL1 */
#define ENABLE_DSPCLK (1u<<3)
#define ENABLE_GPADCLK (1u<<1)
/* RCOSC_CTRL2 */
#define DISABLE_SENSCLK (1u<<14)
#define DISABLE_LOGICLK (1u<<13)
/* SWRESET_BUS */
#define XRST_PMU_I2CM (1u<<16)
#define XRST_I2CM (1u<<11)
#define XRST_UART0 (1u<<10)
#define XRST_HOSTIFC_ISOP (1u<<9)
#define XRST_HOSTIFC (1u<<8)
#define XRST_KAKI (1u<<6)
#define XRST_UART1 (1u<<5)
#define XRST_SAKE (1u<<2)
#define XRST_SFC (1u<<1)
#define XRST_SPIM (1u<<0)
/* SWRESET_SCU */
#define XRST_SCU_SPI (1u<<8)
#define XRST_SCU_ISOP (1u<<7)
#define XRST_SCU_I2C1 (1u<<6)
#define XRST_SCU_I2C2 (1u<<5)
#define XRST_SCU_LPADC (1u<<4)
#define XRST_SCU_HPADC (1u<<2)
/* SYSIOP_CKEN */
#define CKEN_HOSSPI (1u<<17)
#define CKEN_HOSI2C (1u<<16)
#define CKEN_HOSTIFC_SEQ (1u<<15)
#define CKEN_BRG_SCU (1u<<14)
#define CKEN_SYSIOP_RTC (1u<<13)
#define CKEN_RCOSC_OUT (1u<<12)
#define CKEN_AP_CLK (1u<<11)
#define CKEN_RTC_ORG (1u<<10)
#define CKEN_FREQDIS (1u<<9)
#define CKEN_APB (1u<<8)
#define CKEN_AHB_DMAC2 (1u<<7)
#define CKEN_AHB_DMAC1 (1u<<6)
#define CKEN_AHB_DMAC0 (1u<<5)
#define CKEN_BRG_HOST (1u<<4)
#define CKEN_I2CS (1u<<3)
#define CKEN_PCLK_HOSTIFC (1u<<2)
#define CKEN_PCLK_UART0 (1u<<1)
#define CKEN_UART0 (1u<<0)
/* IOOEN_APP */
#define I2S1_LRCK (1u<<5)
#define I2S1_BCK (1u<<4)
#define I2S0_LRCK (1u<<1)
#define I2S0_BCK (1u<<0)
/* SYSIOP_SUB_CKEN */
#define CK_COM_UART_PCLK (1u<<16)
#define CK_SFC_HCLK_LOW (1u<<9)
#define CK_SFC_SFCLK (1u<<8)
#define CK_SFC_HCLK (1u<<7)
#define CK_SFC (CK_SFC_HCLK | CK_SFC_SFCLK | CK_SFC_HCLK_LOW)
#define CK_HCLK_SAKE (1u<<6)
#define CK_I2CM (1u<<5)
#define CK_SPIM (1u<<4)
#define CK_UART1 (1u<<3)
#define CK_AHB_DMAC3 (1u<<2)
#define CK_COM_BRG (1u<<1)
#define CK_AHB_BRG_COMIF (1u<<0)
/* PWD_CTL */
#define PWD_CTL_APP_SUB (1u<<10)
/* SCU_CKEN */
#define SCU_SCU (1u<<0)
#define SCU_I2C0 (1u<<1)
#define SCU_I2C1 (1u<<2)
#define SCU_SPI (1u<<3)
#define SCU_SEQ (1u<<4)
#define SCU_32K (1u<<5)
#define SCU_U32KL (1u<<6)
#define SCU_U32KH (1u<<7)
#define SCU_SC (1u<<8)
/* APP_CKEN */
#define APP_CKEN_CPU (1u<<0)
#define APP_CKEN_MCLK (1u<<1)
#define APP_CKEN_AHB (1u<<3)
/* APP_CKSEL */
#define AUD_MCLK_MASK (3u<<16)
#define AUD_MCLK_EXT (0u<<16) /* External XTAL */
#define AUD_MCLK_XOSC (1u<<16) /* Internal XOSC */
#define AUD_MCLK_RCOSC (2u<<16) /* Internal RCOSC */
/* GNSDSP_CKEN */
#define GNSDSP_CKEN_P1 (1u<<5)
#define GNSDSP_CKEN_COP (1u<<7)
#endif

View File

@ -0,0 +1,58 @@
/****************************************************************************
* arch/arm/src/cxd56xx/hardware/cxd56_cpufifo.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CHIP_CXD56_CPUFIFO_H
#define __ARCH_ARM_SRC_CXD56XX_CHIP_CXD56_CPUFIFO_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
#define CXD56_FIF_PUSH_FULL (CXD56_CPUFIFO_BASE + 0x00)
#define CXD56_FIF_PUSH_WRD0 (CXD56_CPUFIFO_BASE + 0x04)
#define CXD56_FIF_PUSH_WRD1 (CXD56_CPUFIFO_BASE + 0x08)
#define CXD56_FIF_PUSH_CMP (CXD56_CPUFIFO_BASE + 0x0c)
#define CXD56_FIF_PULL_EMP (CXD56_CPUFIFO_BASE + 0x10)
#define CXD56_FIF_PULL_WRD0 (CXD56_CPUFIFO_BASE + 0x14)
#define CXD56_FIF_PULL_WRD1 (CXD56_CPUFIFO_BASE + 0x18)
#define CXD56_FIF_PULL_CMP (CXD56_CPUFIFO_BASE + 0x1c)
#endif /* __ARCH_ARM_SRC_CXD56XX_CHIP_CXD56_CPUFIFO_H */

View File

@ -0,0 +1,89 @@
/****************************************************************************
* arch/arm/src/cxd56xx/hardware/cxd56_crg.h
*
* Copyright (C) 2008-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 Sony Semiconductor Solutions 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
* COPYRIGHT OWNER 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 __ARCH_ARM_SRC_CXD56XX_CHIP_CXD56_CRG_H
#define __ARCH_ARM_SRC_CXD56XX_CHIP_CXD56_CRG_H
/********************************************************************************************
* Included Files
********************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/********************************************************************************************
* Pre-processor Definitions
********************************************************************************************/
#define CXD56_CRG_GEAR_AHB (CXD56_CRG_BASE + 0x0000)
#define CXD56_CRG_GEAR_IMG_UART (CXD56_CRG_BASE + 0x0004)
#define CXD56_CRG_GEAR_IMG_SPI (CXD56_CRG_BASE + 0x0008)
#define CXD56_CRG_GEAR_PER_SDIO (CXD56_CRG_BASE + 0x000c)
#define CXD56_CRG_GEAR_PER_USB (CXD56_CRG_BASE + 0x0010)
#define CXD56_CRG_GEAR_M_IMG_VENB (CXD56_CRG_BASE + 0x0014)
#define CXD56_CRG_GEAR_N_IMG_VENB (CXD56_CRG_BASE + 0x0018)
#define CXD56_CRG_GEAR_IMG_WSPI (CXD56_CRG_BASE + 0x001c)
#define CXD56_CRG_CKEN_EMMC (CXD56_CRG_BASE + 0x0020)
#define CXD56_CRG_RESET (CXD56_CRG_BASE + 0x0030)
#define CXD56_CRG_CK_GATE_AHB (CXD56_CRG_BASE + 0x0040)
#define CXD56_CRG_CK_MON_EN (CXD56_CRG_BASE + 0x0050)
#define CXD56_CRG_APP_TILE_CLK_GATING_ENB (CXD56_ADSP_BASE + 0x02001084)
/* RESET register bits **********************************************************************/
#define XRS_AUD (1<<0)
#define XRS_IMG (1<<4)
#define XRS_USB (1<<8)
#define XRS_SDIO (1<<9)
#define XRS_MMC (1<<10)
#define XRS_MMC_CRG (1<<11)
#define XRS_DSP_GEN (1<<22)
/* CK_GATE_AHB register bits ****************************************************************/
#define CK_GATE_AUD (1<<0)
#define CK_GATE_IMG (1<<4)
#define CK_GATE_USB (1<<8)
#define CK_GATE_SDIO (1<<9)
#define CK_GATE_MMC (1<<10)
#endif

View File

@ -132,4 +132,3 @@
****************************************************************************/
#endif /* __ARCH_ARM_SRC_CXD56XX_HARDWARE_CXD56_UART_H */