rddrone-uavcan146: HRT & RTC timer support

This commit is contained in:
Peter van der Perk 2020-03-25 21:37:28 +01:00 committed by GitHub
parent 3d44077f2c
commit a4e6f96365
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
11 changed files with 247 additions and 314 deletions

View File

@ -67,7 +67,7 @@ px4_add_board(
#reflect
#sd_bench
shutdown
#top
top
#topic_listener
#tune_control
ver

View File

@ -57,6 +57,8 @@
#define BOARD_XTAL_FREQUENCY 8000000
#define BOARD_FTM_FREQ 8000000
/* The S32K146 will run at 112MHz */
/* LED definitions **********************************************************/

View File

@ -5,7 +5,6 @@
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_ARCH_FPU is not set
# CONFIG_NSH_ARGCAT is not set
# CONFIG_NSH_CMDOPT_HEXDUMP is not set
# CONFIG_NSH_CMDPARMS is not set
@ -19,6 +18,8 @@ CONFIG_ARCH_CHIP_S32K146=y
CONFIG_ARCH_CHIP_S32K14X=y
CONFIG_ARCH_CHIP_S32K1XX=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_LOOPSPERMSEC=3997
CONFIG_BUILTIN=y
@ -33,6 +34,7 @@ CONFIG_I2CTOOL_MAXADDR=0x7f
CONFIG_I2CTOOL_MAXBUS=0
CONFIG_I2CTOOL_MINADDR=0x00
CONFIG_INTELHEX_BINARY=y
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LPUART0_RXBUFSIZE=64
CONFIG_LPUART0_TXBUFSIZE=64
CONFIG_LPUART1_RXBUFSIZE=64
@ -54,15 +56,19 @@ CONFIG_RAM_SIZE=126976
CONFIG_RAM_START=0x1fff0000
CONFIG_RAW_BINARY=y
CONFIG_RR_INTERVAL=200
CONFIG_RTC=y
CONFIG_S32K1XX_LPI2C0=y
CONFIG_S32K1XX_LPSPI0=y
CONFIG_S32K1XX_LPUART0=y
CONFIG_S32K1XX_LPUART1=y
CONFIG_S32K1XX_RTC=y
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SPITOOL_DEFFREQ=400000
CONFIG_SPITOOL_MAXBUS=0
CONFIG_SPITOOL_PROGNAME="spi"
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=18
CONFIG_START_MONTH=8
CONFIG_START_YEAR=2019
@ -71,4 +77,5 @@ CONFIG_SYMTAB_ORDEREDBYNAME=y
CONFIG_SYSTEM_I2CTOOL=y
CONFIG_SYSTEM_NSH=y
CONFIG_SYSTEM_SPITOOL=y
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y

View File

@ -92,9 +92,14 @@ __BEGIN_DECLS
/* Count of peripheral clock user configurations */
#define NUM_OF_PERIPHERAL_CLOCKS_0 15
#define NUM_OF_PERIPHERAL_CLOCKS_0 14
/* High-resolution timer */
#define HRT_TIMER 1 /* FTM timer for the HRT */
#define HRT_TIMER_CHANNEL 0 /* Use capture/compare channel 0 */
#define HRT_PPM_CHANNEL 1 /* Use TPM1 capture/compare channel 1 */
/****************************************************************************
* Public Types
****************************************************************************/

View File

@ -76,151 +76,137 @@
const struct clock_configuration_s g_initial_clkconfig = {
.scg =
{
.sirc =
.sirc =
{
.range = SCG_SIRC_RANGE_HIGH, /* RANGE - High range (8 MHz) */
.div1 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SIRCDIV1 */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SIRCDIV2 */
.initialize = true, /* Initialize */
.stopmode = true, /* SIRCSTEN */
.lowpower = true, /* SIRCLPEN */
.locked = false, /* LK */
.range = SCG_SIRC_RANGE_HIGH, /* RANGE - High range (8 MHz) */
.div1 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SIRCDIV1 */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SIRCDIV2 */
.initialize = true, /* Initialize */
.stopmode = false, /* SIRCSTEN */
.lowpower = true, /* SIRCLPEN */
.locked = false, /* LK */
},
.firc =
.firc =
{
.range = SCG_FIRC_RANGE_48M, /* RANGE */
.div1 = SCG_ASYNC_CLOCK_DIV_BY_1, /* FIRCDIV1 */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_1, /* FIRCDIV2 */
.initialize = true, /* Initialize */
.stopmode = false, /* */
.lowpower = false, /* */
.regulator = true, /* FIRCREGOFF */
.locked = false, /* LK */
.range = SCG_FIRC_RANGE_48M, /* RANGE */
.div1 = SCG_ASYNC_CLOCK_DIV_BY_1, /* FIRCDIV1 */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_1, /* FIRCDIV2 */
.initialize = true, /* Initialize */
.regulator = true, /* FIRCREGOFF */
.locked = false, /* LK */
},
.sosc =
.sosc =
{
.mode = SCG_SOSC_MONITOR_DISABLE, /* SOSCCM */
.gain = SCG_SOSC_GAIN_LOW, /* HGO */
.range = SCG_SOSC_RANGE_MID, /* RANGE */
.extref = SCG_SOSC_REF_OSC, /* EREFS */
.div1 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SOSCDIV1 */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SOSCDIV2 */
.initialize = true, /* Initialize */
.stopmode = false, /* */
.lowpower = false, /* */
.locked = false, /* LK */
.mode = SCG_SOSC_MONITOR_DISABLE, /* SOSCCM */
.gain = SCG_SOSC_GAIN_LOW, /* HGO */
.range = SCG_SOSC_RANGE_HIGH, /* RANGE */
.extref = SCG_SOSC_REF_OSC, /* EREFS */
.div1 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SOSCDIV1 */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SOSCDIV2 */
.initialize = true, /* Initialize */
.locked = false, /* LK */
},
.spll =
.spll =
{
.mode = SCG_SPLL_MONITOR_DISABLE, /* SPLLCM */
.div1 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SPLLDIV1 */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SPLLDIV2 */
.prediv = 1, /* PREDIV */
.mult = 40, /* MULT */
.src = 0, /* SOURCE */
.initialize = true, /* Initialize */
.stopmode = false, /* */
.locked = false, /* LK */
.mode = SCG_SPLL_MONITOR_DISABLE, /* SPLLCM */
.div1 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SPLLDIV1 */
.div2 = SCG_ASYNC_CLOCK_DIV_BY_1, /* SPLLDIV2 */
.prediv = 1, /* PREDIV */
.mult = 40, /* MULT */
.src = 0, /* SOURCE */
.initialize = true, /* Initialize */
.locked = false, /* LK */
},
.rtc =
.rtc =
{
.initialize = true, /* Initialize */
.clkin = 0 /* RTC_CLKIN */
.initialize = true, /* Initialize */
.clkin = 0, /* RTC_CLKIN */
},
.clockout =
.clockout =
{
.source = SCG_CLOCKOUT_SRC_FIRC, /* SCG CLKOUTSEL */
.initialize = true, /* Initialize */
.source = SCG_CLOCKOUT_SRC_FIRC, /* SCG CLKOUTSEL */
.initialize = true, /* Initialize */
},
.clockmode =
.clockmode =
{
.rccr = /* RCCR - Run Clock Control Register */
.rccr = /* RCCR - Run Clock Control Register */
{
.src = SCG_SYSTEM_CLOCK_SRC_SYS_PLL, /* SCS */
.divslow = 3, /* DIVSLOW, range 1..16 */
.divbus = 2, /* DIVBUS, range 1..16 */
.divcore = 2 /* DIVCORE, range 1..16 */
.src = SCG_SYSTEM_CLOCK_SRC_SYS_PLL, /* SCS */
.divslow = 3, /* DIVSLOW, range 1..16 */
.divbus = 2, /* DIVBUS, range 1..16 */
.divcore = 2, /* DIVCORE, range 1..16 */
},
.vccr = /* VCCR - VLPR Clock Control Register */
.vccr = /* VCCR - VLPR Clock Control Register */
{
.src = SCG_SYSTEM_CLOCK_SRC_SIRC, /* SCS */
.divslow = 4, /* DIVSLOW, range 1..16 */
.divbus = 1, /* DIVBUS, range 1..16 */
.divcore = 2 /* DIVCORE, range 1..16 */
.src = SCG_SYSTEM_CLOCK_SRC_SIRC, /* SCS */
.divslow = 4, /* DIVSLOW, range 1..16 */
.divbus = 1, /* DIVBUS, range 1..16 */
.divcore = 2, /* DIVCORE, range 1..16 */
},
.hccr =
.hccr =
{
.src = SCG_SYSTEM_CLOCK_SRC_SYS_PLL, /* SCS */
.divslow = 3, /* DIVSLOW, range 1..16 */
.divbus = 2, /* DIVBUS, range 1..16 */
.divcore = 2 /* DIVCORE, range 1..16 */
.src = SCG_SYSTEM_CLOCK_SRC_SYS_PLL, /* SCS */
.divslow = 3, /* DIVSLOW, range 1..16 */
.divbus = 2, /* DIVBUS, range 1..16 */
.divcore = 2, /* DIVCORE, range 1..16 */
},
/* .altclk */
.initialize = true, /* Initialize */
.initialize = true, /* Initialize */
},
},
.sim =
.sim =
{
.clockout = /* Clock Out configuration. */
.clockout = /* Clock Out configuration. */
{
.source = SIM_CLKOUT_SEL_SYSTEM_SCG_CLKOUT, /* CLKOUTSEL */
.divider = 1, /* CLKOUTDIV, range 1..8 */
.initialize = true, /* Initialize */
.enable = false, /* CLKOUTEN */
.source = SIM_CLKOUT_SEL_SYSTEM_SCG_CLKOUT, /* CLKOUTSEL */
.divider = 1, /* CLKOUTDIV, range 1..8 */
.initialize = true, /* Initialize */
.enable = false, /* CLKOUTEN */
},
.lpoclk = /* Low Power Clock configuration. */
.lpoclk = /* Low Power Clock configuration. */
{
.rtc_source = SIM_RTCCLK_SEL_SOSCDIV1_CLK, /* RTCCLKSEL */
.lpo_source = SIM_LPO_CLK_SEL_LPO_128K, /* LPOCLKSEL */
.initialize = true, /* Initialize */
.lpo32k = true, /* LPO32KCLKEN */
.lpo1k = true, /* LPO1KCLKEN */
.rtc_source = SIM_RTCCLK_SEL_SOSCDIV1_CLK, /* RTCCLKSEL */
.lpo_source = SIM_LPO_CLK_SEL_LPO_128K, /* LPOCLKSEL */
.initialize = true, /* Initialize */
.lpo32k = true, /* LPO32KCLKEN */
.lpo1k = true, /* LPO1KCLKEN */
},
.tclk = /* TCLK CLOCK configuration. */
.tclk = /* TCLK CLOCK configuration. */
{
.tclkfreq[0] = 0, /* TCLK0 */
.tclkfreq[1] = 0, /* TCLK1 */
.tclkfreq[2] = 0, /* TCLK2 */
.initialize = true, /* Initialize */
.tclkfreq[0] = 0, /* TCLK0 */
.tclkfreq[1] = 0, /* TCLK1 */
.tclkfreq[2] = 0, /* TCLK2 */
.initialize = true, /* Initialize */
},
.platgate = /* Platform Gate Clock configuration. */
.platgate = /* Platform Gate Clock configuration. */
{
.initialize = true, /* Initialize */
.mscm = true, /* CGCMSCM */
.mpu = true, /* CGCMPU */
.dma = true, /* CGCDMA */
.erm = true, /* CGCERM */
.eim = true, /* CGCEIM */
.initialize = true, /* Initialize */
.mscm = true, /* CGCMSCM */
.mpu = true, /* CGCMPU */
.dma = true, /* CGCDMA */
.erm = true, /* CGCERM */
.eim = true, /* CGCEIM */
},
.traceclk = /* Debug trace Clock Configuration. */
.traceclk = /* Debug trace Clock Configuration. */
{
.source = CLOCK_TRACE_SRC_CORE_CLK, /* TRACECLK_SEL */
.divider = 1, /* TRACEDIV, range 1..8 */
.initialize = true, /* Initialize */
.enable = true, /* TRACEDIVEN */
.fraction = false, /* TRACEFRAC */
.source = CLOCK_TRACE_SRC_CORE_CLK, /* TRACECLK_SEL */
.divider = 1, /* TRACEDIV, range 1..8 */
.initialize = true, /* Initialize */
.enable = true, /* TRACEDIVEN */
.fraction = false, /* TRACEFRAC */
},
#ifdef CONFIG_S32K1XX_HAVE_QSPI
.qspirefclk = /* Quad Spi Internal Reference Clock Gating. */
{
.refclk = false, /* Qspi reference clock gating */
},
#endif
},
.pcc =
.pcc =
{
.count = NUM_OF_PERIPHERAL_CLOCKS_0, /* Number peripheral clock configurations */
.pclks = g_peripheral_clockconfig0 /* Peripheral clock configurations */
.count = NUM_OF_PERIPHERAL_CLOCKS_0, /* Number peripheral clock configurations */
.pclks = g_peripheral_clockconfig0, /* Peripheral clock configurations */
},
.pmc =
.pmc =
{
.lpoclk = /* Low Power Clock configuration. */
.lpoclk = /* Low Power Clock configuration. */
{
.trim = 0, /* Trimming value for LPO */
.initialize = true, /* Initialize */
.enable = true, /* Enable/disable LPO */
.trim = 0, /* Trimming value for LPO */
.initialize = true, /* Initialize */
.enable = true, /* Enable/disable LPO */
},
}
},
};

