Skip to content

Commit

Permalink
S32K add support for Nxp drone boards (#224)
Browse files Browse the repository at this point in the history
* S32K add support for Nxp drone boards

* Update arch/arm/src/s32k1xx/hardware/s32k1xx_rtc.h codestyle

Co-Authored-By: David Sidrane <David.Sidrane@Nscdg.com>

Co-authored-by: Jari van Ewijk <jari.vanewijk@nxp.com>
Co-authored-by: David Sidrane <David.Sidrane@Nscdg.com>
  • Loading branch information
3 people committed Feb 7, 2020
1 parent 2d5141b commit 499607d
Show file tree
Hide file tree
Showing 122 changed files with 11,681 additions and 272 deletions.
6 changes: 3 additions & 3 deletions arch/arm/include/s32k1xx/irq.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,10 @@

#include <nuttx/config.h>

#if defined(CONFIG_ARCH_CHIP_S32K11X)
# include <arch/chip/s32k11x_irq.h>
#elif defined(CONFIG_ARCH_CHIP_S32K14X)
#if defined(CONFIG_ARCH_CHIP_S32K14X)
# include <arch/chip/s32k14x_irq.h>
#elif defined(CONFIG_ARCH_CHIP_S32K11X)
# include <arch/chip/s32k11x_irq.h>
#else
# error Unrecognized S32K1XX part
#endif
Expand Down
15 changes: 13 additions & 2 deletions arch/arm/src/s32k1xx/Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,9 @@ config ARCH_CHIP_S32K14X
config S32K1XX_HAVE_ENET
bool
default n
select ARCH_HAVE_PHY
select ARCH_PHY_INTERRUPT
select ARCH_HAVE_NETDEV_STATISTICS

config S32K1XX_HAVE_EWM
bool
Expand Down Expand Up @@ -183,18 +186,26 @@ config S32K1XX_LPUART0
default n
select S32K1XX_LPUART
select LPUART0_SERIALDRIVER
select ARCH_HAVE_SERIAL_TERMIOS

config S32K1XX_LPUART1
bool "LPUART1"
default n
select S32K1XX_LPUART
select LPUART1_SERIALDRIVER
select ARCH_HAVE_SERIAL_TERMIOS

config S32K1XX_LPUART2
bool "LPUART2"
default n
select S32K1XX_LPUART
select LPUART2_SERIALDRIVER
select ARCH_HAVE_SERIAL_TERMIOS

config S32K1XX_RTC
bool "RTC"
default n


endmenu # S32K1XX Peripheral Selection

Expand Down Expand Up @@ -267,14 +278,14 @@ config S32K1XX_FLASHCFG_FPROT

config S32K1XX_FLASHCFG_FSEC
hex "Flash security byte"
default 0xff
default 0xfe
---help---
Refer to the S32K1xx reference manual or to hardware/s32k1xx_flashcfg.h
for a description of the FSEC bitfields.

config S32K1XX_FLASHCFG_FOPT
hex "Flash nonvolatile option byte"
default 0xff
default 0x7f
---help---
Refer to the S32K1xx reference manual or to hardware/s32k1xx_flashcfg.h
for a description of the FOPT bitfields.
Expand Down
4 changes: 4 additions & 0 deletions arch/arm/src/s32k1xx/Make.defs
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,10 @@ ifeq ($(CONFIG_S32K1XX_ENET),y)
CHIP_CSRCS += s32k1xx_enet.c
endif

ifeq ($(CONFIG_S32K1XX_RTC),y)
CHIP_CSRCS += s32k1xx_rtc.c
endif

# Source files specific to the ARM CPU family and to the S32K1xx chip family

ifeq ($(CONFIG_ARCH_CHIP_S32K11X),y)
Expand Down
7 changes: 6 additions & 1 deletion arch/arm/src/s32k1xx/chip.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,11 @@
#define ARMV6M_PERIPHERAL_INTERRUPTS S32K1XX_IRQ_NEXTINT
#define ARMV7M_PERIPHERAL_INTERRUPTS S32K1XX_IRQ_NEXTINT

/* Cache line sizes (in bytes)for the S32K14X */

#define ARMV7M_DCACHE_LINESIZE 16 /* 16 bytes (4 words) */
#define ARMV7M_ICACHE_LINESIZE 16 /* 16 bytes (4 words) */

/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
Expand All @@ -71,7 +76,7 @@
************************************************************************************/

/************************************************************************************
* Public Functions
* Public Function Prototypes
************************************************************************************/

#endif /* __ARCH_ARM_SRC_S32K1XX_CHIP_H */
16 changes: 10 additions & 6 deletions arch/arm/src/s32k1xx/hardware/s32k148_pinmux.h
Original file line number Diff line number Diff line change
Expand Up @@ -642,14 +642,18 @@
#define PIN_RMII_MDIO (PIN_ALT5 | PIN_PORTB | PIN4)
#define PIN_RMII_RX_DV (PIN_ALT5 | PIN_PORTC | PIN17)
#define PIN_RMII_RX_ER (PIN_ALT5 | PIN_PORTC | PIN16)
#define PIN_RMII_RXD_1 (PIN_ALT5 | PIN_PORTC | PIN0)
#define PIN_RMII_RXD_2 (PIN_ALT5 | PIN_PORTC | PIN1)
#define PIN_RMII_RXD_3 (PIN_ALT4 | PIN_PORTC | PIN0)
#define PIN_RMII_RXD_4 (PIN_ALT4 | PIN_PORTC | PIN1)
#define PIN_RMII_RXD0_1 (PIN_ALT5 | PIN_PORTC | PIN1)
#define PIN_RMII_RXD1_1 (PIN_ALT4 | PIN_PORTC | PIN0)
#define PIN_RMII_RXD0_2 (PIN_ALT5 | PIN_PORTC | PIN0)
#define PIN_RMII_RXD1_2 (PIN_ALT4 | PIN_PORTC | PIN1)
#define PIN_RMII_TX_CLK (PIN_ALT5 | PIN_PORTD | PIN11)
#define PIN_RMII_TX_EN (PIN_ALT5 | PIN_PORTD | PIN12)
#define PIN_RMII_TXD_1 (PIN_ALT5 | PIN_PORTC | PIN2)
#define PIN_RMII_TXD_2 (PIN_ALT5 | PIN_PORTD | PIN7)
#define PIN_RMII_TXD0 (PIN_ALT5 | PIN_PORTC | PIN2)
#define PIN_RMII_TXD1 (PIN_ALT5 | PIN_PORTD | PIN7)

#define PIN_RMII_MDC PIN_RMII_MDC_2
#define PIN_RMII_RXD0 PIN_RMII_RXD0_1
#define PIN_RMII_RXD1 PIN_RMII_RXD1_1

/* NMI */

Expand Down
94 changes: 94 additions & 0 deletions arch/arm/src/s32k1xx/hardware/s32k1xx_rtc.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
/****************************************************************************************************
* arch/arm/src/s32k1xx/chip/s32k1xx_rtc.h
*
* Copyright (C) 2019 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_SRC_S32K1XX_HARDWARE_S32K1XX_RTC_H
#define __ARCH_ARM_SRC_S32K1XX_HARDWARE_S32K1XX_RTC_H

/****************************************************************************************************
* Included Files
****************************************************************************************************/

#include <nuttx/config.h>
#include <hardware/s32k1xx_memorymap.h>

/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/

/* RTC Register Offsets *****************************************************************************/

#define S32K1XX_RTC_TSR_OFFSET 0x0000 /* Time Seconds register */
#define S32K1XX_RTC_TPR_OFFSET 0x0004 /* Time Prescaler Register */
#define S32K1XX_RTC_TAR_OFFSET 0x0008 /* Time Alarm Register */
#define S32K1XX_RTC_TCR_OFFSET 0x000C /* Time Compensation Register */
#define S32K1XX_RTC_CR_OFFSET 0x0010 /* Control Register */
#define S32K1XX_RTC_SR_OFFSET 0x0014 /* Status Register */
#define S32K1XX_RTC_LR_OFFSET 0x0018 /* Lock Register */
#define S32K1XX_RTC_IER_OFFSET 0x001C /* Interrupt Enable Register */

/* RTC Register Addresses ***************************************************************************/

#define S32K1XX_RTC_TSR (S32K1XX_RTC_BASE + S32K1XX_RTC_TSR_OFFSET)
#define S32K1XX_RTC_TPR (S32K1XX_RTC_BASE + S32K1XX_RTC_TPR_OFFSET)
#define S32K1XX_RTC_TAR (S32K1XX_RTC_BASE + S32K1XX_RTC_TAR_OFFSET)
#define S32K1XX_RTC_TCR (S32K1XX_RTC_BASE + S32K1XX_RTC_TCR_OFFSET)
#define S32K1XX_RTC_CR (S32K1XX_RTC_BASE + S32K1XX_RTC_CR_OFFSET)
#define S32K1XX_RTC_SR (S32K1XX_RTC_BASE + S32K1XX_RTC_SR_OFFSET)
#define S32K1XX_RTC_LR (S32K1XX_RTC_BASE + S32K1XX_RTC_LR_OFFSET)
#define S32K1XX_RTC_IER (S32K1XX_RTC_BASE + S32K1XX_RTC_IER_OFFSET)

/* RTC Register Bitfield Definitions ****************************************************************/

/* TSR Bit Fields */

#define RTC_TSR_SHIFT (0)
#define RTC_TSR_MASK (0xffffffff << RTC_TSR_SHIFT)

/* CR Bit Fields */

#define RTC_CR_SWR (1 << 0)
#define RTC_CR_SUP (1 << 2)
#define RTC_CR_UM (1 << 3)
#define RTC_CR_CPS (1 << 5)
#define RTC_CR_LPOS (1 << 7)
#define RTC_CR_CPE (1 << 24)

/* SR Bit Fields */

#define RTC_SR_TIF (1 << 0)
#define RTC_SR_TOF (1 << 1)
#define RTC_SR_TAF (1 << 2)
#define RTC_SR_TCE (1 << 4)
#endif /* __ARCH_ARM_SRC_S32K1XX_HARDWARE_S32K1XX_RTC_H */
1 change: 1 addition & 0 deletions arch/arm/src/s32k1xx/s32k14x/Make.defs
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ CMN_CSRCS += up_assert.c up_blocktask.c up_copyfullstate.c up_createstack.c
CMN_CSRCS += up_doirq.c up_hardfault.c up_initialstate.c up_memfault.c
CMN_CSRCS += up_releasepending.c up_reprioritizertr.c up_schedulesigaction.c
CMN_CSRCS += up_sigdeliver.c up_svcall.c up_trigger_irq.c up_unblocktask.c
CMN_CSRCS += up_systemreset.c

ifeq ($(CONFIG_ARMV7M_LAZYFPU),y)
CMN_ASRCS += up_lazyexception.S
Expand Down
Loading

0 comments on commit 499607d

Please sign in to comment.