nxphlite-v3:Board mods to support 1 Mhz FTM

This commit is contained in:
David Sidrane 2017-05-10 17:12:36 -10:00 committed by Daniel Agar
parent 24edfbcbca
commit 6e2885cc4e
4 changed files with 148 additions and 7 deletions

View File

@ -41,6 +41,9 @@
/************************************************************************************
* Included Files
************************************************************************************/
#undef HW_V3 /*- As shipped from NXP */
#define HW_V3_MOD_RC0 /* Modified board */
#undef HW_V4 /* Next Rev with modes */
#include <nuttx/config.h>
@ -443,13 +446,19 @@
* 2 UART4_TX PTC15 UART4_TX
* 3 UART4_RX PTC14 UART4_RX
* 4 UART4_CTS PTC13 UART4_CTS
* 5 UART4_RTS PTC12 UART4_RTS
* 5 UART4_RTS PTC12 UART4_RTS - V3 HW
* 5 UART4_RTS PTE27 UART4_RTS - V3.RC01 and V4
* -------- ------------ ------- ---------
*/
#define PIN_UART4_RX PIN_UART4_RX_1
#define PIN_UART4_TX PIN_UART4_TX_1
#define PIN_UART4_RTS PIN_UART4_RTS_1
#if defined (HW_V3)
# define PIN_UART4_RTS PIN_UART4_RTS_1
#endif
#if defined(HW_V3_MOD_RC0) || defined(HW_V4)
# define PIN_UART4_RTS PIN_UART4_RTS_2
#endif
#define PIN_UART4_CTS PIN_UART4_CTS_1
/*

View File

@ -42,6 +42,9 @@
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#undef HW_V3 /*- As shipped from NXP */
#define HW_V3_MOD_RC0 /* Modified board */
#undef HW_V4 /* Next Rev with modes */
#include <px4_config.h>
#include <nuttx/compiler.h>
@ -167,7 +170,12 @@ __BEGIN_DECLS
/* Safety Switch
* TBD
*/
#define GPIO_LED_SAFETY (GPIO_HIGHDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTE | PIN27)
#if defined(HW_V3)
# define GPIO_LED_SAFETY (GPIO_HIGHDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTE | PIN27)
#endif
#if defined(HW_V3_MOD_RC0) || defined(HW_V4)
# define GPIO_LED_SAFETY (GPIO_HIGHDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTC | PIN0)
#endif
#define GPIO_BTN_SAFETY (GPIO_PULLUP | PIN_PORTE | PIN28)
/* NXPHlite-v3 GPIOs ****************************************************************/
@ -620,6 +628,16 @@ void nxphlite_automount_initialize(void);
void nxphlite_automount_event(bool inserted);
#endif
/************************************************************************************
* Name: nxphlite_timer_initialize
*
* Description:
* Called to configure the FTM to provide 1 Mhz
*
************************************************************************************/
void nxphlite_timer_initialize(void);
#include "../common/board_common.h"
#endif /* __ASSEMBLY__ */

View File

@ -274,6 +274,7 @@ kinetis_boardinitialize(void)
kinetis_pinconfig(GPIO_LED_D10);
nxphlite_timer_initialize();
/* configure SPI interfaces */

View File

