s5j: clean up unnecessary headers
authorHeesub Shin <heesub.shin@samsung.com>
Mon, 3 Apr 2017 09:06:22 +0000 (18:06 +0900)
committerHeesub Shin <heesub.shin@samsung.com>
Tue, 18 Apr 2017 03:02:06 +0000 (12:02 +0900)
This commit removes all unnecessary header files in S5J.

Change-Id: I9bcd7c7ad85e1c1192e5b93df77c16a403896e27
Signed-off-by: Heesub Shin <heesub.shin@samsung.com>
18 files changed:
os/arch/arm/include/s5j/chip.h [deleted file]
os/arch/arm/include/s5j/chip_types.h [deleted file]
os/arch/arm/include/s5j/dma.h [deleted file]
os/arch/arm/include/s5j/nvram.h [deleted file]
os/arch/arm/include/s5j/s5j_efuse.h [deleted file]
os/arch/arm/include/s5j/s5j_types.h [deleted file]
os/arch/arm/src/s5j/chip.h
os/arch/arm/src/s5j/s5j_boot.c
os/arch/arm/src/s5j/s5j_gpio.c
os/arch/arm/src/s5j/s5j_i2c.c
os/arch/arm/src/s5j/s5j_pwm.c
os/arch/arm/src/s5j/s5j_pwrcal.c
os/arch/arm/src/s5j/s5j_serial.c
os/arch/arm/src/s5j/s5j_serial.h
os/arch/arm/src/s5j/s5j_spi.h
os/arch/arm/src/s5j/s5j_timerisr.c
os/arch/arm/src/s5j/s5j_watchdog.c
os/arch/arm/src/sidk_s5jt200/src/s5jt200_buttons.c

