Merged in alinjerpelea/nuttx (pull request #896)
arch: arm: cxd56xx: add SPI, DMA and RTC * arch: arm: cxd56xx: add SPI support Add SPI support for cxd56xx chip Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com> * arch: arm: cxd56xx: Add DMA support Add DMA support for cxd56xx Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com> * arch: arm: cxd56xx: add RTC functionality Add the RTC functionality for cxd56xx Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com> * arch: arm: cxd56xx: add RTC_DRIVER Add RTC_DRIVER to cxd56xx Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com> * configs: spresense: enable rtc functionality Enable RTC functionality on spresense board Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com> Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
parent
06aa50e9bb
commit
e69471ba2f
@ -62,6 +62,7 @@ config CXD56_FARAPI_VERSION_CHECK
|
||||
|
||||
if CXD56_FARAPI_VERSION_CHECK
|
||||
|
||||
|
||||
config CXD56_FARAPI_VERSION_FAILED_PANIC
|
||||
bool "Far API Version Check Failed to PANIC"
|
||||
default n
|
||||
@ -74,8 +75,35 @@ config CXD56_FARAPI_DEBUG
|
||||
|
||||
endmenu # Far API Configuration
|
||||
|
||||
comment "Timer Options"
|
||||
|
||||
menuconfig CXD56_RTC
|
||||
bool "Real Time Clock (RTC)"
|
||||
default y
|
||||
---help---
|
||||
Support RTC
|
||||
|
||||
if CXD56_RTC
|
||||
|
||||
config CXD56_RTC_LATEINIT
|
||||
bool "Late RTC initialization"
|
||||
default y
|
||||
---help---
|
||||
Enable the late RTC initialization after waiting until the external
|
||||
CXD5247 RTC clock is stable. It will take 2 seconds typically at the
|
||||
initial boot by power on reset.
|
||||
|
||||
endif # CXD56_RTC
|
||||
|
||||
menu "CXD56xx Peripheral Support"
|
||||
|
||||
config CXD56_DMAC
|
||||
bool "DMAC"
|
||||
default y
|
||||
---help---
|
||||
Enables DMAC
|
||||
Currently supports SPI4 TX/RX and SPI5 TX/RX
|
||||
|
||||
config CXD56_GPIO_IRQ
|
||||
bool "GPIO interrupt"
|
||||
default y
|
||||
@ -98,6 +126,171 @@ config CXD56_UART2
|
||||
---help---
|
||||
UART interface with hardware flow control in the application subsystem.
|
||||
|
||||
config CXD56_SPI
|
||||
bool "SPI"
|
||||
|
||||
if CXD56_SPI
|
||||
|
||||
config CXD56_SPI0
|
||||
bool "SPI0"
|
||||
|
||||
menuconfig CXD56_SPI3
|
||||
bool "SPI3"
|
||||
|
||||
if CXD56_SPI3
|
||||
|
||||
config CXD56_SPI3_SCUSEQ
|
||||
bool "SCU Sequencer"
|
||||
default y
|
||||
depends on CXD56_SCU
|
||||
---help---
|
||||
Use the sensor control unit (SCU) sequencer.
|
||||
|
||||
config CXD56_SPI3_CS0
|
||||
bool "SPI3 Chip Select 0"
|
||||
default y
|
||||
---help---
|
||||
Enable chip select 0 of SPI3
|
||||
|
||||
config CXD56_SPI3_CS1
|
||||
bool "SPI3 Chip Select 1"
|
||||
default n
|
||||
---help---
|
||||
Enable chip select 1 of SPI3
|
||||
|
||||
config CXD56_SPI3_CS2
|
||||
bool "SPI3 Chip Select 2"
|
||||
default n
|
||||
---help---
|
||||
Enable chip select 2 of SPI3
|
||||
|
||||
endif # CXD56_SPI3
|
||||
|
||||
menuconfig CXD56_SPI4
|
||||
bool "SPI4"
|
||||
|
||||
if CXD56_SPI4
|
||||
|
||||
config CXD56_DMAC_SPI4_TX
|
||||
bool "DMAC support for SPI4 TX"
|
||||
default n
|
||||
select CXD56_DMAC
|
||||
---help---
|
||||
Enables DMAC for SPI4 TX
|
||||
|
||||
if CXD56_DMAC_SPI4_TX
|
||||
|
||||
config CXD56_DMAC_SPI4_TX_CH
|
||||
int "TX channel"
|
||||
default 2
|
||||
range 2 6
|
||||
|
||||
config CXD56_DMAC_SPI4_TX_MAXSIZE
|
||||
int "Max size to be sent in bytes"
|
||||
default 192000
|
||||
range 1 1572864
|
||||
---help---
|
||||
This value should be same as RX.
|
||||
|
||||
endif # CXD56_DMAC_SPI4_TX
|
||||
|
||||
config CXD56_DMAC_SPI4_RX
|
||||
bool "DMAC support for SPI4 RX"
|
||||
default n
|
||||
select CXD56_DMAC
|
||||
|
||||
---help---
|
||||
Enables DMAC for SPI4 RX
|
||||
|
||||
if CXD56_DMAC_SPI4_RX
|
||||
|
||||
config CXD56_DMAC_SPI4_RX_CH
|
||||
int "RX channel"
|
||||
default 3
|
||||
range 2 6
|
||||
|
||||
config CXD56_DMAC_SPI4_RX_MAXSIZE
|
||||
int "Max size to be received in bytes"
|
||||
default 192000
|
||||
range 1 1572864
|
||||
---help---
|
||||
This value should be same as TX.
|
||||
|
||||
endif # CXD56_DMAC_SPI4_RX
|
||||
|
||||
endif # CXD56_SPI4
|
||||
|
||||
menuconfig CXD56_SPI5
|
||||
bool "SPI5"
|
||||
|
||||
if CXD56_SPI5
|
||||
|
||||
choice
|
||||
prompt "SPI5 pin configuration"
|
||||
default CXD56_SPI5_PINMAP_EMMC
|
||||
|
||||
config CXD56_SPI5_PINMAP_EMMC
|
||||
bool "SPI5 pin assign to eMMC"
|
||||
---help---
|
||||
SPI5 assigns to the shared pins with eMMC.
|
||||
|
||||
config CXD56_SPI5_PINMAP_SDIO
|
||||
bool "SPI5 pin assign to SDIO"
|
||||
---help---
|
||||
SPI5 assigns to the shared pins with SDIO.
|
||||
endchoice
|
||||
|
||||
config CXD56_DMAC_SPI5_TX
|
||||
bool "DMAC support for SPI5 TX"
|
||||
default n
|
||||
select CXD56_DMAC
|
||||
---help---
|
||||
Enables DMAC for SPI5 TX
|
||||
|
||||
if CXD56_DMAC_SPI5_TX
|
||||
|
||||
config CXD56_DMAC_SPI5_TX_CH
|
||||
int "TX channel"
|
||||
default 4
|
||||
range 2 6
|
||||
|
||||
config CXD56_DMAC_SPI5_TX_MAXSIZE
|
||||
int "Max size to be sent in bytes"
|
||||
default 1516
|
||||
range 1 1572864
|
||||
---help---
|
||||
This value should be same as RX.
|
||||
|
||||
endif # CXD56_DMAC_SPI5_TX
|
||||
|
||||
config CXD56_DMAC_SPI5_RX
|
||||
bool "DMAC support for SPI5 RX"
|
||||
default n
|
||||
select CXD56_DMAC
|
||||
|
||||
---help---
|
||||
Enables DMAC for SPI5 RX
|
||||
|
||||
if CXD56_DMAC_SPI5_RX
|
||||
|
||||
config CXD56_DMAC_SPI5_RX_CH
|
||||
int "RX channel"
|
||||
default 5
|
||||
range 2 6
|
||||
|
||||
config CXD56_DMAC_SPI5_RX_MAXSIZE
|
||||
int "Max size to be received in bytes"
|
||||
default 1516
|
||||
range 1 1572864
|
||||
---help---
|
||||
This value should be same as TX.
|
||||
|
||||
endif # CXD56_DMAC_SPI5_RX
|
||||
|
||||
endif # CXD56_SPI5
|
||||
|
||||
endif
|
||||
|
||||
config CXD56_USBDEV
|
||||
bool "USB"
|
||||
default n
|
||||
|
@ -99,6 +99,13 @@ CHIP_CSRCS += cxd56_powermgr.c
|
||||
CHIP_CSRCS += cxd56_farapi.c
|
||||
CHIP_CSRCS += cxd56_sysctl.c
|
||||
|
||||
ifeq ($(CONFIG_CXD56_RTC),y)
|
||||
CHIP_CSRCS += cxd56_rtc.c
|
||||
ifeq ($(CONFIG_RTC_DRIVER),y)
|
||||
CHIP_CSRCS += cxd56_rtc_lowerhalf.c
|
||||
endif
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CXD56_GPIO_IRQ),y)
|
||||
CHIP_CSRCS += cxd56_gpioint.c
|
||||
endif
|
||||
@ -110,3 +117,11 @@ endif
|
||||
ifeq ($(CONFIG_CXD56_SDIO),y)
|
||||
CHIP_CSRCS += cxd56_sdhci.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CXD56_SPI),y)
|
||||
CHIP_CSRCS += cxd56_spi.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CXD56_DMAC),y)
|
||||
CHIP_CSRCS += cxd56_dmac.c
|
||||
endif
|
||||
|
980
arch/arm/src/cxd56xx/cxd56_dmac.c
Normal file
980
arch/arm/src/cxd56xx/cxd56_dmac.c
Normal file
@ -0,0 +1,980 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/cxd56xx/cxd56_dmac.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/kmalloc.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <semaphore.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/irq.h>
|
||||
|
||||
#include "cxd56_dmac.h"
|
||||
|
||||
#define PM_APP_ADMAC 51
|
||||
#define PM_APP_SKDMAC 52
|
||||
#define PM_APP_IDMAC 54
|
||||
|
||||
#define DMAC1_REG_BASE 0x4e020000u /* SMP_DMAC */
|
||||
#define DMAC2_REG_BASE 0x4e021000u /* SMP_SAKE */
|
||||
#define DMAC3_REG_BASE 0x4e102000u /* IMG_DMAC */
|
||||
|
||||
#define is_dmac(n, dev) ((dev) == (struct dmac_register_map *)\
|
||||
DMAC ## n ## _REG_BASE)
|
||||
|
||||
#define NCHANNELS 9
|
||||
|
||||
#define __RO volatile const
|
||||
#define __WO volatile
|
||||
#define __RW volatile
|
||||
|
||||
struct dmac_ch_register_map {
|
||||
__RW uint32_t srcaddr;
|
||||
__RW uint32_t destaddr;
|
||||
__RW uint32_t lli;
|
||||
__RW uint32_t control;
|
||||
__RW uint32_t configuration;
|
||||
uint32_t reserved[3];
|
||||
};
|
||||
|
||||
struct dmac080_ch_register_map {
|
||||
__RW uint32_t srcaddr;
|
||||
__RW uint32_t destaddr;
|
||||
__RW uint32_t lli;
|
||||
__RW uint32_t control;
|
||||
__RW uint32_t configuration;
|
||||
__RW uint32_t deflli;
|
||||
uint32_t reserved[2];
|
||||
};
|
||||
|
||||
struct dmac_register_map {
|
||||
__RO uint32_t intstatus;
|
||||
__RO uint32_t inttcstatus;
|
||||
__WO uint32_t inttcclear;
|
||||
__RO uint32_t interrorstatus;
|
||||
__WO uint32_t interrorclear;
|
||||
__RO uint32_t rawinttcstatus;
|
||||
__RO uint32_t rawinterrorstatus;
|
||||
__RO uint32_t enbldchns;
|
||||
__RW uint32_t softbreq;
|
||||
__RW uint32_t softsreq;
|
||||
__RW uint32_t softlbreq;
|
||||
__RW uint32_t softlsreq;
|
||||
__RW uint32_t configuration;
|
||||
__RW uint32_t sync;
|
||||
|
||||
uint32_t reserved0[50];
|
||||
|
||||
struct dmac_ch_register_map channel[2];
|
||||
};
|
||||
|
||||
struct dmac080_register_map {
|
||||
__RO uint32_t intstatus;
|
||||
__RO uint32_t inttcstatus;
|
||||
__WO uint32_t inttcclear;
|
||||
__RO uint32_t interrorstatus;
|
||||
__WO uint32_t interrorclear;
|
||||
__RO uint32_t rawinttcstatus;
|
||||
__RO uint32_t rawinterrorstatus;
|
||||
__RO uint32_t enbldchns;
|
||||
__RW uint32_t softbreq;
|
||||
__RW uint32_t softsreq;
|
||||
__RW uint32_t softlbreq;
|
||||
__RW uint32_t softlsreq;
|
||||
__RW uint32_t configuration;
|
||||
__RW uint32_t sync;
|
||||
__RW uint32_t sreqmask;
|
||||
|
||||
uint32_t reserved0[49];
|
||||
|
||||
/* XXX: deflli not supported */
|
||||
|
||||
struct dmac_ch_register_map channel[5];
|
||||
};
|
||||
|
||||
#define DMAC_CH_ENABLE (1u<<0)
|
||||
#define DMAC_CH_HALT (1u<<18)
|
||||
#define DMAC_CH_ACTIVE (1u<<17)
|
||||
|
||||
#ifndef itemsof
|
||||
#define itemsof(a) (sizeof(a)/sizeof(a[0]))
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Link list item structure for use scatter/gather operation
|
||||
*/
|
||||
|
||||
typedef struct {
|
||||
uint32_t src_addr; /**< Source address */
|
||||
uint32_t dest_addr; /**< Destination address */
|
||||
uint32_t nextlli; /**< Next link list */
|
||||
uint32_t control; /**< Transfer control */
|
||||
} dmac_lli_t;
|
||||
|
||||
#define CXD56_DMAC_M2M 0 /**< Memory to memory */
|
||||
#define CXD56_DMAC_M2P 1 /**< Memory to peripheral, DMAC controlled */
|
||||
#define CXD56_DMAC_P2M 2 /**< Peripheral to memory, DMAC controlled */
|
||||
#define CXD56_DMAC_P2P 3 /**< Peripheral to peripheral */
|
||||
#define CXD56_DMAC_P2CP 4 /**< P2P destination controlled */
|
||||
#define CXD56_DMAC_M2CP 5 /**< M2P peripheral controlled */
|
||||
#define CXD56_DMAC_CP2M 6 /**< P2M peripheral controlled */
|
||||
#define CXD56_DMAC_CP2P 7 /**< P2P source controlled */
|
||||
|
||||
#define CXD56_DMAC_BSIZE1 0 /**< 1 burst */
|
||||
#define CXD56_DMAC_BSIZE4 1 /**< 4 burst */
|
||||
#define CXD56_DMAC_BSIZE8 2 /**< 8 burst */
|
||||
#define CXD56_DMAC_BSIZE16 3 /**< 16 burst */
|
||||
#define CXD56_DMAC_BSIZE32 4 /**< 32 burst */
|
||||
#define CXD56_DMAC_BSIZE64 5 /**< 64 burst */
|
||||
#define CXD56_DMAC_BSIZE128 6 /**< 128 burst */
|
||||
#define CXD56_DMAC_BSIZE256 7 /**< 256 burst */
|
||||
|
||||
#define CXD56_DMAC_LITTLE_ENDIAN 0 /**< Little endian */
|
||||
#define CXD56_DMAC_BIG_ENDIAN 1 /**< Bit endian */
|
||||
|
||||
#define CXD56_DMAC_MASTER1 0 /**< AHB master 1 */
|
||||
#define CXD56_DMAC_MASTER2 1 /**< AHB master 2 */
|
||||
|
||||
/* max transfer size at a time */
|
||||
|
||||
#define CXD56_DMAC_MAX_SIZE 0xfff
|
||||
|
||||
/**
|
||||
* Helper macro for construct transfer control parameter.
|
||||
* Each parameters are the same with PD_DmacSetControl().
|
||||
*
|
||||
* @par Example:
|
||||
* Here is an example for transfer setting with no interrupt,
|
||||
* address increments, 4 byte, 4 burst and 16380 bytes (4 x 4095).
|
||||
*
|
||||
* @code
|
||||
* list.control = PD_DmacCtrlHelper(0, 1, 1,
|
||||
* PD_DMAC_WIDTH32, PD_DMAC_WIDTH32,
|
||||
* PD_DMAC_BSIZE4, PD_DMAC_BSIZE4,
|
||||
* 0xfffu);
|
||||
* @endcode
|
||||
*/
|
||||
|
||||
#define DMAC_CTRL_HELPER(intr, di, si, dwidth, swidth, dbsize, sbsize, tsize) \
|
||||
(((intr) & 1u) << 31 | \
|
||||
((di) & 1u) << 27 | \
|
||||
((si) & 1u) << 26 | \
|
||||
((dwidth) & 7u) << 21 | \
|
||||
((swidth) & 7u) << 18 | \
|
||||
((dbsize) & 7u) << 15 | \
|
||||
((sbsize) & 7u) << 12 | \
|
||||
((tsize) & 0xfffu))
|
||||
|
||||
/**
|
||||
* Helper macro for construct transfer control parameter
|
||||
* (for APP DMAC channel 2 - 6).
|
||||
* Each parameters are the same with PD_DmacSetExControl().
|
||||
*
|
||||
* @par Example:
|
||||
* Here is an example for transfer setting with no interrupt,
|
||||
* address increments, 4 byte, 4 burst and 16380 bytes (4 x 4095).
|
||||
*
|
||||
* @code
|
||||
* list.control = PD_DmacExCtrlHelper(0, 1, 1, 0, 0,
|
||||
* PD_DMAC_WIDTH32, PD_DMAC_WIDTH32,
|
||||
* PD_DMAC_BSIZE4, PD_DMAC_BSIZE4,
|
||||
* 0xfffu);
|
||||
* @endcode
|
||||
*
|
||||
* @note If you want to different burst sizes to source and destination,
|
||||
* then data may remained in FIFO. In this case, DMAC cannot clear them.
|
||||
* Do not use this configuration to transferring unknown size data (especially
|
||||
* communication peripherals). I recommend the same setting to burst sizes.
|
||||
*/
|
||||
|
||||
#define DMAC_EX_CTRL_HELPER(\
|
||||
intr, di, si, dmaster, smaster, dwidth, swidth, dbsize, sbsize, tsize) \
|
||||
(((intr) & 1u) << 31 | \
|
||||
((di) & 1u) << 30 | \
|
||||
((si) & 1u) << 29 | \
|
||||
((dmaster) & 1u) << 28 | \
|
||||
((smaster) & 1u) << 27 | \
|
||||
((dwidth) & 3u) << 25 | \
|
||||
((swidth) & 3u) << 23 | \
|
||||
((dbsize) & 3u) << 21 | \
|
||||
((sbsize) & 3u) << 19 | \
|
||||
((tsize) & 0x7ffffu))
|
||||
|
||||
static int open_channels = 0;
|
||||
|
||||
static int intr_handler_admac0(int irq, FAR void *context, FAR void *arg);
|
||||
static int intr_handler_admac1(int irq, FAR void *context, FAR void *arg);
|
||||
static int intr_handler_idmac(int irq, FAR void *context, FAR void *arg);
|
||||
static int intr_handler_skdmac0(int irq, FAR void *context, FAR void *arg);
|
||||
static int intr_handler_skdmac1(int irq, FAR void *context, FAR void *arg);
|
||||
static uint32_t irq_map[] = {
|
||||
CXD56_IRQ_APP_DMAC0,
|
||||
CXD56_IRQ_APP_DMAC1,
|
||||
CXD56_IRQ_IDMAC,
|
||||
CXD56_IRQ_IDMAC,
|
||||
CXD56_IRQ_IDMAC,
|
||||
CXD56_IRQ_IDMAC,
|
||||
CXD56_IRQ_IDMAC,
|
||||
CXD56_IRQ_SKDMAC_0,
|
||||
CXD56_IRQ_SKDMAC_1,
|
||||
};
|
||||
|
||||
static int (*intc_handler[])(int irq, FAR void *context, FAR void *arg) = {
|
||||
intr_handler_admac0,
|
||||
intr_handler_admac1,
|
||||
intr_handler_idmac,
|
||||
intr_handler_idmac,
|
||||
intr_handler_idmac,
|
||||
intr_handler_idmac,
|
||||
intr_handler_idmac,
|
||||
intr_handler_skdmac0,
|
||||
intr_handler_skdmac1,
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************/
|
||||
|
||||
/* This structure describes one DMA channel */
|
||||
|
||||
struct dma_channel_s
|
||||
{
|
||||
uint8_t chan; /* DMA channel number (0-CXD56_DMA_NCHANNELS) */
|
||||
bool inuse; /* TRUE: The DMA channel is in use */
|
||||
dma_config_t config; /* Current configuration */
|
||||
dmac_lli_t * list; /* Link list */
|
||||
dma_callback_t callback; /* Callback invoked when the DMA completes */
|
||||
void *arg; /* Argument passed to callback function */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/* This is the array of all DMA channels */
|
||||
|
||||
static struct dma_channel_s g_dmach[NCHANNELS];
|
||||
static sem_t g_dmaexc;
|
||||
|
||||
static int dma_init(int ch);
|
||||
static int dma_uninit(int ch);
|
||||
static int dma_open(int ch);
|
||||
static int dma_close(int ch);
|
||||
static int dma_setconfig(int ch, int itc, int ierr, int flowctrl,
|
||||
int destperi, int srcperi);
|
||||
static int dma_setintrcallback(int ch, dma_callback_t func, void *data);
|
||||
static int dma_clearintrcallback(int ch);
|
||||
static int dma_start(int ch, dmac_lli_t *list);
|
||||
static int dma_stop(int ch);
|
||||
|
||||
static int ch2dmac(int ch)
|
||||
{
|
||||
switch (ch) {
|
||||
case 0: case 1:
|
||||
return 1;
|
||||
case 2: case 3: case 4: case 5: case 6: /* APP IDMAC */
|
||||
return 3;
|
||||
case 7: case 8: /* APP SKDMAC */
|
||||
return 2;
|
||||
default:
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
static struct dmac_register_map *get_device(int ch)
|
||||
{
|
||||
int id = ch2dmac(ch);
|
||||
|
||||
switch (id) {
|
||||
case 1: return (struct dmac_register_map *)DMAC1_REG_BASE;
|
||||
case 2: return (struct dmac_register_map *)DMAC2_REG_BASE;
|
||||
case 3: return (struct dmac_register_map *)DMAC3_REG_BASE;
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
static struct dmac_ch_register_map *get_channel(int ch)
|
||||
{
|
||||
struct dmac_register_map *dev = get_device(ch);
|
||||
if (dev == NULL)
|
||||
return NULL;
|
||||
|
||||
if (is_dmac(2, dev)) {
|
||||
return &dev->channel[ch - 7];
|
||||
}
|
||||
else if (is_dmac(3, dev)) {
|
||||
return &((struct dmac080_register_map *)dev)->channel[ch - 2];
|
||||
}
|
||||
|
||||
return &dev->channel[ch & 1];
|
||||
}
|
||||
|
||||
static int get_pmid(int ch)
|
||||
{
|
||||
switch (ch) {
|
||||
case 0: case 1:
|
||||
return PM_APP_ADMAC;
|
||||
case 2: case 3: case 4: case 5: case 6:
|
||||
return PM_APP_IDMAC;
|
||||
case 7: case 8:
|
||||
return PM_APP_SKDMAC;
|
||||
default:
|
||||
break; /* may not comes here */
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
struct dmac_ch_register_frame {
|
||||
uint32_t srcaddr;
|
||||
uint32_t destaddr;
|
||||
uint32_t lli;
|
||||
uint32_t control;
|
||||
uint32_t configuration;
|
||||
};
|
||||
|
||||
struct dmac_register_frame {
|
||||
uint32_t configuration;
|
||||
struct dmac_ch_register_frame channel[2];
|
||||
};
|
||||
|
||||
static void _dmac_intc_handler(int ch)
|
||||
{
|
||||
struct dmac_register_map *dev = get_device(ch);
|
||||
struct dma_channel_s *dmach;
|
||||
uint32_t mask;
|
||||
int itc;
|
||||
int err;
|
||||
|
||||
mask = (1u << (ch & 1));
|
||||
|
||||
if (is_dmac(2, dev)) {
|
||||
mask = 1u << (ch - 7);
|
||||
}
|
||||
else if (is_dmac(3, dev)) {
|
||||
mask = 1u << (ch - 2);
|
||||
}
|
||||
|
||||
itc = dev->inttcstatus & mask;
|
||||
err = dev->interrorstatus & mask;
|
||||
dev->inttcclear = itc;
|
||||
dev->interrorclear = err;
|
||||
|
||||
dmach = &g_dmach[ch];
|
||||
|
||||
if (dmach->callback) {
|
||||
int flags = itc ? CXD56_DMA_INTR_ITC : 0;
|
||||
flags |= err ? CXD56_DMA_INTR_ERR : 0;
|
||||
dmach->callback((DMA_HANDLE)dmach, flags, dmach->arg);
|
||||
}
|
||||
}
|
||||
|
||||
static int intr_handler_admac0(int irq, FAR void *context, FAR void *arg)
|
||||
{
|
||||
_dmac_intc_handler(0);
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int intr_handler_admac1(int irq, FAR void *context, FAR void *arg)
|
||||
{
|
||||
_dmac_intc_handler(1);
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int intr_handler_idmac(int irq, FAR void *context, FAR void *arg)
|
||||
{
|
||||
struct dmac_register_map *dev = get_device(2); /* XXX */
|
||||
uint32_t stat = dev->intstatus & 0x1f;
|
||||
int i;
|
||||
|
||||
for (i = 2; stat; i++, stat >>= 1) {
|
||||
if (stat & 1)
|
||||
_dmac_intc_handler(i);
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int intr_handler_skdmac0(int irq, FAR void *context, FAR void *arg)
|
||||
{
|
||||
_dmac_intc_handler(7);
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int intr_handler_skdmac1(int irq, FAR void *context, FAR void *arg)
|
||||
{
|
||||
_dmac_intc_handler(8);
|
||||
return OK;
|
||||
}
|
||||
|
||||
static void controller_power_on(int ch)
|
||||
{
|
||||
int id = get_pmid(ch);
|
||||
|
||||
if (id == PM_APP_SKDMAC)
|
||||
return;
|
||||
|
||||
/* TODO power on */
|
||||
}
|
||||
|
||||
static void controller_power_off(int ch)
|
||||
{
|
||||
int id = get_pmid(ch);
|
||||
|
||||
if (id == PM_APP_SKDMAC) /* Do not disable SKDMAC, leave it to SAKE driver. */
|
||||
return;
|
||||
|
||||
/* TODO power off */
|
||||
}
|
||||
|
||||
int dma_init(int ch)
|
||||
{
|
||||
int id = ch2dmac(ch);
|
||||
|
||||
if (!id)
|
||||
return -ENODEV;
|
||||
|
||||
controller_power_on(ch);
|
||||
|
||||
irq_attach(irq_map[ch], intc_handler[ch], NULL);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int dma_uninit(int ch)
|
||||
{
|
||||
int id = ch2dmac(ch);
|
||||
|
||||
if (!id)
|
||||
return -ENODEV;
|
||||
|
||||
controller_power_off(ch);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int dma_open(int ch)
|
||||
{
|
||||
struct dmac_register_map *dmac = get_device(ch);
|
||||
irqstate_t flags;
|
||||
|
||||
if (dmac == NULL)
|
||||
return -ENODEV;
|
||||
|
||||
flags = enter_critical_section();
|
||||
|
||||
if (open_channels & (1u << ch)) {
|
||||
leave_critical_section(flags);
|
||||
return -EBUSY;
|
||||
}
|
||||
open_channels |= 1u << ch;
|
||||
|
||||
leave_critical_section(flags);
|
||||
|
||||
g_dmach[ch].callback = NULL;
|
||||
g_dmach[ch].arg = NULL;
|
||||
|
||||
dmac->sync = 0;
|
||||
dmac->configuration |= 1;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int dma_close(int ch)
|
||||
{
|
||||
struct dmac_register_map *dmac = get_device(ch);
|
||||
uint32_t enabled;
|
||||
irqstate_t flags;
|
||||
uint32_t chmask;
|
||||
int shift;
|
||||
|
||||
if (dmac == NULL)
|
||||
return -ENODEV;
|
||||
|
||||
shift = ch & 1;
|
||||
|
||||
if (is_dmac(2, dmac)) {
|
||||
shift = ch - 7;
|
||||
}
|
||||
else if (is_dmac(3, dmac)) {
|
||||
shift = ch - 2;
|
||||
}
|
||||
|
||||
enabled = dmac->enbldchns;
|
||||
if (enabled & (1 << shift))
|
||||
return -EBUSY;
|
||||
|
||||
dma_clearintrcallback(ch);
|
||||
|
||||
flags = enter_critical_section();
|
||||
|
||||
chmask = (3u << (ch & ~1));
|
||||
|
||||
if (is_dmac(2, dmac)) {
|
||||
chmask = 0x3u << 7;
|
||||
}
|
||||
else if (is_dmac(3, dmac)) {
|
||||
chmask = 0x1fu << 2;
|
||||
}
|
||||
|
||||
open_channels &= ~(1u << ch);
|
||||
|
||||
/* Stop device if both of channels are already closed */
|
||||
|
||||
if (!(open_channels & chmask))
|
||||
dmac->configuration &= ~1;
|
||||
|
||||
leave_critical_section(flags);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int dma_setconfig(int ch, int itc, int ierr, int flowctrl,
|
||||
int destperi, int srcperi)
|
||||
{
|
||||
struct dmac_ch_register_map *channel = get_channel(ch);
|
||||
if (channel == NULL)
|
||||
return -ENODEV;
|
||||
|
||||
channel->configuration = (itc & 1) << 15 |
|
||||
(ierr & 1) << 14 |
|
||||
(flowctrl & 7) << 11 |
|
||||
|
||||
/* Burst enable */
|
||||
|
||||
1 << 25 | 1 << 24 |
|
||||
|
||||
(destperi & 0xf) << 6 |
|
||||
(srcperi & 0xf) << 1;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int dma_setintrcallback(int ch, dma_callback_t func, void *data)
|
||||
{
|
||||
if (ch >= NCHANNELS)
|
||||
return -ENODEV;
|
||||
|
||||
g_dmach[ch].callback = func;
|
||||
g_dmach[ch].arg = data;
|
||||
|
||||
up_enable_irq(irq_map[ch]);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int dma_clearintrcallback(int ch)
|
||||
{
|
||||
if (ch >= NCHANNELS)
|
||||
return -ENODEV;
|
||||
|
||||
g_dmach[ch].callback = NULL;
|
||||
g_dmach[ch].arg = NULL;
|
||||
|
||||
up_disable_irq(irq_map[ch]);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int dma_start(int ch, dmac_lli_t *list)
|
||||
{
|
||||
struct dmac_ch_register_map *channel = get_channel(ch);
|
||||
if (channel == NULL)
|
||||
return -ENODEV;
|
||||
|
||||
if (list) {
|
||||
channel->srcaddr = list->src_addr;
|
||||
channel->destaddr = list->dest_addr;
|
||||
channel->lli = list->nextlli;
|
||||
channel->control = list->control;
|
||||
}
|
||||
|
||||
channel->configuration |= DMAC_CH_ENABLE;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int dma_stop(int ch)
|
||||
{
|
||||
struct dmac_ch_register_map *channel = get_channel(ch);
|
||||
if (channel == NULL)
|
||||
return -ENODEV;
|
||||
|
||||
if (!(channel->configuration & DMAC_CH_ENABLE))
|
||||
return 0; /* already stopped */
|
||||
|
||||
/* Set HALT and poll Active bit for FIFO is cleaned */
|
||||
|
||||
channel->configuration |= DMAC_CH_HALT;
|
||||
|
||||
(void) channel->lli;
|
||||
(void) channel->lli;
|
||||
|
||||
while (channel->configuration & DMAC_CH_ACTIVE);
|
||||
|
||||
channel->configuration &= ~(DMAC_CH_HALT | DMAC_CH_ENABLE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_dmainitialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize the DMA subsystem
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void weak_function up_dmainitialize(void)
|
||||
{
|
||||
int i;
|
||||
|
||||
dmainfo("Initialize DMAC\n");
|
||||
|
||||
/* Initialize the channel list */
|
||||
|
||||
for (i = 0; i < NCHANNELS; i++)
|
||||
{
|
||||
g_dmach[i].chan = i;
|
||||
}
|
||||
|
||||
sem_init(&g_dmaexc, 0, 1);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_dmachannel
|
||||
*
|
||||
* Description:
|
||||
* Allocate a DMA channel. This function gives the caller mutually exclusive
|
||||
* access to a DMA channel.
|
||||
*
|
||||
* If no DMA channel is available, then cxd56_dmachannel() will wait until
|
||||
* the holder of a channel relinquishes the channel by calling
|
||||
* cxd56_dmafree().
|
||||
*
|
||||
* Input parameters:
|
||||
* ch - DMA channel to use
|
||||
* maxsize - Max size to be transfered in bytes
|
||||
*
|
||||
* Returned Value:
|
||||
* This function ALWAYS returns a non-NULL, void* DMA channel handle.
|
||||
*
|
||||
* Assumptions:
|
||||
* - The caller can wait for a DMA channel to be freed if it is not
|
||||
* available.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
DMA_HANDLE cxd56_dmachannel(int ch, ssize_t maxsize)
|
||||
{
|
||||
struct dma_channel_s *dmach;
|
||||
int n;
|
||||
|
||||
/* Get exclusive access to allocate channel */
|
||||
|
||||
sem_wait(&g_dmaexc);
|
||||
|
||||
if (ch < 0 || ch >= NCHANNELS)
|
||||
{
|
||||
dmaerr("Invalid channel number %d.\n", ch);
|
||||
goto err;
|
||||
}
|
||||
dmach = &g_dmach[ch];
|
||||
|
||||
if (maxsize == 0)
|
||||
{
|
||||
dmaerr("Invalid max size: %d\n", maxsize);
|
||||
goto err;
|
||||
}
|
||||
|
||||
if (dmach->inuse)
|
||||
{
|
||||
dmaerr("Channel already in use.\n");
|
||||
goto err;
|
||||
}
|
||||
|
||||
dmainfo("DMA channel %d\n", dmach->chan);
|
||||
|
||||
n = maxsize / CXD56_DMAC_MAX_SIZE;
|
||||
if ((maxsize % CXD56_DMAC_MAX_SIZE) != 0)
|
||||
{
|
||||
n++;
|
||||
}
|
||||
|
||||
dmach->list = (dmac_lli_t *)kmm_malloc(n * sizeof(dmac_lli_t));
|
||||
if (dmach->list == NULL)
|
||||
{
|
||||
dmainfo("Failed to malloc\n");
|
||||
goto err;
|
||||
}
|
||||
|
||||
/* Initialize hardware */
|
||||
|
||||
dma_init(dmach->chan);
|
||||
dma_open(dmach->chan);
|
||||
|
||||
dmach->inuse = true;
|
||||
|
||||
sem_post(&g_dmaexc);
|
||||
|
||||
return (DMA_HANDLE)dmach;
|
||||
|
||||
err:
|
||||
sem_post(&g_dmaexc);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_dmafree
|
||||
*
|
||||
* Description:
|
||||
* Release a DMA channel. If another thread is waiting for this DMA channel
|
||||
* in a call to cxd56_dmachannel, then this function will re-assign the
|
||||
* DMA channel to that thread and wake it up.
|
||||
*
|
||||
* NOTE: The 'handle' used in this argument must NEVER be used again until
|
||||
* cxd56_dmachannel() is called again to re-gain access to the channel.
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
* Assumptions:
|
||||
* - The caller holds the DMA channel.
|
||||
* - There is no DMA in progress
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void cxd56_dmafree(DMA_HANDLE handle)
|
||||
{
|
||||
struct dma_channel_s *dmach = (struct dma_channel_s *)handle;
|
||||
|
||||
if (dmach == NULL)
|
||||
{
|
||||
dmaerr("Invalid handle.\n");
|
||||
return;
|
||||
}
|
||||
|
||||
sem_wait(&g_dmaexc);
|
||||
|
||||
if (!dmach->inuse)
|
||||
{
|
||||
dmaerr("Channel %d already freed.\n", dmach->chan);
|
||||
goto err;
|
||||
}
|
||||
|
||||
dmainfo("free DMA channel %d\n", dmach->chan);
|
||||
|
||||
kmm_free(dmach->list);
|
||||
|
||||
dma_close(dmach->chan);
|
||||
dma_uninit(dmach->chan);
|
||||
|
||||
dmach->inuse = false;
|
||||
|
||||
err:
|
||||
sem_post(&g_dmaexc);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_rxdmasetup
|
||||
*
|
||||
* Description:
|
||||
* Configure an RX (peripheral-to-memory) DMA before starting the transfer.
|
||||
*
|
||||
* Input Parameters:
|
||||
* paddr - Peripheral address (source)
|
||||
* maddr - Memory address (destination)
|
||||
* nbytes - Number of bytes to transfer. Must be an even multiple of the
|
||||
* configured transfer size.
|
||||
* config - Channel configuration selections
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void cxd56_rxdmasetup(DMA_HANDLE handle, uintptr_t paddr, uintptr_t maddr,
|
||||
size_t nbytes, dma_config_t config)
|
||||
{
|
||||
struct dma_channel_s *dmach = (struct dma_channel_s *)handle;
|
||||
int i;
|
||||
int list_num;
|
||||
uintptr_t dst;
|
||||
size_t rest;
|
||||
int peri;
|
||||
|
||||
DEBUGASSERT(dmach != NULL && dmach->inuse && dmach->list != NULL);
|
||||
|
||||
dst = maddr;
|
||||
rest = nbytes;
|
||||
|
||||
list_num = (nbytes + CXD56_DMAC_MAX_SIZE - 1) / CXD56_DMAC_MAX_SIZE;
|
||||
for (i = 0; i < list_num - 1; i++)
|
||||
{
|
||||
dmach->list[i].src_addr = paddr;
|
||||
dmach->list[i].dest_addr = dst;
|
||||
dmach->list[i].nextlli = (uint32_t)&dmach->list[i + 1];
|
||||
dmach->list[i].control = DMAC_EX_CTRL_HELPER(0, 1, 0, /* interrupt / Dest inc / Src inc */
|
||||
CXD56_DMAC_MASTER1, CXD56_DMAC_MASTER2, /* AHB dst master / AHB src master (fixed) */
|
||||
config.dest_width, config.src_width, /* Dest / Src transfer width */
|
||||
CXD56_DMAC_BSIZE4, CXD56_DMAC_BSIZE4, /* Dest / Src burst size (fixed) */
|
||||
CXD56_DMAC_MAX_SIZE);
|
||||
|
||||
dst += CXD56_DMAC_MAX_SIZE;
|
||||
rest -= CXD56_DMAC_MAX_SIZE;
|
||||
}
|
||||
|
||||
dmach->list[i].src_addr = paddr;
|
||||
dmach->list[i].dest_addr = dst;
|
||||
dmach->list[i].nextlli = 0;
|
||||
dmach->list[i].control = DMAC_EX_CTRL_HELPER(1, 1, 0, /* interrupt / Dest inc / Src inc */
|
||||
CXD56_DMAC_MASTER1, CXD56_DMAC_MASTER2, /* AHB dst master / AHB src master (fixed) */
|
||||
config.dest_width, config.src_width, /* Dest / Src transfer width */
|
||||
CXD56_DMAC_BSIZE4, CXD56_DMAC_BSIZE4, /* Dest / Src burst size (fixed) */
|
||||
rest);
|
||||
|
||||
peri = config.channel_cfg & CXD56_DMA_PERIPHERAL_MASK;
|
||||
dma_setconfig(dmach->chan, 1, 1, CXD56_DMAC_P2M, 0, peri);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_txdmasetup
|
||||
*
|
||||
* Description:
|
||||
* Configure an TX (memory-to-peripheral) DMA before starting the transfer.
|
||||
*
|
||||
* Input Parameters:
|
||||
* paddr - Peripheral address (destination)
|
||||
* maddr - Memory address (source)
|
||||
* nbytes - Number of bytes to transfer. Must be an even multiple of the
|
||||
* configured transfer size.
|
||||
* config - Channel configuration selections
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void cxd56_txdmasetup(DMA_HANDLE handle, uintptr_t paddr, uintptr_t maddr,
|
||||
size_t nbytes, dma_config_t config)
|
||||
{
|
||||
struct dma_channel_s *dmach = (struct dma_channel_s *)handle;
|
||||
int i;
|
||||
int list_num;
|
||||
uintptr_t src;
|
||||
size_t rest;
|
||||
int peri;
|
||||
|
||||
DEBUGASSERT(dmach != NULL && dmach->inuse && dmach->list != NULL);
|
||||
|
||||
src = maddr;
|
||||
rest = nbytes;
|
||||
|
||||
list_num = (nbytes + CXD56_DMAC_MAX_SIZE - 1) / CXD56_DMAC_MAX_SIZE;
|
||||
for (i = 0; i < list_num - 1; i++)
|
||||
{
|
||||
dmach->list[i].src_addr = src;
|
||||
dmach->list[i].dest_addr = paddr;
|
||||
dmach->list[i].nextlli = (uint32_t)&dmach->list[i + 1];
|
||||
dmach->list[i].control = DMAC_EX_CTRL_HELPER(0, 0, 1, /* interrupt / Dest inc / Src inc */
|
||||
CXD56_DMAC_MASTER2, CXD56_DMAC_MASTER1, /* AHB dst master / AHB src master (fixed) */
|
||||
config.dest_width, config.src_width, /* Dest / Src transfer width (fixed) */
|
||||
CXD56_DMAC_BSIZE1, CXD56_DMAC_BSIZE1, /* Dest / Src burst size (fixed) */
|
||||
CXD56_DMAC_MAX_SIZE);
|
||||
|
||||
src += CXD56_DMAC_MAX_SIZE;
|
||||
rest -= CXD56_DMAC_MAX_SIZE;
|
||||
}
|
||||
|
||||
dmach->list[i].src_addr = src;
|
||||
dmach->list[i].dest_addr = paddr;
|
||||
dmach->list[i].nextlli = 0;
|
||||
dmach->list[i].control = DMAC_EX_CTRL_HELPER(1, 0, 1, /* interrupt / Dest inc / Src inc */
|
||||
CXD56_DMAC_MASTER2, CXD56_DMAC_MASTER1, /* AHB dst master / AHB src master (fixed) */
|
||||
config.dest_width, config.src_width, /* Dest / Src transfer width (fixed) */
|
||||
CXD56_DMAC_BSIZE4, CXD56_DMAC_BSIZE4, /* Dest / Src burst size (fixed) */
|
||||
rest);
|
||||
|
||||
peri = config.channel_cfg & CXD56_DMA_PERIPHERAL_MASK;
|
||||
dma_setconfig(dmach->chan, 1, 1, CXD56_DMAC_M2P, peri, 0);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_dmastart
|
||||
*
|
||||
* Description:
|
||||
* Start the DMA transfer
|
||||
*
|
||||
* Assumptions:
|
||||
* - DMA handle allocated by cxd56_dmachannel()
|
||||
* - No DMA in progress
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void cxd56_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg)
|
||||
{
|
||||
struct dma_channel_s *dmach = (struct dma_channel_s *)handle;
|
||||
|
||||
DEBUGASSERT(dmach && dmach->inuse);
|
||||
|
||||
/* Save the DMA complete callback info */
|
||||
|
||||
dma_setintrcallback(dmach->chan, callback, arg);
|
||||
dma_start(dmach->chan, dmach->list);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_dmastop
|
||||
*
|
||||
* Description:
|
||||
* Cancel the DMA. After cxd56_dmastop() is called, the DMA channel is
|
||||
* reset and cxd56_dmasetup() must be called before cxd56_dmastart() can be
|
||||
* called again
|
||||
*
|
||||
* Assumptions:
|
||||
* - DMA handle allocated by cxd56_dmachannel()
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void cxd56_dmastop(DMA_HANDLE handle)
|
||||
{
|
||||
struct dma_channel_s *dmach = (struct dma_channel_s *)handle;
|
||||
|
||||
DEBUGASSERT(dmach);
|
||||
|
||||
dma_stop(dmach->chan);
|
||||
dma_clearintrcallback(dmach->chan);
|
||||
}
|
209
arch/arm/src/cxd56xx/cxd56_dmac.h
Normal file
209
arch/arm/src/cxd56xx/cxd56_dmac.h
Normal file
@ -0,0 +1,209 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/cxd56xx/cxd56_dmac.h
|
||||
*
|
||||
* Copyright (C) 2009, 2011-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 NuttX 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 cxd56_dmac.h
|
||||
*/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_CXD56XX_CXD56_DMAC_H
|
||||
#define __ARCH_ARM_SRC_CXD56XX_CXD56_DMAC_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "hardware/cxd56_dmac_common.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#define CXD56_DMA_PERIPHERAL_MASK (0x0f)
|
||||
#define CXD56_DMA_PERIPHERAL_UART2_TX (0)
|
||||
#define CXD56_DMA_PERIPHERAL_UART2_RX (1)
|
||||
#define CXD56_DMA_PERIPHERAL_SPI4_TX (2)
|
||||
#define CXD56_DMA_PERIPHERAL_SPI4_RX (3)
|
||||
#define CXD56_DMA_PERIPHERAL_SPI5_TX (4)
|
||||
#define CXD56_DMA_PERIPHERAL_SPI5_RX (5)
|
||||
|
||||
#define CXD56_DMA_INTR_ITC (1u<<0) /**< Terminal count interrupt status */
|
||||
#define CXD56_DMA_INTR_ERR (1u<<1) /**< Error interrupt status */
|
||||
|
||||
#define CXD56_DMAC_WIDTH8 0 /**< 8 bit width */
|
||||
#define CXD56_DMAC_WIDTH16 1 /**< 16 bit width */
|
||||
#define CXD56_DMAC_WIDTH32 2 /**< 32 bit width */
|
||||
|
||||
/****************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_dmachannel
|
||||
*
|
||||
* Description:
|
||||
* Allocate a DMA channel. This function gives the caller mutually exclusive
|
||||
* access to a DMA channel.
|
||||
*
|
||||
* If no DMA channel is available, then cxd56_dmachannel() will wait until
|
||||
* the holder of a channel relinquishes the channel by calling
|
||||
* cxd56_dmafree().
|
||||
*
|
||||
* Input parameters:
|
||||
* ch - DMA channel to use
|
||||
* maxsize - Max size to be transfered in bytes
|
||||
*
|
||||
* Returned Value:
|
||||
* This function ALWAYS returns a non-NULL, void* DMA channel handle.
|
||||
*
|
||||
* Assumptions:
|
||||
* - The caller can wait for a DMA channel to be freed if it is not
|
||||
* available.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
DMA_HANDLE cxd56_dmachannel(int ch, ssize_t maxsize);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_dmafree
|
||||
*
|
||||
* Description:
|
||||
* Release a DMA channel. If another thread is waiting for this DMA channel
|
||||
* in a call to cxd56_dmachannel, then this function will re-assign the DMA
|
||||
* channel to that thread and wake it up.
|
||||
*
|
||||
* NOTE: The 'handle' used in this argument must NEVER be used again until
|
||||
* cxd56_dmachannel() is called again to re-gain access to the channel.
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
* Assumptions:
|
||||
* - The caller holds the DMA channel.
|
||||
* - There is no DMA in progress
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void cxd56_dmafree(DMA_HANDLE handle);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_rxdmasetup
|
||||
*
|
||||
* Description:
|
||||
* Configure an RX (peripheral-to-memory) DMA before starting the transfer.
|
||||
*
|
||||
* Input Parameters:
|
||||
* paddr - Peripheral address (source)
|
||||
* maddr - Memory address (destination)
|
||||
* nbytes - Number of bytes to transfer. Must be an even multiple of the
|
||||
* configured transfer size.
|
||||
* config - Channel configuration selections
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void cxd56_rxdmasetup(DMA_HANDLE handle, uintptr_t paddr, uintptr_t maddr,
|
||||
size_t nbytes, dma_config_t config);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_txdmasetup
|
||||
*
|
||||
* Description:
|
||||
* Configure an TX (memory-to-peripheral) DMA before starting the transfer.
|
||||
*
|
||||
* Input Parameters:
|
||||
* paddr - Peripheral address (destination)
|
||||
* maddr - Memory address (source)
|
||||
* nbytes - Number of bytes to transfer. Must be an even multiple of the
|
||||
* configured transfer size.
|
||||
* config - Channel configuration selections
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void cxd56_txdmasetup(DMA_HANDLE handle, uintptr_t paddr, uintptr_t maddr,
|
||||
size_t nbytes, dma_config_t config);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_dmastart
|
||||
*
|
||||
* Description:
|
||||
* Start the DMA transfer
|
||||
*
|
||||
* Assumptions:
|
||||
* - DMA handle allocated by cxd56_dmachannel()
|
||||
* - No DMA in progress
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void cxd56_dmastart(DMA_HANDLE handle, dma_callback_t callback, void *arg);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_dmastop
|
||||
*
|
||||
* Description:
|
||||
* Cancel the DMA. After cxd56_dmastop() is called, the DMA channel is reset
|
||||
* and cxd56_dmasetup() must be called before cxd56_dmastart() can be called
|
||||
* again
|
||||
*
|
||||
* Assumptions:
|
||||
* - DMA handle allocated by cxd56_dmachannel()
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void cxd56_dmastop(DMA_HANDLE handle);
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_DMAC_H */
|
665
arch/arm/src/cxd56xx/cxd56_rtc.c
Normal file
665
arch/arm/src/cxd56xx/cxd56_rtc.c
Normal file
@ -0,0 +1,665 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/cxd56xx/cxd56_rtc.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 <stdlib.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/wdog.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "cxd56_rtc.h"
|
||||
|
||||
#include "hardware/cxd5602_topreg.h"
|
||||
#include "hardware/cxd5602_memorymap.h"
|
||||
#include "hardware/cxd5602_backupmem.h"
|
||||
#include "hardware/cxd56_rtc.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration ********************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_HIRES
|
||||
# ifndef CONFIG_RTC_FREQUENCY
|
||||
# define CONFIG_RTC_FREQUENCY 32768
|
||||
# endif
|
||||
# if CONFIG_RTC_FREQUENCY != 32768
|
||||
# error "Only lo-res CONFIG_RTC_FREQUENCY of 32.768kHz is supported"
|
||||
# endif
|
||||
#else
|
||||
# ifndef CONFIG_RTC_FREQUENCY
|
||||
# define CONFIG_RTC_FREQUENCY 1
|
||||
# endif
|
||||
# if CONFIG_RTC_FREQUENCY != 1
|
||||
# error "Only lo-res CONFIG_RTC_FREQUENCY of 1Hz is supported"
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/* convert seconds to 64bit counter value running at 32kHz */
|
||||
|
||||
#define SEC_TO_CNT(sec) ((uint64_t)(((uint64_t)(sec)) << 15))
|
||||
|
||||
/* convert nano-seconds to 32kHz counter less than 1 second */
|
||||
|
||||
#define NSEC_TO_PRECNT(nsec) \
|
||||
(((nsec) / (NSEC_PER_SEC / CONFIG_RTC_FREQUENCY)) & 0x7fff)
|
||||
|
||||
#define MAGIC_RTC_SAVE (0x12aae190077a80ull)
|
||||
|
||||
/* RTC clcok stable waiting time (interval x retry) */
|
||||
|
||||
#define RTC_CLOCK_CHECK_INTERVAL (200) /* milliseconds */
|
||||
#define RTC_CLOCK_CHECK_MAX_RETRY (15)
|
||||
|
||||
/************************************************************************************
|
||||
* Private Types
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
struct alm_cbinfo_s
|
||||
{
|
||||
volatile alm_callback_t ac_cb; /* Client callback function */
|
||||
volatile FAR void *ac_arg; /* Argument to pass with the callback function */
|
||||
};
|
||||
#endif
|
||||
|
||||
struct rtc_backup_s
|
||||
{
|
||||
uint64_t magic;
|
||||
int64_t reserved0;
|
||||
int64_t offset; /* offset time from RTC HW value */
|
||||
int64_t reserved1;
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
* Private Data
|
||||
************************************************************************************/
|
||||
|
||||
/* Callback to use when the alarm expires */
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
static struct alm_cbinfo_s g_alarmcb[RTC_ALARM_LAST];
|
||||
#endif
|
||||
|
||||
/* Saved data for persistent RTC time */
|
||||
|
||||
static struct rtc_backup_s *g_rtc_save;
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
||||
volatile bool g_rtc_enabled = false;
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: rtc_dumptime
|
||||
*
|
||||
* Description:
|
||||
* Dump RTC
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_DEBUG_RTC
|
||||
static void rtc_dumptime(FAR const struct timespec *tp, FAR const char *msg)
|
||||
{
|
||||
FAR struct tm tm;
|
||||
|
||||
(void)gmtime_r(&tp->tv_sec, &tm);
|
||||
|
||||
rtcinfo("%s:\n", msg);
|
||||
rtcinfo("RTC %u.%09u\n", tp->tv_sec, tp->tv_nsec);
|
||||
rtcinfo("%4d/%02d/%02d %02d:%02d:%02d\n",
|
||||
tm.tm_year, tm.tm_mon, tm.tm_mday,
|
||||
tm.tm_hour, tm.tm_min, tm.tm_sec);
|
||||
}
|
||||
#else
|
||||
# define rtc_dumptime(tp, msg)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: cxd56_rtc_interrupt
|
||||
*
|
||||
* Description:
|
||||
* RTC interrupt service routine
|
||||
*
|
||||
* Input Parameters:
|
||||
* irq - The IRQ number that generated the interrupt
|
||||
* context - Architecture specific register save information.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; A negated errno value on failure.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
static int cxd56_rtc_interrupt(int irq, FAR void *context, FAR void *arg)
|
||||
{
|
||||
FAR struct alm_cbinfo_s *cbinfo;
|
||||
alm_callback_t cb;
|
||||
FAR void *cb_arg;
|
||||
uint32_t source, clear;
|
||||
int id;
|
||||
int ret = OK;
|
||||
|
||||
/* interrupt clear */
|
||||
|
||||
source = getreg32(CXD56_RTC0_ALMFLG);
|
||||
|
||||
if (source & RTCREG_ALM0_MASK)
|
||||
{
|
||||
id = RTC_ALARM0;
|
||||
clear = source & RTCREG_ALM0_MASK;
|
||||
}
|
||||
else if (source & RTCREG_ALM1_MASK)
|
||||
{
|
||||
id = RTC_ALARM1;
|
||||
clear = source & RTCREG_ALM1_MASK;
|
||||
}
|
||||
else if (source & RTCREG_ALM2_MASK)
|
||||
{
|
||||
id = RTC_ALARM2;
|
||||
clear = source & RTCREG_ALM2_MASK;
|
||||
}
|
||||
else
|
||||
{
|
||||
rtcerr("ERROR: Invalid ALARM\n");
|
||||
return ret;
|
||||
}
|
||||
putreg32(clear, CXD56_RTC0_ALMCLR);
|
||||
putreg32(0, CXD56_RTC0_ALMOUTEN(id));
|
||||
|
||||
cbinfo = &g_alarmcb[id];
|
||||
|
||||
if (cbinfo->ac_cb != NULL)
|
||||
{
|
||||
/* Alarm callback */
|
||||
|
||||
cb = cbinfo->ac_cb;
|
||||
cb_arg = (FAR void*)cbinfo->ac_arg;
|
||||
|
||||
cbinfo->ac_cb = NULL;
|
||||
cbinfo->ac_arg = NULL;
|
||||
|
||||
cb(cb_arg, id);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Name: cxd56_rtc_initialize
|
||||
*
|
||||
* Description:
|
||||
* Actually initialize the hardware RTC. This function is called in the
|
||||
* initialization sequence, thereafter may be called when wdog timer is expired.
|
||||
*
|
||||
* Input Parameters:
|
||||
* arg: Not used
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void cxd56_rtc_initialize(int argc, uint32_t arg)
|
||||
{
|
||||
struct timespec ts;
|
||||
#ifdef CONFIG_CXD56_RTC_LATEINIT
|
||||
static WDOG_ID s_wdog = NULL;
|
||||
static int s_retry = 0;
|
||||
|
||||
if (s_wdog == NULL)
|
||||
{
|
||||
s_wdog = wd_create();
|
||||
}
|
||||
|
||||
/* Check whether RTC clock source selects the external RTC and the synchronization
|
||||
* from the external RTC is completed.
|
||||
*/
|
||||
|
||||
g_rtc_save = (struct rtc_backup_s*)BKUP->rtc_saved_data;
|
||||
|
||||
if (((getreg32(CXD56_TOPREG_CKSEL_ROOT) & STATUS_RTC_MASK) != STATUS_RTC_SEL) ||
|
||||
(g_rtc_save->magic != MAGIC_RTC_SAVE))
|
||||
{
|
||||
|
||||
/* Retry until RTC clock is stable */
|
||||
|
||||
if (s_retry++ < RTC_CLOCK_CHECK_MAX_RETRY) {
|
||||
|
||||
rtcinfo("retry count: %d\n", s_retry);
|
||||
|
||||
if (OK == wd_start(s_wdog, MSEC2TICK(RTC_CLOCK_CHECK_INTERVAL),
|
||||
(wdentry_t)cxd56_rtc_initialize, 1, (wdparm_t)NULL))
|
||||
{
|
||||
/* Again, this function is called recursively */
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
rtcerr("ERROR: Use inaccurate RCRTC instead of RTC\n");
|
||||
}
|
||||
|
||||
/* RTC clock is stable, or give up using the external RTC */
|
||||
|
||||
if (s_wdog != NULL)
|
||||
{
|
||||
wd_delete(s_wdog);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
/* Configure RTC interrupt to catch overflow and alarm interrupts. */
|
||||
|
||||
irq_attach(CXD56_IRQ_RTC0_A0, cxd56_rtc_interrupt, NULL);
|
||||
irq_attach(CXD56_IRQ_RTC0_A2, cxd56_rtc_interrupt, NULL);
|
||||
irq_attach(CXD56_IRQ_RTC_INT, cxd56_rtc_interrupt, NULL);
|
||||
up_enable_irq(CXD56_IRQ_RTC0_A0);
|
||||
up_enable_irq(CXD56_IRQ_RTC0_A2);
|
||||
up_enable_irq(CXD56_IRQ_RTC_INT);
|
||||
#endif
|
||||
|
||||
/* If saved data is invalid, clear offset information */
|
||||
|
||||
if (g_rtc_save->magic != MAGIC_RTC_SAVE)
|
||||
{
|
||||
g_rtc_save->offset = 0;
|
||||
}
|
||||
|
||||
if (g_rtc_save->offset == 0)
|
||||
{
|
||||
/* Keep the system operating time before RTC is enabled. */
|
||||
|
||||
clock_systimespec(&ts);
|
||||
}
|
||||
|
||||
/* Synchronize the system time to the RTC time */
|
||||
|
||||
clock_synchronize();
|
||||
|
||||
if (g_rtc_save->offset == 0)
|
||||
{
|
||||
/* Reflect the system operating time to RTC offset data. */
|
||||
|
||||
g_rtc_save->offset = SEC_TO_CNT(ts.tv_sec) | NSEC_TO_PRECNT(ts.tv_nsec);
|
||||
}
|
||||
|
||||
/* Make it possible to use the RTC timer functions */
|
||||
|
||||
g_rtc_enabled = true;
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_rtc_initialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize the hardware RTC per the selected configuration. This function is
|
||||
* called once during the OS initialization sequence
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int up_rtc_initialize(void)
|
||||
{
|
||||
cxd56_rtc_initialize(1, (wdparm_t)NULL);
|
||||
return OK;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_rtc_time
|
||||
*
|
||||
* Description:
|
||||
* Get the current time in seconds. This is similar to the standard time()
|
||||
* function. This interface is only required if the low-resolution RTC/counter
|
||||
* hardware implementation selected. It is only used by the RTOS during
|
||||
* initialization to set up the system time when CONFIG_RTC is set but neither
|
||||
* CONFIG_RTC_HIRES nor CONFIG_RTC_DATETIME are set.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* The current time in seconds
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef CONFIG_RTC_HIRES
|
||||
time_t up_rtc_time(void)
|
||||
{
|
||||
uint64_t count;
|
||||
|
||||
count = cxd56_rtc_count();
|
||||
count += g_rtc_save->offset;
|
||||
count >>= 15; /* convert to 1sec resolution */
|
||||
|
||||
return (time_t)count/CONFIG_RTC_FREQUENCY;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_rtc_gettime
|
||||
*
|
||||
* Description:
|
||||
* Get the current time from the high resolution RTC clock/counter. This interface
|
||||
* is only supported by the high-resolution RTC/counter hardware implementation.
|
||||
* It is used to replace the system timer.
|
||||
*
|
||||
* Input Parameters:
|
||||
* tp - The location to return the high resolution time value.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_HIRES
|
||||
int up_rtc_gettime(FAR struct timespec *tp)
|
||||
{
|
||||
uint64_t count;
|
||||
|
||||
count = cxd56_rtc_count();
|
||||
count += g_rtc_save->offset;
|
||||
|
||||
/* Then we can save the time in seconds and fractional seconds. */
|
||||
|
||||
tp->tv_sec = count / CONFIG_RTC_FREQUENCY;
|
||||
tp->tv_nsec = (count % CONFIG_RTC_FREQUENCY)*(NSEC_PER_SEC/CONFIG_RTC_FREQUENCY);
|
||||
|
||||
rtc_dumptime(tp, "Getting time");
|
||||
|
||||
return OK;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: up_rtc_settime
|
||||
*
|
||||
* Description:
|
||||
* Set the RTC to the provided time. All RTC implementations must be able to
|
||||
* set their time based on a standard timespec.
|
||||
*
|
||||
* Input Parameters:
|
||||
* tp - the time to use
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int up_rtc_settime(FAR const struct timespec *tp)
|
||||
{
|
||||
irqstate_t flags;
|
||||
uint64_t count;
|
||||
|
||||
flags = enter_critical_section();
|
||||
|
||||
#ifdef RTC_DIRECT_CONTROL
|
||||
/* wait until previous write request is completed */
|
||||
|
||||
while (RTCREG_WREQ_BUSYA_MASK & getreg32(CXD56_RTC0_WRREGREQ));
|
||||
|
||||
putreg32(tp->tv_sec, CXD56_RTC0_WRREGPOSTCNT);
|
||||
putreg32(NSEC_TO_PRECNT(tp->tv_nsec), CXD56_RTC0_WRREGPRECNT);
|
||||
|
||||
putreg32(RTCREG_WREQ_BUSYA_MASK, CXD56_RTC0_WRREGREQ);
|
||||
|
||||
/* wait until write request reflected */
|
||||
|
||||
while (RTCREG_WREQ_BUSYB_MASK & getreg32(CXD56_RTC0_WRREGREQ));
|
||||
|
||||
#else
|
||||
/* Only save the difference from HW raw value */
|
||||
|
||||
count = SEC_TO_CNT(tp->tv_sec) | NSEC_TO_PRECNT(tp->tv_nsec);
|
||||
g_rtc_save->offset = (int64_t)count - (int64_t)cxd56_rtc_count();
|
||||
#endif
|
||||
|
||||
leave_critical_section(flags);
|
||||
|
||||
rtc_dumptime(tp, "Setting time");
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: cxd56_rtc_count
|
||||
*
|
||||
* Description:
|
||||
* Get RTC raw counter value
|
||||
*
|
||||
* Returned Value:
|
||||
* 64bit counter value running at 32kHz
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
uint64_t cxd56_rtc_count(void)
|
||||
{
|
||||
uint64_t val;
|
||||
irqstate_t flags;
|
||||
|
||||
/*
|
||||
* The pre register is latched with reading the post rtcounter register,
|
||||
* so these registers always have to been read in the below order,
|
||||
* 1st post -> 2nd pre, and should be operated in atomic.
|
||||
*/
|
||||
|
||||
flags = enter_critical_section();
|
||||
|
||||
val = (uint64_t)getreg32(CXD56_RTC0_RTPOSTCNT) << 15;
|
||||
val |= getreg32(CXD56_RTC0_RTPRECNT);
|
||||
|
||||
leave_critical_section(flags);
|
||||
|
||||
return val;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: cxd56_rtc_almcount
|
||||
*
|
||||
* Description:
|
||||
* Get RTC raw alarm counter value
|
||||
*
|
||||
* Returned Value:
|
||||
* 64bit alarm counter value running at 32kHz
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
uint64_t cxd56_rtc_almcount(void)
|
||||
{
|
||||
uint64_t val;
|
||||
irqstate_t flags;
|
||||
|
||||
flags = enter_critical_section();
|
||||
|
||||
val = (uint64_t)getreg32(CXD56_RTC0_SETALMPOSTCNT(0)) << 15;
|
||||
val |= (getreg32(CXD56_RTC0_SETALMPRECNT(0)) & 0x7fff);
|
||||
|
||||
leave_critical_section(flags);
|
||||
|
||||
return val;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: cxd56_rtc_setalarm
|
||||
*
|
||||
* Description:
|
||||
* Set up an alarm.
|
||||
*
|
||||
* Input Parameters:
|
||||
* alminfo - Information about the alarm configuration.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
int cxd56_rtc_setalarm(FAR struct alm_setalarm_s *alminfo)
|
||||
{
|
||||
FAR struct alm_cbinfo_s *cbinfo;
|
||||
irqstate_t flags;
|
||||
int ret = -EBUSY;
|
||||
int id;
|
||||
uint64_t count;
|
||||
|
||||
ASSERT(alminfo != NULL);
|
||||
DEBUGASSERT(RTC_ALARM_LAST > alminfo->as_id);
|
||||
|
||||
/* Set the alarm in hardware and enable interrupts */
|
||||
|
||||
id = alminfo->as_id;
|
||||
cbinfo = &g_alarmcb[id];
|
||||
|
||||
if (cbinfo->ac_cb == NULL)
|
||||
{
|
||||
/* The set the alarm */
|
||||
|
||||
flags = enter_critical_section();
|
||||
|
||||
cbinfo->ac_cb = alminfo->as_cb;
|
||||
cbinfo->ac_arg = alminfo->as_arg;
|
||||
|
||||
count = SEC_TO_CNT(alminfo->as_time.tv_sec) |
|
||||
NSEC_TO_PRECNT(alminfo->as_time.tv_nsec);
|
||||
|
||||
count -= g_rtc_save->offset;
|
||||
|
||||
/* wait until previous alarm request is completed */
|
||||
|
||||
while (RTCREG_ASET_BUSY_MASK & getreg32(CXD56_RTC0_SETALMPRECNT(id)));
|
||||
|
||||
putreg32((uint32_t)(count >> 15), CXD56_RTC0_SETALMPOSTCNT(id));
|
||||
putreg32((uint32_t)(count & 0x7fff), CXD56_RTC0_SETALMPRECNT(id));
|
||||
|
||||
while (RTCREG_ALM_BUSY_MASK & getreg32(CXD56_RTC0_ALMOUTEN(id)));
|
||||
|
||||
putreg32(RTCREG_ALM_EN_MASK | RTCREG_ALM_ERREN_MASK,
|
||||
CXD56_RTC0_ALMOUTEN(id));
|
||||
|
||||
while (RTCREG_ALM_BUSY_MASK & getreg32(CXD56_RTC0_ALMOUTEN(id)));
|
||||
|
||||
leave_critical_section(flags);
|
||||
|
||||
rtc_dumptime(&alminfo->as_time, "New Alarm time");
|
||||
ret = OK;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: cxd56_rtc_cancelalarm
|
||||
*
|
||||
* Description:
|
||||
* Cancel an alaram.
|
||||
*
|
||||
* Input Parameters:
|
||||
* alarmid - Identifies the alarm to be cancelled
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
int cxd56_rtc_cancelalarm(enum alm_id_e alarmid)
|
||||
{
|
||||
FAR struct alm_cbinfo_s *cbinfo;
|
||||
irqstate_t flags;
|
||||
int ret = -ENODATA;
|
||||
|
||||
DEBUGASSERT(RTC_ALARM_LAST > alarmid);
|
||||
|
||||
/* Set the alarm in hardware and enable interrupts */
|
||||
|
||||
cbinfo = &g_alarmcb[alarmid];
|
||||
|
||||
if (cbinfo->ac_cb != NULL)
|
||||
{
|
||||
/* Unset the alarm */
|
||||
|
||||
flags = enter_critical_section();
|
||||
|
||||
cbinfo->ac_cb = NULL;
|
||||
|
||||
while (RTCREG_ALM_BUSY_MASK & getreg32(CXD56_RTC0_ALMOUTEN(alarmid)));
|
||||
|
||||
putreg32(0, CXD56_RTC0_ALMOUTEN(alarmid));
|
||||
|
||||
leave_critical_section(flags);
|
||||
|
||||
ret = OK;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
#endif
|
191
arch/arm/src/cxd56xx/cxd56_rtc.h
Normal file
191
arch/arm/src/cxd56xx/cxd56_rtc.h
Normal file
@ -0,0 +1,191 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/cxd56xx/cxd56_rtc.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_RTC_H
|
||||
#define __ARCH_ARM_SRC_CXD56XX_CXD56_RTC_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <time.h>
|
||||
#include <nuttx/timers/rtc.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
|
||||
/* The form of an alarm callback */
|
||||
|
||||
typedef CODE void (*alm_callback_t)(FAR void *arg, unsigned int alarmid);
|
||||
|
||||
enum alm_id_e
|
||||
{
|
||||
RTC_ALARM0 = 0, /* RTC ALARM 0 */
|
||||
RTC_ALARM_LAST,
|
||||
RTC_ALARM1 = 1, /* RTC ALARM 1 */
|
||||
RTC_ALARM2, /* RTC ALARM 2 (relative) */
|
||||
};
|
||||
|
||||
/* Structure used to pass parmaters to set an alarm */
|
||||
|
||||
struct alm_setalarm_s
|
||||
{
|
||||
int as_id; /* enum alm_id_e */
|
||||
struct timespec as_time; /* Alarm expiration time */
|
||||
alm_callback_t as_cb; /* Callback (if non-NULL) */
|
||||
FAR void *as_arg; /* Argument for callback */
|
||||
};
|
||||
|
||||
#endif /* CONFIG_RTC_ALARM */
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: cxd56_rtc_count
|
||||
*
|
||||
* Description:
|
||||
* Get RTC raw counter value
|
||||
*
|
||||
* Returned Value:
|
||||
* 64bit counter value running at 32kHz
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
uint64_t cxd56_rtc_count(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: cxd56_rtc_almcount
|
||||
*
|
||||
* Description:
|
||||
* Get RTC raw alarm counter value
|
||||
*
|
||||
* Returned Value:
|
||||
* 64bit alarm counter value running at 32kHz
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
uint64_t cxd56_rtc_almcount(void);
|
||||
#endif /* CONFIG_RTC_ALARM */
|
||||
|
||||
/************************************************************************************
|
||||
* Name: cxd56_rtc_setalarm
|
||||
*
|
||||
* Description:
|
||||
* Set up an alarm.
|
||||
*
|
||||
* Input Parameters:
|
||||
* alminfo - Information about the alarm configuration.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
int cxd56_rtc_setalarm(FAR struct alm_setalarm_s *alminfo);
|
||||
#endif /* CONFIG_RTC_ALARM */
|
||||
|
||||
/************************************************************************************
|
||||
* Name: cxd56_rtc_cancelalarm
|
||||
*
|
||||
* Description:
|
||||
* Cancel an alaram.
|
||||
*
|
||||
* Input Parameters:
|
||||
* alarmid - Identifies the alarm to be cancelled
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) on success; a negated errno on failure
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
int cxd56_rtc_cancelalarm(enum alm_id_e alarmid);
|
||||
#endif /* CONFIG_RTC_ALARM */
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_rtc_lowerhalf
|
||||
*
|
||||
* Description:
|
||||
* Instantiate the RTC lower half driver for the STM32L4. General usage:
|
||||
*
|
||||
* #include <nuttx/timers/rtc.h>
|
||||
* #include "stm32l4_rtc.h>
|
||||
*
|
||||
* struct rtc_lowerhalf_s *lower;
|
||||
* lower = stm32l4_rtc_lowerhalf();
|
||||
* rtc_initialize(0, lower);
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* On success, a non-NULL RTC lower interface is returned. NULL is
|
||||
* returned on any failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_DRIVER
|
||||
FAR struct rtc_lowerhalf_s *cxd56_rtc_lowerhalf(void);
|
||||
#endif /* CONFIG_RTC_DRIVER */
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_RTC_H */
|
544
arch/arm/src/cxd56xx/cxd56_rtc_lowerhalf.c
Normal file
544
arch/arm/src/cxd56xx/cxd56_rtc_lowerhalf.c
Normal file
@ -0,0 +1,544 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/cxd56xx/cxd56_rtc_lowerhalf.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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* REVISIT: This driver is *not* thread-safe! */
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdbool.h>
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/timers/rtc.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "cxd56_rtc.h"
|
||||
|
||||
#ifdef CONFIG_RTC_DRIVER
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
struct cxd56_cbinfo_s
|
||||
{
|
||||
volatile rtc_alarm_callback_t cb; /* Callback when the alarm expires */
|
||||
volatile FAR void *priv; /* Private argurment to accompany callback */
|
||||
};
|
||||
#endif
|
||||
|
||||
/* This is the private type for the RTC state. It must be cast compatible
|
||||
* with struct rtc_lowerhalf_s.
|
||||
*/
|
||||
|
||||
struct cxd56_lowerhalf_s
|
||||
{
|
||||
/* This is the contained reference to the read-only, lower-half
|
||||
* operations vtable (which may lie in FLASH or ROM)
|
||||
*/
|
||||
|
||||
FAR const struct rtc_ops_s *ops;
|
||||
|
||||
/* Data following is private to this driver and not visible outside of
|
||||
* this file.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
/* Alarm callback information */
|
||||
|
||||
struct cxd56_cbinfo_s cbinfo[RTC_ALARM_LAST];
|
||||
#endif
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
/* Prototypes for static methods in struct rtc_ops_s */
|
||||
|
||||
static int cxd56_rdtime(FAR struct rtc_lowerhalf_s *lower,
|
||||
FAR struct rtc_time *rtctime);
|
||||
static int cxd56_settime(FAR struct rtc_lowerhalf_s *lower,
|
||||
FAR const struct rtc_time *rtctime);
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
static int cxd56_setalarm(FAR struct rtc_lowerhalf_s *lower,
|
||||
FAR const struct lower_setalarm_s *alarminfo);
|
||||
static int cxd56_setrelative(FAR struct rtc_lowerhalf_s *lower,
|
||||
FAR const struct lower_setrelative_s *alarminfo);
|
||||
static int cxd56_cancelalarm(FAR struct rtc_lowerhalf_s *lower,
|
||||
int alarmid);
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
/* CXD56 RTC driver operations */
|
||||
|
||||
static const struct rtc_ops_s g_rtc_ops =
|
||||
{
|
||||
.rdtime = cxd56_rdtime,
|
||||
.settime = cxd56_settime,
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
.setalarm = cxd56_setalarm,
|
||||
.setrelative = cxd56_setrelative,
|
||||
.cancelalarm = cxd56_cancelalarm,
|
||||
#endif
|
||||
#ifdef CONFIG_RTC_IOCTL
|
||||
.ioctl = NULL,
|
||||
#endif
|
||||
#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS
|
||||
.destroy = NULL,
|
||||
#endif
|
||||
};
|
||||
|
||||
/* CXD56 RTC device state */
|
||||
|
||||
static struct cxd56_lowerhalf_s g_rtc_lowerhalf =
|
||||
{
|
||||
.ops = &g_rtc_ops,
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_alarm_callback
|
||||
*
|
||||
* Description:
|
||||
* This is the function that is called from the RTC driver when the alarm
|
||||
* goes off. It just invokes the upper half drivers callback.
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
static void cxd56_alarm_callback(FAR void *arg, unsigned int alarmid)
|
||||
{
|
||||
FAR struct cxd56_lowerhalf_s *lower;
|
||||
FAR struct cxd56_cbinfo_s *cbinfo;
|
||||
rtc_alarm_callback_t cb;
|
||||
FAR void *priv;
|
||||
|
||||
DEBUGASSERT((RTC_ALARM0 <= alarmid) && (alarmid < RTC_ALARM_LAST));
|
||||
|
||||
lower = (struct cxd56_lowerhalf_s *)arg;
|
||||
cbinfo = &lower->cbinfo[alarmid];
|
||||
|
||||
/* Sample and clear the callback information to minimize the window in
|
||||
* time in which race conditions can occur.
|
||||
*/
|
||||
|
||||
cb = (rtc_alarm_callback_t)cbinfo->cb;
|
||||
priv = (FAR void *)cbinfo->priv;
|
||||
|
||||
cbinfo->cb = NULL;
|
||||
cbinfo->priv = NULL;
|
||||
|
||||
/* Perform the callback */
|
||||
|
||||
if (cb != NULL)
|
||||
{
|
||||
cb(priv, alarmid);
|
||||
}
|
||||
}
|
||||
#endif /* CONFIG_RTC_ALARM */
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_rdtime
|
||||
*
|
||||
* Description:
|
||||
* Implements the rdtime() method of the RTC driver interface
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - A reference to RTC lower half driver state structure
|
||||
* rcttime - The location in which to return the current RTC time.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned
|
||||
* on any failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int cxd56_rdtime(FAR struct rtc_lowerhalf_s *lower,
|
||||
FAR struct rtc_time *rtctime)
|
||||
{
|
||||
#if defined(CONFIG_RTC_HIRES)
|
||||
FAR struct timespec ts;
|
||||
int ret;
|
||||
|
||||
/* Get the higher resolution time */
|
||||
|
||||
ret = up_rtc_gettime(&ts);
|
||||
if (ret < 0)
|
||||
{
|
||||
goto errout_with_errno;
|
||||
}
|
||||
|
||||
/* Convert the one second epoch time to a struct tm. This operation
|
||||
* depends on the fact that struct rtc_time and struct tm are cast
|
||||
* compatible.
|
||||
*/
|
||||
|
||||
if (!gmtime_r(&ts.tv_sec, (FAR struct tm *)rtctime))
|
||||
{
|
||||
goto errout_with_errno;
|
||||
}
|
||||
|
||||
return OK;
|
||||
|
||||
errout_with_errno:
|
||||
ret = get_errno();
|
||||
DEBUGASSERT(ret > 0);
|
||||
return -ret;
|
||||
|
||||
#else
|
||||
time_t timer;
|
||||
|
||||
/* The resolution of time is only 1 second */
|
||||
|
||||
timer = up_rtc_time();
|
||||
|
||||
/* Convert the one second epoch time to a struct tm */
|
||||
|
||||
if (!gmtime_r(&timer, (FAR struct tm *)rtctime))
|
||||
{
|
||||
int errcode = get_errno();
|
||||
DEBUGASSERT(errcode > 0);
|
||||
return -errcode;
|
||||
}
|
||||
|
||||
return OK;
|
||||
#endif
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_settime
|
||||
*
|
||||
* Description:
|
||||
* Implements the settime() method of the RTC driver interface
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - A reference to RTC lower half driver state structure
|
||||
* rcttime - The new time to set
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned
|
||||
* on any failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int cxd56_settime(FAR struct rtc_lowerhalf_s *lower,
|
||||
FAR const struct rtc_time *rtctime)
|
||||
{
|
||||
struct timespec ts;
|
||||
|
||||
/* Convert the struct rtc_time to a time_t. Here we assume that struct
|
||||
* rtc_time is cast compatible with struct tm.
|
||||
*/
|
||||
|
||||
ts.tv_sec = mktime((FAR struct tm *)rtctime);
|
||||
ts.tv_nsec = 0;
|
||||
|
||||
/* Now set the time (to one second accuracy) */
|
||||
|
||||
return up_rtc_settime(&ts);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_setalarm
|
||||
*
|
||||
* Description:
|
||||
* Set a new alarm. This function implements the setalarm() method of the
|
||||
* RTC driver interface
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - A reference to RTC lower half driver state structure
|
||||
* alarminfo - Provided information needed to set the alarm
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned
|
||||
* on any failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
static int cxd56_setalarm(FAR struct rtc_lowerhalf_s *lower,
|
||||
FAR const struct lower_setalarm_s *alarminfo)
|
||||
{
|
||||
FAR struct cxd56_lowerhalf_s *priv;
|
||||
FAR struct cxd56_cbinfo_s *cbinfo;
|
||||
struct alm_setalarm_s lowerinfo;
|
||||
int ret = -EINVAL;
|
||||
|
||||
DEBUGASSERT(lower != NULL && alarminfo != NULL);
|
||||
DEBUGASSERT((RTC_ALARM0 == alarminfo->id) || (RTC_ALARM1 == alarminfo->id));
|
||||
|
||||
priv = (FAR struct cxd56_lowerhalf_s *)lower;
|
||||
|
||||
if ((RTC_ALARM0 == alarminfo->id) || (RTC_ALARM1 == alarminfo->id))
|
||||
{
|
||||
/* Remember the callback information */
|
||||
|
||||
cbinfo = &priv->cbinfo[alarminfo->id];
|
||||
cbinfo->cb = alarminfo->cb;
|
||||
cbinfo->priv = alarminfo->priv;
|
||||
|
||||
/* Set the alarm */
|
||||
|
||||
lowerinfo.as_id = alarminfo->id;
|
||||
lowerinfo.as_cb = cxd56_alarm_callback;
|
||||
lowerinfo.as_arg = priv;
|
||||
|
||||
/* Convert the RTC time to a timespec (1 second accuracy) */
|
||||
|
||||
lowerinfo.as_time.tv_sec = mktime((FAR struct tm *)&alarminfo->time);
|
||||
lowerinfo.as_time.tv_nsec = 0;
|
||||
|
||||
/* And set the alarm */
|
||||
|
||||
ret = cxd56_rtc_setalarm(&lowerinfo);
|
||||
if (ret < 0)
|
||||
{
|
||||
cbinfo->cb = NULL;
|
||||
cbinfo->priv = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_setrelative
|
||||
*
|
||||
* Description:
|
||||
* Set a new alarm relative to the current time. This function implements
|
||||
* the setrelative() method of the RTC driver interface
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - A reference to RTC lower half driver state structure
|
||||
* alarminfo - Provided information needed to set the alarm
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned
|
||||
* on any failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
static int cxd56_setrelative(FAR struct rtc_lowerhalf_s *lower,
|
||||
FAR const struct lower_setrelative_s *alarminfo)
|
||||
{
|
||||
struct lower_setalarm_s setalarm;
|
||||
FAR struct timespec ts;
|
||||
struct alm_setalarm_s lowerinfo;
|
||||
FAR struct cxd56_lowerhalf_s *priv;
|
||||
FAR struct cxd56_cbinfo_s *cbinfo;
|
||||
time_t seconds;
|
||||
int ret = -EINVAL;
|
||||
|
||||
DEBUGASSERT(lower != NULL && alarminfo != NULL);
|
||||
DEBUGASSERT((RTC_ALARM0 <= alarminfo->id) && (alarminfo->id < RTC_ALARM_LAST));
|
||||
|
||||
if (((alarminfo->id == RTC_ALARM0) || (alarminfo->id == RTC_ALARM1)) &&
|
||||
(alarminfo->reltime > 0))
|
||||
{
|
||||
/* Disable pre-emption while we do this so that we don't have to worry
|
||||
* about being suspended and working on an old time.
|
||||
*/
|
||||
|
||||
sched_lock();
|
||||
|
||||
#if defined(CONFIG_RTC_HIRES)
|
||||
/* Get the higher resolution time */
|
||||
|
||||
ret = up_rtc_gettime(&ts);
|
||||
if (ret < 0)
|
||||
{
|
||||
sched_unlock();
|
||||
return ret;
|
||||
}
|
||||
#else
|
||||
/* The resolution of time is only 1 second */
|
||||
|
||||
ts.tv_sec = up_rtc_time();
|
||||
ts.tv_nsec = 0;
|
||||
#endif
|
||||
|
||||
/* Add the seconds offset. Add one to the number of seconds because
|
||||
* we are unsure of the phase of the timer.
|
||||
*/
|
||||
|
||||
seconds = ts.tv_sec + (alarminfo->reltime + 1);
|
||||
|
||||
(void)gmtime_r(&seconds, (FAR struct tm *)&setalarm.time);
|
||||
|
||||
/* The set the alarm using this absolute time */
|
||||
|
||||
setalarm.id = alarminfo->id;
|
||||
setalarm.cb = alarminfo->cb;
|
||||
setalarm.priv = alarminfo->priv;
|
||||
|
||||
ret = cxd56_setalarm(lower, &setalarm);
|
||||
|
||||
sched_unlock();
|
||||
}
|
||||
else if ((alarminfo->id == RTC_ALARM2) && (alarminfo->reltime > 0))
|
||||
{
|
||||
sched_lock();
|
||||
|
||||
priv = (FAR struct cxd56_lowerhalf_s *)lower;
|
||||
|
||||
/* Remember the callback information */
|
||||
|
||||
cbinfo = &priv->cbinfo[alarminfo->id];
|
||||
cbinfo->cb = alarminfo->cb;
|
||||
cbinfo->priv = alarminfo->priv;
|
||||
|
||||
/* Set the alarm */
|
||||
|
||||
lowerinfo.as_id = alarminfo->id;
|
||||
lowerinfo.as_cb = cxd56_alarm_callback;
|
||||
lowerinfo.as_arg = priv;
|
||||
|
||||
lowerinfo.as_time.tv_sec = alarminfo->reltime;
|
||||
lowerinfo.as_time.tv_nsec = 0;
|
||||
|
||||
ret = cxd56_rtc_setalarm(&lowerinfo);
|
||||
if (ret < 0)
|
||||
{
|
||||
cbinfo->cb = NULL;
|
||||
cbinfo->priv = NULL;
|
||||
}
|
||||
|
||||
sched_unlock();
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_cancelalarm
|
||||
*
|
||||
* Description:
|
||||
* Cancel the current alarm. This function implements the cancelalarm()
|
||||
* method of the RTC driver interface
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - A reference to RTC lower half driver state structure
|
||||
* alarmid - the alarm id
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned
|
||||
* on any failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_RTC_ALARM
|
||||
static int cxd56_cancelalarm(FAR struct rtc_lowerhalf_s *lower, int alarmid)
|
||||
{
|
||||
FAR struct cxd56_lowerhalf_s *priv;
|
||||
FAR struct cxd56_cbinfo_s *cbinfo;
|
||||
int ret = -EINVAL;
|
||||
|
||||
DEBUGASSERT(lower != NULL);
|
||||
DEBUGASSERT((RTC_ALARM0 <= alarmid) && (alarmid < RTC_ALARM_LAST));
|
||||
|
||||
priv = (FAR struct cxd56_lowerhalf_s *)lower;
|
||||
|
||||
if ((RTC_ALARM0 <= alarmid) && (alarmid < RTC_ALARM_LAST))
|
||||
{
|
||||
/* Nullify callback information to reduce window for race conditions */
|
||||
|
||||
cbinfo = &priv->cbinfo[alarmid];
|
||||
cbinfo->cb = NULL;
|
||||
cbinfo->priv = NULL;
|
||||
|
||||
/* Then cancel the alarm */
|
||||
|
||||
ret = cxd56_rtc_cancelalarm((enum alm_id_e)alarmid);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_rtc_lowerhalf
|
||||
*
|
||||
* Description:
|
||||
* Instantiate the RTC lower half driver for the CXD56. General usage:
|
||||
*
|
||||
* #include <nuttx/timers/rtc.h>
|
||||
* #include "cxd56_rtc.h"
|
||||
*
|
||||
* struct rtc_lowerhalf_s *lower;
|
||||
* lower = cxd56_rtc_lowerhalf();
|
||||
* rtc_initialize(0, lower);
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* On success, a non-NULL RTC lower interface is returned. NULL is
|
||||
* returned on any failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
FAR struct rtc_lowerhalf_s *cxd56_rtc_lowerhalf(void)
|
||||
{
|
||||
return (FAR struct rtc_lowerhalf_s *)&g_rtc_lowerhalf;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_RTC_DRIVER */
|
1625
arch/arm/src/cxd56xx/cxd56_spi.c
Normal file
1625
arch/arm/src/cxd56xx/cxd56_spi.c
Normal file
File diff suppressed because it is too large
Load Diff
224
arch/arm/src/cxd56xx/cxd56_spi.h
Normal file
224
arch/arm/src/cxd56xx/cxd56_spi.h
Normal file
@ -0,0 +1,224 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/cxd56xx/cxd56_spi.h
|
||||
*
|
||||
* Copyright (C) 2012, 2015 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 NuttX 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_SPI_H
|
||||
#define __ARCH_ARM_SRC_CXD56XX_CXD56_SPI_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include "hardware/cxd56_spi.h"
|
||||
|
||||
#if defined(CONFIG_CXD56_SPI0) || defined(CONFIG_CXD56_SPI3) || \
|
||||
defined(CONFIG_CXD56_SPI4) || defined(CONFIG_CXD56_SPI5)
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
/* This header file defines interfaces to common SPI logic.
|
||||
* To use this common SPI logic on your board:
|
||||
*
|
||||
* 1. Provide logic in cxd56_boardinitialize() to configure SPI chip select pins.
|
||||
* 2. Provide cxd56_spi0/1select() and cxd56_spi0/1status() functions in your
|
||||
* board-specific logic. These functions will perform chip selection
|
||||
* and status operations using GPIOs in the way your board is configured.
|
||||
* 3. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
|
||||
* cxd56_spi0/1cmddata() functions in your board-specific logic. These
|
||||
* functions will perform cmd/data selection operations using GPIOs in the
|
||||
* way your board is configured.
|
||||
* 4. Your low level board initialization logic should call cxd56_spibus_initialize.
|
||||
* 5. The handle returned by cxd56_spibus_initialize() may then be used to bind the
|
||||
* SPI driver to higher level logic (e.g., calling mmcsd_spislotinitialize(),
|
||||
* for example, will bind the SPI driver to the SPI MMC/SD driver).
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* 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_spibus_initialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize the selected SPI port
|
||||
*
|
||||
* Input Parameter:
|
||||
* port - Port number
|
||||
*
|
||||
* Returned Value:
|
||||
* Valid SPI device structure reference on success; a NULL on failure
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
FAR struct spi_dev_s *cxd56_spibus_initialize(int port);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_spiXselect, cxd56_spiXstatus, and cxd56_spiXcmddata
|
||||
*
|
||||
* Description:
|
||||
* These functions must be provided in your board-specific logic. The
|
||||
* cxd56_spi0/1select functions will perform chip selection and the
|
||||
* cxd56_spi0/1status will perform status operations using GPIOs in the way your
|
||||
* board is configured.
|
||||
*
|
||||
* If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, then
|
||||
* cxd56_spi0/1cmddata must also be provided. This functions performs cmd/data
|
||||
* selection operations using GPIOs in the way your board is configured.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_CXD56_SPI0
|
||||
void cxd56_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected);
|
||||
uint8_t cxd56_spi0status(FAR struct spi_dev_s *dev, uint32_t devid);
|
||||
#ifdef CONFIG_SPI_CMDDATA
|
||||
int cxd56_spi0cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_CXD56_SPI3
|
||||
void cxd56_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected);
|
||||
uint8_t cxd56_spi3status(FAR struct spi_dev_s *dev, uint32_t devid);
|
||||
#ifdef CONFIG_SPI_CMDDATA
|
||||
int cxd56_spi3cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_CXD56_SPI4
|
||||
void cxd56_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected);
|
||||
uint8_t cxd56_spi4status(FAR struct spi_dev_s *dev, uint32_t devid);
|
||||
#ifdef CONFIG_SPI_CMDDATA
|
||||
int cxd56_spi4cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_CXD56_SPI5
|
||||
void cxd56_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected);
|
||||
uint8_t cxd56_spi5status(FAR struct spi_dev_s *dev, uint32_t devid);
|
||||
#ifdef CONFIG_SPI_CMDDATA
|
||||
int cxd56_spi5cmddata(FAR struct spi_dev_s *dev, uint32_t devid, bool cmd);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: spi_flush
|
||||
*
|
||||
* Description:
|
||||
* Flush and discard any words left in the RX fifo. This can be called
|
||||
* from spi0/1select after a device is deselected (if you worry about such
|
||||
* things).
|
||||
*
|
||||
* Input Parameters:
|
||||
* dev - Device-specific state data
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void spi_flush(FAR struct spi_dev_s *dev);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: cxd56_spiXregister
|
||||
*
|
||||
* Description:
|
||||
* If the board supports a card detect callback to inform the SPI-based
|
||||
* MMC/SD driver when an SD card is inserted or removed, then
|
||||
* CONFIG_SPI_CALLBACK should be defined and the following function(s) must
|
||||
* must be implemented. These functions implements the registercallback
|
||||
* method of the SPI interface (see include/nuttx/spi/spi.h for details)
|
||||
*
|
||||
* Input Parameters:
|
||||
* dev - Device-specific state data
|
||||
* callback - The function to call on the media change
|
||||
* arg - A caller provided value to return with the callback
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 on success; negated errno on failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_SPI_CALLBACK
|
||||
#ifdef CONFIG_CXD56_SPI0
|
||||
int cxd56_spi0register(FAR struct spi_dev_s *dev, spi_mediachange_t callback,
|
||||
FAR void *arg);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_CXD56_SPI3
|
||||
int cxd56_spi3register(FAR struct spi_dev_s *dev, spi_mediachange_t callback,
|
||||
FAR void *arg);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_CXD56_SPI4
|
||||
int cxd56_spi4register(FAR struct spi_dev_s *dev, spi_mediachange_t callback,
|
||||
FAR void *arg);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_CXD56_SPI5
|
||||
int cxd56_spi5register(FAR struct spi_dev_s *dev, spi_mediachange_t callback,
|
||||
FAR void *arg);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* CONFIG_CXD56_SPI0/3/4/5 */
|
||||
#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_SPI_H */
|
80
arch/arm/src/cxd56xx/hardware/cxd56_dmac_common.h
Normal file
80
arch/arm/src/cxd56xx/hardware/cxd56_dmac_common.h
Normal file
@ -0,0 +1,80 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/cxd56xx/cxd56_dmac_common.h
|
||||
*
|
||||
* Copyright (C) 2009, 2011-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 NuttX 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 cxd56_dmac_common.h
|
||||
*/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_CXD56XX_CXD56_DMAC_COMMON_H
|
||||
#define __ARCH_ARM_SRC_CXD56XX_CXD56_DMAC_COMMON_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
/************************************************************************************
|
||||
* Public Types
|
||||
************************************************************************************/
|
||||
|
||||
/* DMA_HANDLE provides an opaque are reference that can be used to represent a DMA
|
||||
* channel.
|
||||
*/
|
||||
|
||||
typedef FAR void *DMA_HANDLE;
|
||||
|
||||
/* Description:
|
||||
* This is the type of the callback that is used to inform the user of the the
|
||||
* completion of the DMA.
|
||||
*
|
||||
* Input Parameters:
|
||||
* handle - Refers tot he DMA channel or stream
|
||||
* status - A bit encoded value that provides the completion status. See the
|
||||
* DMASTATUS_* definitions above.
|
||||
* arg - A user-provided value that was provided when cxd56_dmastart() was
|
||||
* called.
|
||||
*/
|
||||
|
||||
typedef void (*dma_callback_t)(DMA_HANDLE handle, uint8_t status, void *arg);
|
||||
|
||||
/* Type of 'config' argument passed to cxd56_rxdmasetup() and cxd56_txdmasetup.
|
||||
* See CXD56_DMA_* encodings above. If these encodings exceed 16-bits, then this
|
||||
* should be changed to a uint32_t.
|
||||
*/
|
||||
|
||||
typedef struct {
|
||||
uint16_t channel_cfg;
|
||||
uint8_t dest_width;
|
||||
uint8_t src_width;
|
||||
} dma_config_t;
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_CXD56XX_CXD56_DMAC_COMMON_H */
|
140
arch/arm/src/cxd56xx/hardware/cxd56_rtc.h
Normal file
140
arch/arm/src/cxd56xx/hardware/cxd56_rtc.h
Normal file
@ -0,0 +1,140 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/cxd56xx/hardware/cxd56_rtc.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_RTC_H
|
||||
#define __ARCH_ARM_SRC_CXD56XX_CHIP_CXD56_RTC_H
|
||||
|
||||
/****************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************/
|
||||
|
||||
#include "hardware/cxd5602_memorymap.h"
|
||||
|
||||
/****************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************************/
|
||||
|
||||
/* Register offsets *********************************************************************/
|
||||
|
||||
#define RTC_WRREGPOSTCNT (0x0)
|
||||
#define RTC_WRREGPRECNT (0x4)
|
||||
#define RTC_WRREGREQ (0x8)
|
||||
#define RTC_WRINTPOSTCNT (0x10)
|
||||
#define RTC_WRINTPRECNT (0x14)
|
||||
#define RTC_WRINTCTRL (0x18)
|
||||
#define RTC_WRINTCLR (0x1c)
|
||||
#define RTC_OFFSETVAL (0x20)
|
||||
#define RTC_OFFSETREQ (0x24)
|
||||
#define RTC_RDREQ (0x30)
|
||||
#define RTC_RDPOSTCNT (0x34)
|
||||
#define RTC_RDPRECNT (0x38)
|
||||
#define RTC_RTPOSTCNT (0x40)
|
||||
#define RTC_RTPRECNT (0x44)
|
||||
#define RTC_SETALMPOSTCNT(id) (0x50 + ((id) * 0x8))
|
||||
#define RTC_SETALMPRECNT(id) (0x54 + ((id) * 0x8))
|
||||
#define RTC_SETALMPOSTCNT0 (0x50)
|
||||
#define RTC_SETALMPRECNT0 (0x54)
|
||||
#define RTC_SETALMPOSTCNT1 (0x58)
|
||||
#define RTC_SETALMPRECNT1 (0x5c)
|
||||
#define RTC_SETALMPOSTCNT2 (0x60)
|
||||
#define RTC_SETALMPRECNT2 (0x64)
|
||||
#define RTC_ALMCLR (0x70)
|
||||
#define RTC_ALMOUTEN(id) (0x74 + ((id) * 0x4))
|
||||
#define RTC_ALMOUTEN0 (0x74)
|
||||
#define RTC_ALMOUTEN1 (0x78)
|
||||
#define RTC_ALMOUTEN2 (0x7c)
|
||||
#define RTC_ALMFLG (0x80)
|
||||
#define RTC_DBGSETALMPOSTCNT0 (0x90)
|
||||
#define RTC_DBGSETALMPRECNT0 (0x94)
|
||||
#define RTC_DBGSETALMPOSTCNT1 (0x98)
|
||||
#define RTC_DBGSETALMPRECNT1 (0x9c)
|
||||
#define RTC_DBGSETALMPOSTCNT2 (0xa0)
|
||||
#define RTC_DBGSETALMPRECNT2 (0xa4)
|
||||
|
||||
/* Register Addresses *******************************************************************/
|
||||
|
||||
#define CXD56_RTC0_WRREGPOSTCNT (CXD56_RTC0_BASE + RTC_WRREGPOSTCNT)
|
||||
#define CXD56_RTC0_WRREGPRECNT (CXD56_RTC0_BASE + RTC_WRREGPRECNT)
|
||||
#define CXD56_RTC0_WRREGREQ (CXD56_RTC0_BASE + RTC_WRREGREQ)
|
||||
#define CXD56_RTC0_WRINTPOSTCNT (CXD56_RTC0_BASE + RTC_WRINTPOSTCNT)
|
||||
#define CXD56_RTC0_WRINTPRECNT (CXD56_RTC0_BASE + RTC_WRINTPRECNT)
|
||||
#define CXD56_RTC0_WRINTCTRL (CXD56_RTC0_BASE + RTC_WRINTCTRL)
|
||||
#define CXD56_RTC0_WRINTCLR (CXD56_RTC0_BASE + RTC_WRINTCLR)
|
||||
#define CXD56_RTC0_OFFSETVAL (CXD56_RTC0_BASE + RTC_OFFSETVAL)
|
||||
#define CXD56_RTC0_OFFSETREQ (CXD56_RTC0_BASE + RTC_OFFSETREQ)
|
||||
#define CXD56_RTC0_RDREQ (CXD56_RTC0_BASE + RTC_RDREQ)
|
||||
#define CXD56_RTC0_RDPOSTCNT (CXD56_RTC0_BASE + RTC_RDPOSTCNT)
|
||||
#define CXD56_RTC0_RDPRECNT (CXD56_RTC0_BASE + RTC_RDPRECNT)
|
||||
#define CXD56_RTC0_RTPOSTCNT (CXD56_RTC0_BASE + RTC_RTPOSTCNT)
|
||||
#define CXD56_RTC0_RTPRECNT (CXD56_RTC0_BASE + RTC_RTPRECNT)
|
||||
#define CXD56_RTC0_SETALMPOSTCNT(id) (CXD56_RTC0_BASE + RTC_SETALMPOSTCNT(id))
|
||||
#define CXD56_RTC0_SETALMPRECNT(id) (CXD56_RTC0_BASE + RTC_SETALMPRECNT(id))
|
||||
#define CXD56_RTC0_ALMCLR (CXD56_RTC0_BASE + RTC_ALMCLR)
|
||||
#define CXD56_RTC0_ALMOUTEN(id) (CXD56_RTC0_BASE + RTC_ALMOUTEN(id))
|
||||
#define CXD56_RTC0_ALMFLG (CXD56_RTC0_BASE + RTC_ALMFLG)
|
||||
|
||||
/* Register bit definitions *************************************************************/
|
||||
|
||||
/* Flag/Clear Register */
|
||||
|
||||
#define RTCREG_ALM0_FLAG_MASK (1u << 0)
|
||||
#define RTCREG_ALM1_FLAG_MASK (1u << 1)
|
||||
#define RTCREG_ALM2_FLAG_MASK (1u << 2)
|
||||
#define RTCREG_ALM0_ERR_FLAG_MASK (1u << 16)
|
||||
#define RTCREG_ALM1_ERR_FLAG_MASK (1u << 17)
|
||||
|
||||
#define RTCREG_ALM0_MASK (RTCREG_ALM0_FLAG_MASK | RTCREG_ALM0_ERR_FLAG_MASK)
|
||||
#define RTCREG_ALM1_MASK (RTCREG_ALM1_FLAG_MASK | RTCREG_ALM1_ERR_FLAG_MASK)
|
||||
#define RTCREG_ALM2_MASK (RTCREG_ALM2_FLAG_MASK)
|
||||
|
||||
/* Write Request */
|
||||
|
||||
#define RTCREG_WREQ_BUSYA_MASK (1u << 0)
|
||||
#define RTCREG_WREQ_BUSYB_MASK (1u << 1)
|
||||
|
||||
/* Alarm Request */
|
||||
|
||||
#define RTCREG_ASET_BUSY_MASK (1u << 16)
|
||||
|
||||
/* Alarm Enable */
|
||||
|
||||
#define RTCREG_ALM_EN_MASK (1u << 0)
|
||||
#define RTCREG_ALM_BUSY_MASK (1u << 8)
|
||||
#define RTCREG_ALM_DBG_MASK (1u << 15)
|
||||
#define RTCREG_ALM_ERREN_MASK (1u << 16)
|
||||
#define RTCREG_ALM_ERRDBG_MASK (1u << 31)
|
||||
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_CXD56XX_CHIP_CXD56_RTC_H */
|
211
arch/arm/src/cxd56xx/hardware/cxd56_spi.h
Normal file
211
arch/arm/src/cxd56xx/hardware/cxd56_spi.h
Normal file
@ -0,0 +1,211 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/cxd56xx/hardware/cxd56_spi.h
|
||||
*
|
||||
* Copyright (C) 2012 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 NuttX 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_SPI_H
|
||||
#define __ARCH_ARM_SRC_CXD56XX_CHIP_CXD56_SPI_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* 8 frame FIFOs for both transmit and receive */
|
||||
|
||||
#define CXD56_SPI_FIFOSZ 8
|
||||
|
||||
/* Register offsets *********************************************************/
|
||||
|
||||
#define CXD56_SPI_CR0_OFFSET 0x0000 /* Control Register 0 */
|
||||
#define CXD56_SPI_CR1_OFFSET 0x0004 /* Control Register 1 */
|
||||
#define CXD56_SPI_DR_OFFSET 0x0008 /* Data Register */
|
||||
#define CXD56_SPI_SR_OFFSET 0x000c /* Status Register */
|
||||
#define CXD56_SPI_CPSR_OFFSET 0x0010 /* Clock Prescale Register */
|
||||
#define CXD56_SPI_IMSC_OFFSET 0x0014 /* Interrupt Mask Set and Clear Reg */
|
||||
#define CXD56_SPI_RIS_OFFSET 0x0018 /* Raw Interrupt Status Register */
|
||||
#define CXD56_SPI_MIS_OFFSET 0x001c /* Masked Interrupt Status Register */
|
||||
#define CXD56_SPI_ICR_OFFSET 0x0020 /* Interrupt Clear Register */
|
||||
#define CXD56_SPI_DMACR_OFFSET 0x0024 /* DMA Control Register */
|
||||
#define CXD56_SPI_CSMODE_OFFSET 0x0090 /* CS control mode */
|
||||
#define CXD56_SPI_CS_OFFSET 0x0094 /* CS output */
|
||||
#define CXD56_SPI_SLAVETYPE_OFFSET 0x0098 /* Slave type */
|
||||
|
||||
/* Register addresses *******************************************************/
|
||||
|
||||
#define CXD56_SPI4_CR0 (CXD56_IMG_SPI_BASE+CXD56_SPI_CR0_OFFSET)
|
||||
#define CXD56_SPI4_CR1 (CXD56_IMG_SPI_BASE+CXD56_SPI_CR1_OFFSET)
|
||||
#define CXD56_SPI4_DR (CXD56_IMG_SPI_BASE+CXD56_SPI_DR_OFFSET)
|
||||
#define CXD56_SPI4_SR (CXD56_IMG_SPI_BASE+CXD56_SPI_SR_OFFSET)
|
||||
#define CXD56_SPI4_CPSR (CXD56_IMG_SPI_BASE+CXD56_SPI_CPSR_OFFSET)
|
||||
#define CXD56_SPI4_IMSC (CXD56_IMG_SPI_BASE+CXD56_SPI_IMSC_OFFSET)
|
||||
#define CXD56_SPI4_RIS (CXD56_IMG_SPI_BASE+CXD56_SPI_RIS_OFFSET)
|
||||
#define CXD56_SPI4_MIS (CXD56_IMG_SPI_BASE+CXD56_SPI_MIS_OFFSET)
|
||||
#define CXD56_SPI4_ICR (CXD56_IMG_SPI_BASE+CXD56_SPI_ICR_OFFSET)
|
||||
#define CXD56_SPI4_DMACR (CXD56_IMG_SPI_BASE+CXD56_SPI_DMACR_OFFSET)
|
||||
|
||||
#define CXD56_SPI5_CR0 (CXD56_IMG_WSPI_BASE+CXD56_SPI_CR0_OFFSET)
|
||||
#define CXD56_SPI5_CR1 (CXD56_IMG_WSPI_BASE+CXD56_SPI_CR1_OFFSET)
|
||||
#define CXD56_SPI5_DR (CXD56_IMG_WSPI_BASE+CXD56_SPI_DR_OFFSET)
|
||||
#define CXD56_SPI5_SR (CXD56_IMG_WSPI_BASE+CXD56_SPI_SR_OFFSET)
|
||||
#define CXD56_SPI5_CPSR (CXD56_IMG_WSPI_BASE+CXD56_SPI_CPSR_OFFSET)
|
||||
#define CXD56_SPI5_IMSC (CXD56_IMG_WSPI_BASE+CXD56_SPI_IMSC_OFFSET)
|
||||
#define CXD56_SPI5_RIS (CXD56_IMG_WSPI_BASE+CXD56_SPI_RIS_OFFSET)
|
||||
#define CXD56_SPI5_MIS (CXD56_IMG_WSPI_BASE+CXD56_SPI_MIS_OFFSET)
|
||||
#define CXD56_SPI5_ICR (CXD56_IMG_WSPI_BASE+CXD56_SPI_ICR_OFFSET)
|
||||
#define CXD56_SPI5_DMACR (CXD56_IMG_WSPI_BASE+CXD56_SPI_DMACR_OFFSET)
|
||||
|
||||
#define CXD56_SPI0_CR0 (CXD56_SPIM_BASE+CXD56_SPI_CR0_OFFSET)
|
||||
#define CXD56_SPI0_CR1 (CXD56_SPIM_BASE+CXD56_SPI_CR1_OFFSET)
|
||||
#define CXD56_SPI0_DR (CXD56_SPIM_BASE+CXD56_SPI_DR_OFFSET)
|
||||
#define CXD56_SPI0_SR (CXD56_SPIM_BASE+CXD56_SPI_SR_OFFSET)
|
||||
#define CXD56_SPI0_CPSR (CXD56_SPIM_BASE+CXD56_SPI_CPSR_OFFSET)
|
||||
#define CXD56_SPI0_IMSC (CXD56_SPIM_BASE+CXD56_SPI_IMSC_OFFSET)
|
||||
#define CXD56_SPI0_RIS (CXD56_SPIM_BASE+CXD56_SPI_RIS_OFFSET)
|
||||
#define CXD56_SPI0_MIS (CXD56_SPIM_BASE+CXD56_SPI_MIS_OFFSET)
|
||||
#define CXD56_SPI0_ICR (CXD56_SPIM_BASE+CXD56_SPI_ICR_OFFSET)
|
||||
#define CXD56_SPI0_DMACR (CXD56_SPIM_BASE+CXD56_SPI_DMACR_OFFSET)
|
||||
#define CXD56_SPI0_CSMODE (CXD56_SPIM_BASE+CXD56_SPI_CSMODE_OFFSET)
|
||||
#define CXD56_SPI0_CS (CXD56_SPIM_BASE+CXD56_SPI_CS_OFFSET)
|
||||
#define CXD56_SPI0_SLAVETYPE (CXD56_SPIM_BASE+CXD56_SPI_SLAVETYPE_OFFSET)
|
||||
|
||||
#define CXD56_SPI3_CR0 (CXD56_SCU_SPI_BASE+CXD56_SPI_CR0_OFFSET)
|
||||
#define CXD56_SPI3_CR1 (CXD56_SCU_SPI_BASE+CXD56_SPI_CR1_OFFSET)
|
||||
#define CXD56_SPI3_DR (CXD56_SCU_SPI_BASE+CXD56_SPI_DR_OFFSET)
|
||||
#define CXD56_SPI3_SR (CXD56_SCU_SPI_BASE+CXD56_SPI_SR_OFFSET)
|
||||
#define CXD56_SPI3_CPSR (CXD56_SCU_SPI_BASE+CXD56_SPI_CPSR_OFFSET)
|
||||
#define CXD56_SPI3_IMSC (CXD56_SCU_SPI_BASE+CXD56_SPI_IMSC_OFFSET)
|
||||
#define CXD56_SPI3_RIS (CXD56_SCU_SPI_BASE+CXD56_SPI_RIS_OFFSET)
|
||||
#define CXD56_SPI3_MIS (CXD56_SCU_SPI_BASE+CXD56_SPI_MIS_OFFSET)
|
||||
#define CXD56_SPI3_ICR (CXD56_SCU_SPI_BASE+CXD56_SPI_ICR_OFFSET)
|
||||
#define CXD56_SPI3_DMACR (CXD56_SCU_SPI_BASE+CXD56_SPI_DMACR_OFFSET)
|
||||
#define CXD56_SPI3_CSMODE (CXD56_SCU_SPI_BASE+CXD56_SPI_CSMODE_OFFSET)
|
||||
#define CXD56_SPI3_CS (CXD56_SCU_SPI_BASE+CXD56_SPI_CS_OFFSET)
|
||||
#define CXD56_SPI3_SLAVETYPE (CXD56_SCU_SPI_BASE+CXD56_SPI_SLAVETYPE_OFFSET)
|
||||
|
||||
/* Register bit definitions *************************************************/
|
||||
|
||||
/* Control Register 0 */
|
||||
|
||||
#define SPI_CR0_DSS_SHIFT (0) /* Bits 0-3: DSS Data Size Select */
|
||||
#define SPI_CR0_DSS_MASK (15 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_4BIT (3 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_5BIT (4 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_6BIT (5 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_7BIT (6 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_8BIT (7 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_9BIT (8 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_10BIT (9 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_11BIT (10 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_12BIT (11 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_13BIT (12 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_14BIT (13 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_15BIT (14 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_DSS_16BIT (15 << SPI_CR0_DSS_SHIFT)
|
||||
#define SPI_CR0_FRF_SHIFT (4) /* Bits 4-5: FRF Frame Format */
|
||||
#define SPI_CR0_FRF_MASK (3 << SPI_CR0_FRF_SHIFT)
|
||||
#define SPI_CR0_FRF_SPI (0 << SPI_CR0_FRF_SHIFT)
|
||||
#define SPI_CR0_FRF_TI (1 << SPI_CR0_FRF_SHIFT)
|
||||
#define SPI_CR0_FRF_UWIRE (2 << SPI_CR0_FRF_SHIFT)
|
||||
#define SPI_CR0_CPOL (1 << 6) /* Bit 6: Clock Out Polarity */
|
||||
#define SPI_CR0_CPHA (1 << 7) /* Bit 7: Clock Out Phase */
|
||||
#define SPI_CR0_SCR_SHIFT (8) /* Bits 8-15: Serial Clock Rate */
|
||||
#define SPI_CR0_SCR_MASK (0xff << SPI_CR0_SCR_SHIFT)
|
||||
/* Bits 8-31: Reserved */
|
||||
|
||||
/* Control Register 1 */
|
||||
|
||||
#define SPI_CR1_LBM (1 << 0) /* Bit 0: Loop Back Mode */
|
||||
#define SPI_CR1_SSE (1 << 1) /* Bit 1: SPI Enable */
|
||||
#define SPI_CR1_MS (1 << 2) /* Bit 2: Master/Slave Mode */
|
||||
#define SPI_CR1_SOD (1 << 3) /* Bit 3: Slave Output Disable */
|
||||
/* Bits 4-31: Reserved */
|
||||
|
||||
/* Data Register */
|
||||
|
||||
#define SPI_DR_MASK (0xffff) /* Bits 0-15: Data */
|
||||
/* Bits 16-31: Reserved */
|
||||
|
||||
/* Status Register */
|
||||
|
||||
#define SPI_SR_TFE (1 << 0) /* Bit 0: Transmit FIFO Empty */
|
||||
#define SPI_SR_TNF (1 << 1) /* Bit 1: Transmit FIFO Not Full */
|
||||
#define SPI_SR_RNE (1 << 2) /* Bit 2: Receive FIFO Not Empty */
|
||||
#define SPI_SR_RFF (1 << 3) /* Bit 3: Receive FIFO Full */
|
||||
#define SPI_SR_BSY (1 << 4) /* Bit 4: Busy */
|
||||
/* Bits 5-31: Reserved */
|
||||
|
||||
/* Clock Prescale Register */
|
||||
|
||||
#define SPI_CPSR_DVSR_MASK (0xff) /* Bits 0-7: clock = SPI_PCLK/DVSR */
|
||||
/* Bits 8-31: Reserved */
|
||||
|
||||
/* Common format for interrupt control registers:
|
||||
*
|
||||
* Interrupt Mask Set and Clear Register (IMSC)
|
||||
* Raw Interrupt Status Register (RIS)
|
||||
* Masked Interrupt Status Register (MIS)
|
||||
* Interrupt Clear Register (ICR)
|
||||
*/
|
||||
|
||||
#define SPI_INT_ROR (1 << 0) /* Bit 0: RX FIFO overrun */
|
||||
#define SPI_INT_RT (1 << 1) /* Bit 1: RX FIFO timeout */
|
||||
#define SPI_INT_RX (1 << 2) /* Bit 2: RX FIFO at least half full */
|
||||
#define SPI_INT_TX (1 << 3 ) /* Bit 3: TX FIFO at least half empy */
|
||||
/* Bits 4-31: Reserved */
|
||||
|
||||
/* DMA Control Register */
|
||||
|
||||
#define SPI_DMACR_RXDMAE (1 << 0) /* Bit 0: Receive DMA Enable */
|
||||
#define SPI_DMACR_TXDMAE (1 << 1) /* Bit 1: Transmit DMA Enable */
|
||||
/* Bits 2-31: Reserved */
|
||||
|
||||
/****************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_CXD56XX_CHIP_CXD56_SPI_H */
|
@ -35,6 +35,8 @@ CONFIG_PREALLOC_WDOGS=16
|
||||
CONFIG_RAM_SIZE=1572864
|
||||
CONFIG_RAM_START=0x0d000000
|
||||
CONFIG_RR_INTERVAL=200
|
||||
CONFIG_RTC=y
|
||||
CONFIG_RTC_DRIVER=y
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SPI=y
|
||||
|
@ -62,6 +62,11 @@
|
||||
#include "cxd56_gpio.h"
|
||||
#include "cxd56_pinconfig.h"
|
||||
|
||||
#ifdef CONFIG_CXD56_RTC
|
||||
#include <nuttx/timers/rtc.h>
|
||||
#include "cxd56_rtc.h"
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_CXD56_CPUFIFO
|
||||
#include "cxd56_cpufifo.h"
|
||||
#endif
|
||||
@ -161,6 +166,10 @@ int cxd56_bringup(void)
|
||||
wlock.count = 0;
|
||||
up_pm_acquire_wakelock(&wlock);
|
||||
|
||||
#ifdef CONFIG_RTC_DRIVER
|
||||
rtc_initialize(0, cxd56_rtc_lowerhalf());
|
||||
#endif
|
||||
|
||||
cxd56_uart_initialize();
|
||||
cxd56_timerisr_initialize();
|
||||
|
||||
|
@ -46,7 +46,8 @@ CONFIG_PREALLOC_WDOGS=16
|
||||
CONFIG_RAM_SIZE=1572864
|
||||
CONFIG_RAM_START=0x0d000000
|
||||
CONFIG_RR_INTERVAL=200
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_RTC=y
|
||||
CONFIG_RTC_DRIVER=y
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SPI=y
|
||||
|
Loading…
Reference in New Issue
Block a user