View File

@ -43,6 +43,8 @@
#include "board_config.h"
#include <px4_platform_common/init.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@ -87,6 +89,9 @@ int board_app_initialize(uintptr_t arg)
return OK;
#else
px4_platform_init();
/* Perform board-specific initialization */
return s32k1xx_bringup();

View File

@ -79,108 +79,96 @@
const struct peripheral_clock_config_s g_peripheral_clockconfig0[] = {
{
.clkname = ADC0_CLK,
.clkgate = true,
.clksrc = CLK_SRC_FIRC,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
.clkname = FLEXCAN0_CLK,
#ifdef CONFIG_S32K1XX_FLEXCAN0
.clkgate = true,
#else
.clkgate = false,
#endif
},
{
.clkname = ADC1_CLK,
.clkgate = true,
.clksrc = CLK_SRC_FIRC,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
.clkname = FLEXCAN1_CLK,
#ifdef CONFIG_S32K1XX_FLEXCAN1
.clkgate = true,
#else
.clkgate = false,
#endif
},
{
.clkname = LPI2C0_CLK,
.clkgate = true,
.clksrc = CLK_SRC_SIRC,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
.clkname = LPI2C0_CLK,
#ifdef CONFIG_S32K1XX_LPI2C0
.clkgate = true,
#else
.clkgate = false,
#endif
.clksrc = CLK_SRC_SIRC_DIV2,
},
{
.clkname = LPSPI0_CLK,
.clkgate = true,
.clksrc = CLK_SRC_SIRC,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
.clkname = LPSPI0_CLK,
#ifdef CONFIG_S32K1XX_LPSPI0
.clkgate = true,
#else
.clkgate = false,
#endif
.clksrc = CLK_SRC_SIRC_DIV2,
},
{
.clkname = LPSPI1_CLK,
.clkgate = false,
.clksrc = CLK_SRC_FIRC,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
.clkname = LPUART0_CLK,
#ifdef CONFIG_S32K1XX_LPUART0
.clkgate = true,
#else
.clkgate = false,
#endif
.clksrc = CLK_SRC_SIRC_DIV2,
},
{
.clkname = LPSPI2_CLK,
.clkgate = false,
.clksrc = CLK_SRC_FIRC,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
.clkname = LPUART1_CLK,
#ifdef CONFIG_S32K1XX_LPUART1
.clkgate = true,
#else
.clkgate = false,
#endif
.clksrc = CLK_SRC_SIRC_DIV2,
},
{
.clkname = LPTMR0_CLK,
.clkgate = true,
.clksrc = CLK_SRC_SIRC,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
},
{
.clkname = LPUART0_CLK,
.clkgate = true,
.clksrc = CLK_SRC_SIRC,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
},
{
.clkname = LPUART1_CLK,
.clkgate = true,
.clksrc = CLK_SRC_SIRC,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
},
{
.clkname = LPUART2_CLK,
.clkgate = false,
.clksrc = CLK_SRC_SIRC,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
},
{
.clkname = PORTA_CLK,
.clkgate = true,
.clkname = RTC0_CLK,
#ifdef CONFIG_S32K1XX_RTC
.clkgate = true,
#else
.clkgate = false,
#endif
.clksrc = CLK_SRC_OFF,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
},
{
.clkname = PORTB_CLK,
.clkname = FTM0_CLK,
.clkgate = true,
.clksrc = CLK_SRC_OFF,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
.clksrc = CLK_SRC_SIRC,
},
{
.clkname = PORTC_CLK,
.clkname = FTM1_CLK,
.clkgate = true,
.clksrc = CLK_SRC_OFF,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
.clksrc = CLK_SRC_SIRC,
},
{
.clkname = PORTD_CLK,
.clkgate = true,
.clksrc = CLK_SRC_OFF,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
.clkname = PORTA_CLK,
.clkgate = true,
},
{
.clkname = PORTE_CLK,
.clkgate = true,
.clksrc = CLK_SRC_OFF,
.frac = MULTIPLY_BY_ONE,
.divider = 1,
}
.clkname = PORTB_CLK,
.clkgate = true,
},
{
.clkname = PORTC_CLK,
.clkgate = true,
},
{
.clkname = PORTD_CLK,
.clkgate = true,
},
{
.clkname = PORTE_CLK,
.clkgate = true,
},
};