diff --git a/os/arch/arm/include/s5j/chip.h b/os/arch/arm/include/s5j/chip.h
deleted file mode 100644 (file)
index 5bdf12e..0000000
+++ /dev/null
@@ -1,99 +0,0 @@
-/****************************************************************************
- *
- * Copyright 2016 Samsung Electronics All Rights Reserved.
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing,
- * software distributed under the License is distributed on an
- * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
- * either express or implied. See the License for the specific
- * language governing permissions and limitations under the License.
- *
- ****************************************************************************/
-/****************************************************************************************************
- * arch/arm/include/s5j/chip.h
- *
- *   Copyright (C) 2013-2015 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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_INCLUDE_S5J_CHIP_H
-#define __ARCH_ARM_INCLUDE_S5J_CHIP_H
-
-/****************************************************************************************************
- * Included Files
- ****************************************************************************************************/
-
-#include <tinyara/config.h>
-
-/****************************************************************************************************
- * Pre-processor Definitions
- ****************************************************************************************************/
-
-#define S5J_NTIMERS         0  /* Four 16/32-bit timers */
-#define S5J_NWIDETIMERS     0  /* No 32/64-bit timers */
-#define S5J_NWDT            0  /* One watchdog timer */
-#define S5J_NETHCONTROLLERS 0  /* One Ethernet controller */
-#define S5J_NLCD            0  /* No LCD controller */
-#undef  S5J_ETHTS                              /* No timestamp register */
-#define S5J_NSSI            0  /* Two SSI modules */
-#define S5J_NUARTS          1  /* Two UART modules */
-#define S5J_NI2C            0  /* Two I2C modules */
-#define S5J_NADC            0  /* One ADC module */
-#define S5J_NPWM            0  /* No PWM generator modules */
-#define S5J_NQEI            0  /* No quadrature encoders */
-#define S5J_NPORTS          0  /* 8 Ports (GPIOA-H) 5-38 GPIOs */
-#define S5J_NCANCONTROLLER  0  /* No CAN controllers */
-#define S5J_NUSBOTGFS       0  /* No USB 2.0 OTG FS */
-#define S5J_NUSBOTGHS       0  /* No USB 2.0 OTG HS */
-#define S5J_NCRC            0  /* No CRC module */
-#define S5J_NAES            0  /* No AES module */
-#define S5J_NDES            0  /* No DES module */
-#define S5J_NHASH           0  /* No SHA1/MD5 hash module */
-
-/****************************************************************************************************
- * Public Types
- ****************************************************************************************************/
-
-/****************************************************************************************************
- * Public Data
- ****************************************************************************************************/
-
-/****************************************************************************************************
- * Public Functions
- ****************************************************************************************************/
-
-#endif                                                 /* __ARCH_ARM_INCLUDE_S5J_CHIP_H */
diff --git a/os/arch/arm/include/s5j/chip_types.h b/os/arch/arm/include/s5j/chip_types.h
deleted file mode 100644 (file)
index 14f1ee5..0000000
+++ /dev/null
@@ -1,24 +0,0 @@
-/****************************************************************************
- *
- * Copyright 2016 Samsung Electronics All Rights Reserved.
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing,
- * software distributed under the License is distributed on an
- * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
- * either express or implied. See the License for the specific
- * language governing permissions and limitations under the License.
- *
- ****************************************************************************/
-
-#ifndef __INCLUDE_CHIP_TYPES_H
-#define __INCLUDE_CHIP_TYPES_H
-
-#include <arch/chip/s5j_types.h>
-
-#endif
diff --git a/os/arch/arm/include/s5j/dma.h b/os/arch/arm/include/s5j/dma.h
deleted file mode 100644 (file)
index 87e5fe9..0000000
+++ /dev/null
@@ -1,30 +0,0 @@
-/****************************************************************************
- *
- * Copyright 2016 Samsung Electronics All Rights Reserved.
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing,
- * software distributed under the License is distributed on an
- * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
- * either express or implied. See the License for the specific
- * language governing permissions and limitations under the License.
- *
- ****************************************************************************/
-
-#ifndef __INCLUDE_DMA_H
-#define __INCLUDE_DMA_H
-
-#ifndef CONFIG_S5J_DMA
-#error DMA IS NOT ENABLED
-#endif
-
-int dma_memcpy(void *dst, void *src, unsigned int size, unsigned int ch_num);
-s16 dma_allocate_m2m_channel(void);
-void dma_free_m2m_channel(s16 ch);
-
-#endif
diff --git a/os/arch/arm/include/s5j/nvram.h b/os/arch/arm/include/s5j/nvram.h
deleted file mode 100644 (file)
index 4b62970..0000000
+++ /dev/null
@@ -1,25 +0,0 @@
-/****************************************************************************
- *
- * Copyright 2016 Samsung Electronics All Rights Reserved.
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing,
- * software distributed under the License is distributed on an
- * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
- * either express or implied. See the License for the specific
- * language governing permissions and limitations under the License.
- *
- ****************************************************************************/
-#ifndef __ARCH_ARM_INCLUDE_NVRAM_H
-#define __ARCH_ARM_INCLUDE_NVRAM_H
-
-u32 Nv_Write(u32 targetAddr, u32 sourceAddr, u32 sizeByte);
-u32 Nv_Read(u32 targetAddr, u32 sourceAddr, u32 sizeByte);
-u32 Nv_Erase(u32 targetAddr, u32 sizeByte);
-
-#endif
diff --git a/os/arch/arm/include/s5j/s5j_efuse.h b/os/arch/arm/include/s5j/s5j_efuse.h
deleted file mode 100644 (file)
index 83a6827..0000000
+++ /dev/null
@@ -1,161 +0,0 @@
-/****************************************************************************
- *
- * Copyright 2016 Samsung Electronics All Rights Reserved.
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing,
- * software distributed under the License is distributed on an
- * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
- * either express or implied. See the License for the specific
- * language governing permissions and limitations under the License.
- *
- ****************************************************************************/
-
-#ifndef __ARCH_ARM_INCLUDE_S5J_S5J_EFUSE_H
-#define __ARCH_ARM_INCLUDE_S5J_S5J_EFUSE_H
-
-#include <arch/chip/s5j_types.h>
-
-#define EFUSE_BASE_ADDR 0x80000000
-
-#define rEFUSE_PRODUCT_ID         EFUSE_BASE_ADDR + 0x0
-#define rEFUSE_SFR_APB            EFUSE_BASE_ADDR + 0x100
-#define rEFUSE_CHIPID_0           EFUSE_BASE_ADDR + 0x204
-#define rEFUSE_CHIPID_1           EFUSE_BASE_ADDR + 0x208
-#define rEFUSE_CHIPID_2           EFUSE_BASE_ADDR + 0x20C
-#define rEFUSE_CHIPID_3           EFUSE_BASE_ADDR + 0x210
-#define rEFUSE_PRODUCT_VER        EFUSE_BASE_ADDR + 0x220
-#define rEFUSE_N_SECU_RD_DATA0    EFUSE_BASE_ADDR + 0x318
-#define rEFUSE_N_SECU_RD_DATA1    EFUSE_BASE_ADDR + 0x31C
-#define rEFUSE_N_SECU_RD_DATA2    EFUSE_BASE_ADDR + 0x320
-#define rEFUSE_N_SECU_RD_DATA3    EFUSE_BASE_ADDR + 0x324
-#define rEFUSE_CONTROL            EFUSE_BASE_ADDR + 0x328
-#define rEFUSE_CONFIG             EFUSE_BASE_ADDR + 0x32C
-#define rEFUSE_PROG_DATA0         EFUSE_BASE_ADDR + 0x334
-#define rEFUSE_PROG_DATA1         EFUSE_BASE_ADDR + 0x338
-#define rEFUSE_PROG_DATA2         EFUSE_BASE_ADDR + 0x33C
-#define rEFUSE_PROG_DATA3         EFUSE_BASE_ADDR + 0x340
-#define rEFUSE_PROG_DEBUG         EFUSE_BASE_ADDR + 0x370
-#define rEFUSE_SENSING_DEBUG      EFUSE_BASE_ADDR + 0x374
-#define rEFUSE_INT                EFUSE_BASE_ADDR + 0x3FC
-#define rEFUSE_INT_STATUS         EFUSE_BASE_ADDR + 0x400
-#define rEFUSE_INT_EN             EFUSE_BASE_ADDR + 0x404
-#define rEFUSE_TIME_PARA0         EFUSE_BASE_ADDR + 0x408
-#define rEFUSE_TIME_PARA1         EFUSE_BASE_ADDR + 0x40C
-#define rEFUSE_STATUS             EFUSE_BASE_ADDR + 0x428
-#define rEFUSE_SECU_SPARE0        EFUSE_BASE_ADDR + 0x42C
-#define rEFUSE_N_SECU_SPARE0      EFUSE_BASE_ADDR + 0x434
-#define rEFUSE_SECKEY0            EFUSE_BASE_ADDR + 0x500
-#define rEFUSE_SECKEY1            EFUSE_BASE_ADDR + 0x504
-#define rEFUSE_SECKEY2            EFUSE_BASE_ADDR + 0x508
-#define rEFUSE_SECKEY3            EFUSE_BASE_ADDR + 0x50C
-#define rEFUSE_SECKEY4            EFUSE_BASE_ADDR + 0x510
-#define rEFUSE_SECKEY5            EFUSE_BASE_ADDR + 0x514
-#define rEFUSE_SECKEY6            EFUSE_BASE_ADDR + 0x518
-#define rEFUSE_SECKEY7            EFUSE_BASE_ADDR + 0x51C
-
-//Addr
-#define FSOURCE0_BIRA_MCU_KEY_ADDR            0
-#define FSOURCE0_BIRA_WLBT_ADDR               0x80
-#define FSOURCE0_CHIPID_ADDR                  0x100
-#define FSOURCE0_AP_HW_OPTION_ADDR            0x180
-#define FSOURCE0_SSS_CM0_ROLLBACK_CNT_ADDR    0x200
-#define FSOURCE0_SSS_ROOT_ENC_KEY_ADDR        0x400
-#define FSOURCE0_SSS_BACK_ENC_KEY_ADDR        0x500
-#define FSOURCE0_SSS_CM0_SECURE_BOOT_KEY_ADDR 0x600
-#define FSOURCE0_SSS_PRIVATE_KEY_ADDR         0x800
-#define FSOURCE0_SECURE_KEY_ADDR              0xC00
-#define FSOURCE0_SW_RW_RESION_ADDR            0xD00
-#define FSOURCE1_SW_RW_RESION_ADDR            0x2000
-
-//Size
-#define FSOURCE0_BIRA_MCU_KEY_SIZE            0x80
-#define FSOURCE0_BIRA_WLBT_SIZE               0x80
-#define FSOURCE0_CHIPID_SIZE                  0x80
-#define FSOURCE0_AP_HW_OPTION_SIZE            0x80
-#define FSOURCE0_SSS_CM0_ROLLBACK_CNT_SIZE    0x20
-#define FSOURCE0_SSS_ROOT_ENC_KEY_SIZE        0x100
-#define FSOURCE0_SSS_BACK_ENC_KEY_SIZE        0x100
-#define FSOURCE0_SSS_CM0_SECURE_BOOT_KEY_SIZE 0x200
-#define FSOURCE0_SSS_PRIVATE_KEY_SIZE         0x200
-#define FSOURCE0_SECURE_KEY_SIZE              0x100
-#define FSOURCE0_SW_RW_RESION_SIZE            0x400
-#define FSOURCE1_SW_RW_RESION_SIZE            0x1000
-
-struct bank_info_s {
-       u8  Bnak_name[30];
-       u32 StartAddr;
-       u32 bank_size;
-       u32 Fusing_owner;
-       u32 SW_read_enable;
-       u32 HW_output_enable;
-};
-typedef struct bank_info_s BANK_INFO;
-
-enum {
-       BIRA_MCU_KEY = 0,
-       BIRA_WLBT_KEY,
-       CHIPID,
-       AP_HW_OPTION,
-       SSS_CM0_ROLLBACK_CNT,
-       SSS_ROOT_ENC_KEY,
-       SSS_BACK_ENC_KEY,
-       SSS_CM0_SECURE_BOOT_KEY,
-       SSS_PRIVATE_KEY,
-       SECURE_KEY,
-       SW_RW_RESION_0,
-       SW_RW_RESION_1,
-       BANK_MAX
-} BANK;
-
-enum {
-       EDS = 0,
-       CUSTOMER,
-} FUSE_OWNER;
-
-enum {
-       SW_READ = 0,
-       SW_READ_DIRECT,
-       NO_SW_READ,
-} SW_READ_EN;
-
-enum {
-       HW_OUTPUT = 0,
-       NO_HW_OUTPUT,
-} HW_OUTPUT_EN;
-
-enum {
-       PGM_VERIFY_DONE_INT = 0,
-       PGM_VERIFY_FAIL_INT,
-       PGM_DONE_INT,
-       READ_DONE_INT
-} INT_EN;
-
-enum {
-       PGM_VERIFY_DONE = 0,
-       PGM_VERIFY_FAIL,
-       PGM_DONE,
-       READ_DONE
-} INT_STATUS;
-
-enum {
-       SW_RESET = 0,
-       PGM_VERIFY,
-       PGM,
-       READ
-};
-
-enum {
-       EFUSE_RCS = 0,
-       EFUSE_READ_SIZE,
-       EFUSE_PGM_SIZE,
-       EFUSE_SW_PRE_READING,
-       EFUSE_ADDRESS
-};
-
-#endif                                                 /* __ARCH_ARM_INCLUDE_S5J_S5J_EFUSE_H */
diff --git a/os/arch/arm/include/s5j/s5j_types.h b/os/arch/arm/include/s5j/s5j_types.h
deleted file mode 100644 (file)
index 7d051bc..0000000
+++ /dev/null
@@ -1,207 +0,0 @@
-/****************************************************************************
- *
- * Copyright 2016 Samsung Electronics All Rights Reserved.
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing,
- * software distributed under the License is distributed on an
- * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
- * either express or implied. See the License for the specific
- * language governing permissions and limitations under the License.
- *
- ****************************************************************************/
-/****************************************************************************
- * arch/arm/include/s5j/s5j_types.h
- *
- *   Copyright (C) 2007-2009, 2011-2012, 2014-2015 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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_INCLUDE_S5J_S5J_TYPES_H
-#define __ARCH_ARM_INCLUDE_S5J_S5J_TYPES_H
-
-#include <tinyara/config.h>
-#include <tinyara/arch.h>
-#include <sys/types.h>
-
-#ifndef NULL
-#define NULL  (0)
-#endif
-
-#ifndef __int64
-typedef long long __int64;
-#endif
-
-typedef float  f32;                            // 32-bit Floating-Point Number
-typedef double f64;                            // 16-bit Floating-Point Number
-
-#ifndef uint32
-typedef unsigned int uint32;
-#endif
-
-#ifndef sint32
-typedef int sint32;
-#endif
-
-#ifdef AARCH_64
-typedef unsigned long long uregister;
-#else
-typedef unsigned int uregister;
-#endif
-
-typedef __signed__ char __s8;
-typedef unsigned char __u8;
-
-typedef __signed__ short __s16;
-typedef unsigned short __u16;
-
-typedef __signed__ int __s32;
-#ifndef CONFIG_ENABLE_IOTIVITY
-typedef unsigned int __u32;
-#endif
-
-typedef signed char s8;
-typedef unsigned char u8;
-
-typedef signed short s16;
-typedef unsigned short u16;
-
-typedef signed int s32;
-typedef unsigned int u32;
-
-typedef signed long long s64;
-typedef unsigned long long u64;
-
-typedef unsigned char BYTE;
-typedef unsigned int UINT;
-typedef unsigned long ADDRESS;
-
-typedef u64 cycle_t;
-typedef unsigned long long cycle_t;
-
-typedef unsigned long phy_addr_t;
-
-#define OK                  0
-//#define ERROR               (-1)
-//#define TIMEOUT             (-2)
-#define REPEATER_NOT_READY  (-3)
-#define ILLEGAL_DEVICE      (-4)
-//#define FALSE               (0)
-//#define TRUE                (1)
-#define PASS      (1)
-#define FAIL      (0)
-#define SEC       (0)
-#define NSEC      (1)
-
-#define ENABLE    (1)
-#define DISABLE   (0)
-
-#define MHz   1000000
-
-#ifndef __packed
-#define __packed    __attribute__((__packed__))
-#endif
-
-#ifndef container_of
-#define container_of(ptr, type, member) \
-       do {\
-               const typeof(((type *)0)->member)*__mptr = (ptr);\
-               (type *)((char *)__mptr - offsetof(type, member));\
-       } while (0)
-#endif
-
-#define udelay(usec)    up_udelay(usec)
-#define mdelay(msec)    up_mdelay(msec)
-
-#define __irq
-
-#define CONFIG_STACK_SIZE 0x800
-#define CONFIG_HEAP_SIZE  0x40000
-#define CONFIG_FIN_HZ     26000000
-
-
-#define Assert(b) ({if (!(b)) {printf("\n %s(line %d)\n", __FILE__, __LINE__); do {} while (1); } })
-
-#define __iomem
-
-#define __raw_writel(d, b)  (*(volatile unsigned int *)(b) = (d))
-#define __raw_readl(b)      (*(volatile unsigned int *)(b))
-
-#define writel(v, c)  (*(volatile unsigned int *)(c) = (v))
-#define readl(c)      (*(volatile unsigned int *)(c))
-
-#define Outp32(addr, data)  (*(volatile u32 *)(addr) = (data))
-#define Outp16(addr, data)  (*(volatile u16 *)(addr) = (data))
-#define Outp8(addr, data)   (*(volatile u8 *)(addr) = (data))
-#define Inp32(addr)   (*(volatile u32 *)(addr))
-#define Inp16(addr)   (*(volatile u16 *)(addr))
-#define Inp8(addr)    (*(volatile u8 *)(addr))
-
-#define SetBits(uAddr, uBaseBit, uMaskValue, uSetValue) \
-       Outp32(uAddr, (Inp32(uAddr) & ~((uMaskValue) << (uBaseBit))) | (((uMaskValue) & (uSetValue)) << (uBaseBit)))
-
-#define ClearBits(uAddr, uBaseBit, uMaskValue, uSetValue) \
-       Outp32(uAddr, (Inp32(uAddr) & ~((uMaskValue) << (uBaseBit))) & ~(((uMaskValue) & (uSetValue)) << (uBaseBit)))
-
-#define GetBits(uAddr, uBaseBit, uMaskValue) ((Inp32(uAddr) >> (uBaseBit)) & (uMaskValue))
-
-#define SET_REG(reg, bitfield, val) \
-       do {\
-               int __temp = Inp32(reg);\
-               __temp &= ~(bitfield);\
-               __temp |= ((bitfield) & (val));\
-               Outp32(reg, __temp);\
-       } while (0)
-
-#define HW_REG32(base, offset)  (*(volatile u32 *)((unsigned int)base + ((unsigned int)offset)))
-#define HW_REG16(base, offset)  (*(volatile u16 *)((unsigned int)base + ((unsigned int)offset)))
-#define HW_REG8(base, offset)   (*(volatile u8 *)((unsigned int)base + ((unsigned int)offset)))
-
-#define cprintf printf
-
-#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0]))
-
-#ifndef BUG
-#define BUG() \
-       do {\
-               printf("BUG: failure at %s:%d/%s()!\n", __FILE__, __LINE__, __FUNCTION__); \
-       } while (0)
-#define BUG_ON(condition) do { if (unlikely((condition) != 0)) BUG(); } while (0)
-#endif                                                 /* BUG */
-
-#define setbit(addr, bit, value)  __raw_writel((__raw_readl(addr) & ~(1 << bit)) | ((value & 0x1) << bit), addr)
-
-#endif
index b8c5e96..9767c1d 100644 (file)
@@ -58,7 +58,6 @@
  ************************************************************************************/
 
 #include <tinyara/config.h>
