mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 13:02:25 +08:00
NXP UCANS32K: Add Support for PWM
S32K1XX HRT: Allow any channel of any FTM timer to be used NXP UCANS32K: Enable additional FlexTimers and use FTM5 for HRT NXP UCANS32K - Change FTM clocksource to system oscillator NXP UCANS32K - Only need one FlexTimer and channel for PWM output NXP UCANS32K will have only one PWM header by default S32K1XX support FlexTimers beyond FTM3 S32K1XX io_timer.c - replace references to Kinetis S32K1XX io_timer.c correct register names S32K1XX input_capture.c and pwm_servo.c replace references to Kinetis
This commit is contained in:
committed by
David Sidrane
parent
4ed3ecea41
commit
35dce9aff6
@@ -41,6 +41,7 @@ add_library(drivers_board
|
||||
init.c
|
||||
periphclocks.c
|
||||
spi.c
|
||||
timer_config.cpp
|
||||
userleds.c
|
||||
)
|
||||
|
||||
|
||||
@@ -90,13 +90,32 @@ __BEGIN_DECLS
|
||||
|
||||
/* Count of peripheral clock user configurations */
|
||||
|
||||
#define NUM_OF_PERIPHERAL_CLOCKS_0 14
|
||||
#define NUM_OF_PERIPHERAL_CLOCKS_0 18
|
||||
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 1 /* FTM timer for the HRT */
|
||||
#define HRT_TIMER 5 /* 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 */
|
||||
|
||||
/* Timer I/O PWM and capture
|
||||
*
|
||||
* ?? PWM outputs are configured.
|
||||
* ?? Timer inputs are configured.
|
||||
*
|
||||
* Pins:
|
||||
* Defined in board.h
|
||||
*/
|
||||
// todo:Design this!
|
||||
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 1
|
||||
|
||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||
|
||||
#define BOARD_HAS_LED_PWM 1
|
||||
|
||||
#define LED_TIM3_CH1OUT /* PTD1 RGB_R */ PIN_FTM3_CH1_1
|
||||
#define LED_TIM3_CH5OUT /* PTC9 RGB_G */ PIN_FTM3_CH5_1
|
||||
#define LED_TIM3_CH4OUT /* PTC8 RGB_B */ PIN_FTM3_CH4_1
|
||||
|
||||
/****************************************************************************
|
||||
* Public Types
|
||||
|
||||
@@ -144,12 +144,32 @@ const struct peripheral_clock_config_s g_peripheral_clockconfig0[] = {
|
||||
{
|
||||
.clkname = FTM0_CLK,
|
||||
.clkgate = true,
|
||||
.clksrc = CLK_SRC_SIRC,
|
||||
.clksrc = CLK_SRC_SOSC_DIV1,
|
||||
},
|
||||
{
|
||||
.clkname = FTM1_CLK,
|
||||
.clkgate = true,
|
||||
.clksrc = CLK_SRC_SIRC,
|
||||
.clksrc = CLK_SRC_SOSC_DIV1,
|
||||
},
|
||||
{
|
||||
.clkname = FTM2_CLK,
|
||||
.clkgate = true,
|
||||
.clksrc = CLK_SRC_SOSC_DIV1,
|
||||
},
|
||||
{
|
||||
.clkname = FTM3_CLK,
|
||||
.clkgate = true,
|
||||
.clksrc = CLK_SRC_SOSC_DIV1,
|
||||
},
|
||||
{
|
||||
.clkname = FTM4_CLK,
|
||||
.clkgate = true,
|
||||
.clksrc = CLK_SRC_SOSC_DIV1,
|
||||
},
|
||||
{
|
||||
.clkname = FTM5_CLK,
|
||||
.clkgate = true,
|
||||
.clksrc = CLK_SRC_SOSC_DIV1,
|
||||
},
|
||||
{
|
||||
.clkname = PORTA_CLK,
|
||||
|
||||
@@ -0,0 +1,179 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016, 2018 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
|
||||
* 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 PX4 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 timer_config.c
|
||||
*
|
||||
* Configuration data for the S32K1XX pwm_servo, input capture and pwm input driver.
|
||||
*
|
||||
* Note that these arrays must always be fully-sized.
|
||||
*/
|
||||
|
||||
// TODO:Stubbed out for now
|
||||
#include <stdint.h>
|
||||
|
||||
#include "hardware/s32k1xx_pcc.h"
|
||||
#include "hardware/s32k1xx_ftm.h"
|
||||
#include "s32k1xx_pin.h"
|
||||
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <px4_arch/io_timer_hw_description.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Register accessors */
|
||||
|
||||
#define _REG(_addr) (*(volatile uint32_t *)(_addr))
|
||||
|
||||
/* Timer register accessors */
|
||||
|
||||
#define REG(t, _reg) _REG(S32K1XX_FTM##t##_BASE + (_reg))
|
||||
|
||||
#define rSC(t) REG(t,S32K1XX_FTM_SC_OFFSET)
|
||||
#define rCNT(t) REG(t,S32K1XX_FTM_CNT_OFFSET)
|
||||
#define rMOD(t) REG(t,S32K1XX_FTM_MOD_OFFSET)
|
||||
#define rC0SC(t) REG(t,S32K1XX_FTM_C0SC_OFFSET)
|
||||
#define rC0V(t) REG(t,S32K1XX_FTM_C0V_OFFSET)
|
||||
#define rC1SC(t) REG(t,S32K1XX_FTM_C1SC_OFFSET)
|
||||
#define rC1V(t) REG(t,S32K1XX_FTM_C1V_OFFSET)
|
||||
#define rC2SC(t) REG(t,S32K1XX_FTM_C2SC_OFFSET)
|
||||
#define rC2V(t) REG(t,S32K1XX_FTM_C2V_OFFSET)
|
||||
#define rC3SC(t) REG(t,S32K1XX_FTM_C3SC_OFFSET)
|
||||
#define rC3V(t) REG(t,S32K1XX_FTM_C3V_OFFSET)
|
||||
#define rC4SC(t) REG(t,S32K1XX_FTM_C4SC_OFFSET)
|
||||
#define rC4V(t) REG(t,S32K1XX_FTM_C4V_OFFSET)
|
||||
#define rC5SC(t) REG(t,S32K1XX_FTM_C5SC_OFFSET)
|
||||
#define rC5V(t) REG(t,S32K1XX_FTM_C5V_OFFSET)
|
||||
#define rC6SC(t) REG(t,S32K1XX_FTM_C6SC_OFFSET)
|
||||
#define rC6V(t) REG(t,S32K1XX_FTM_C6V_OFFSET)
|
||||
#define rC7SC(t) REG(t,S32K1XX_FTM_C7SC_OFFSET)
|
||||
#define rC7V(t) REG(t,S32K1XX_FTM_C7V_OFFSET)
|
||||
|
||||
#define rCNTIN(t) REG(t,S32K1XX_FTM_CNTIN_OFFSET)
|
||||
#define rSTATUS(t) REG(t,S32K1XX_FTM_STATUS_OFFSET)
|
||||
#define rMODE(t) REG(t,S32K1XX_FTM_MODE_OFFSET)
|
||||
#define rSYNC(t) REG(t,S32K1XX_FTM_SYNC_OFFSET)
|
||||
#define rOUTINIT(t) REG(t,S32K1XX_FTM_OUTINIT_OFFSET)
|
||||
#define rOUTMASK(t) REG(t,S32K1XX_FTM_OUTMASK_OFFSET)
|
||||
#define rCOMBINE(t) REG(t,S32K1XX_FTM_COMBINE_OFFSET)
|
||||
#define rDEADTIME(t) REG(t,S32K1XX_FTM_DEADTIME_OFFSET)
|
||||
#define rEXTTRIG(t) REG(t,S32K1XX_FTM_EXTTRIG_OFFSET)
|
||||
#define rPOL(t) REG(t,S32K1XX_FTM_POL_OFFSET)
|
||||
#define rFMS(t) REG(t,S32K1XX_FTM_FMS_OFFSET)
|
||||
#define rFILTER(t) REG(t,S32K1XX_FTM_FILTER_OFFSET)
|
||||
#define rFLTCTRL(t) REG(t,S32K1XX_FTM_FLTCTRL_OFFSET)
|
||||
#define rQDCTRL(t) REG(t,S32K1XX_FTM_QDCTRL_OFFSET)
|
||||
#define rCONF(t) REG(t,S32K1XX_FTM_CONF_OFFSET)
|
||||
#define rFLTPOL(t) REG(t,S32K1XX_FTM_FLTPOL_OFFSET)
|
||||
#define rSYNCONF(t) REG(t,S32K1XX_FTM_SYNCONF_OFFSET)
|
||||
#define rINVCTRL(t) REG(t,S32K1XX_FTM_INVCTRL_OFFSET)
|
||||
#define rSWOCTRL(t) REG(t,S32K1XX_FTM_SWOCTRL_OFFSET)
|
||||
#define rPWMLOAD(t) REG(t,S32K1XX_FTM_PWMLOAD_OFFSET)
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::FTM0),
|
||||
//initIOTimer(Timer::FTM2),
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel7}, {GPIO::PortE, GPIO::Pin9}),
|
||||
//initIOTimerChannel(io_timers, {Timer::FTM2, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}),
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
initIOTimerChannelMapping(io_timers, timer_io_channels);
|
||||
|
||||
const struct io_timers_t led_pwm_timers[MAX_LED_TIMERS] = {
|
||||
// To Do: Remove or add the right definitions.
|
||||
/*
|
||||
{
|
||||
.base = S32K1XX_FTM0_BASE,
|
||||
.clock_register = S32K1XX_PCC_FTM0,
|
||||
.clock_bit = PCC_CGC,
|
||||
//.vectorno = 0,
|
||||
},
|
||||
*/
|
||||
};
|
||||
|
||||
const struct timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = {
|
||||
// To Do: Remove or add the right definitions.
|
||||
/*
|
||||
{
|
||||
.gpio_out = LED_TIM3_CH1OUT, // RGB_R
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 2,
|
||||
},
|
||||
{
|
||||
.gpio_out = LED_TIM3_CH5OUT, // RGB_G
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 6,
|
||||
},
|
||||
{
|
||||
.gpio_out = LED_TIM3_CH4OUT, // RGB_B
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 5,
|
||||
},
|
||||
*/
|
||||
};
|
||||
|
||||
void ucans32k_timer_initialize(void)
|
||||
{
|
||||
/* Select external clock (set to SOSC in periphclocks.c) as source for FTM0, and FTM2 */
|
||||
|
||||
uint32_t regval = _REG(S32K1XX_FTM0_SC);
|
||||
regval &= ~(FTM_SC_CLKS_MASK);
|
||||
regval |= FTM_SC_CLKS_FTM;
|
||||
_REG(S32K1XX_FTM0_SC) = regval;
|
||||
|
||||
regval = _REG(S32K1XX_FTM2_SC);
|
||||
regval &= ~(FTM_SC_CLKS_MASK);
|
||||
regval |= FTM_SC_CLKS_FTM;
|
||||
_REG(S32K1XX_FTM2_SC) = regval;
|
||||
|
||||
/* Enabled System Clock Gating Control for FTM0, and FTM2 */
|
||||
|
||||
regval = _REG(S32K1XX_PCC_FTM0);
|
||||
regval |= PCC_CGC;
|
||||
_REG(S32K1XX_PCC_FTM0) = regval;
|
||||
|
||||
regval = _REG(S32K1XX_PCC_FTM2);
|
||||
regval |= PCC_CGC;
|
||||
_REG(S32K1XX_PCC_FTM2) = regval;
|
||||
}
|
||||
@@ -0,0 +1,36 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2019 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
|
||||
* 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 PX4 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
|
||||
#include "../../../s32k1xx/include/px4_arch/hw_description.h"
|
||||
@@ -0,0 +1,36 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2019 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
|
||||
* 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 PX4 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
|
||||
#include "../../../s32k1xx/include/px4_arch/io_timer_hw_description.h"
|
||||
@@ -69,7 +69,7 @@
|
||||
#include "hardware/s32k1xx_ftm.h"
|
||||
|
||||
#undef PPM_DEBUG
|
||||
//#define CONFIG_DEBUG_HRT
|
||||
|
||||
#ifdef CONFIG_DEBUG_HRT
|
||||
# define hrtinfo _info
|
||||
#else
|
||||
@@ -85,17 +85,44 @@
|
||||
|
||||
/* HRT configuration */
|
||||
|
||||
#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 HRT_TIMER_CLOCK BOARD_FTM_FREQ /* The input clock frequency to the FTM block */
|
||||
#define HRT_TIMER_BASE CAT(CAT(S32K1XX_FTM, HRT_TIMER), _BASE) /* The Base address of the FTM */
|
||||
|
||||
/* The FTM Interrupt vector */
|
||||
|
||||
#if defined(CONFIG_ARCH_CHIP_S32K14X)
|
||||
# if (HRT_TIMER_CHANNEL == 0) || (HRT_TIMER_CHANNEL == 1)
|
||||
# define HRT_TIMER_VECTOR CAT(CAT(S32K1XX_IRQ_FTM, HRT_TIMER), _CH0_1)
|
||||
# elif (HRT_TIMER_CHANNEL == 2) || (HRT_TIMER_CHANNEL == 3)
|
||||
# define HRT_TIMER_VECTOR CAT(CAT(S32K1XX_IRQ_FTM, HRT_TIMER), _CH2_3)
|
||||
# elif (HRT_TIMER_CHANNEL == 4) || (HRT_TIMER_CHANNEL == 5)
|
||||
# define HRT_TIMER_VECTOR CAT(CAT(S32K1XX_IRQ_FTM, HRT_TIMER), _CH4_5)
|
||||
# elif (HRT_TIMER_CHANNEL == 6) || (HRT_TIMER_CHANNEL == 7)
|
||||
# define HRT_TIMER_VECTOR CAT(CAT(S32K1XX_IRQ_FTM, HRT_TIMER), _CH6_7)
|
||||
# endif
|
||||
#elif defined(CONFIG_ARCH_CHIP_S32K11X)
|
||||
# define HRT_TIMER_VECTOR CAT(CAT(S32K1XX_IRQ_FTM, HRT_TIMER), _CH0_7)
|
||||
#endif
|
||||
|
||||
#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
|
||||
#elif HRT_TIMER == 2 && defined(CONFIG_KINETIS_TPM2)
|
||||
# error must not set CONFIG_STM32_TIM2=y and HRT_TIMER=2
|
||||
#if HRT_TIMER == 0 && defined(CONFIG_S32K1XX_FTM0)
|
||||
# error must not set CONFIG_S32K1XX_FTM0=y and HRT_TIMER=0
|
||||
#elif HRT_TIMER == 1 && defined(CONFIG_S32K1XX_FTM1)
|
||||
# error must not set CONFIG_S32K1XX_FTM1=y and HRT_TIMER=1
|
||||
#elif HRT_TIMER == 2 && defined(CONFIG_S32K1XX_FTM2)
|
||||
# error must not set CONFIG_S32K1XX_FTM1=y and HRT_TIMER=2
|
||||
#elif HRT_TIMER == 3 && defined(CONFIG_S32K1XX_FTM3)
|
||||
# error must not set CONFIG_S32K1XX_FTM1=y and HRT_TIMER=3
|
||||
#elif HRT_TIMER == 4 && defined(CONFIG_S32K1XX_FTM4)
|
||||
# error must not set CONFIG_S32K1XX_FTM1=y and HRT_TIMER=4
|
||||
#elif HRT_TIMER == 5 && defined(CONFIG_S32K1XX_FTM5)
|
||||
# error must not set CONFIG_S32K1XX_FTM1=y and HRT_TIMER=5
|
||||
#elif HRT_TIMER == 6 && defined(CONFIG_S32K1XX_FTM6)
|
||||
# error must not set CONFIG_S32K1XX_FTM1=y and HRT_TIMER=6
|
||||
#elif HRT_TIMER == 7 && defined(CONFIG_S32K1XX_FTM7)
|
||||
# error must not set CONFIG_S32K1XX_FTM1=y and HRT_TIMER=7
|
||||
#endif
|
||||
|
||||
/*
|
||||
@@ -149,12 +176,25 @@
|
||||
#define rC0V REG(S32K1XX_FTM_C0V_OFFSET)
|
||||
#define rC1SC REG(S32K1XX_FTM_C1SC_OFFSET)
|
||||
#define rC1V REG(S32K1XX_FTM_C1V_OFFSET)
|
||||
#define rC2SC REG(S32K1XX_FTM_C2SC_OFFSET)
|
||||
#define rC2V REG(S32K1XX_FTM_C2V_OFFSET)
|
||||
#define rC3SC REG(S32K1XX_FTM_C3SC_OFFSET)
|
||||
#define rC3V REG(S32K1XX_FTM_C3V_OFFSET)
|
||||
#define rC4SC REG(S32K1XX_FTM_C4SC_OFFSET)
|
||||
#define rC4V REG(S32K1XX_FTM_C4V_OFFSET)
|
||||
#define rC5SC REG(S32K1XX_FTM_C5SC_OFFSET)
|
||||
#define rC5V REG(S32K1XX_FTM_C5V_OFFSET)
|
||||
#define rC6SC REG(S32K1XX_FTM_C6SC_OFFSET)
|
||||
#define rC6V REG(S32K1XX_FTM_C6V_OFFSET)
|
||||
#define rC7SC REG(S32K1XX_FTM_C7SC_OFFSET)
|
||||
#define rC7V REG(S32K1XX_FTM_C7V_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
|
||||
*/
|
||||
@@ -163,8 +203,8 @@
|
||||
# define rCNSC_HRT CAT3(rC, HRT_TIMER_CHANNEL, SC) /* Channel Status and Control 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
|
||||
#if HRT_TIMER_CHANNEL > 7
|
||||
# error HRT_TIMER_CHANNEL must be a value between 0 and 7
|
||||
#endif
|
||||
|
||||
/*
|
||||
@@ -207,15 +247,15 @@ static void hrt_call_invoke(void);
|
||||
|
||||
/* Specific registers and bits used by PPM sub-functions */
|
||||
|
||||
#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(FTM_STATUS_CH, HRT_PPM_CHANNEL ,F) /* Capture and Compare Status Register used by PPM */
|
||||
#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(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 */
|
||||
|
||||
#if (HRT_PPM_CHANNEL != 0) && (HRT_PPM_CHANNEL != 1)
|
||||
# error HRT_PPM_CHANNEL must be a value between 0 and 1
|
||||
#if HRT_PPM_CHANNEL > 7
|
||||
# error HRT_PPM_CHANNEL must be a value between 0 and 7
|
||||
#endif
|
||||
|
||||
# if (HRT_PPM_CHANNEL == HRT_TIMER_CHANNEL)
|
||||
@@ -284,7 +324,7 @@ static void hrt_ppm_decode(uint32_t status);
|
||||
*/
|
||||
static void hrt_tim_init(void)
|
||||
{
|
||||
/* Clock is enabled in S32K1XX_pheriphclocks.c */
|
||||
/* FTM clock should be configured in s32k1xx_periphclocks.c */
|
||||
|
||||
/* claim our interrupt vector */
|
||||
|
||||
@@ -298,20 +338,27 @@ static void hrt_tim_init(void)
|
||||
rMOD = HRT_COUNTER_PERIOD - 1;
|
||||
|
||||
rCNSC_HRT = (FTM_CNSC_CHF | FTM_CNSC_CHIE | FTM_CNSC_MSA);
|
||||
|
||||
#ifdef HRT_PPM_CHANNEL
|
||||
rCNSC_PPM = (FTM_CNSC_CHF | CNSC_PPM);
|
||||
#endif
|
||||
|
||||
rCOMBINE = 0;
|
||||
rPOL = 0;
|
||||
rFILTER = 0;
|
||||
rQDCTRL = 0;
|
||||
rCONF = 0xC0; //FTM continues in DBG
|
||||
rCONF = 0x03 << FTM_CONF_BDMMODE_SHIFT; /* FTM continues when chip is in debug mode */
|
||||
|
||||
/* set an initial capture a little ways off */
|
||||
|
||||
#ifdef HRT_PPM_CHANNEL
|
||||
rCNV_PPM = 0;
|
||||
#endif
|
||||
|
||||
rCNV_HRT = 1000;
|
||||
|
||||
/* Use FIXEDCLK src and enable the timer
|
||||
* Set calculate prescaler for HRT_TIMER_FREQ */
|
||||
/* Use external clock source (selected in periphclocks.c) and enable the timer. Set prescaler for HRT_TIMER_FREQ */
|
||||
|
||||
rSC |= (FTM_SC_TOIE | FTM_SC_CLKS_EXTCLK |
|
||||
(LOG_2(HRT_TIMER_CLOCK / HRT_TIMER_FREQ) << FTM_SC_PS_SHIFT
|
||||
& FTM_SC_PS_MASK));
|
||||
@@ -484,6 +531,7 @@ hrt_tim_isr(int irq, void *context, void *arg)
|
||||
uint32_t status = rSTATUS;
|
||||
|
||||
/* ack the interrupts we just read */
|
||||
|
||||
rSTATUS = 0x00;
|
||||
|
||||
#ifdef HRT_PPM_CHANNEL
|
||||
@@ -623,7 +671,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
|
||||
}
|
||||
|
||||
|
||||
@@ -0,0 +1,242 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2019 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
|
||||
* 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 PX4 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <s32k1xx_pin.h>
|
||||
#include "hardware/s32k1xx_pcc.h"
|
||||
#include "hardware/s32k1xx_ftm.h"
|
||||
|
||||
#include <px4_platform_common/constexpr_util.h>
|
||||
|
||||
/*
|
||||
* Timers
|
||||
*/
|
||||
|
||||
namespace Timer
|
||||
{
|
||||
enum Timer {
|
||||
FTM0 = 0,
|
||||
FTM1,
|
||||
FTM2,
|
||||
FTM3,
|
||||
FTM4,
|
||||
FTM5,
|
||||
FTM6,
|
||||
FTM7,
|
||||
};
|
||||
enum Channel {
|
||||
Channel0 = 0,
|
||||
Channel1,
|
||||
Channel2,
|
||||
Channel3,
|
||||
Channel4,
|
||||
Channel5,
|
||||
Channel6,
|
||||
Channel7,
|
||||
};
|
||||
struct TimerChannel {
|
||||
Timer timer;
|
||||
Channel channel;
|
||||
};
|
||||
}
|
||||
|
||||
static inline constexpr uint32_t timerBaseRegister(Timer::Timer timer)
|
||||
{
|
||||
switch (timer) {
|
||||
case Timer::FTM0: return S32K1XX_FTM0_BASE;
|
||||
|
||||
case Timer::FTM1: return S32K1XX_FTM1_BASE;
|
||||
|
||||
case Timer::FTM2: return S32K1XX_FTM2_BASE;
|
||||
|
||||
case Timer::FTM3: return S32K1XX_FTM3_BASE;
|
||||
|
||||
case Timer::FTM4: return S32K1XX_FTM4_BASE;
|
||||
|
||||
case Timer::FTM5: return S32K1XX_FTM5_BASE;
|
||||
|
||||
case Timer::FTM6: return S32K1XX_FTM6_BASE;
|
||||
|
||||
case Timer::FTM7: return S32K1XX_FTM7_BASE;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
* GPIO
|
||||
*/
|
||||
|
||||
namespace GPIO
|
||||
{
|
||||
enum Port {
|
||||
PortInvalid = 0,
|
||||
PortA,
|
||||
PortB,
|
||||
PortC,
|
||||
PortD,
|
||||
PortE,
|
||||
};
|
||||
enum Pin {
|
||||
Pin0 = 0,
|
||||
Pin1,
|
||||
Pin2,
|
||||
Pin3,
|
||||
Pin4,
|
||||
Pin5,
|
||||
Pin6,
|
||||
Pin7,
|
||||
Pin8,
|
||||
Pin9,
|
||||
Pin10,
|
||||
Pin11,
|
||||
Pin12,
|
||||
Pin13,
|
||||
Pin14,
|
||||
Pin15,
|
||||
Pin16,
|
||||
Pin17,
|
||||
Pin18,
|
||||
Pin19,
|
||||
Pin20,
|
||||
Pin21,
|
||||
Pin22,
|
||||
Pin23,
|
||||
Pin24,
|
||||
Pin25,
|
||||
Pin26,
|
||||
Pin27,
|
||||
Pin28,
|
||||
Pin29,
|
||||
Pin30,
|
||||
Pin31,
|
||||
};
|
||||
struct GPIOPin {
|
||||
Port port;
|
||||
Pin pin;
|
||||
};
|
||||
}
|
||||
|
||||
static inline constexpr uint32_t getGPIOPort(GPIO::Port port)
|
||||
{
|
||||
switch (port) {
|
||||
case GPIO::PortA: return PIN_PORTA;
|
||||
|
||||
case GPIO::PortB: return PIN_PORTB;
|
||||
|
||||
case GPIO::PortC: return PIN_PORTC;
|
||||
|
||||
case GPIO::PortD: return PIN_PORTD;
|
||||
|
||||
case GPIO::PortE: return PIN_PORTE;
|
||||
|
||||
default: break;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static inline constexpr uint32_t getGPIOPin(GPIO::Pin pin)
|
||||
{
|
||||
switch (pin) {
|
||||
case GPIO::Pin0: return PIN0;
|
||||
|
||||
case GPIO::Pin1: return PIN1;
|
||||
|
||||
case GPIO::Pin2: return PIN2;
|
||||
|
||||
case GPIO::Pin3: return PIN3;
|
||||
|
||||
case GPIO::Pin4: return PIN4;
|
||||
|
||||
case GPIO::Pin5: return PIN5;
|
||||
|
||||
case GPIO::Pin6: return PIN6;
|
||||
|
||||
case GPIO::Pin7: return PIN7;
|
||||
|
||||
case GPIO::Pin8: return PIN8;
|
||||
|
||||
case GPIO::Pin9: return PIN9;
|
||||
|
||||
case GPIO::Pin10: return PIN10;
|
||||
|
||||
case GPIO::Pin11: return PIN11;
|
||||
|
||||
case GPIO::Pin12: return PIN12;
|
||||
|
||||
case GPIO::Pin13: return PIN13;
|
||||
|
||||
case GPIO::Pin14: return PIN14;
|
||||
|
||||
case GPIO::Pin15: return PIN15;
|
||||
|
||||
case GPIO::Pin16: return PIN16;
|
||||
|
||||
case GPIO::Pin17: return PIN17;
|
||||
|
||||
case GPIO::Pin18: return PIN18;
|
||||
|
||||
case GPIO::Pin19: return PIN19;
|
||||
|
||||
case GPIO::Pin20: return PIN20;
|
||||
|
||||
case GPIO::Pin21: return PIN21;
|
||||
|
||||
case GPIO::Pin22: return PIN22;
|
||||
|
||||
case GPIO::Pin23: return PIN23;
|
||||
|
||||
case GPIO::Pin24: return PIN24;
|
||||
|
||||
case GPIO::Pin25: return PIN25;
|
||||
|
||||
case GPIO::Pin26: return PIN26;
|
||||
|
||||
case GPIO::Pin27: return PIN27;
|
||||
|
||||
case GPIO::Pin28: return PIN28;
|
||||
|
||||
case GPIO::Pin29: return PIN29;
|
||||
|
||||
case GPIO::Pin30: return PIN30;
|
||||
|
||||
case GPIO::Pin31: return PIN31;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -45,17 +45,13 @@
|
||||
#pragma once
|
||||
__BEGIN_DECLS
|
||||
/* configuration limits */
|
||||
#ifdef BOARD_NUM_IO_TIMERS
|
||||
#define MAX_IO_TIMERS BOARD_NUM_IO_TIMERS
|
||||
#else
|
||||
#define MAX_IO_TIMERS 2
|
||||
#endif
|
||||
#define MAX_TIMER_IO_CHANNELS 16
|
||||
#define MAX_IO_TIMERS 1
|
||||
#define MAX_TIMER_IO_CHANNELS 1
|
||||
|
||||
#define MAX_LED_TIMERS 2
|
||||
#define MAX_TIMER_LED_CHANNELS 6
|
||||
#define MAX_LED_TIMERS 1
|
||||
#define MAX_TIMER_LED_CHANNELS 3
|
||||
|
||||
#define IO_TIMER_ALL_MODES_CHANNELS 0
|
||||
#define IO_TIMER_ALL_MODES_CHANNELS 0
|
||||
|
||||
typedef enum io_timer_channel_mode_t {
|
||||
IOTimerChanMode_NotUsed = 0,
|
||||
|
||||
@@ -0,0 +1,279 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2019 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
|
||||
* 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 PX4 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
|
||||
#include <px4_arch/io_timer.h>
|
||||
#include <px4_arch/hw_description.h>
|
||||
#include <px4_platform_common/constexpr_util.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform/io_timer_init.h>
|
||||
#include "hardware/s32k1xx_ftm.h"
|
||||
#include "hardware/s32k1xx_pcc.h"
|
||||
|
||||
/* TO DO: This mess only supports FTM 0-5, not 6-7 (only available on S32K148).
|
||||
* It's also hard to check if it is correct. *Should* work for S32K146, not confirmed for other S32K1XX MCUs. */
|
||||
|
||||
static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t io_timers_conf[MAX_IO_TIMERS],
|
||||
Timer::TimerChannel timer, GPIO::GPIOPin pin)
|
||||
{
|
||||
timer_io_channels_t ret{};
|
||||
|
||||
uint32_t gpio_af = 0;
|
||||
|
||||
switch (pin.port) {
|
||||
case GPIO::PortA:
|
||||
if (pin.pin == GPIO::Pin0 || pin.pin == GPIO::Pin1 || pin.pin == GPIO::Pin2 || pin.pin == GPIO::Pin3 ||
|
||||
pin.pin == GPIO::Pin10 || pin.pin == GPIO::Pin11 || pin.pin == GPIO::Pin12 || pin.pin == GPIO::Pin13 ||
|
||||
pin.pin == GPIO::Pin15 || pin.pin == GPIO::Pin16 || pin.pin == GPIO::Pin17 || pin.pin == GPIO::Pin25 ||
|
||||
pin.pin == GPIO::Pin26 || pin.pin == GPIO::Pin27 || pin.pin == GPIO::Pin28 || pin.pin == GPIO::Pin29 ||
|
||||
pin.pin == GPIO::Pin30 || pin.pin == GPIO::Pin31) {
|
||||
gpio_af = PIN_ALT2;
|
||||
|
||||
} else if (pin.pin == GPIO::Pin7) {
|
||||
gpio_af = PIN_ALT3;
|
||||
|
||||
} else if (pin.pin == GPIO::Pin6) {
|
||||
gpio_af = PIN_ALT4;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case GPIO::PortB:
|
||||
if (pin.pin == GPIO::Pin2 || pin.pin == GPIO::Pin3 || pin.pin == GPIO::Pin4 || pin.pin == GPIO::Pin5 ||
|
||||
pin.pin == GPIO::Pin8 || pin.pin == GPIO::Pin9 || pin.pin == GPIO::Pin10 || pin.pin == GPIO::Pin11 ||
|
||||
pin.pin == GPIO::Pin12 || pin.pin == GPIO::Pin13 || pin.pin == GPIO::Pin14 || pin.pin == GPIO::Pin15 ||
|
||||
pin.pin == GPIO::Pin16 || pin.pin == GPIO::Pin17 || pin.pin == GPIO::Pin18) {
|
||||
gpio_af = PIN_ALT2;
|
||||
|
||||
} else if (pin.pin == GPIO::Pin0 || pin.pin == GPIO::Pin1) {
|
||||
gpio_af = PIN_ALT6;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case GPIO::PortC:
|
||||
if (pin.pin == GPIO::Pin0 || pin.pin == GPIO::Pin1) {
|
||||
if (timer.timer == 0) {
|
||||
gpio_af = PIN_ALT2;
|
||||
|
||||
} else if (timer.timer == 1) {
|
||||
gpio_af = PIN_ALT6;
|
||||
}
|
||||
|
||||
} else if (pin.pin == GPIO::Pin11 || pin.pin == GPIO::Pin12 || pin.pin == GPIO::Pin13) {
|
||||
if (timer.timer == 3) {
|
||||
gpio_af = PIN_ALT2;
|
||||
|
||||
} else if (timer.timer == 2 || timer.timer == 4) {
|
||||
gpio_af = PIN_ALT3;
|
||||
}
|
||||
|
||||
} else if (pin.pin == GPIO::Pin2 || pin.pin == GPIO::Pin3 || pin.pin == GPIO::Pin4 || pin.pin == GPIO::Pin5 ||
|
||||
pin.pin == GPIO::Pin10 || pin.pin == GPIO::Pin14 || pin.pin == GPIO::Pin15 || pin.pin == GPIO::Pin27 ||
|
||||
pin.pin == GPIO::Pin28 || pin.pin == GPIO::Pin29 || pin.pin == GPIO::Pin30 || pin.pin == GPIO::Pin31) {
|
||||
gpio_af = PIN_ALT2;
|
||||
|
||||
} else if (pin.pin == GPIO::Pin6 || pin.pin == GPIO::Pin7 || pin.pin == GPIO::Pin8 || pin.pin == GPIO::Pin9) {
|
||||
gpio_af = PIN_ALT4;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case GPIO::PortD:
|
||||
if (pin.pin == GPIO::Pin0 || pin.pin == GPIO::Pin1) {
|
||||
if (timer.timer == 0) {
|
||||
gpio_af = PIN_ALT2;
|
||||
|
||||
} else if (timer.timer == 2) {
|
||||
gpio_af = PIN_ALT4;
|
||||
}
|
||||
|
||||
} else if (pin.pin == GPIO::Pin2 || pin.pin == GPIO::Pin3 || pin.pin == GPIO::Pin5 || pin.pin == GPIO::Pin10 ||
|
||||
pin.pin == GPIO::Pin11 || pin.pin == GPIO::Pin12 || pin.pin == GPIO::Pin13 || pin.pin == GPIO::Pin14 ||
|
||||
pin.pin == GPIO::Pin15 || pin.pin == GPIO::Pin16 || pin.pin == GPIO::Pin18) {
|
||||
gpio_af = PIN_ALT2;
|
||||
|
||||
} else if (pin.pin == GPIO::Pin8 || pin.pin == GPIO::Pin9) {
|
||||
gpio_af = PIN_ALT6;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case GPIO::PortE:
|
||||
if (pin.pin == GPIO::Pin7 || pin.pin == GPIO::Pin8 || pin.pin == GPIO::Pin9 || pin.pin == GPIO::Pin13 ||
|
||||
pin.pin == GPIO::Pin20 || pin.pin == GPIO::Pin21 || pin.pin == GPIO::Pin22 || pin.pin == GPIO::Pin23 ||
|
||||
pin.pin == GPIO::Pin24 || pin.pin == GPIO::Pin25) {
|
||||
gpio_af = PIN_ALT2;
|
||||
|
||||
} else if (pin.pin == GPIO::Pin2 || pin.pin == GPIO::Pin4 || pin.pin == GPIO::Pin5 || pin.pin == GPIO::Pin6 ||
|
||||
pin.pin == GPIO::Pin10 || pin.pin == GPIO::Pin11 || pin.pin == GPIO::Pin15 || pin.pin == GPIO::Pin16) {
|
||||
gpio_af = PIN_ALT4;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
default: break;
|
||||
}
|
||||
|
||||
uint32_t gpio_pin_port = getGPIOPort(pin.port) | getGPIOPin(pin.pin);
|
||||
ret.gpio_in = gpio_af | gpio_pin_port;
|
||||
ret.gpio_out = gpio_af | gpio_pin_port;
|
||||
|
||||
ret.timer_channel = (int)timer.channel + 1;
|
||||
|
||||
// find timer index
|
||||
ret.timer_index = 0xff;
|
||||
const uint32_t timer_base = timerBaseRegister(timer.timer);
|
||||
|
||||
for (int i = 0; i < MAX_IO_TIMERS; ++i) {
|
||||
if (io_timers_conf[i].base == timer_base) {
|
||||
ret.timer_index = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
constexpr_assert(ret.timer_index != 0xff, "Timer not found");
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static inline constexpr io_timers_t initIOTimer(Timer::Timer timer)
|
||||
{
|
||||
bool nuttx_config_timer_enabled = false;
|
||||
io_timers_t ret{};
|
||||
|
||||
switch (timer) {
|
||||
case Timer::FTM0:
|
||||
ret.base = S32K1XX_FTM0_BASE;
|
||||
ret.clock_register = S32K1XX_PCC_FTM0;
|
||||
ret.clock_bit = PCC_CGC;
|
||||
#if defined(CONFIG_ARCH_CHIP_S32K14X) /* S32K14X has a different vectornumber than S32K11X */
|
||||
ret.vectorno =
|
||||
S32K1XX_IRQ_FTM0_CH0_1; /* To Do: There are now multiple interrupts per FTM... Need to work around this somehow. */
|
||||
#elif defined(CONFIG_ARCH_CHIP_S32K11X)
|
||||
ret.vectorno = S32K1XX_IRQ_FTM0_CH0_7;
|
||||
#endif
|
||||
#ifdef CONFIG_S32K1XX_FTM0
|
||||
nuttx_config_timer_enabled = true;
|
||||
#endif
|
||||
break;
|
||||
|
||||
case Timer::FTM1:
|
||||
ret.base = S32K1XX_FTM1_BASE;
|
||||
ret.clock_register = S32K1XX_PCC_FTM1;
|
||||
ret.clock_bit = PCC_CGC;
|
||||
#if defined(CONFIG_ARCH_CHIP_S32K14X) /* S32K14X has a different vectornumber than S32K11X */
|
||||
ret.vectorno =
|
||||
S32K1XX_IRQ_FTM1_CH0_1; /* To Do: There are now multiple interrupts per FTM... Need to work around this somehow. */
|
||||
#elif defined(CONFIG_ARCH_CHIP_S32K11X)
|
||||
ret.vectorno = S32K1XX_IRQ_FTM1_CH0_7;
|
||||
#endif
|
||||
#ifdef CONFIG_S32K1XX_FTM1
|
||||
nuttx_config_timer_enabled = true;
|
||||
#endif
|
||||
break;
|
||||
|
||||
case Timer::FTM2:
|
||||
ret.base = S32K1XX_FTM2_BASE;
|
||||
ret.clock_register = S32K1XX_PCC_FTM2;
|
||||
ret.clock_bit = PCC_CGC;
|
||||
ret.vectorno =
|
||||
S32K1XX_IRQ_FTM2_CH0_1; /* To Do: There are now multiple interrupts per FTM... Need to work around this somehow. */
|
||||
#ifdef CONFIG_S32K1XX_FTM2
|
||||
nuttx_config_timer_enabled = true;
|
||||
#endif
|
||||
break;
|
||||
|
||||
case Timer::FTM3:
|
||||
ret.base = S32K1XX_FTM3_BASE;
|
||||
ret.clock_register = S32K1XX_PCC_FTM3;
|
||||
ret.clock_bit = PCC_CGC;
|
||||
ret.vectorno =
|
||||
S32K1XX_IRQ_FTM3_CH0_1; /* To Do: There are now multiple interrupts per FTM... Need to work around this somehow. */
|
||||
#ifdef CONFIG_S32K1XX_FTM3
|
||||
nuttx_config_timer_enabled = true;
|
||||
#endif
|
||||
break;
|
||||
|
||||
case Timer::FTM4:
|
||||
ret.base = S32K1XX_FTM4_BASE;
|
||||
ret.clock_register = S32K1XX_PCC_FTM4;
|
||||
ret.clock_bit = PCC_CGC;
|
||||
ret.vectorno =
|
||||
S32K1XX_IRQ_FTM4_CH0_1; /* To Do: There are now multiple interrupts per FTM... Need to work around this somehow. */
|
||||
#ifdef CONFIG_S32K1XX_FTM4
|
||||
nuttx_config_timer_enabled = true;
|
||||
#endif
|
||||
break;
|
||||
|
||||
case Timer::FTM5:
|
||||
ret.base = S32K1XX_FTM5_BASE;
|
||||
ret.clock_register = S32K1XX_PCC_FTM5;
|
||||
ret.clock_bit = PCC_CGC;
|
||||
ret.vectorno =
|
||||
S32K1XX_IRQ_FTM5_CH0_1; /* To Do: There are now multiple interrupts per FTM... Need to work around this somehow. */
|
||||
#ifdef CONFIG_S32K1XX_FTM5
|
||||
nuttx_config_timer_enabled = true;
|
||||
#endif
|
||||
break;
|
||||
|
||||
case Timer::FTM6:
|
||||
ret.base = S32K1XX_FTM6_BASE;
|
||||
ret.clock_register = S32K1XX_PCC_FTM6;
|
||||
ret.clock_bit = PCC_CGC;
|
||||
ret.vectorno =
|
||||
S32K1XX_IRQ_FTM6_CH0_1; /* To Do: There are now multiple interrupts per FTM... Need to work around this somehow. */
|
||||
#ifdef CONFIG_S32K1XX_FTM6
|
||||
nuttx_config_timer_enabled = true;
|
||||
#endif
|
||||
break;
|
||||
|
||||
case Timer::FTM7:
|
||||
ret.base = S32K1XX_FTM7_BASE;
|
||||
ret.clock_register = S32K1XX_PCC_FTM7;
|
||||
ret.clock_bit = PCC_CGC;
|
||||
ret.vectorno =
|
||||
S32K1XX_IRQ_FTM7_CH0_1; /* To Do: There are now multiple interrupts per FTM... Need to work around this somehow. */
|
||||
#ifdef CONFIG_S32K1XX_FTM7
|
||||
nuttx_config_timer_enabled = true;
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
||||
// This is not strictly required, but for consistency let's make sure NuttX timers are disabled
|
||||
constexpr_assert(!nuttx_config_timer_enabled, "IO Timer requires NuttX timer config to be disabled (S32K1XX_FTMx)");
|
||||
|
||||
return ret;
|
||||
}
|
||||
@@ -74,19 +74,19 @@
|
||||
#include <drivers/drv_input_capture.h>
|
||||
#include <px4_arch/io_timer.h>
|
||||
|
||||
#include <kinetis.h>
|
||||
#include "hardware/kinetis_sim.h"
|
||||
#include "hardware/kinetis_ftm.h"
|
||||
#include "s32k1xx_pin.h"
|
||||
#include "hardware/s32k1xx_pcc.h"
|
||||
#include "hardware/s32k1xx_ftm.h"
|
||||
|
||||
|
||||
#define _REG(_addr) (*(volatile uint32_t *)(_addr))
|
||||
#define _REG(_addr) (*(volatile uint32_t *)(_addr))
|
||||
#define _REG32(_base, _reg) (*(volatile uint32_t *)(_base + _reg))
|
||||
#define REG(_tmr, _reg) _REG32(io_timers[_tmr].base, _reg)
|
||||
|
||||
|
||||
/* Timer register accessors */
|
||||
|
||||
#define rFILTER(_tmr) REG(_tmr,KINETIS_FTM_FILTER_OFFSET)
|
||||
#define rFILTER(_tmr) REG(_tmr, S32K1XX_FTM_FILTER_OFFSET)
|
||||
|
||||
static input_capture_stats_t channel_stats[MAX_TIMER_IO_CHANNELS];
|
||||
|
||||
@@ -110,7 +110,7 @@ static void input_capture_chan_handler(void *context, const io_timers_t *timer,
|
||||
|
||||
channel_stats[chan_index].chan_in_edges_out++;
|
||||
channel_stats[chan_index].last_time = isrs_time - (isrs_rcnt - capture);
|
||||
uint32_t overflow = _REG32(timer, KINETIS_FTM_CSC_OFFSET(chan->timer_channel - 1)) & FTM_CSC_CHF;
|
||||
uint32_t overflow = _REG32(timer, S32K1XX_FTM_CNSC_OFFSET(chan->timer_channel - 1)) & FTM_CNSC_CHF;
|
||||
|
||||
if (overflow) {
|
||||
|
||||
@@ -320,20 +320,20 @@ int up_input_capture_get_trigger(unsigned channel, input_capture_edge *edge)
|
||||
rv = OK;
|
||||
|
||||
uint32_t timer = timer_io_channels[channel].timer_index;
|
||||
uint16_t rvalue = _REG32(timer, KINETIS_FTM_CSC_OFFSET(timer_io_channels[channel].timer_channel - 1));
|
||||
rvalue &= (FTM_CSC_MSB | FTM_CSC_MSA);
|
||||
uint16_t rvalue = _REG32(timer, S32K1XX_FTM_CNSC_OFFSET(timer_io_channels[channel].timer_channel - 1));
|
||||
rvalue &= (FTM_CNSC_MSB | FTM_CNSC_MSA);
|
||||
|
||||
switch (rvalue) {
|
||||
|
||||
case (FTM_CSC_MSA):
|
||||
case (FTM_CNSC_MSA):
|
||||
*edge = Rising;
|
||||
break;
|
||||
|
||||
case (FTM_CSC_MSB):
|
||||
case (FTM_CNSC_MSB):
|
||||
*edge = Falling;
|
||||
break;
|
||||
|
||||
case (FTM_CSC_MSB|FTM_CSC_MSA):
|
||||
case (FTM_CNSC_MSB | FTM_CNSC_MSA):
|
||||
*edge = Both;
|
||||
break;
|
||||
|
||||
@@ -364,15 +364,15 @@ int up_input_capture_set_trigger(unsigned channel, input_capture_edge edge)
|
||||
break;
|
||||
|
||||
case Rising:
|
||||
edge_bits = FTM_CSC_MSA;
|
||||
edge_bits = FTM_CNSC_MSA;
|
||||
break;
|
||||
|
||||
case Falling:
|
||||
edge_bits = FTM_CSC_MSB;
|
||||
edge_bits = FTM_CNSC_MSB;
|
||||
break;
|
||||
|
||||
case Both:
|
||||
edge_bits = (FTM_CSC_MSB | FTM_CSC_MSA);
|
||||
edge_bits = (FTM_CNSC_MSB | FTM_CNSC_MSA);
|
||||
break;
|
||||
|
||||
default:
|
||||
@@ -381,10 +381,10 @@ int up_input_capture_set_trigger(unsigned channel, input_capture_edge edge)
|
||||
|
||||
uint32_t timer = timer_io_channels[channel].timer_index;
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
uint32_t rvalue = _REG32(timer, KINETIS_FTM_CSC_OFFSET(timer_io_channels[channel].timer_channel - 1));
|
||||
rvalue &= (FTM_CSC_MSB | FTM_CSC_MSA);
|
||||
uint32_t rvalue = _REG32(timer, S32K1XX_FTM_CNSC_OFFSET(timer_io_channels[channel].timer_channel - 1));
|
||||
rvalue &= (FTM_CNSC_MSB | FTM_CNSC_MSA);
|
||||
rvalue |= edge_bits;
|
||||
_REG32(timer, KINETIS_FTM_CSC_OFFSET(timer_io_channels[channel].timer_channel - 1)) = rvalue;
|
||||
_REG32(timer, S32K1XX_FTM_CNSC_OFFSET(timer_io_channels[channel].timer_channel - 1)) = rvalue;
|
||||
px4_leave_critical_section(flags);
|
||||
rv = OK;
|
||||
}
|
||||
|
||||
@@ -34,7 +34,7 @@
|
||||
/**
|
||||
* @file io_timer.c
|
||||
*
|
||||
* Servo driver supporting PWM servos connected to Kinetis FTM timer blocks.
|
||||
* Servo driver supporting PWM servos connected to S32K1XX FlexTimer blocks.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
@@ -58,9 +58,9 @@
|
||||
|
||||
#include <px4_arch/io_timer.h>
|
||||
|
||||
#include <kinetis.h>
|
||||
#include "hardware/kinetis_sim.h"
|
||||
#include "hardware/kinetis_ftm.h"
|
||||
#include "s32k1xx_pin.h"
|
||||
#include "hardware/s32k1xx_pcc.h"
|
||||
#include "hardware/s32k1xx_ftm.h"
|
||||
|
||||
|
||||
static int io_timer_handler0(int irq, void *context, void *arg);
|
||||
@@ -72,12 +72,10 @@ static int io_timer_handler5(int irq, void *context, void *arg);
|
||||
static int io_timer_handler6(int irq, void *context, void *arg);
|
||||
static int io_timer_handler7(int irq, void *context, void *arg);
|
||||
|
||||
/* The FTM pre-scalers are limited to Divide by 2^n where n={1-7}
|
||||
* Therefore we use Y1 at 16 Mhz to drive FTM_CLKIN0 (PCT12)
|
||||
* and use this at a 16Mhz clock for FTM0, FTM2 and FTM3.
|
||||
/* The FTM pre-scalers are limited to divide by 2^n where n={1-7}.
|
||||
*
|
||||
* FTM0 will drive FMU_CH1-4, FTM3 will drive FMU_CH5,6, and
|
||||
* U_TRI. FTM2 will be used as input capture on U_ECH
|
||||
* All FTM blocks have their clock sources set to the system oscillator
|
||||
* which should generate an 8 MHz clock.
|
||||
*/
|
||||
#if !defined(BOARD_PWM_FREQ)
|
||||
#define BOARD_PWM_FREQ 1000000
|
||||
@@ -87,73 +85,73 @@ static int io_timer_handler7(int irq, void *context, void *arg);
|
||||
#define BOARD_ONESHOT_FREQ 8000000
|
||||
#endif
|
||||
|
||||
#define FTM_SRC_CLOCK_FREQ 16000000
|
||||
#define FTM_SRC_CLOCK_FREQ 8000000
|
||||
|
||||
#define MAX_CHANNELS_PER_TIMER 8
|
||||
|
||||
#define _REG(_addr) (*(volatile uint32_t *)(_addr))
|
||||
#define _REG(_addr) (*(volatile uint32_t *)(_addr))
|
||||
#define _REG32(_base, _reg) (*(volatile uint32_t *)(_base + _reg))
|
||||
#define REG(_tmr, _reg) _REG32(io_timers[_tmr].base, _reg)
|
||||
|
||||
|
||||
/* Timer register accessors */
|
||||
|
||||
#define rSC(_tmr) REG(_tmr,KINETIS_FTM_SC_OFFSET)
|
||||
#define rCNT(_tmr) REG(_tmr,KINETIS_FTM_CNT_OFFSET)
|
||||
#define rMOD(_tmr) REG(_tmr,KINETIS_FTM_MOD_OFFSET)
|
||||
#define rC0SC(_tmr) REG(_tmr,KINETIS_FTM_C0SC_OFFSET)
|
||||
#define rC0V(_tmr) REG(_tmr,KINETIS_FTM_C0V_OFFSET)
|
||||
#define rC1SC(_tmr) REG(_tmr,KINETIS_FTM_C1SC_OFFSET)
|
||||
#define rC1V(_tmr) REG(_tmr,KINETIS_FTM_C1V_OFFSET)
|
||||
#define rC2SC(_tmr) REG(_tmr,KINETIS_FTM_C2SC_OFFSET)
|
||||
#define rC2V(_tmr) REG(_tmr,KINETIS_FTM_C2V_OFFSET)
|
||||
#define rC3SC(_tmr) REG(_tmr,KINETIS_FTM_C3SC_OFFSET)
|
||||
#define rC3V(_tmr) REG(_tmr,KINETIS_FTM_C3V_OFFSET)
|
||||
#define rC4SC(_tmr) REG(_tmr,KINETIS_FTM_C4SC_OFFSET)
|
||||
#define rC4V(_tmr) REG(_tmr,KINETIS_FTM_C4V_OFFSET)
|
||||
#define rC5SC(_tmr) REG(_tmr,KINETIS_FTM_C5SC_OFFSET)
|
||||
#define rC5V(_tmr) REG(_tmr,KINETIS_FTM_C5V_OFFSET)
|
||||
#define rC6SC(_tmr) REG(_tmr,KINETIS_FTM_C6SC_OFFSET)
|
||||
#define rC6V(_tmr) REG(_tmr,KINETIS_FTM_C6V_OFFSET)
|
||||
#define rC7SC(_tmr) REG(_tmr,KINETIS_FTM_C7SC_OFFSET)
|
||||
#define rC7V(_tmr) REG(_tmr,KINETIS_FTM_C7V_OFFSET)
|
||||
#define rSC(_tmr) REG(_tmr, S32K1XX_FTM_SC_OFFSET)
|
||||
#define rCNT(_tmr) REG(_tmr, S32K1XX_FTM_CNT_OFFSET)
|
||||
#define rMOD(_tmr) REG(_tmr, S32K1XX_FTM_MOD_OFFSET)
|
||||
#define rC0SC(_tmr) REG(_tmr, S32K1XX_FTM_C0SC_OFFSET)
|
||||
#define rC0V(_tmr) REG(_tmr, S32K1XX_FTM_C0V_OFFSET)
|
||||
#define rC1SC(_tmr) REG(_tmr, S32K1XX_FTM_C1SC_OFFSET)
|
||||
#define rC1V(_tmr) REG(_tmr, S32K1XX_FTM_C1V_OFFSET)
|
||||
#define rC2SC(_tmr) REG(_tmr, S32K1XX_FTM_C2SC_OFFSET)
|
||||
#define rC2V(_tmr) REG(_tmr, S32K1XX_FTM_C2V_OFFSET)
|
||||
#define rC3SC(_tmr) REG(_tmr, S32K1XX_FTM_C3SC_OFFSET)
|
||||
#define rC3V(_tmr) REG(_tmr, S32K1XX_FTM_C3V_OFFSET)
|
||||
#define rC4SC(_tmr) REG(_tmr, S32K1XX_FTM_C4SC_OFFSET)
|
||||
#define rC4V(_tmr) REG(_tmr, S32K1XX_FTM_C4V_OFFSET)
|
||||
#define rC5SC(_tmr) REG(_tmr, S32K1XX_FTM_C5SC_OFFSET)
|
||||
#define rC5V(_tmr) REG(_tmr, S32K1XX_FTM_C5V_OFFSET)
|
||||
#define rC6SC(_tmr) REG(_tmr, S32K1XX_FTM_C6SC_OFFSET)
|
||||
#define rC6V(_tmr) REG(_tmr, S32K1XX_FTM_C6V_OFFSET)
|
||||
#define rC7SC(_tmr) REG(_tmr, S32K1XX_FTM_C7SC_OFFSET)
|
||||
#define rC7V(_tmr) REG(_tmr, S32K1XX_FTM_C7V_OFFSET)
|
||||
|
||||
#define rCNTIN(_tmr) REG(_tmr,KINETIS_FTM_CNTIN_OFFSET)
|
||||
#define rSTATUS(_tmr) REG(_tmr,KINETIS_FTM_STATUS_OFFSET)
|
||||
#define rMODE(_tmr) REG(_tmr,KINETIS_FTM_MODE_OFFSET)
|
||||
#define rSYNC(_tmr) REG(_tmr,KINETIS_FTM_SYNC_OFFSET)
|
||||
#define rOUTINIT(_tmr) REG(_tmr,KINETIS_FTM_OUTINIT_OFFSET)
|
||||
#define rOUTMASK(_tmr) REG(_tmr,KINETIS_FTM_OUTMASK_OFFSET)
|
||||
#define rCOMBINE(_tmr) REG(_tmr,KINETIS_FTM_COMBINE_OFFSET)
|
||||
#define rDEADTIME(_tmr) REG(_tmr,KINETIS_FTM_DEADTIME_OFFSET)
|
||||
#define rEXTTRIG(_tmr) REG(_tmr,KINETIS_FTM_EXTTRIG_OFFSET)
|
||||
#define rPOL(_tmr) REG(_tmr,KINETIS_FTM_POL_OFFSET)
|
||||
#define rFMS(_tmr) REG(_tmr,KINETIS_FTM_FMS_OFFSET)
|
||||
#define rFILTER(_tmr) REG(_tmr,KINETIS_FTM_FILTER_OFFSET)
|
||||
#define rFLTCTRL(_tmr) REG(_tmr,KINETIS_FTM_FLTCTRL_OFFSET)
|
||||
#define rQDCTRL(_tmr) REG(_tmr,KINETIS_FTM_QDCTRL_OFFSET)
|
||||
#define rCONF(_tmr) REG(_tmr,KINETIS_FTM_CONF_OFFSET)
|
||||
#define rFLTPOL(_tmr) REG(_tmr,KINETIS_FTM_FLTPOL_OFFSET)
|
||||
#define rSYNCONF(_tmr) REG(_tmr,KINETIS_FTM_SYNCONF_OFFSET)
|
||||
#define rINVCTRL(_tmr) REG(_tmr,KINETIS_FTM_INVCTRL_OFFSET)
|
||||
#define rSWOCTRL(_tmr) REG(_tmr,KINETIS_FTM_SWOCTRL_OFFSET)
|
||||
#define rPWMLOAD(_tmr) REG(_tmr,KINETIS_FTM_PWMLOAD_OFFSET)
|
||||
#define rCNTIN(_tmr) REG(_tmr, S32K1XX_FTM_CNTIN_OFFSET)
|
||||
#define rSTATUS(_tmr) REG(_tmr, S32K1XX_FTM_STATUS_OFFSET)
|
||||
#define rMODE(_tmr) REG(_tmr, S32K1XX_FTM_MODE_OFFSET)
|
||||
#define rSYNC(_tmr) REG(_tmr, S32K1XX_FTM_SYNC_OFFSET)
|
||||
#define rOUTINIT(_tmr) REG(_tmr, S32K1XX_FTM_OUTINIT_OFFSET)
|
||||
#define rOUTMASK(_tmr) REG(_tmr, S32K1XX_FTM_OUTMASK_OFFSET)
|
||||
#define rCOMBINE(_tmr) REG(_tmr, S32K1XX_FTM_COMBINE_OFFSET)
|
||||
#define rDEADTIME(_tmr) REG(_tmr, S32K1XX_FTM_DEADTIME_OFFSET)
|
||||
#define rEXTTRIG(_tmr) REG(_tmr, S32K1XX_FTM_EXTTRIG_OFFSET)
|
||||
#define rPOL(_tmr) REG(_tmr, S32K1XX_FTM_POL_OFFSET)
|
||||
#define rFMS(_tmr) REG(_tmr, S32K1XX_FTM_FMS_OFFSET)
|
||||
#define rFILTER(_tmr) REG(_tmr, S32K1XX_FTM_FILTER_OFFSET)
|
||||
#define rFLTCTRL(_tmr) REG(_tmr, S32K1XX_FTM_FLTCTRL_OFFSET)
|
||||
#define rQDCTRL(_tmr) REG(_tmr, S32K1XX_FTM_QDCTRL_OFFSET)
|
||||
#define rCONF(_tmr) REG(_tmr, S32K1XX_FTM_CONF_OFFSET)
|
||||
#define rFLTPOL(_tmr) REG(_tmr, S32K1XX_FTM_FLTPOL_OFFSET)
|
||||
#define rSYNCONF(_tmr) REG(_tmr, S32K1XX_FTM_SYNCONF_OFFSET)
|
||||
#define rINVCTRL(_tmr) REG(_tmr, S32K1XX_FTM_INVCTRL_OFFSET)
|
||||
#define rSWOCTRL(_tmr) REG(_tmr, S32K1XX_FTM_SWOCTRL_OFFSET)
|
||||
#define rPWMLOAD(_tmr) REG(_tmr, S32K1XX_FTM_PWMLOAD_OFFSET)
|
||||
|
||||
#define CnSC_RESET (FTM_CSC_CHF|FTM_CSC_CHIE|FTM_CSC_MSB|FTM_CSC_MSA|FTM_CSC_ELSB|FTM_CSC_ELSA|FTM_CSC_DMA)
|
||||
#define CnSC_CAPTURE_INIT (FTM_CSC_CHIE|FTM_CSC_ELSB|FTM_CSC_ELSA) // Both
|
||||
#define CnSC_RESET (FTM_CNSC_CHF | FTM_CNSC_CHIE | FTM_CNSC_MSB | FTM_CNSC_MSA | FTM_CNSC_ELSB | FTM_CNSC_ELSA | FTM_CNSC_DMA)
|
||||
#define CnSC_CAPTURE_INIT (FTM_CNSC_CHIE | FTM_CNSC_ELSB | FTM_CNSC_ELSA) // Both
|
||||
|
||||
#if defined(BOARD_PWM_DRIVE_ACTIVE_LOW)
|
||||
#define CnSC_PWMOUT_INIT (FTM_CSC_MSB|FTM_CSC_ELSA)
|
||||
#define CnSC_PWMOUT_INIT (FTM_CNSC_MSB | FTM_CNSC_ELSA)
|
||||
#else
|
||||
#define CnSC_PWMOUT_INIT (FTM_CSC_MSB|FTM_CSC_ELSB)
|
||||
#define CnSC_PWMOUT_INIT (FTM_CNSC_MSB | FTM_CNSC_ELSB)
|
||||
#endif
|
||||
|
||||
#define FTM_SYNC (FTM_SYNC_SWSYNC)
|
||||
|
||||
#define CnSC_PWMIN_INIT 0 // TBD
|
||||
|
||||
// NotUsed PWMOut PWMIn Capture OneShot Trigger
|
||||
io_timer_channel_allocation_t channel_allocations[IOTimerChanModeSize] = { UINT16_MAX, 0, 0, 0, 0, 0 };
|
||||
// NotUsed PWMOut PWMIn Capture OneShot Trigger
|
||||
io_timer_channel_allocation_t channel_allocations[IOTimerChanModeSize] = { UINT16_MAX, 0, 0, 0, 0, 0 };
|
||||
|
||||
typedef uint8_t io_timer_allocation_t; /* big enough to hold MAX_IO_TIMERS */
|
||||
|
||||
@@ -210,15 +208,15 @@ static int io_timer_handler(uint16_t timer_index)
|
||||
if (channel_handlers[chan_index].callback) {
|
||||
channel_handlers[chan_index].callback(channel_handlers[chan_index].context, tmr,
|
||||
chan_index, &timer_io_channels[chan_index],
|
||||
now, count, _REG32(tmr->base, KINETIS_FTM_CV_OFFSET(chan_index)));
|
||||
now, count, _REG32(tmr->base, S32K1XX_FTM_CNV_OFFSET(chan_index)));
|
||||
}
|
||||
}
|
||||
|
||||
/* Did it set again during call out ?*/
|
||||
/* Did it set again during call out? */
|
||||
|
||||
if (rSTATUS(timer_index) & chan) {
|
||||
|
||||
/* Error we has a second edge before we serviced the fist */
|
||||
/* Error - we had a second edge before we serviced the first */
|
||||
|
||||
io_timer_channel_stats[chan_index].overflows++;
|
||||
}
|
||||
@@ -562,7 +560,7 @@ void io_timer_trigger(void)
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
|
||||
for (actions = 0; actions < MAX_IO_TIMERS && action_cache[actions] != 0; actions++) {
|
||||
_REG32(action_cache[actions], KINETIS_FTM_SYNC_OFFSET) |= FTM_SYNC;
|
||||
_REG32(action_cache[actions], S32K1XX_FTM_SYNC_OFFSET) |= FTM_SYNC;
|
||||
}
|
||||
|
||||
px4_leave_critical_section(flags);
|
||||
@@ -588,11 +586,11 @@ int io_timer_init_timer(unsigned timer)
|
||||
|
||||
/* disable and configure the timer */
|
||||
|
||||
rSC(timer) = FTM_SC_CLKS_NONE;
|
||||
rCNT(timer) = 0;
|
||||
rSC(timer) = FTM_SC_CLKS_DIS;
|
||||
rCNT(timer) = 0;
|
||||
|
||||
rMODE(timer) = 0;
|
||||
rSYNCONF(timer) = (FTM_SYNCONF_SYNCMODE | FTM_SYNCONF_SWWRBUF | FTM_SYNCONF_SWRSTCNT);
|
||||
rMODE(timer) = 0;
|
||||
rSYNCONF(timer) = (FTM_SYNCONF_SYNCMODE | FTM_SYNCONF_SWWRBUF | FTM_SYNCONF_SWRSTCNT);
|
||||
|
||||
/* Set to run in debug mode */
|
||||
|
||||
@@ -641,6 +639,14 @@ int io_timer_init_timer(unsigned timer)
|
||||
if (handler) {
|
||||
irq_attach(io_timers[timer].vectorno, handler, NULL);
|
||||
up_enable_irq(io_timers[timer].vectorno);
|
||||
#if defined(CONFIG_ARCH_CHIP_S32K14X) /* Quick (and not very nice) workaround for the multiple interrupts per FTM on S32K14X */
|
||||
irq_attach(io_timers[timer].vectorno + 1, handler, NULL);
|
||||
up_enable_irq(io_timers[timer].vectorno + 1);
|
||||
irq_attach(io_timers[timer].vectorno + 2, handler, NULL);
|
||||
up_enable_irq(io_timers[timer].vectorno + 2);
|
||||
irq_attach(io_timers[timer].vectorno + 3, handler, NULL);
|
||||
up_enable_irq(io_timers[timer].vectorno + 3);
|
||||
#endif
|
||||
}
|
||||
|
||||
px4_leave_critical_section(flags);
|
||||
@@ -757,13 +763,13 @@ int io_timer_channel_init(unsigned channel, io_timer_channel_mode_t mode,
|
||||
|
||||
uint32_t chan = timer_io_channels[channel].timer_channel - 1;
|
||||
|
||||
uint16_t rvalue = REG(timer, KINETIS_FTM_CSC_OFFSET(chan));
|
||||
uint16_t rvalue = REG(timer, S32K1XX_FTM_CNSC_OFFSET(chan));
|
||||
rvalue &= ~clearbits;
|
||||
rvalue |= setbits;
|
||||
REG(timer, KINETIS_FTM_CSC_OFFSET(chan)) = rvalue;
|
||||
REG(timer, S32K1XX_FTM_CNSC_OFFSET(chan)) = rvalue;
|
||||
|
||||
//if (gpio){ TODO: NEEDED?
|
||||
REG(timer, KINETIS_FTM_CV_OFFSET(0)) = 0;
|
||||
REG(timer, S32K1XX_FTM_CNV_OFFSET(0)) = 0;
|
||||
|
||||
channel_handlers[channel].callback = channel_handler;
|
||||
channel_handlers[channel].context = context;
|
||||
@@ -800,7 +806,7 @@ int io_timer_set_enable(bool state, io_timer_channel_mode_t mode, io_timer_chann
|
||||
case IOTimerChanMode_PWMIn:
|
||||
case IOTimerChanMode_Capture:
|
||||
if (state) {
|
||||
bits |= FTM_CSC_CHIE;
|
||||
bits |= FTM_CNSC_CHIE;
|
||||
}
|
||||
|
||||
break;
|
||||
@@ -837,7 +843,7 @@ int io_timer_set_enable(bool state, io_timer_channel_mode_t mode, io_timer_chann
|
||||
uint32_t chan = timer_io_channels[chan_index].timer_channel - 1;
|
||||
uint32_t timer = channels_timer(chan_index);
|
||||
action_cache[timer].base = io_timers[timer].base;
|
||||
action_cache[timer].cnsc[action_cache[timer].index].cnsc_offset = io_timers[timer].base + KINETIS_FTM_CSC_OFFSET(chan);
|
||||
action_cache[timer].cnsc[action_cache[timer].index].cnsc_offset = io_timers[timer].base + S32K1XX_FTM_CNSC_OFFSET(chan);
|
||||
action_cache[timer].cnsc[action_cache[timer].index].cnsc_value = bits;
|
||||
|
||||
if ((state &&
|
||||
@@ -872,19 +878,19 @@ int io_timer_set_enable(bool state, io_timer_channel_mode_t mode, io_timer_chann
|
||||
/* Any On ?*/
|
||||
|
||||
/* Assume not */
|
||||
uint32_t regval = _REG32(action_cache[actions].base, KINETIS_FTM_SC_OFFSET);
|
||||
uint32_t regval = _REG32(action_cache[actions].base, S32K1XX_FTM_SC_OFFSET);
|
||||
regval &= ~(FTM_SC_CLKS_MASK);
|
||||
|
||||
if (any_on != 0) {
|
||||
|
||||
/* force an update to preload all registers */
|
||||
_REG32(action_cache[actions].base, KINETIS_FTM_SYNC_OFFSET) |= FTM_SYNC;
|
||||
_REG32(action_cache[actions].base, S32K1XX_FTM_SYNC_OFFSET) |= FTM_SYNC;
|
||||
|
||||
/* arm requires the timer be enabled */
|
||||
regval |= (FTM_SC_CLKS_EXTCLK);
|
||||
}
|
||||
|
||||
_REG32(action_cache[actions].base, KINETIS_FTM_SC_OFFSET) = regval;
|
||||
_REG32(action_cache[actions].base, S32K1XX_FTM_SC_OFFSET) = regval;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -919,7 +925,7 @@ int io_timer_set_ccr(unsigned channel, uint16_t value)
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
uint32_t save = rSC(timer);
|
||||
rSC(timer) = save & ~(FTM_SC_CLKS_MASK);
|
||||
REG(timer, KINETIS_FTM_CV_OFFSET(timer_io_channels[channel].timer_channel - 1)) = value;
|
||||
REG(timer, S32K1XX_FTM_CNV_OFFSET(timer_io_channels[channel].timer_channel - 1)) = value;
|
||||
rSC(timer) = save;
|
||||
px4_leave_critical_section(flags);
|
||||
}
|
||||
@@ -938,7 +944,7 @@ uint16_t io_channel_get_ccr(unsigned channel)
|
||||
if ((mode == IOTimerChanMode_PWMOut) ||
|
||||
(mode == IOTimerChanMode_OneShot) ||
|
||||
(mode == IOTimerChanMode_Trigger)) {
|
||||
value = REG(channels_timer(channel), KINETIS_FTM_CV_OFFSET(timer_io_channels[channel].timer_channel - 1));
|
||||
value = REG(channels_timer(channel), S32K1XX_FTM_CNV_OFFSET(timer_io_channels[channel].timer_channel - 1));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -34,10 +34,7 @@
|
||||
/*
|
||||
* @file drv_pwm_servo.c
|
||||
*
|
||||
* Servo driver supporting PWM servos connected to STM32 timer blocks.
|
||||
*
|
||||
* Works with any of the 'generic' or 'advanced' STM32 timers that
|
||||
* have output pins, does not require an interrupt.
|
||||
* Servo driver supporting PWM servos connected to S32K1XX FlexTimer blocks.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
@@ -60,7 +57,7 @@
|
||||
|
||||
#include <px4_arch/io_timer.h>
|
||||
|
||||
#include <kinetis.h>
|
||||
#include "s32k1xx_pin.h"
|
||||
|
||||
int up_pwm_servo_set(unsigned channel, servo_position_t value)
|
||||
{
|
||||
|
||||
Reference in New Issue
Block a user