@ -1 +1 @@
Subproject commit 9d006171883937823b8a10613507d7c5825b81de
Subproject commit b902d4ca3d79ffbd5148670cb13bfeef7d917555

View File

@ -1,7 +1,8 @@
/****************************************************************************
*
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
* Author: @author David Sidrane <david_s5@nscdg.com>
* Author: @author Peter van der Perk <peter.vanderperk@nxp.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -40,6 +41,7 @@
#include <px4_platform_common/px4_config.h>
#include <errno.h>
#include <nuttx/board.h>
#include <hardware/s32k1xx_rcm.h>
#ifdef CONFIG_BOARDCTL_RESET
@ -87,16 +89,14 @@ int board_set_bootload_mode(board_reset_e mode)
break;
case board_reset_enter_bootloader:
regvalue = 0xb007b007;
regvalue = RCM_PARAM_ESW;
break;
default:
return -EINVAL;
}
//todo need nvram for reboot to botloader
UNUSED(regvalue);
//*((uint32_t *) KINETIS_VBATR_BASE) = regvalue;
*((uint32_t *) S32K1XX_RCM_SRS) = regvalue;
return OK;
}

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2016-2017 PX4 Development Team. All rights reserved.
* Copyright (c) 2016-2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -33,16 +33,17 @@
/**
* @file drv_hrt.c
* Author: David Sidrane <david_s5@nscdg.com>
* Author: Peter van der Perk <peter.vanderperk@nxp.com>
* David Sidrane <david_s5@nscdg.com>
*
* High-resolution timer callouts and timekeeping.
*
* This can use any Kinetis TPM timer.
* This can use any S32K FTM timer.
*
* Note that really, this could use systick too, but that's
* monopolised by NuttX and stealing it would just be awkward.
*
* We don't use the NuttX Kinetis driver per se; rather, we
* We don't use the NuttX S32K driver per se; rather, we
* claim the timer and then drive it directly.
*/
@ -65,63 +66,10 @@
#include <board_config.h>
#include <drivers/drv_hrt.h>
#include "chip.h"
#include "hardware/s32k1xx_sim.h"
//todo:stubs
#define HRT_COUNTER_PERIOD 65536
#define HRT_COUNTER_SCALE(_c) (_c)
hrt_abstime
hrt_absolute_time(void)
{
hrt_abstime abstime;
uint32_t count;
irqstate_t flags;
/*
* Counter state. Marked volatile as they may change
* inside this routine but outside the irqsave/restore
* pair. Discourage the compiler from moving loads/stores
* to these outside of the protected range.
*/
static volatile hrt_abstime base_time;
static volatile uint32_t last_count;
/* prevent re-entry */
flags = px4_enter_critical_section();
/* get the current counter value */
count = 0; //rCNT todo:fix this;
/*
* Determine whether the counter has wrapped since the
* last time we're called.
*
* This simple test is sufficient due to the guarantee that
* we are always called at least once per counter period.
*/
if (count < last_count) {
base_time += HRT_COUNTER_PERIOD;
}
/* save the count for next time */
last_count = count;
/* compute the current time */
abstime = HRT_COUNTER_SCALE(base_time + count);
px4_leave_critical_section(flags);
return abstime;
}
#if 0
#include "kinetis_tpm.h"
#include "hardware/s32k1xx_ftm.h"
#undef PPM_DEBUG
//#define CONFIG_DEBUG_HRT
#ifdef CONFIG_DEBUG_HRT
# define hrtinfo _info
#else
@ -137,10 +85,12 @@ hrt_absolute_time(void)
/* HRT configuration */
#define HRT_TIMER_CLOCK BOARD_TPM_FREQ /* The input clock frequency to the TPM block */
#define HRT_TIMER_BASE CAT(CAT(KINETIS_TPM, HRT_TIMER),_BASE) /* The Base address of the TPM */
#define HRT_TIMER_VECTOR CAT(KINETIS_IRQ_TPM, HRT_TIMER) /* The TPM Interrupt vector */
#define HRT_SIM_SCGC2_TPM CAT(SIM_SCGC2_TPM, HRT_TIMER) /* The Clock Gating enable bit for this TPM */
#define HRT_TIMER_CLOCK BOARD_FTM_FREQ /* The input clock frequency to the FTM block */
#define HRT_TIMER_BASE S32K1XX_FTM0_BASE /* The Base address of the FTM */
#define HRT_TIMER_VECTOR S32K1XX_IRQ_FTM0_CH0_1 /* The FTM Interrupt vector */
#define LOG_1(n) (((n) >= 2) ? 1 : 0)
#define LOG_2(n) (((n) >= 1<<2) ? (2 + LOG_1((n)>>2)) : LOG_1(n))
#if HRT_TIMER == 1 && defined(CONFIG_KINETIS_TPM1)
# error must not set CONFIG_KINETIS_TPM1=y and HRT_TIMER=1
@ -192,27 +142,26 @@ hrt_absolute_time(void)
#define REG(_reg) _REG(HRT_TIMER_BASE + (_reg))
#define rSC REG(KINETIS_TPM_SC_OFFSET)
#define rCNT REG(KINETIS_TPM_CNT_OFFSET)
#define rMOD REG(KINETIS_TPM_MOD_OFFSET)
#define rC0SC REG(KINETIS_TPM_C0SC_OFFSET)
#define rC0V REG(KINETIS_TPM_C0V_OFFSET)
#define rC1SC REG(KINETIS_TPM_C1SC_OFFSET)
#define rC1V REG(KINETIS_TPM_C1V_OFFSET)
#define rSTATUS REG(KINETIS_TPM_STATUS_OFFSET)
#define rCOMBINE REG(KINETIS_TPM_COMBINE_OFFSET)
#define rPOL REG(KINETIS_TPM_POL_OFFSET)
#define rFILTER REG(KINETIS_TPM_FILTER_OFFSET)
#define rQDCTRL REG(KINETIS_TPM_QDCTRL_OFFSET)
#define rCONF REG(KINETIS_TPM_CONF_OFFSET)
#define rSC REG(S32K1XX_FTM_SC_OFFSET)
#define rCNT REG(S32K1XX_FTM_CNT_OFFSET)
#define rMOD REG(S32K1XX_FTM_MOD_OFFSET)
#define rC0SC REG(S32K1XX_FTM_C0SC_OFFSET)
#define rC0V REG(S32K1XX_FTM_C0V_OFFSET)
#define rC1SC REG(S32K1XX_FTM_C1SC_OFFSET)
#define rC1V REG(S32K1XX_FTM_C1V_OFFSET)
#define rSTATUS REG(S32K1XX_FTM_STATUS_OFFSET)
#define rCOMBINE REG(S32K1XX_FTM_COMBINE_OFFSET)
#define rPOL REG(S32K1XX_FTM_POL_OFFSET)
#define rFILTER REG(S32K1XX_FTM_FILTER_OFFSET)
#define rQDCTRL REG(S32K1XX_FTM_QDCTRL_OFFSET)
#define rCONF REG(S32K1XX_FTM_CONF_OFFSET)
/*
* Specific registers and bits used by HRT sub-functions
*/
# define rCNV_HRT CAT3(rC, HRT_TIMER_CHANNEL, V) /* Channel Value Register used by HRT */
# define rCNSC_HRT CAT3(rC, HRT_TIMER_CHANNEL, SC) /* Channel Status and Control Register used by HRT */
# define STATUS_HRT CAT3(TPM_STATUS_CH, HRT_TIMER_CHANNEL, F) /* Capture and Compare Status Register used by HRT */
# define STATUS_HRT CAT3(FTM_STATUS_CH, HRT_TIMER_CHANNEL, F) /* Capture and Compare Status Register used by HRT */
#if (HRT_TIMER_CHANNEL != 0) && (HRT_TIMER_CHANNEL != 1)
# error HRT_TIMER_CHANNEL must be a value between 0 and 1
@ -229,6 +178,11 @@ static uint16_t latency_baseline;
/* timer count at interrupt (for latency purposes) */
static uint16_t latency_actual;
/* latency histogram */
const uint16_t latency_bucket_count = LATENCY_BUCKET_COUNT;
const uint16_t latency_buckets[LATENCY_BUCKET_COUNT] = { 1, 2, 5, 10, 20, 50, 100, 1000 };
__EXPORT uint32_t latency_counters[LATENCY_BUCKET_COUNT + 1];
/* timer-specific functions */
static void hrt_tim_init(void);
static int hrt_tim_isr(int irq, void *context, void *args);
@ -255,8 +209,8 @@ static void hrt_call_invoke(void);
#define rCNV_PPM CAT3(rC,HRT_PPM_CHANNEL,V) /* Channel Value Register used by PPM */
#define rCNSC_PPM CAT3(rC,HRT_PPM_CHANNEL,SC) /* Channel Status and Control Register used by PPM */
#define STATUS_PPM CAT3(TPM_STATUS_CH, HRT_PPM_CHANNEL ,F) /* Capture and Compare Status Register used by PPM */
#define CNSC_PPM (TPM_CnSC_CHIE | TPM_CnSC_ELSB | TPM_CnSC_ELSA) /* Input Capture configuration both Edges, interrupt */
#define STATUS_PPM CAT3(FTM_STATUS_CH, HRT_PPM_CHANNEL ,F) /* Capture and Compare Status Register used by PPM */
#define CNSC_PPM (FTM_CNSC_CHIE | FTM_CNSC_ELSB | FTM_CNSC_ELSA) /* Input Capture configuration both Edges, interrupt */
/* Sanity checking */
@ -330,21 +284,7 @@ static void hrt_ppm_decode(uint32_t status);
*/
static void hrt_tim_init(void)
{
/* Select a the clock source to the TPM */
uint32_t regval = _REG(KINETIS_SIM_SOPT2);
regval &= ~(SIM_SOPT2_TPMSRC_MASK);
regval |= BOARD_TPM_CLKSRC;
_REG(KINETIS_SIM_SOPT2) = regval;
/* Enabled System Clock Gating Control for TPM */
regval = _REG(KINETIS_SIM_SCGC2);
regval |= HRT_SIM_SCGC2_TPM;
_REG(KINETIS_SIM_SCGC2) = regval;
/* Clock is enabled in S32K1XX_pheriphclocks.c */
/* claim our interrupt vector */
@ -352,28 +292,29 @@ static void hrt_tim_init(void)
/* disable and configure the timer */
rSC = TPM_SC_TOF;
rSC = FTM_SC_TOF;
rCNT = 0;
rMOD = HRT_COUNTER_PERIOD - 1;
rSTATUS = (TPM_STATUS_TOF | STATUS_HRT | STATUS_PPM);
rCNSC_HRT = (TPM_CnSC_CHF | TPM_CnSC_CHIE | TPM_CnSC_MSA);
rCNSC_PPM = (TPM_CnSC_CHF | CNSC_PPM);
rCNSC_HRT = (FTM_CNSC_CHF | FTM_CNSC_CHIE | FTM_CNSC_MSA);
rCNSC_PPM = (FTM_CNSC_CHF | CNSC_PPM);
rCOMBINE = 0;
rPOL = 0;
rFILTER = 0;
rQDCTRL = 0;
rCONF = TPM_CONF_DBGMODE_CONT;
rCONF = 0xC0; //FTM continues in DBG
/* set an initial capture a little ways off */
rCNV_PPM = 0;
rCNV_HRT = 1000;
/* enable the timer */
rSC |= (TPM_SC_TOIE | TPM_SC_CMOD_LPTPM_CLK | TPM_SC_PS_DIV16);
/* Use FIXEDCLK src and enable the timer
* Set calculate prescaler for HRT_TIMER_FREQ */
rSC |= (FTM_SC_TOIE | FTM_SC_CLKS_FIXED |
(LOG_2(HRT_TIMER_CLOCK / HRT_TIMER_FREQ) << FTM_SC_PS_SHIFT
& FTM_SC_PS_MASK));
/* enable interrupts */
up_enable_irq(HRT_TIMER_VECTOR);
@ -543,13 +484,13 @@ hrt_tim_isr(int irq, void *context, void *arg)
uint32_t status = rSTATUS;
/* ack the interrupts we just read */
rSTATUS = status;
rSTATUS = 0x00;
#ifdef HRT_PPM_CHANNEL
/* was this a PPM edge? */
if (status & (STATUS_PPM)) {
rCNSC_PPM = rCNSC_PPM & ~(FTM_SC_RF);
hrt_ppm_decode(status);
}
@ -557,6 +498,7 @@ hrt_tim_isr(int irq, void *context, void *arg)
/* was this a timer tick? */
if (status & STATUS_HRT) {
rCNSC_HRT = rCNSC_HRT & ~(FTM_SC_RF);
/* do latency calculations */
hrt_latency_update();
@ -685,7 +627,7 @@ hrt_init(void)
#ifdef HRT_PPM_CHANNEL
/* configure the PPM input pin */
px4_arch_configgpio(GPIO_PPM_IN);
//px4_arch_configgpio(GPIO_PPM_IN);
#endif
}
@ -933,4 +875,3 @@ hrt_call_delay(struct hrt_call *entry, hrt_abstime delay)
}
#endif /* HRT_TIMER */
#endif