-#include <arch/chip/chip.h>
 
 /* Then get all of the register definitions */
 #ifdef CONFIG_ARCH_CHIP_S5JT200
index 1527bee..ad6e5eb 100644 (file)
@@ -66,7 +66,6 @@
 #include "up_internal.h"
 
 #include <chip.h>
-#include <arch/chip/chip_types.h>
 #include "s5j_watchdog.h"
 #include "arm.h"
 #ifdef CONFIG_ARMV7M_MPU
index aa50b7a..1f17be1 100644 (file)
@@ -63,7 +63,6 @@
 #include <errno.h>
 
 #include <arch/irq.h>
-#include <arch/chip/chip_types.h>
 #include <tinyara/gpio.h>
 #include <tinyara/wdog.h>
 #include <tinyara/wqueue.h>
index 41c9470..0d0ed74 100644 (file)
@@ -536,7 +536,7 @@ static int try_address(struct s5j_i2c_priv_s *priv, u8 addr, int retries)
                        break;
                }
                hsi2c_stop(priv);
-               udelay(priv->timeout / 2);
+               up_udelay(priv->timeout / 2);
                hsi2c_start(priv);
        }
 
@@ -910,10 +910,10 @@ static int hsi2c_cleanup(struct s5j_i2c_priv_s *priv)
        priv->xfer_speed = I2C_SPEED_400KHZ;
 
        putreg32(0x80000000, priv->config->base + CTL);