@ -43,10 +43,8 @@
#include <stdint.h>
#include <kinetis.h>
//#include <kinetis_ftm.h>
//#include <stm32.h> // TODO:Stubbed in for now
//#include <stm32_gpio.h>
//#include <stm32_tim.h>
#include "chip/kinetis_sim.h"
#include "chip/kinetis_ftm.h"
#include <drivers/drv_pwm_output.h>
#include <drivers/kinetis/drv_io_timer.h>
@ -58,3 +56,118 @@ __EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
};
#define _REG(_addr) (*(volatile uint32_t *)(_addr))
/* Timer register accessors */
#define REG(t, _reg) _REG(KINETIS_FTM##t##_BASE + (_reg))
#define rSC(t) REG(t,KINETIS_FTM_SC_OFFSET)
#define rCNT(t) REG(t,KINETIS_FTM_CNT_OFFSET)
#define rMOD(t) REG(t,KINETIS_FTM_MOD_OFFSET)
#define rC0SC(t) REG(t,KINETIS_FTM_C0SC_OFFSET)
#define rC0V(t) REG(t,KINETIS_FTM_C0V_OFFSET)
#define rC1SC(t) REG(t,KINETIS_FTM_C1SC_OFFSET)
#define rC1V(t) REG(t,KINETIS_FTM_C1V_OFFSET)
#define rC2SC(t) REG(t,KINETIS_FTM_C2SC_OFFSET)
#define rC2V(t) REG(t,KINETIS_FTM_C2V_OFFSET)
#define rC3SC(t) REG(t,KINETIS_FTM_C3SC_OFFSET)
#define rC3V(t) REG(t,KINETIS_FTM_C3V_OFFSET)
#define rC4SC(t) REG(t,KINETIS_FTM_C4SC_OFFSET)
#define rC4V(t) REG(t,KINETIS_FTM_C4V_OFFSET)
#define rC5SC(t) REG(t,KINETIS_FTM_C5SC_OFFSET)
#define rC5V(t) REG(t,KINETIS_FTM_C5V_OFFSET)
#define rC6SC(t) REG(t,KINETIS_FTM_C6SC_OFFSET)
#define rC6V(t) REG(t,KINETIS_FTM_C6V_OFFSET)
#define rC7SC(t) REG(t,KINETIS_FTM_C7SC_OFFSET)
#define rC7V(t) REG(t,KINETIS_FTM_C7V_OFFSET)
#define rCNTIN(t) REG(t,KINETIS_FTM_CNTIN_OFFSET)
#define rSTATUS(t) REG(t,KINETIS_FTM_STATUS_OFFSET)
#define rMODE(t) REG(t,KINETIS_FTM_MODE_OFFSET)
#define rSYNC(t) REG(t,KINETIS_FTM_SYNC_OFFSET)
#define rOUTINIT(t) REG(t,KINETIS_FTM_OUTINIT_OFFSET)
#define rOUTMASK(t) REG(t,KINETIS_FTM_OUTMASK_OFFSET)
#define rCOMBINE(t) REG(t,KINETIS_FTM_COMBINE_OFFSET)
#define rDEADTIME(t) REG(t,KINETIS_FTM_DEADTIME_OFFSET)
#define rEXTTRIG(t) REG(t,KINETIS_FTM_EXTTRIG_OFFSET)
#define rPOL(t) REG(t,KINETIS_FTM_POL_OFFSET)
#define rFMS(t) REG(t,KINETIS_FTM_FMS_OFFSET)
#define rFILTER(t) REG(t,KINETIS_FTM_FILTER_OFFSET)
#define rFLTCTRL(t) REG(t,KINETIS_FTM_FLTCTRL_OFFSET)
#define rQDCTRL(t) REG(t,KINETIS_FTM_QDCTRL_OFFSET)
#define rCONF(t) REG(t,KINETIS_FTM_CONF_OFFSET)
#define rFLTPOL(t) REG(t,KINETIS_FTM_FLTPOL_OFFSET)
#define rSYNCONF(t) REG(t,KINETIS_FTM_SYNCONF_OFFSET)
#define rINVCTRL(t) REG(t,KINETIS_FTM_INVCTRL_OFFSET)
#define rSWOCTRL(t) REG(t,KINETIS_FTM_SWOCTRL_OFFSET)
#define rPWMLOAD(t) REG(t,KINETIS_FTM_PWMLOAD_OFFSET)
#if !defined(BOARD_PWM_FREQ)
#define BOARD_PWM_FREQ 1000000
#endif
#if !defined(BOARD_ONESHOT_FREQ)
#define BOARD_ONESHOT_FREQ 8000000
#endif
__EXPORT void nxphlite_timer_initialize(void)
{
/* We will uses FTM2 (CH0) on PTA10 drive FTM_CLKIN0 (PCT12)*/
kinetis_pinconfig(PIN_FTM2_CH0_1);
kinetis_pinconfig(PIN_FTM_CLKIN0_3);
uint32_t regval = _REG(KINETIS_SIM_SOPT4);
regval &= ~(SIM_SOPT4_FTM0CLKSEL | SIM_SOPT4_FTM3CLKSEL);
_REG(KINETIS_SIM_SOPT4) = regval;
/* Enabled System Clock Gating Control for FTM 0 and 2*/
regval = _REG(KINETIS_SIM_SCGC6);
regval |= SIM_SCGC6_FTM0 | SIM_SCGC6_FTM2;
_REG(KINETIS_SIM_SCGC6) = regval;
/* Enabled System Clock Gating Control for FTM 2 and 3 */
regval = _REG(KINETIS_SIM_SCGC3);
regval |= SIM_SCGC3_FTM2 | SIM_SCGC3_FTM3;
_REG(KINETIS_SIM_SCGC3) = regval;
/* disable and configure the FTM2 as
* Bus Clock 56 Mhz
* PS 1
* MOD 28 or 7 for 1 Mhz and 3.5 Mhz
*/
rSC(2) = FTM_SC_CLKS_NONE | FTM_SC_PS_1;
rCNT(2) = 0;
/* Generate 2 times the Freq */
rMOD(2) = (BOARD_BUS_FREQ / (BOARD_PWM_FREQ * 2)) - 1;
/* toggle on every compare adds a divide by 2 */
rC0SC(2) = (FTM_CSC_CHF | FTM_CSC_MSA | FTM_CSC_ELSA);
/* Match on the wrap */
rC0V(2) = 0;
/* Set to run in debug mode */
rCONF(2) |= FTM_CONF_BDMMODE_MASK;
/* enable the timer */
rSC(2) |= FTM_SC_CLKS_SYSCLK;
}