View File

@ -1,7 +1,8 @@
/****************************************************************************
*
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
* Author: @author David Sidrane <david_s5@nscdg.com>
* Copyright (C) 2019 PX4 Development Team. All rights reserved.
* Author: @author Peter van der Perk <peter.vanderperk@nxp.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -34,7 +35,7 @@
/**
* @file board_mcu_version.c
* Implementation of Kinetis based SoC version API
* Implementation of S32K1xx based SoC version API
*/
#include <px4_platform_common/px4_config.h>
@ -43,20 +44,18 @@
#include "up_arch.h"
#include "hardware/s32k1xx_sim.h"
//todo upstrem chip id defs
#define CHIP_TAG "S32K1??"
#define CHIP_TAG "S32K1XX"
#define CHIP_TAG_LEN sizeof(CHIP_TAG)-1
int board_mcu_version(char *rev, const char **revstr, const char **errata)
{
uint32_t sim_sdid = getreg32(S32K1XX_SIM_SDID);
UNUSED(sim_sdid);
static char chip[sizeof(CHIP_TAG)] = CHIP_TAG;
chip[CHIP_TAG_LEN - 2] = '0' /*+ ((sim_sdid & SIM_SDID_FAMILYID_MASK) >> SIM_SDID_FAMILYID_SHIFT) */;
chip[CHIP_TAG_LEN - 1] = '0' /*+ ((sim_sdid & SIM_SDID_SUBFAMID_MASK) >> SIM_SDID_SUBFAMID_SHIFT)*/;
chip[CHIP_TAG_LEN - 2] = '0' + ((sim_sdid & SIM_SDID_GENERATION_MASK) >> SIM_SDID_GENERATION_SHIFT);
chip[CHIP_TAG_LEN - 1] = '0' + ((sim_sdid & SIM_SDID_SUBSERIES_MASK) >> SIM_SDID_SUBSERIES_SHIFT);
*revstr = chip;
*rev = '0' /*+ ((sim_sdid & SIM_SDID_REVID_MASK) >> SIM_SDID_REVID_SHIFT)*/;
*rev = '0' + ((sim_sdid & SIM_SDID_REVID_MASK) >> SIM_SDID_REVID_SHIFT);
if (errata) {
*errata = NULL;