-       udelay(10);
+       up_udelay(10);
 
        putreg32(0x0, priv->config->base + CTL);
-       udelay(100);
+       up_udelay(100);
 
        return 0;
 }
index 7538491..d05495a 100644 (file)
@@ -70,7 +70,6 @@
 #include <tinyara/pwm.h>
 
 #include <arch/chip/irq.h>
-#include <arch/chip/chip_types.h>
 
 #include "chip.h"
 #include "up_arch.h"
index 0df232b..63f8cf7 100644 (file)
@@ -57,7 +57,6 @@
 #include <sys/types.h>
 #include <string.h>
 #include <tinyara/kmalloc.h>
-#include <arch/chip/chip_types.h>
 #include <arch/chip/irq.h>
 #include <chip.h>
 
index 8ed878b..7baebdd 100644 (file)
@@ -81,7 +81,6 @@
 #include <termios.h>
 #endif
 
-#include <arch/chip/chip_types.h>
 #include <chip.h>
 
 /****************************************************************************
index 8af30f0..3f76987 100644 (file)
@@ -57,8 +57,6 @@
 #ifndef __ARCH_ARM_SRC_S5J_S5J_SERIAL_H
 #define __ARCH_ARM_SRC_S5J_S5J_SERIAL_H
 
-#include <arch/chip/chip_types.h>
-
 /* Register Map */
 #define UART_LCON       0x00
 #define UART_CON        0x04
index 1f5855e..12d4285 100644 (file)
@@ -56,7 +56,6 @@
 /****************************************************************************
  * Included Files
  ****************************************************************************/
-#include <arch/chip/chip_types.h>
 #include <arch/chip/irq.h>
 #include <chip.h>
 #include <chip/s5j_gpio.h>
index 6625ac1..a03be88 100644 (file)
@@ -57,6 +57,7 @@
 #include <tinyara/config.h>
 
 #include <stdint.h>
+#include <time.h>
 
 #include <arch/board/board.h>
 #include "chip.h"
index 9104c7c..fb4900d 100644 (file)
@@ -66,7 +66,6 @@
 
 #include "up_arch.h"
 
-#include <arch/chip/chip_types.h>
 #include "s5j_watchdog.h"
 #include <arch/irq.h>
 #include <chip.h>
index c68a015..22ac5c3 100644 (file)
 #include <errno.h>
 
 #include <tinyara/board.h>
-#include <arch/chip/chip.h>
 #include <tinyara/irq.h>
 
-#include <arch/chip/chip_types.h>
 #include <chip.h>
 
 #ifdef CONFIG_ARCH_BUTTONS