diff --git a/boards/nxp/fmuk66-e/default.cmake b/boards/nxp/fmuk66-e/default.cmake new file mode 100644 index 0000000000..c57fe07bad --- /dev/null +++ b/boards/nxp/fmuk66-e/default.cmake @@ -0,0 +1,118 @@ + +px4_add_board( + PLATFORM nuttx + VENDOR nxp + MODEL fmuk66-e + LABEL default + TOOLCHAIN arm-none-eabi + ARCHITECTURE cortex-m4 + ROMFSROOT px4fmu_common + TESTING + UAVCAN_INTERFACES 2 + SERIAL_PORTS + GPS1:/dev/ttyS3 + TEL1:/dev/ttyS4 + TEL2:/dev/ttyS1 + DRIVERS + adc + barometer # all available barometer drivers + barometer/mpl3115a2 + batt_smbus + camera_capture + camera_trigger + differential_pressure # all available differential pressure drivers + distance_sensor # all available distance sensor drivers + gps + #heater + #imu # all available imu drivers + imu/bosch/bmi088 + imu/invensense/icm42688p + irlock + lights/blinkm + lights/rgbled + lights/rgbled_ncp5623c + lights/rgbled_pwm + magnetometer # all available magnetometer drivers + mkblctrl + #optical_flow # all available optical flow drivers + optical_flow/px4flow + #osd + pca9685 + power_monitor/ina226 + #protocol_splitter + pwm_out_sim + pwm_out + rc_input + roboclaw + safety_button + tap_esc + telemetry # all available telemetry drivers + #test_ppm # NOT Portable YET + tone_alarm + uavcan + MODULES + airspeed_selector + attitude_estimator_q + battery_status + camera_feedback + commander + dataman + ekf2 + events + fw_att_control + fw_pos_control_l1 + land_detector + landing_target_estimator + load_mon + local_position_estimator + logger + mavlink + mc_att_control + mc_hover_thrust_estimator + mc_pos_control + mc_rate_control + navigator + rc_update + rover_pos_control + sensors + sih + temperature_compensation + vmount + vtol_att_control + SYSTEMCMDS + bl_update + #dmesg + dumpfile + esc_calib + #hardfault_log # Needs bbsrm + i2cdetect + led_control + mixer + motor_ramp + motor_test + mtd + nshterm + param + perf + pwm + reboot + reflect + sd_bench + tests # tests and test runner + top + topic_listener + tune_control + usb_connected + ver + work_queue + EXAMPLES + fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control + hello + hwtest # Hardware test + #matlab_csv_serial + px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html + px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html + rover_steering_control # Rover example app + uuv_example_app + work_item + ) diff --git a/boards/nxp/fmuk66-e/firmware.prototype b/boards/nxp/fmuk66-e/firmware.prototype new file mode 100644 index 0000000000..0def290a26 --- /dev/null +++ b/boards/nxp/fmuk66-e/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 30, + "magic": "PX4FWv1", + "description": "Firmware for the NXPFMUK66E board", + "image": "", + "build_time": 0, + "summary": "NXPFMUK66E", + "version": "0.1", + "image_size": 0, + "image_maxsize": 2096112, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/nxp/fmuk66-e/init/rc.board_defaults b/boards/nxp/fmuk66-e/init/rc.board_defaults new file mode 100644 index 0000000000..531e7fde58 --- /dev/null +++ b/boards/nxp/fmuk66-e/init/rc.board_defaults @@ -0,0 +1,13 @@ + +# +# NXP fmuk66-e specific board defaults +#------------------------------------------------------------------------------ + + +if [ $AUTOCNF = yes ] +then + +fi + +rgbled_pwm start +safety_button start diff --git a/boards/nxp/fmuk66-e/init/rc.board_mavlink b/boards/nxp/fmuk66-e/init/rc.board_mavlink new file mode 100644 index 0000000000..fbe9af9a8b --- /dev/null +++ b/boards/nxp/fmuk66-e/init/rc.board_mavlink @@ -0,0 +1,7 @@ +#!/bin/sh +# +# NXP fmuk66-e specific board MAVLink startup script. +#------------------------------------------------------------------------------ + +# Start MAVLink on the USB port +mavlink start -d /dev/ttyACM0 diff --git a/boards/nxp/fmuk66-e/init/rc.board_sensors b/boards/nxp/fmuk66-e/init/rc.board_sensors new file mode 100644 index 0000000000..99f18aac6f --- /dev/null +++ b/boards/nxp/fmuk66-e/init/rc.board_sensors @@ -0,0 +1,19 @@ +#!/bin/sh +# +# NXP fmuk66-e specific board defaults +#------------------------------------------------------------------------------ + +adc start + +# Internal Mag I2C bus roll 180, yaw 90 +bmm150 -I -R 10 start + +# Onboard I2C baros +bmp280 -I start + +# Internal SPI (accel + mag) +bmi088 -A -R 4 -s start +bmi088 -G -R 4 -s start + +# Internal SPI bus ICM-42688 +icm42688p -R 12 -s start diff --git a/boards/nxp/fmuk66-e/nuttx-config/Kconfig b/boards/nxp/fmuk66-e/nuttx-config/Kconfig new file mode 100644 index 0000000000..df8b0f628d --- /dev/null +++ b/boards/nxp/fmuk66-e/nuttx-config/Kconfig @@ -0,0 +1,47 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# + +config FMUK66_SDHC_AUTOMOUNT + bool "SDHC automounter" + default n + depends on FS_AUTOMOUNTER && KINETIS_SDHC + +if FMUK66_SDHC_AUTOMOUNT + +config FMUK66_SDHC_AUTOMOUNT_FSTYPE + string "SDHC file system type" + default "vfat" + +config FMUK66_SDHC_AUTOMOUNT_BLKDEV + string "SDHC block device" + default "/dev/mmcsd0" + +config FMUK66_SDHC_AUTOMOUNT_MOUNTPOINT + string "SDHC mount point" + default "/fs/microsd" + +config FMUK66_SDHC_AUTOMOUNT_DDELAY + int "SDHC debounce delay (milliseconds)" + default 1000 + +config FMUK66_SDHC_AUTOMOUNT_UDELAY + int "SDHC unmount retry delay (milliseconds)" + default 2000 + +endif # FMUK66_SDHC_AUTOMOUNT + +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-6 as PROBE_1-6 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided GPIO FMU-CH1-6 as PROBE_1-6 to provide timing signals from selected drivers" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-6 to provide timing signals from selected drivers. diff --git a/boards/nxp/fmuk66-e/nuttx-config/include/board.h b/boards/nxp/fmuk66-e/nuttx-config/include/board.h new file mode 100644 index 0000000000..c3982226aa --- /dev/null +++ b/boards/nxp/fmuk66-e/nuttx-config/include/board.h @@ -0,0 +1,533 @@ +/************************************************************************************ + * configs/nxp/fmuk66-e/include/board.h + * + * Copyright (C) 2016-2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Jordan MacIntyre + * David Sidrane + * + * 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 __CONFIG_NXP_FMUK66_V3_INCLUDE_BOARD_H +#define __CONFIG_NXP_FMUK66_V3_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* + * The FMUK66-v3 is populated with a MK66FN2M0VLQ18 has 2 MiB of FLASH and + * 256 KiB of SRAM. + */ +/* Clocking *************************************************************************/ +/* The NXP FMUK66-E uses a 16MHz external powered Oscillator. The Kinetis MCU startup + * from an internal digitally-controlled oscillator (DCO). Nuttx will enable the main + * external oscillator EXTAL0. The external oscillator can range from + * 32.768 KHz up to 50 MHz. The default external source for the MCG oscillator inputs + * EXTAL. + * + * Y1 a High-frequency, Oscillator + */ +#define BOARD_EXTAL_LP 1 +#define BOARD_EXTAL_FREQ 16000000 /* 16MHz Oscillator Y1 */ +#define BOARD_XTAL32_FREQ 32768 /* 32KHz RTC Oscillator */ + +#define BOARD_OSC_CR OSC_CR_ERCLKEN /* Enable the OSCERCLK */ +#define BOARD_OSC_DIV OSC_DIV_ERPS_DIV1 /* No OSCERCLK Divide */ + +/* FLL Configuration. + * BOARD_EXTAL_FREQ / BOARD_FRDIV has to be in the range 31.25 kHz to 39.0625 + * 16 Mhz / MCG_C1_FRDIV_DIV512 = 31.25 kHz * 640 the default for MCG_C4 + * FLL is 20Mhz + */ +#define BOARD_FRDIV MCG_C1_FRDIV_DIV512 + +/* PLL Configuration. Either the external clock or crystal frequency is used to + * select the PRDIV value. Only reference clock frequencies are supported that will + * produce a KINETIS_MCG_PLL_REF_MIN=8MHz >= PLLIN <=KINETIS_MCG_PLL_REF_MAX=16Mhz + * reference clock to the PLL. + * + * PLL Input frequency: PLLIN = REFCLK / PRDIV = 16 MHz / 2 = 8Mhz MHz + * PLL Output frequency: PLLOUT = PLLIN * VDIV = 8 MHz * 42 = 336 MHz + * MCG Frequency: PLLOUT = 168 Mhz = 336 MHz / KINETIS_MCG_PLL_INTERNAL_DIVBY=2 + * + * PRDIV register value is the divider minus KINETIS_MCG_C5_PRDIV_BASE. + * VDIV register value is offset by KINETIS_MCG_C6_VDIV_BASE. + */ + +#define BOARD_PRDIV 2 /* PLL External Reference Divider */ +#define BOARD_VDIV 42 /* PLL VCO Divider (frequency multiplier) */ + +/* Define additional MCG_C2 Setting */ + +#define BOARD_MCG_C2_FCFTRIM 0 /* Do not enable FCFTRIM */ +#define BOARD_MCG_C2_LOCRE0 MCG_C2_LOCRE0 /* Enable reset on loss of clock */ + +#define BOARD_PLLIN_FREQ (BOARD_EXTAL_FREQ / BOARD_PRDIV) +#define BOARD_PLLOUT_FREQ (BOARD_PLLIN_FREQ * BOARD_VDIV) +#define BOARD_MCG_FREQ (BOARD_PLLOUT_FREQ/KINETIS_MCG_PLL_INTERNAL_DIVBY) + +/* SIM CLKDIV1 dividers */ + +#define BOARD_OUTDIV1 1 /* Core = MCG, 168 MHz */ +#define BOARD_OUTDIV2 3 /* Bus = MCG / 3, 56 MHz */ +#define BOARD_OUTDIV3 3 /* FlexBus = MCG / 3, 56 MHz */ +#define BOARD_OUTDIV4 6 /* Flash clock = MCG / 6, 28 MHz */ + +#define BOARD_CORECLK_FREQ (BOARD_MCG_FREQ / BOARD_OUTDIV1) +#define BOARD_BUS_FREQ (BOARD_MCG_FREQ / BOARD_OUTDIV2) +#define BOARD_FLEXBUS_FREQ (BOARD_MCG_FREQ / BOARD_OUTDIV3) +#define BOARD_FLASHCLK_FREQ (BOARD_MCG_FREQ / BOARD_OUTDIV4) + +/* Use BOARD_MCG_FREQ as the output SIM_SOPT2 MUX selected by + * SIM_SOPT2[PLLFLLSEL] + */ + +#define BOARD_SOPT2_PLLFLLSEL SIM_SOPT2_PLLFLLSEL_MCGPLLCLK +#define BOARD_SOPT2_FREQ BOARD_MCG_FREQ + +/* Divider output clock = Divider input clock × [ (USBFRAC+1) / (USBDIV+1) ] + * SIM_CLKDIV2_FREQ = BOARD_SOPT2_FREQ × [ (USBFRAC+1) / (USBDIV+1) ] + * 48Mhz = 168Mhz X [(1 + 1) / (6 + 1)] + * 48Mhz = 168Mhz / (6 + 1) * (1 + 1) + */ + +#define BOARD_SIM_CLKDIV2_USBFRAC 2 +#define BOARD_SIM_CLKDIV2_USBDIV 7 +#define BOARD_SIM_CLKDIV2_FREQ (BOARD_SOPT2_FREQ / BOARD_SIM_CLKDIV2_USBDIV * BOARD_SIM_CLKDIV2_USBFRAC) +#define BOARD_USB_CLKSRC SIM_SOPT2_USBSRC +#define BOARD_USB_FREQ BOARD_SIM_CLKDIV2_FREQ + + +/* Divider output clock = Divider input clock * ((PLLFLLFRAC+1)/(PLLFLLDIV+1)) + * SIM_CLKDIV3_FREQ = BOARD_SOPT2_FREQ × [ (PLLFLLFRAC+1) / (PLLFLLDIV+1)] + * 84 Mhz = 168 Mhz X [(0 + 1) / (1 + 1)] + * 84 Mhz = 168 Mhz / (1 + 1) * (0 + 1) + */ + +#define BOARD_SIM_CLKDIV3_PLLFLLFRAC 1 +#define BOARD_SIM_CLKDIV3_PLLFLLDIV 2 +#define BOARD_SIM_CLKDIV3_FREQ (BOARD_SOPT2_FREQ / BOARD_SIM_CLKDIV3_PLLFLLDIV * BOARD_SIM_CLKDIV3_PLLFLLFRAC) + +#define BOARD_LPUART0_CLKSRC SIM_SOPT2_LPUARTSRC_MCGCLK +#define BOARD_LPUART0_FREQ BOARD_SIM_CLKDIV3_FREQ + +#define BOARD_TPM_CLKSRC SIM_SOPT2_TPMSRC_OCSERCLK +#define BOARD_TPM_FREQ BOARD_EXTAL_FREQ + +/* SDHC clocking ********************************************************************/ + +/* SDCLK configurations corresponding to various modes of operation. Formula is: + * + * SDCLK frequency = (base clock) / (prescaler * divisor) + * + * The SDHC module is always configure configured so that the core clock is the base + * clock. Possible values for prescaler and divisor are: + * + * SDCLKFS: {2, 4, 8, 16, 32, 63, 128, 256} + * DVS: {1..16} + */ + +/* SDHC pull-up resistors **********************************************************/ + +/* There are external pull-ups on the NXP fmuk66-e + * So enable we do not them. + */ + +#undef BOARD_SDHC_ENABLE_PULLUPS + +/* Identification mode: Optimal 400KHz, Actual 168Mhz / (32 * 14) = 375 KHz */ + +#define BOARD_SDHC_IDMODE_PRESCALER SDHC_SYSCTL_SDCLKFS_DIV32 +#define BOARD_SDHC_IDMODE_DIVISOR SDHC_SYSCTL_DVS_DIV(14) + +/* MMC normal mode: Optimal 20MHz, Actual 168Mhz / (2 * 5) = 16.8 MHz */ + +#define BOARD_SDHC_MMCMODE_PRESCALER SDHC_SYSCTL_SDCLKFS_DIV2 +#define BOARD_SDHC_MMCMODE_DIVISOR SDHC_SYSCTL_DVS_DIV(5) + +/* SD normal mode (1-bit): Optimal 20MHz, Actual 168Mhz / (2 * 5) = 16.8 MHz */ + +#define BOARD_SDHC_SD1MODE_PRESCALER SDHC_SYSCTL_SDCLKFS_DIV2 +#define BOARD_SDHC_SD1MODE_DIVISOR SDHC_SYSCTL_DVS_DIV(5) + +/* SD normal mode (4-bit): Optimal 25MHz, Actual Actual 168Mhz / (2 * 4) = 21 MHz (with DMA) + * SD normal mode (4-bit): Optimal 20MHz, Actual 168Mhz / (2 * 5) = 16.8 MHz (no DMA) + */ + +#ifdef CONFIG_KINETIS_SDHC_DMA +# define BOARD_SDHC_SD4MODE_PRESCALER SDHC_SYSCTL_SDCLKFS_DIV2 +# define BOARD_SDHC_SD4MODE_DIVISOR SDHC_SYSCTL_DVS_DIV(4) +#else +# define BOARD_SDHC_SD4MODE_PRESCALER SDHC_SYSCTL_SDCLKFS_DIV2 +# define BOARD_SDHC_SD4MODE_DIVISOR SDHC_SYSCTL_DVS_DIV(5) +#endif + + +/* LED definitions ******************************************************************/ +/* The NXP FMUK66-E has a separate Red, Green and Blue LEDs driven by the K66 as + * follows: + * + * LED K66 + * ------ ------------------------------------------------------- + * RED FB_CS0_b/ UART2_CTS_b / ADC0_SE5b / SPI0_SCK / FTM3_CH1/ PTD1 + * GREEN FTM2_FLT0/ CMP0_IN3/ FB_AD6 / I2S0_RX_BCLK/ FTM3_CH5/ ADC1_SE5b/ PTC9 + * BLUE CMP0_IN2/ FB_AD7 / I2S0_MCLK/ FTM3_CH4/ ADC1_SE4b/ PTC8 + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any + * way. The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED_R 0 +#define BOARD_LED_G 1 +#define BOARD_LED_B 2 +#define BOARD_NLEDS 3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED_R_BIT (1 << BOARD_LED_R) +#define BOARD_LED_G_BIT (1 << BOARD_LED_G) +#define BOARD_LED_B_BIT (1 << BOARD_LED_B) + +/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board + * the NXP FMUK66-E. The following definitions describe how NuttX controls + * the LEDs: + * + * SYMBOL Meaning LED state + * RED GREEN BLUE + * ------------------- ---------------------------- ----------------- */ +#define LED_STARTED 1 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 2 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 0 /* Interrupts enabled OFF OFF ON */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON OFF */ +#define LED_INIRQ 0 /* In an interrupt (no change) */ +#define LED_SIGNAL 0 /* In a signal handler (no change) */ +#define LED_ASSERTION 0 /* An assertion failed (no change) */ +#define LED_PANIC 4 /* The system has crashed FLASH OFF OFF */ +#undef LED_IDLE /* K66 is in sleep mode (Not used) */ + +/* Alternative pin resolution *******************************************************/ +/* If there are alternative configurations for various pins in the + * kinetis_k66pinmux.h header file, those alternative pins will be labeled with a + * suffix like _1, _2, etc. The logic in this file must select the correct pin + * configuration for the board by defining a pin configuration (with no suffix) that + * maps to the correct alternative. + */ + +/* CAN + * Signal Conn Port Pin Name + * ------- -------- ----- ----- -------- + * CAN0TX P8-2(H) PTB18 97 CAN0_TX + * CAN0RX P8-3(L) PTB19 98 CAN0_RX + * CAN1TX P19-2(H) PTC16 123 CAN1_TX + * CAN1RX P19-3(L) PTC17 124 CAN1_RX + * + */ +#define PIN_CAN0_RX PIN_CAN0_RX_2 +#define PIN_CAN0_TX PIN_CAN0_TX_2 +#define PIN_CAN1_RX PIN_CAN1_RX_2 +#define PIN_CAN1_TX PIN_CAN1_TX_2 + +/* 12C + * + */ + +/* I2C0 + * + * This device can be pinned out to be either or + + * Bit Pin Device Signal Usage Conn + * ----- --- ------- --------------------------- ------ + * PTB2 83 I2C0_SCL U_ECH Ultrasonic P13-3 + * PTB3 84 I2C0_SDA U_TRI Ultrasonic P13-2 + * ----- --- ------- --------------------------- ------ + * + * Bit Pin Device Signal Usage Conn + * ----- --- ------- --------------------------- ------ + * PTE24 45 I2C0_SCL IIC_SCL NFC Connector, IIC P2-2 + * PTE25 46 I2C0_SDA IIC_SDA NFC Connector, IIC P2-3 + * ----- --- ------- --------------------------- ------ + */ + +#define PIN_I2C0_SCL PIN_I2C0_SCL_4 /* PTE24 IIC_SCL */ +#define PIN_I2C0_SDA PIN_I2C0_SDA_4 /* PTE25 IIC_SDA */ + +/* I2C1 + * + * Bit Pin Device Signal Usage Conn + * ----- --- ------- -------------- ------------- ------ + * PTC10 115 I2C1_SCL P_SCL, GPS_SCL Pressure, GPS P3-4 + * PTC11 116 I2C1_SDA P_SDA, GPS_SDA Pressure, GPS P3-5 + * ----- --- ------- -------------- ------------- ------ + */ + +#define PIN_I2C1_SCL PIN_I2C1_SCL_1 /* PTC10 GPS / Pressure Sensor*/ +#define PIN_I2C1_SDA PIN_I2C1_SDA_1 /* PTC11 GPS / Pressure Sensor */ + + +/* SPI + * + */ + +/* SPI0 FRAM */ + +#define PIN_SPI0_PCS0 PIN_SPI0_PCS2_1 /* PTC2 SPI_CS FRAM_CS */ +#define PIN_SPI0_SCK PIN_SPI0_SCK_2 /* PTC5 SPI_CLK FRAM_SCK */ +#define PIN_SPI0_OUT PIN_SPI0_SOUT_2 /* PTC6 SPI_OUT FRAM_MOSI */ +#define PIN_SPI0_SIN PIN_SPI0_SIN_2 /* PTC7 SPI_IN FRAM_MISO */ + +/* SPI1 + * FXOS8700CQ Accelerometer + * FXAS21002CQ Gyroscope + */ + +#define PIN_SPI1_PCS0 PIN_SPI1_PCS0_1 /* PTB10 A_CS */ +#define PIN_SPI1_PCS1 PIN_SPI1_PCS1_1 /* PTB9 GM_CS */ +#define PIN_SPI1_SCK PIN_SPI1_SCK_1 /* PTB11 A_SCLK */ +#define PIN_SPI1_OUT PIN_SPI1_SOUT_1 /* PTB16 A_MOSI */ +#define PIN_SPI1_SIN PIN_SPI1_SIN_1 /* PTB17 A_MISO */ + +/* SPI2 + * Bit Pin Device Signal Conn + * ----- --- ------- --------- ------ + * PTB20 99 SPI2_PCS0 SPI2_CS P18-5 + * PTB21 100 SPI2_SCK SPI2_CLK P18-2 + * PTB22 101 SPI2_SOUT SPI2_OUT P18-3 + * PTB23 102 SPI2_SIN SPI2_IN P18-4 + * + */ + +#define PIN_SPI2_PCS0 PIN_SPI2_PCS0_1 /* PTB20 SPI2_CS */ +#define PIN_SPI2_SCK PIN_SPI2_SCK_1 /* PTB21 SPI2_CLK */ +#define PIN_SPI2_OUT PIN_SPI2_SOUT_1 /* PTB22 SPI2_OUT */ +#define PIN_SPI2_SIN PIN_SPI2_SIN_1 /* PTB23 SPI2_IN */ + +/* UART + * + * NuttX Will use LPUART0 as the Console + * + * LPUAR0 + * P16 Pin Name K66 Name + * -------- ------------ ------ --------- + * 2 UART_TX PTD9 LPUART0_TX + * 3 UART_RX PTD8 LPUART0_RX + * -------- ----- ------ --------- + */ + +#define PIN_LPUART0_RX (PIN_LPUART0_RX_3 | GPIO_PULLUP) +#define PIN_LPUART0_TX PIN_LPUART0_TX_3 + +/* UART0 + * + * J7 Pin Name K66 Name + * -------- ------------ ------- --------- + * 2 PTA2 UART0_TX + * 3 PTA1 UART0_RX + * 4 PTB3 UART0_CTS + * 5 PTB2 UART0_RTS + * -------- ------------ ------- --------- + */ + +#define PIN_UART0_RX PIN_UART0_RX_1 +#define PIN_UART0_TX PIN_UART0_TX_1 +#define PIN_UART0_CTS PIN_UART0_CTS_3 +#define PIN_UART0_RTS PIN_UART0_RTS_3 + +/* UART1 + * + * Pin Name K66 Name + * ------------- -------------- ----- --------- + * P14-3,P15-2 FrSky_IN_RC_IN PTC3 UART1_RX + * P14-2 FrSky_OUT PTC4 UART1_TX + * ------------- ------------ ----- --------- + */ + +#define PIN_UART1_RX PIN_UART1_RX_1 +#define PIN_UART1_TX PIN_UART1_TX_1 + +/* UART2 + * No Alternative pins for UART2 + * + * P7 Pin Name K66 Name + * -------- ------------ ------- --------- + * 2 GPS_TX PTD3 UART2_TX + * 3 GPS_RX PTD2 UART2_RX + * -------- ------------ ------- --------- + */ + +/* UART4 + * + * P10 Pin Name K66 Name + * -------- ------------ ------- --------- + * 2 UART4_TX PTC15 UART4_TX + * 3 UART4_RX PTC14 UART4_RX + * 4 UART4_CTS PTC13 UART4_CTS + * 5 UART4_RTS PTE27 UART4_RTS + * -------- ------------ ------- --------- + */ + +#define PIN_UART4_RX PIN_UART4_RX_1 +#define PIN_UART4_TX PIN_UART4_TX_1 +#define PIN_UART4_RTS PIN_UART4_RTS_2 +#define PIN_UART4_CTS PIN_UART4_CTS_1 + +/* + * Ethernet TJA1100 OPEN Alliance BroadR-Reach PHY for Automotive Ethernet + * ----------------------------------------------------------------------- + * + * -------------- ----------------- ----------------------------------------- + * TJA1100 Board Signal(s) K66F Pin + * Pin Signal Function pinmux Name + * --- ---------- ----------------- ------------------------------------------ + * 1 MDC RMII0_MDC PTB1/RMII0_MDC PIN_RMII0_MDC + * 2 INT RMII0_INT_B, PTA27 PTA27 + * 3 nRST ENET_RST PTA28 PTA28 + * 4 VDDA(1V8) Cap to GND --- --- + * 5 XO 25Mhz OSC --- --- + * 6 XI 25Mhz OSC --- --- + * 7 VDDA(3V3) E_3V3 --- --- + * 8 LED (LED_ENABLE = 1) WAKE (LED_ENABLE = 0) --- + * 8 VBAT E_3V3 --- --- + * 10 nINH ENET_INH PTA8 PTA8 + * 11 VDDA(TX) E_3V3 --- --- + * 12 TRX_P ENET_P --- --- + * 13 TRX_M ENET_P --- --- + * 14 VDDD(3V3) E_3V3 --- --- + * 15 GND --- --- --- + * 16 VDDD(1V8) Cap to GND --- --- + * 17 RXER RMII0_RXER PTA5/RMII0_RXER PIN_RMII0_RXER + * 18 CRS_DIV RMII_CRSDV PTA14/RMII0_CRS_DV PIN_RMII0_CRS_DV + * 19 TXEN RMII0_TXEN PTA15/RMII0_TXEN PIN_RMII0_TXEN + * 20 GND --- --- --- + * 21 CONFIG1 ENET_CON1 THIS PIN IS A NO CONNECT + * 22 CONFIG0 ENET_CONFIG0 PTA24 PTA24 + * 23 RXD1 RMII0_RXD_1 PTA12/RMII0_RXD1 PIN_RMII0_RXD1 + * 24 RXD0 RMII0_RXD_0 PTA13/RMII0_RXD0 PIN_RMII0_RXD0 + * 25 REF_CLK E_REF_CLK PTE26/ENET_1588_CLKIN PIN_ENET_1588_CLKIN + * 26 GND2 --- --- --- + * 27 VDD(IO) E_3V3 --- --- + * 28 TXC --- --- --- + * 29 TXEN RMII_TXEN PTA15/RMII0_TXEN PIN_RMII0_TXEN + * 30 TXD3 + * 31 TXD2 + * 32 TXD1 RMII0_TXD_1 PTA17/RMII0_TXD1 PIN_RMII0_TXD1 + * 33 TXD0 RMII0_TXD_0 PTA16/RMII0_TXD0 PIN_RMII0_TXD0 + * 34 TXER + * 35 EN ENET_EN PTA29 PTA29 + * 36 MDIO RMII0_MDIO PTB0/RMII0_MDIO PIN_RMII0_MDIO + * --- ---------- ----------------- ------------------------------------ + * + */ + +#define PIN_RMII0_MDIO PIN_RMII0_MDIO_1 +#define PIN_RMII0_MDC PIN_RMII0_MDC_1 +#define PIN_ENET_PHY_RST (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTA | PIN28) +#define PIN_ENET_PHY_EN (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTA | PIN29) + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_LOWDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTC | PIN1) +# define PROBE_2 (GPIO_LOWDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTA | PIN6) +# define PROBE_3 (GPIO_LOWDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTD | PIN4) +# define PROBE_4 (GPIO_LOWDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTD | PIN5) +# define PROBE_5 (GPIO_LOWDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTE | PIN11) +# define PROBE_6 (GPIO_LOWDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTE | PIN12) + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { kinetis_pinconfig(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { kinetis_pinconfig(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { kinetis_pinconfig(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { kinetis_pinconfig(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { kinetis_pinconfig(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { kinetis_pinconfig(PROBE_6); } \ + } while(0) + +# define PROBE(n,s) do {kinetis_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/************************************************************************************ + * Name: kinetis_boardinitialize + * + * Description: + * All kinetis architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void kinetis_boardinitialize(void); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIG_NXP_FMUK66_V3_INCLUDE_BOARD_H */ diff --git a/boards/nxp/fmuk66-e/nuttx-config/nsh/defconfig b/boards/nxp/fmuk66-e/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..403f572c2b --- /dev/null +++ b/boards/nxp/fmuk66-e/nuttx-config/nsh/defconfig @@ -0,0 +1,224 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_OS_API is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="kinetis" +CONFIG_ARCH_CHIP_KINETIS=y +CONFIG_ARCH_CHIP_MK66FN2M0VMD18=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=15175 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_BULKIN_REQLEN=96 +CONFIG_CDCACM_PRODUCTID=0x001c +CONFIG_CDCACM_PRODUCTSTR="PX4 FMUK66 v3.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=8000 +CONFIG_CDCACM_VENDORID=0x1FC9 +CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_ETH0_PHY_TJA1100=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_AUTOMOUNTER=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_KINETIS_ADC0=y +CONFIG_KINETIS_ADC1=y +CONFIG_KINETIS_CRC=y +CONFIG_KINETIS_DMA=y +CONFIG_KINETIS_EMAC_RMIICLK1588CLKIN=y +CONFIG_KINETIS_ENET=y +CONFIG_KINETIS_FLEXCAN0=y +CONFIG_KINETIS_FLEXCAN1=y +CONFIG_KINETIS_GPIOIRQ=y +CONFIG_KINETIS_I2C0=y +CONFIG_KINETIS_I2C1=y +CONFIG_KINETIS_LPTMR0=y +CONFIG_KINETIS_LPUART0=y +CONFIG_KINETIS_MERGE_TTY=y +CONFIG_KINETIS_PDB=y +CONFIG_KINETIS_PIT=y +CONFIG_KINETIS_PORTAINTS=y +CONFIG_KINETIS_PORTBINTS=y +CONFIG_KINETIS_PORTCINTS=y +CONFIG_KINETIS_PORTDINTS=y +CONFIG_KINETIS_PORTEINTS=y +CONFIG_KINETIS_RTC=y +CONFIG_KINETIS_SDHC=y +CONFIG_KINETIS_SERIALBRK_BSDCOMPAT=y +CONFIG_KINETIS_SPI0=y +CONFIG_KINETIS_SPI1=y +CONFIG_KINETIS_SPI2=y +CONFIG_KINETIS_UART0=y +CONFIG_KINETIS_UART0_RXDMA=y +CONFIG_KINETIS_UART1=y +CONFIG_KINETIS_UART1_RXDMA=y +CONFIG_KINETIS_UART2=y +CONFIG_KINETIS_UART2_RXDMA=y +CONFIG_KINETIS_UART4=y +CONFIG_KINETIS_UART4_RXDMA=y +CONFIG_KINETIS_UARTFIFOS=y +CONFIG_KINETIS_UART_BREAKS=y +CONFIG_KINETIS_UART_EXTEDED_BREAK=y +CONFIG_KINETIS_UART_INVERT=y +CONFIG_KINETIS_USBDCD=y +CONFIG_KINETS_LPUART_LOWEST=y +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_STRERROR=y +CONFIG_LPUART0_BAUD=57600 +CONFIG_LPUART0_SERIAL_CONSOLE=y +CONFIG_MAX_WDOGPARMS=2 +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_MULTIBLOCK_DISABLE=y +CONFIG_MMCSD_SDIO=y +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_RAMTRON=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_THREAD=y +CONFIG_NETINIT_THREAD_PRIORITY=49 +CONFIG_NETUTILS_TELNETD=y +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_SOLINGER=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NFILE_DESCRIPTORS=15 +CONFIG_NFILE_STREAMS=8 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARCHROMFS=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_DISABLE_BASENAME=y +CONFIG_NSH_DISABLE_DIRNAME=y +CONFIG_NSH_DISABLE_EXPORT=y +CONFIG_NSH_DISABLE_HEXDUMP=y +CONFIG_NSH_DISABLE_LOSETUP=y +CONFIG_NSH_DISABLE_MB=y +CONFIG_NSH_DISABLE_MH=y +CONFIG_NSH_DISABLE_MKFIFO=y +CONFIG_NSH_DISABLE_MKRD=y +CONFIG_NSH_DISABLE_PUT=y +CONFIG_NSH_DISABLE_REBOOT=y +CONFIG_NSH_DISABLE_TELNETD=y +CONFIG_NSH_DISABLE_UNAME=y +CONFIG_NSH_DISABLE_WGET=y +CONFIG_NSH_DISABLE_XD=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_READLINE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_PIPES=y +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PREALLOC_WDOGS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAMTRON_WRITEWAIT=y +CONFIG_RAM_SIZE=262144 +CONFIG_RAM_START=0x1fff0000 +CONFIG_RAW_BINARY=y +CONFIG_RTC=y +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SEM_NNESTPRIO=8 +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_CUTERM=y +CONFIG_SYSTEM_CUTERM_DEFAULT_BAUD=57600 +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TIME_EXTENDED=y +CONFIG_UART0_IFLOWCONTROL=y +CONFIG_UART0_OFLOWCONTROL=y +CONFIG_UART1_RXBUFSIZE=600 +CONFIG_UART1_TXBUFSIZE=1100 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_IFLOWCONTROL=y +CONFIG_UART4_OFLOWCONTROL=y +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1100 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_DUALSPEED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_WATCHDOG=y diff --git a/boards/nxp/fmuk66-e/nuttx-config/scripts/script.ld b/boards/nxp/fmuk66-e/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..92c5732af1 --- /dev/null +++ b/boards/nxp/fmuk66-e/nuttx-config/scripts/script.ld @@ -0,0 +1,179 @@ +/**************************************************************************** + * configs/nxp_fmuk66-e/scripts/flash.ld + * + * Copyright (C) 2016, 2017 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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. + * + ****************************************************************************/ + +/* The MK66FN2M0VLQ18 has 2 MiB of FLASH beginning at address 0x0000:0000 and + * 256 KiB of SRAM beginning at address 0x1fff:0000- (SRAM_L) (64Kib) and + * 0x2000:0000 196 Kib (SRAM_U). + * + * NOTE: that the first part of the K66 FLASH region is reserved for + * interrupt vectflash and, following that, is a region from 0x0000:0400 + * to 0x0000:040f that is reserved for the FLASH control fields (FCF). + * + * NOTE: The on-chip RAM is split evenly among SRAM_L and SRAM_U. The RAM is + * also implemented such that the SRAM_L and SRAM_U ranges form a + * contiguous block in the memory map. + */ + +MEMORY +{ + vectflash (rx) : ORIGIN = 0x00006000, LENGTH = 1K + cfmprotect (rx) : ORIGIN = 0x00006400, LENGTH = 16 + progflash (rx) : ORIGIN = 0x00006410, LENGTH = 2M - ((6*4K) + 1K + 16) + datasram (rwx) : ORIGIN = 0x1fff0000, LENGTH = 256K +} + +OUTPUT_ARCH(arm) +ENTRY(__start) +EXTERN(__flashconfigbytes) +SECTIONS +{ + .vectors : { + _svectors = ABSOLUTE(.); + KEEP(*(.vectors)) + _evectors = ABSOLUTE(.); + } > vectflash + + .cfmprotect : { + KEEP(*(.cfmconfig)) + } > cfmprotect + + .text : { + _stext = ABSOLUTE(.); + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + /* + * This is a hack to make the newlib libm __errno() call + * use the NuttX get_errno_ptr() function. + */ + __errno = get_errno_ptr; + . = ALIGN(8); + FILL(0xff) + . += 8; + } > progflash =0xff + + /* + * Init functions (static constructors and the like) + */ + + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + . = ALIGN(8); + FILL(0xff) + . += 8; + } > progflash + + /* + * Construction data for parameters. + */ + __param ALIGN(4): { + __param_start = ABSOLUTE(.); + KEEP(*(__param*)) + __param_end = ABSOLUTE(.); + . = ALIGN(8); + FILL(0xff) + . += 8; + } > progflash + + .ARM.extab : { + *(.ARM.extab*) + . = ALIGN(8); + FILL(0xff) + . += 8; + } > progflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > progflash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + . = ALIGN(8); + FILL(0xff) + . += 8; + } > datasram AT > progflash + + .ramfunc ALIGN(4): { + _sramfuncs = ABSOLUTE(.); + *(.ramfunc .ramfunc.*) + _eramfuncs = ABSOLUTE(.); + . = ALIGN(8); + FILL(0xff) + . += 8; + } > datasram AT > progflash =0xff + + _framfuncs = LOADADDR(.ramfunc); + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > datasram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/nxp/fmuk66-e/nuttx-config/socketcan/defconfig b/boards/nxp/fmuk66-e/nuttx-config/socketcan/defconfig new file mode 100644 index 0000000000..c939320e86 --- /dev/null +++ b/boards/nxp/fmuk66-e/nuttx-config/socketcan/defconfig @@ -0,0 +1,221 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_OS_API is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="kinetis" +CONFIG_ARCH_CHIP_KINETIS=y +CONFIG_ARCH_CHIP_MK66FN2M0VMD18=y +CONFIG_ARCH_INTERRUPTSTACK=512 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=15175 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_C99_BOOL8=y +CONFIG_CDCACM=y +CONFIG_CDCACM_BULKIN_REQLEN=96 +CONFIG_CDCACM_PRODUCTID=0x001c +CONFIG_CDCACM_PRODUCTSTR="PX4 FMUK66 v3.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=8000 +CONFIG_CDCACM_VENDORID=0x1FC9 +CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS" +CONFIG_CLOCK_MONOTONIC=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_ETH0_PHY_TJA1100=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_AUTOMOUNTER=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_IOB_NBUFFERS=48 +CONFIG_IOB_NCHAINS=16 +CONFIG_KINETIS_ADC0=y +CONFIG_KINETIS_ADC1=y +CONFIG_KINETIS_CRC=y +CONFIG_KINETIS_DMA=y +CONFIG_KINETIS_EMAC_RMIICLK1588CLKIN=y +CONFIG_KINETIS_ENET=y +CONFIG_KINETIS_FLEXCAN0=y +CONFIG_KINETIS_FLEXCAN1=y +CONFIG_KINETIS_GPIOIRQ=y +CONFIG_KINETIS_I2C0=y +CONFIG_KINETIS_I2C1=y +CONFIG_KINETIS_LPTMR0=y +CONFIG_KINETIS_LPUART0=y +CONFIG_KINETIS_MERGE_TTY=y +CONFIG_KINETIS_PDB=y +CONFIG_KINETIS_PIT=y +CONFIG_KINETIS_PORTAINTS=y +CONFIG_KINETIS_PORTBINTS=y +CONFIG_KINETIS_PORTCINTS=y +CONFIG_KINETIS_PORTDINTS=y +CONFIG_KINETIS_PORTEINTS=y +CONFIG_KINETIS_RTC=y +CONFIG_KINETIS_SDHC=y +CONFIG_KINETIS_SERIALBRK_BSDCOMPAT=y +CONFIG_KINETIS_SPI0=y +CONFIG_KINETIS_SPI1=y +CONFIG_KINETIS_SPI2=y +CONFIG_KINETIS_UART0=y +CONFIG_KINETIS_UART0_RXDMA=y +CONFIG_KINETIS_UART1=y +CONFIG_KINETIS_UART1_RXDMA=y +CONFIG_KINETIS_UART2=y +CONFIG_KINETIS_UART2_RXDMA=y +CONFIG_KINETIS_UART4=y +CONFIG_KINETIS_UART4_RXDMA=y +CONFIG_KINETIS_UARTFIFOS=y +CONFIG_KINETIS_UART_BREAKS=y +CONFIG_KINETIS_UART_EXTEDED_BREAK=y +CONFIG_KINETIS_UART_INVERT=y +CONFIG_KINETIS_USBDCD=y +CONFIG_KINETS_LPUART_LOWEST=y +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_STRERROR=y +CONFIG_LPUART0_BAUD=57600 +CONFIG_LPUART0_SERIAL_CONSOLE=y +CONFIG_MAX_WDOGPARMS=2 +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_MULTIBLOCK_DISABLE=y +CONFIG_MMCSD_SDIO=y +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_RAMTRON=y +CONFIG_NETDEV_IFINDEX=y +CONFIG_NETDEV_LATEINIT=y +CONFIG_NETUTILS_TELNETD=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_CAN=y +CONFIG_NET_CAN_NOTIFIER=y +CONFIG_NET_CAN_RAW_TX_DEADLINE=y +CONFIG_NET_CAN_SOCK_OPTS=y +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_TCP=y +CONFIG_NET_TIMESTAMP=y +CONFIG_NET_UDP=y +CONFIG_NFILE_DESCRIPTORS=15 +CONFIG_NFILE_STREAMS=8 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARCHROMFS=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_DISABLE_BASENAME=y +CONFIG_NSH_DISABLE_DD=y +CONFIG_NSH_DISABLE_DIRNAME=y +CONFIG_NSH_DISABLE_EXPORT=y +CONFIG_NSH_DISABLE_HEXDUMP=y +CONFIG_NSH_DISABLE_LOSETUP=y +CONFIG_NSH_DISABLE_MB=y +CONFIG_NSH_DISABLE_MH=y +CONFIG_NSH_DISABLE_MKFIFO=y +CONFIG_NSH_DISABLE_MKRD=y +CONFIG_NSH_DISABLE_PUT=y +CONFIG_NSH_DISABLE_REBOOT=y +CONFIG_NSH_DISABLE_TELNETD=y +CONFIG_NSH_DISABLE_UNAME=y +CONFIG_NSH_DISABLE_WGET=y +CONFIG_NSH_DISABLE_XD=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_READLINE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_PIPES=y +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PREALLOC_WDOGS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAMTRON_WRITEWAIT=y +CONFIG_RAM_SIZE=262144 +CONFIG_RAM_START=0x1fff0000 +CONFIG_RAW_BINARY=y +CONFIG_RTC=y +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SEM_NNESTPRIO=8 +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_CUTERM=y +CONFIG_SYSTEM_CUTERM_DEFAULT_BAUD=57600 +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TIME_EXTENDED=y +CONFIG_UART0_IFLOWCONTROL=y +CONFIG_UART0_OFLOWCONTROL=y +CONFIG_UART1_RXBUFSIZE=600 +CONFIG_UART1_TXBUFSIZE=1100 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_IFLOWCONTROL=y +CONFIG_UART4_OFLOWCONTROL=y +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1100 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_DUALSPEED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_USERMAIN_STACKSIZE=2944 +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_WATCHDOG=y diff --git a/boards/nxp/fmuk66-e/socketcan.cmake b/boards/nxp/fmuk66-e/socketcan.cmake new file mode 100644 index 0000000000..8003adc163 --- /dev/null +++ b/boards/nxp/fmuk66-e/socketcan.cmake @@ -0,0 +1,118 @@ + +px4_add_board( + PLATFORM nuttx + VENDOR nxp + MODEL fmuk66-e + LABEL socketcan + TOOLCHAIN arm-none-eabi + ARCHITECTURE cortex-m4 + ROMFSROOT px4fmu_common + TESTING + UAVCAN_INTERFACES 2 + SERIAL_PORTS + GPS1:/dev/ttyS3 + TEL1:/dev/ttyS4 + TEL2:/dev/ttyS1 + DRIVERS + adc + barometer # all available barometer drivers + barometer/mpl3115a2 + batt_smbus + camera_capture + camera_trigger + differential_pressure # all available differential pressure drivers + distance_sensor # all available distance sensor drivers + gps + #heater + #imu # all available imu drivers + imu/bosch/bmi088 + imu/invensense/icm42688p + irlock + lights/blinkm + lights/rgbled + lights/rgbled_ncp5623c + lights/rgbled_pwm + magnetometer # all available magnetometer drivers + mkblctrl + #optical_flow # all available optical flow drivers + optical_flow/px4flow + #osd + pca9685 + power_monitor/ina226 + #protocol_splitter + pwm_out_sim + pwm_out + rc_input + roboclaw + safety_button + tap_esc + telemetry # all available telemetry drivers + #test_ppm # NOT Portable YET + tone_alarm + #uavcannode_v1 + MODULES + airspeed_selector + attitude_estimator_q + battery_status + camera_feedback + commander + dataman + ekf2 + events + fw_att_control + fw_pos_control_l1 + land_detector + landing_target_estimator + load_mon + local_position_estimator + logger + mavlink + mc_att_control + mc_hover_thrust_estimator + mc_pos_control + mc_rate_control + navigator + rc_update + rover_pos_control + sensors + sih + temperature_compensation + vmount + vtol_att_control + SYSTEMCMDS + bl_update + #dmesg + dumpfile + esc_calib + #hardfault_log # Needs bbsrm + i2cdetect + led_control + mixer + motor_ramp + motor_test + mtd + nshterm + param + perf + pwm + reboot + reflect + sd_bench + tests # tests and test runner + top + topic_listener + tune_control + usb_connected + ver + work_queue + EXAMPLES + fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control + hello + hwtest # Hardware test + #matlab_csv_serial + px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html + px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html + rover_steering_control # Rover example app + uuv_example_app + work_item + ) diff --git a/boards/nxp/fmuk66-e/src/CMakeLists.txt b/boards/nxp/fmuk66-e/src/CMakeLists.txt new file mode 100644 index 0000000000..2c563c1f83 --- /dev/null +++ b/boards/nxp/fmuk66-e/src/CMakeLists.txt @@ -0,0 +1,53 @@ +############################################################################ +# +# 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. +# +############################################################################ + +add_library(drivers_board + autoleds.c + automount.c + can.c + i2c.cpp + init.c + led.c + sdhc.c + spi.cpp + timer_config.cpp + usb.c +) + +target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + drivers__led # drv_led_start + px4_layer + ) diff --git a/boards/nxp/fmuk66-e/src/autoleds.c b/boards/nxp/fmuk66-e/src/autoleds.c new file mode 100644 index 0000000000..79efd95014 --- /dev/null +++ b/boards/nxp/fmuk66-e/src/autoleds.c @@ -0,0 +1,164 @@ +/**************************************************************************** + * + * Copyright (C) 2016-2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * + * 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. + * + ****************************************************************************/ +/* + * This module shall be used during board bring up of Nuttx. + * + * The NXP FMUK66-E has a separate Red, Green and Blue LEDs driven by the K66 + * as follows: + * + * LED K66 + * ------ ------------------------------------------------------- + * RED FB_CS0_b/ UART2_CTS_b / ADC0_SE5b / SPI0_SCK / FTM3_CH1/ PTD1 + * GREEN FTM2_FLT0/ CMP0_IN3/ FB_AD6 / I2S0_RX_BCLK/ FTM3_CH5/ ADC1_SE5b/ PTC9 + * BLUE CMP0_IN2/ FB_AD7 / I2S0_MCLK/ FTM3_CH4/ ADC1_SE4b/ PTC8 + * + * If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board + * the NXP fmuk66-e. The following definitions describe how NuttX controls + * the LEDs: + * + * SYMBOL Meaning LED state + * RED GREEN BLUE + * ------------------- ----------------------- ----------------- + * LED_STARTED NuttX has been started OFF OFF OFF + * LED_HEAPALLOCATE Heap has been allocated OFF OFF ON + * LED_IRQSENABLED Interrupts enabled OFF OFF ON + * LED_STACKCREATED Idle stack created OFF ON OFF + * LED_INIRQ In an interrupt (no change) + * LED_SIGNAL In a signal handler (no change) + * LED_ASSERTION An assertion failed (no change) + * LED_PANIC The system has crashed FLASH OFF OFF + * LED_IDLE K66 is in sleep mode (Optional, not used) + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "kinetis.h" +#include "board_config.h" + +#ifdef CONFIG_ARCH_LEDS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Summary of all possible settings */ + +#define LED_NOCHANGE 0 /* LED_IRQSENABLED, LED_INIRQ, LED_SIGNAL, LED_ASSERTION */ +#define LED_OFF_OFF_OFF 1 /* LED_STARTED */ +#define LED_OFF_OFF_ON 2 /* LED_HEAPALLOCATE */ +#define LED_OFF_ON_OFF 3 /* LED_STACKCREATED */ +#define LED_ON_OFF_OFF 4 /* LED_PANIC */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + * + * Description: + * Initialize the on-board LED + * + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + kinetis_pinconfig(GPIO_LED_R); + kinetis_pinconfig(GPIO_LED_G); + kinetis_pinconfig(GPIO_LED_B); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (led != LED_NOCHANGE) { + bool redoff = true; + bool greenoff = true; + bool blueoff = true; + + switch (led) { + default: + case LED_OFF_OFF_OFF: + break; + + case LED_OFF_OFF_ON: + blueoff = false; + break; + + case LED_OFF_ON_OFF: + greenoff = false; + break; + + case LED_ON_OFF_OFF: + redoff = false; + break; + } + + kinetis_gpiowrite(GPIO_LED_R, redoff); + kinetis_gpiowrite(GPIO_LED_G, greenoff); + kinetis_gpiowrite(GPIO_LED_B, blueoff); + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (led == LED_ON_OFF_OFF) { + kinetis_gpiowrite(GPIO_LED_R, true); + kinetis_gpiowrite(GPIO_LED_G, true); + kinetis_gpiowrite(GPIO_LED_B, true); + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/nxp/fmuk66-e/src/automount.c b/boards/nxp/fmuk66-e/src/automount.c new file mode 100644 index 0000000000..f69f7fc8f5 --- /dev/null +++ b/boards/nxp/fmuk66-e/src/automount.c @@ -0,0 +1,304 @@ +/************************************************************************************ + * + * Copyright (C) 2016-2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#if defined(CONFIG_FS_AUTOMOUNTER_DEBUG) && !defined(CONFIG_DEBUG_FS) +# define CONFIG_DEBUG_FS 1 +#endif + +#include +#include + +#include +#include +#include + +#include "board_config.h" +#ifdef HAVE_AUTOMOUNTER + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Types + ************************************************************************************/ +/* This structure represents the changeable state of the automounter */ + +struct fmuk66_automount_state_s { + volatile automount_handler_t handler; /* Upper half handler */ + FAR void *arg; /* Handler argument */ + bool enable; /* Fake interrupt enable */ + bool pending; /* Set if there an event while disabled */ +}; + +/* This structure represents the static configuration of an automounter */ + +struct fmuk66_automount_config_s { + /* This must be first thing in structure so that we can simply cast from struct + * automount_lower_s to struct fmuk66_automount_config_s + */ + + struct automount_lower_s lower; /* Publicly visible part */ + FAR struct fmuk66_automount_state_s *state; /* Changeable state */ +}; + +/************************************************************************************ + * Private Function Prototypes + ************************************************************************************/ + +static int fmuk66_attach(FAR const struct automount_lower_s *lower, automount_handler_t isr, FAR void *arg); +static void fmuk66_enable(FAR const struct automount_lower_s *lower, bool enable); +static bool fmuk66_inserted(FAR const struct automount_lower_s *lower); + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +static struct fmuk66_automount_state_s g_sdhc_state; +static const struct fmuk66_automount_config_s g_sdhc_config = { + .lower = + { + .fstype = CONFIG_FMUK66_SDHC_AUTOMOUNT_FSTYPE, + .blockdev = CONFIG_FMUK66_SDHC_AUTOMOUNT_BLKDEV, + .mountpoint = CONFIG_FMUK66_SDHC_AUTOMOUNT_MOUNTPOINT, + .ddelay = MSEC2TICK(CONFIG_FMUK66_SDHC_AUTOMOUNT_DDELAY), + .udelay = MSEC2TICK(CONFIG_FMUK66_SDHC_AUTOMOUNT_UDELAY), + .attach = fmuk66_attach, + .enable = fmuk66_enable, + .inserted = fmuk66_inserted + }, + .state = &g_sdhc_state +}; + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: fmuk66_attach + * + * Description: + * Attach a new SDHC event handler + * + * Input Parameters: + * lower - An instance of the auto-mounter lower half state structure + * isr - The new event handler to be attach + * arg - Client data to be provided when the event handler is invoked. + * + * Returned Value: + * Always returns OK + * + ************************************************************************************/ + +static int fmuk66_attach(FAR const struct automount_lower_s *lower, automount_handler_t isr, FAR void *arg) +{ + FAR const struct fmuk66_automount_config_s *config; + FAR struct fmuk66_automount_state_s *state; + + /* Recover references to our structure */ + + config = (FAR struct fmuk66_automount_config_s *)lower; + DEBUGASSERT(config != NULL && config->state != NULL); + + state = config->state; + + /* Save the new handler info (clearing the handler first to eliminate race + * conditions). + */ + + state->handler = NULL; + state->pending = false; + state->arg = arg; + state->handler = isr; + return OK; +} + +/************************************************************************************ + * Name: fmuk66_enable + * + * Description: + * Enable card insertion/removal event detection + * + * Input Parameters: + * lower - An instance of the auto-mounter lower half state structure + * enable - True: enable event detection; False: disable + * + * Returned Value: + * None + * + ************************************************************************************/ + +static void fmuk66_enable(FAR const struct automount_lower_s *lower, bool enable) +{ + FAR const struct fmuk66_automount_config_s *config; + FAR struct fmuk66_automount_state_s *state; + irqstate_t flags; + + /* Recover references to our structure */ + + config = (FAR struct fmuk66_automount_config_s *)lower; + DEBUGASSERT(config != NULL && config->state != NULL); + + state = config->state; + + /* Save the fake enable setting */ + + flags = enter_critical_section(); + state->enable = enable; + + /* Did an interrupt occur while interrupts were disabled? */ + + if (enable && state->pending) { + /* Yes.. perform the fake interrupt if the interrutp is attached */ + + if (state->handler) { + bool inserted = fmuk66_cardinserted(); + (void)state->handler(&config->lower, state->arg, inserted); + } + + state->pending = false; + } + + leave_critical_section(flags); +} + +/************************************************************************************ + * Name: fmuk66_inserted + * + * Description: + * Check if a card is inserted into the slot. + * + * Input Parameters: + * lower - An instance of the auto-mounter lower half state structure + * + * Returned Value: + * True if the card is inserted; False otherwise + * + ************************************************************************************/ + +static bool fmuk66_inserted(FAR const struct automount_lower_s *lower) +{ + return fmuk66_cardinserted(); +} + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: fmuk66_automount_initialize + * + * Description: + * Configure auto-mounters for each enable and so configured SDHC + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ************************************************************************************/ + +void fmuk66_automount_initialize(void) +{ + FAR void *handle; + + finfo("Initializing automounter(s)\n"); + + /* Initialize the SDHC0 auto-mounter */ + + handle = automount_initialize(&g_sdhc_config.lower); + + if (!handle) { + ferr("ERROR: Failed to initialize auto-mounter for SDHC0\n"); + } +} + +/************************************************************************************ + * Name: fmuk66_automount_event + * + * Description: + * The SDHC card detection logic has detected an insertion or removal event. It + * has already scheduled the MMC/SD block driver operations. Now we need to + * schedule the auto-mount event which will occur with a substantial delay to make + * sure that everything has settle down. + * + * Input Parameters: + * slotno - Identifies the SDHC0 slot: SDHC0_SLOTNO or SDHC1_SLOTNO. There is a + * terminology problem here: Each SDHC supports two slots, slot A and slot B. + * Only slot A is used. So this is not a really a slot, but an HSCMI peripheral + * number. + * inserted - True if the card is inserted in the slot. False otherwise. + * + * Returned Value: + * None + * + * Assumptions: + * Interrupts are disabled. + * + ************************************************************************************/ + +void fmuk66_automount_event(bool inserted) +{ + FAR const struct fmuk66_automount_config_s *config = &g_sdhc_config; + FAR struct fmuk66_automount_state_s *state = &g_sdhc_state; + + /* Is the auto-mounter interrupt attached? */ + + if (state->handler) { + /* Yes.. Have we been asked to hold off interrupts? */ + + if (!state->enable) { + /* Yes.. just remember the there is a pending interrupt. We will + * deliver the interrupt when interrupts are "re-enabled." + */ + + state->pending = true; + + } else { + /* No.. forward the event to the handler */ + + (void)state->handler(&config->lower, state->arg, inserted); + } + } +} + +#endif /* HAVE_AUTOMOUNTER */ diff --git a/boards/nxp/fmuk66-e/src/board_config.h b/boards/nxp/fmuk66-e/src/board_config.h new file mode 100644 index 0000000000..35d0b13bc5 --- /dev/null +++ b/boards/nxp/fmuk66-e/src/board_config.h @@ -0,0 +1,562 @@ +/**************************************************************************** + * + * Copyright (c) 2013-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 board_config.h + * + * NXP fmuk66-e internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ +#include +#include +#include + +__BEGIN_DECLS + +/* these headers are not C++ safe */ +#include +#include +#include + +__END_DECLS + +/* FMUK66 GPIOs ***********************************************************************************/ +/* LEDs */ +/* An RGB LED is connected through GPIO as shown below: + * TBD (no makring on schematic) + * LED K66 + * ------ ------------------------------------------------------- + * RED FB_CS0_b/ UART2_CTS_b / ADC0_SE5b / SPI0_SCK / FTM3_CH1/ PTD1 + * GREEN FTM2_FLT0/ CMP0_IN3/ FB_AD6 / I2S0_RX_BCLK/ FTM3_CH5/ ADC1_SE5b/ PTC9 + * BLUE CMP0_IN2/ FB_AD7 / I2S0_MCLK/ FTM3_CH4/ ADC1_SE4b/ PTC8 + */ + +#define GPIO_LED_R (GPIO_HIGHDRIVE | GPIO_OUTPUT_ONE | PIN_PORTD | PIN1) +#define GPIO_LED_G (GPIO_HIGHDRIVE | GPIO_OUTPUT_ONE | PIN_PORTC | PIN9) +#define GPIO_LED_B (GPIO_HIGHDRIVE | GPIO_OUTPUT_ONE | PIN_PORTC | PIN8) + + +#define GPIO_LED_1 (GPIO_HIGHDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTD | PIN13) +#define GPIO_LED_2 (GPIO_HIGHDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTD | PIN14) + +#define BOARD_HAS_CONTROL_STATUS_LEDS 1 // Use D9 and D10 +#define BOARD_OVERLOAD_LED LED_AMBER +#define BOARD_ARMED_STATE_LED LED_GREEN + +#define GPIO_NFC_IO (GPIO_HIGHDRIVE | GPIO_OUTPUT_ONE | PIN_PORTA | PIN26) +#define GPIO_SENSOR_P_EN (GPIO_HIGHDRIVE | GPIO_OUTPUT_ONE | PIN_PORTB | PIN8) + + +/* UART tty Mapping + * Device tty alt Connector Name + * ------- ---------- -------------- --------- ------------------------- + * LPUART0 /dev/tty0 /dev/console J16 DCD-Mini + * UART0 /dev/tty1 --- J7 SERIAL 2 / TELEMETRY 2 / IRDA + * UART1 /dev/tty2 --- J15 SERIAL4/FrSky, RC_IN + * UART2 /dev/tty3 --- J3 GPS connector + * UART4 /dev/tty4 --- J10 SERIAL 1 / TELEMETRY 1 + */ + +/* High-resolution timer */ +#define HRT_TIMER 1 /* TPM1 timer for the HRT */ +#define HRT_TIMER_CHANNEL 0 /* Use capture/compare channel 0 */ + +/* PPM IN + */ + +#define HRT_PPM_CHANNEL 1 /* Use TPM1 capture/compare channel 1 */ +#define GPIO_PPM_IN PIN_TPM1_CH1_1 /* PTC3 USART1 RX and PTA9 and PIN_TPM1_CH1 AKA FrSky_IN_RC_IN */ + + +/* + * + * NXP fmuk66-e has separate RC_IN + * + * GPIO PPM_IN on PTA9 PIN_TPM1_CH1 and PCT3 USART1 RX + * SPEKTRUM_RX (it's TX or RX in Bind) on PCT3 USART1 RX + * Inversion is possible the UART + * The FMU can drive GPIO PPM_IN as an output + */ + +/* Spektrum controls ******************************************************/ + +/* Power is a p-Channel FET */ + +#define GPIO_SPEKTRUM_P_EN (GPIO_HIGHDRIVE | GPIO_OUTPUT_ONE | PIN_PORTA | PIN7) + +/* For binding the Spektrum 3-pin interfaces is used with it TX (output) + * as an input Therefore we drive are UARTx_RX (normaly an input) as an + * output + */ + +#define GPIO_PPM_IN_AS_OUT (GPIO_HIGHDRIVE | GPIO_OUTPUT_ONE | PIN_PORTC | PIN3) + +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(PIN_UART1_RX) +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +/* RC input */ + +#define RC_SERIAL_PORT "/dev/ttyS2" /* UART1 */ +#define GPIO_RSSI_IN PIN_ADC1_SE13 + +/* Ethernet Control + * + * Uninitialized to Reset Disabled and Inhibited + * All pins driven low to not back feed when power is off + */ + +#define nGPIO_ETHERNET_P_EN (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTE | PIN10) +#define GPIO_ENET_RST (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTA | PIN28) +#define GPIO_ENET_EN (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTA | PIN29) +#define GPIO_ENET_INH (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTA | PIN8) + +/* CAN Control + * Control pin S allows two operating modes to be selected: + * high-speed mode (Low) or silent mode (high) + */ + +#define GPIO_CAN0_STB (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTC | PIN19) +#define GPIO_CAN1_STB (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTC | PIN18) + + +/* Safety Switch + * TBD + */ +#define GPIO_LED_SAFETY (GPIO_HIGHDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTC | PIN0) +#define GPIO_BTN_SAFETY (GPIO_PULLUP | PIN_PORTE | PIN28) + +/* NXP FMUK66-E GPIOs ****************************************************************/ + +/* SDHC + * + * A micro Secure Digital (SD) card slot is available on the board connected to + * the SD Host Controller (SDHC) signals of the MCU. This slot will accept micro + * format SD memory cards. The SD card detect pin (PTE6) is an open switch that + * shorts with VDD when card is inserted. + * + * ------------ ------------- -------- + * SD Card Slot Board Signal K66 Pin + * ------------ ------------- -------- + * DAT0 SDHC0_D0 PTE1 + * DAT1 SDHC0_D1 PTE0 + * DAT2 SDHC0_D2 PTE5 + * CD/DAT3 SDHC0_D3 PTE4 + * CMD SDHC0_CMD PTE3 + * CLK SDHC0_DCLK PTE2 + * SWITCH D_CARD_DETECT PTD10 + * CAED_P_EN PTD6 + * ------------ ------------- -------- + * + * There is no Write Protect pin available to the K66 + */ +#define nVDD_3V3_SD_CARD_EN (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTA | PIN25) + + +/* SE050 Secure Element */ +#define SE050_ENA (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTA | PIN24) +#define SE050_RST_N (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTD | PIN11) + +//#define GPIO_SD_CARDDETECT (GPIO_PULLUP | PIN_INT_BOTH | PIN_PORTD | PIN10) + +/* SPI device reset signals + * In Active state + */ + +/* Sensor interrupts */ + +#define GPIO_nSPI1_DRDY1_BMI1088_ACCEL_INT1 (GPIO_PULLUP | PIN_INT_FALLING | PIN_PORTD | PIN12) +#define GPIO_nSPI1_DRDY2_BMI1088_GYRO_INT2 (GPIO_PULLUP | PIN_INT_FALLING | PIN_PORTE | PIN7) +#define GPIO_nSPI1_DRDY3_ICM42688_INT1 (GPIO_PULLUP | PIN_INT_FALLING | PIN_PORTE | PIN9) + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 + * Firmware in the adc driver. ADC1 has 32 channels, with some a/b selection overlap + * in the AD4-AD7 range on the same ADC. + * + * Only ADC1 is used + * Bits 31:0 are ADC1 channels 31:0 + */ + +#define ADC1_CH(c) (((c) & 0x1f)) /* Define ADC number Channel number */ +#define ADC1_GPIO(n) PIN_ADC1_SE##n + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define ADC_USB_VBUS_VALID ADC1_CH(0) /* USB_VBUS_VALID 29 - ADC1_DP0 */ +#define ADC_BATTERY_VOLTAGE_CHANNEL ADC1_CH(10) /* BAT_VSENS 85 PTB4 ADC1_SE10 */ +#define ADC_BATTERY_CURRENT_CHANNEL ADC1_CH(11) /* BAT_ISENS 86 PTB5 ADC1_SE11 */ +#define ADC_5V_RAIL_SENSE ADC1_CH(12) /* 5V_VSENS 87 PTB6 ADC1_SE12 */ +#define ADC_RSSI_IN ADC1_CH(13) /* RSSI_IN 88 PTB7 ADC1_SE13 */ +#define ADC_AD1 ADC1_CH(16) /* AD1 35 - ADC1_SE16 */ +#define ADC_AD2 ADC1_CH(18) /* AD2 37 - ADC1_SE18 */ +#define ADC_AD3 ADC1_CH(23) /* AD3 39 - ADC1_SE23 */ + +/* Mask use to initialize the ADC driver */ + +#define ADC_CHANNELS ((1 << ADC_USB_VBUS_VALID) | \ + (1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL) | \ + (1 << ADC_5V_RAIL_SENSE) | \ + (1 << ADC_RSSI_IN) | \ + (1 << ADC_AD1) | \ + (1 << ADC_AD2) | \ + (1 << ADC_AD3)) + + +/* GPIO that require Configuration */ + +#define PX4_ADC_GPIO \ + /* PTB4 ADC1_SE10 */ ADC1_GPIO(10), \ + /* PTB5 ADC1_SE11 */ ADC1_GPIO(11), \ + /* PTB6 ADC1_SE12 */ ADC1_GPIO(12), \ + /* PTB7 ADC1_SE13 */ ADC1_GPIO(13) + + + +#define BOARD_BATTERY1_V_DIV (10.177939394f) +#define BOARD_BATTERY1_A_PER_V (15.391030303f) + + +/* User GPIOs + * + */ + +/* Timer I/O PWM and capture + * + * 14 PWM outputs are configured. + * 14 Timer inputs are configured. + * + * Pins: + * Defined in board.h + */ +// todo:Design this! + +#define DIRECT_PWM_OUTPUT_CHANNELS 10 +#define DIRECT_INPUT_TIMER_CHANNELS 10 + +/* Power supply control and monitoring GPIOs */ +// None + +#define GPIO_PERIPH_3V3_EN 0 + + +/* Tone alarm output PTA11 - TMP 2_CH1 is On +P12-4, -P12-5 + * It is driving a NPN + */ +#define TONE_ALARM_TIMER 2 /* timer */ +#define TONE_ALARM_CHANNEL 1 /* channel */ +#define GPIO_TONE_ALARM_IDLE (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTA | PIN11) +#define GPIO_TONE_ALARM (PIN_TPM2_CH1_1) + +/* USB + * + * VBUS detection is on 29 ADC_DPM0 and PTE8 + */ +#define GPIO_USB_VBUS_VALID /* PTE8 */ (GPIO_PULLUP | PIN_PORTE | PIN8) + +/* PWM input driver. Use FMU PWM14 pin + * todo:desing this + */ +#define PWMIN_TIMER 0 +#define PWMIN_TIMER_CHANNEL 2 +#define GPIO_PWM_IN GPIO_FTM0_CH2IN + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_ETH_EN(on_true) px4_arch_gpiowrite(nGPIO_ETHERNET_P_EN, !(on_true)) +// Do not have #define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, !(on_true)) +// Do not have #define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_HIPOWER_EN, !(on_true)) +#define VDD_3V3_SENSORS_EN(on_true) px4_arch_gpiowrite(GPIO_SENSOR_P_EN, (on_true)) +#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_SPEKTRUM_P_EN, !(on_true)) +#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_SPEKTRUM_P_EN) +// Do not have #define VDD_5V_RC_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_RC_EN, (on_true)) +// Do not have #define VDD_5V_WIFI_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_WIFI_EN, (on_true)) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(nVDD_3V3_SD_CARD_EN, !(on_true)) + +/* Map to control term used in RC lib */ +#define SPEKTRUM_POWER(on_true) VDD_3V3_SPEKTRUM_POWER_EN((on_true)) + + +/* + * By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ + +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_USB_VBUS_VALID)) +#define BOARD_ADC_BRICK_VALID (1) +#define BOARD_ADC_SERVO_VALID (1) +#define BOARD_ADC_PERIPH_5V_OC (0) +#define BOARD_ADC_HIPOWER_5V_OC (0) + +#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 + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + GPIO_LED_R, \ + GPIO_LED_G, \ + GPIO_LED_B, \ + GPIO_SENSOR_P_EN, \ + nVDD_3V3_SD_CARD_EN, \ + nGPIO_ETHERNET_P_EN, \ + GPIO_SPEKTRUM_P_EN, \ + SE050_ENA, \ + SE050_RST_N, \ + PX4_ADC_GPIO, \ + GPIO_USB_VBUS_VALID, \ + GPIO_ENET_RST, \ + GPIO_ENET_EN, \ + GPIO_ENET_INH, \ + PIN_CAN0_RX, \ + PIN_CAN0_TX, \ + PIN_CAN1_RX, \ + PIN_CAN1_TX, \ + GPIO_CAN0_STB, \ + GPIO_CAN1_STB, \ + GPIO_BTN_SAFETY, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_NFC_IO, \ + GPIO_LED_1, \ + GPIO_LED_2 \ + } + +/* Automounter */ + +#define HAVE_MMCSD 1 +#define HAVE_AUTOMOUNTER 1 +#if !defined(CONFIG_FS_AUTOMOUNTER) || !defined(HAVE_MMCSD) +# undef HAVE_AUTOMOUNTER +# undef CONFIG_FMUK66_SDHC_AUTOMOUNT +#endif + +#ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT +# undef HAVE_AUTOMOUNTER +#endif + +/* Automounter defaults */ + +#ifdef HAVE_AUTOMOUNTER + +# ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT_FSTYPE +# define CONFIG_FMUK66_SDHC_AUTOMOUNT_FSTYPE "vfat" +# endif + +# ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT_BLKDEV +# define CONFIG_FMUK66_SDHC_AUTOMOUNT_BLKDEV "/dev/mmcds0" +# endif + +# ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT_MOUNTPOINT +# define CONFIG_FMUK66_SDHC_AUTOMOUNT_MOUNTPOINT "/mnt/sdcard" +# endif + +# ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT_DDELAY +# define CONFIG_FMUK66_SDHC_AUTOMOUNT_DDELAY 1000 +# endif + +# ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT_UDELAY +# define CONFIG_FMUK66_SDHC_AUTOMOUNT_UDELAY 2000 +# endif +#endif /* HAVE_AUTOMOUNTER */ + +#define BOARD_HAS_NOISY_FXOS8700_MAG 1 // Disable internal MAG + +#define BOARD_NUM_IO_TIMERS 3 + +/************************************************************************************ + * Public data + ************************************************************************************/ + +__BEGIN_DECLS + +#ifndef __ASSEMBLY__ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: fmuk66_spidev_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the NXP FMUK66-E board. + * + ************************************************************************************/ + +void fmuk66_spidev_initialize(void); + +/************************************************************************************ + * Name: fmuk66_spi_bus_initialize + * + * Description: + * Called to configure SPI Buses. + * + ************************************************************************************/ + +int fmuk66_spi_bus_initialize(void); + +/**************************************************************************************************** + * Name: board_spi_reset board_peripheral_reset + * + * Description: + * Called to reset SPI and the perferal bus + * + ****************************************************************************************************/ +void board_peripheral_reset(int ms); + +/************************************************************************************ + * Name: fmuk66_bringup + * + * Description: + * Bring up board features + * + ************************************************************************************/ + +#if defined(CONFIG_LIB_BOARDCTL) || defined(CONFIG_BOARD_INITIALIZE) +int fmuk66_bringup(void); +#endif + +/**************************************************************************** + * Name: fmuk66_sdhc_initialize + * + * Description: + * Inititialize the SDHC SD card slot + * + ****************************************************************************/ + +int fmuk66_sdhc_initialize(void); + +/************************************************************************************ + * Name: fmuk66_cardinserted + * + * Description: + * Check if a card is inserted into the SDHC slot + * + ************************************************************************************/ + +#ifdef HAVE_AUTOMOUNTER +bool fmuk66_cardinserted(void); +#else +# define fmuk66_cardinserted() (false) +#endif + +/************************************************************************************ + * Name: fmuk66_writeprotected + * + * Description: + * Check if the card in the MMC/SD slot is write protected + * + ************************************************************************************/ + +#ifdef HAVE_AUTOMOUNTER +bool fmuk66_writeprotected(void); +#else +# define fmuk66_writeprotected() (false) +#endif + +/************************************************************************************ + * Name: fmuk66_automount_initialize + * + * Description: + * Configure auto-mounter for the configured SDHC slot + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + ************************************************************************************/ + +#ifdef HAVE_AUTOMOUNTER +void fmuk66_automount_initialize(void); +#endif + +/************************************************************************************ + * Name: fmuk66_automount_event + * + * Description: + * The SDHC card detection logic has detected an insertion or removal event. It + * has already scheduled the MMC/SD block driver operations. Now we need to + * schedule the auto-mount event which will occur with a substantial delay to make + * sure that everything has settle down. + * + * Input Parameters: + * inserted - True if the card is inserted in the slot. False otherwise. + * + * Returned Value: + * None + * + * Assumptions: + * Interrupts are disabled. + * + ************************************************************************************/ + +#ifdef HAVE_AUTOMOUNTER +void fmuk66_automount_event(bool inserted); +#endif + +/************************************************************************************ + * Name: fmuk66_timer_initialize + * + * Description: + * Called to configure the FTM to provide 1 Mhz + * + ************************************************************************************/ + +void fmuk66_timer_initialize(void); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/nxp/fmuk66-e/src/can.c b/boards/nxp/fmuk66-e/src/can.c new file mode 100644 index 0000000000..b0e9ff91c9 --- /dev/null +++ b/boards/nxp/fmuk66-e/src/can.c @@ -0,0 +1,129 @@ +/**************************************************************************** + * + * 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 can.c + * + * Board-specific CAN functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include +#include +#include "up_arch.h" + +#include "board_config.h" + +#ifdef CONFIG_CAN + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(KINETIS_FLEXCAN0) && defined(KINETIS_FLEXCAN1) +# warning "Both CAN0 and CAN1 are enabled. Assuming only CAN0." +# undef KINETIS_FLEXCAN0 +#endif + +#ifdef KINETIS_FLEXCAN0 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call kinetis_caninitialize() to get an instance of the CAN interface */ + + can = kinetis_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif diff --git a/boards/nxp/fmuk66-e/src/i2c.cpp b/boards/nxp/fmuk66-e/src/i2c.cpp new file mode 100644 index 0000000000..75b583b868 --- /dev/null +++ b/boards/nxp/fmuk66-e/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 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 + * 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. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusInternal(PX4_BUS_NUMBER_TO_PX4(1)), + initI2CBusExternal(PX4_BUS_NUMBER_TO_PX4(0)), +}; diff --git a/boards/nxp/fmuk66-e/src/init.c b/boards/nxp/fmuk66-e/src/init.c new file mode 100644 index 0000000000..95fdceca5b --- /dev/null +++ b/boards/nxp/fmuk66-e/src/init.c @@ -0,0 +1,307 @@ +/**************************************************************************** + * + * 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 init.c + * + * NXP fmuk66-e specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +#include "up_arch.h" +#include + +#include +#include + +#include + +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* + * Ideally we'd be able to get these from up_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + +/**************************************************************************** + * Protected Functions + ****************************************************************************/ +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ + +void board_on_reset(int status) +{ + for (int i = 0; i < 6; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + px4_arch_configgpio(io_timer_channel_get_gpio_output(6)); // Echo trigger pin + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(7))); + + if (status >= 0) { + up_mdelay(6); + } +} + +/************************************************************************************ + * Name: board_read_VBUS_state + * + * Description: + * All boards must provide a way to read the state of VBUS, this my be simple + * digital input on a GPIO. Or something more complicated like a Analong input + * or reading a bit from a USB controller register. + * + * Returns - 0 if connected. + * + ************************************************************************************/ + +int board_read_VBUS_state(void) +{ + return BOARD_ADC_USB_CONNECTED ? 0 : 1; +} + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ +} + +/************************************************************************************ + * Name: kinetis_boardinitialize + * + * Description: + * All Kinetis architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void +kinetis_boardinitialize(void) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + board_autoled_initialize(); + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + fmuk66_timer_initialize(); + + /* Power on Spektrum */ + + VDD_3V3_SPEKTRUM_POWER_EN(true); +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + + VDD_3V3_SD_CARD_EN(true); + VDD_3V3_SENSORS_EN(true); + + /* configure SPI interfaces */ + + fmuk66_spidev_initialize(); + + VDD_ETH_EN(true); + + px4_platform_init(); + + /* configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "DMA alloc FAILED\n"); + } + + /* set up the serial DMA polling */ +#ifdef SERIAL_HAVE_DMA + static struct hrt_call serial_dma_call; + struct timespec ts; + + /* + * Poll at 1ms intervals for received bytes that have not triggered + * a DMA event. + */ + ts.tv_sec = 0; + ts.tv_nsec = 1000000; + + hrt_call_every(&serial_dma_call, + ts_to_abstime(&ts), + ts_to_abstime(&ts), + (hrt_callout)kinetis_serial_dma_poll, + NULL); +#endif + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_off(LED_GREEN); + led_off(LED_BLUE); + + int ret = fmuk66_sdhc_initialize(); + + if (ret != OK) { + board_autoled_on(LED_RED); + return ret; + } + +#ifdef HAVE_AUTOMOUNTER + /* Initialize the auto-mounter */ + + fmuk66_automount_initialize(); +#endif + + /* Configure SPI-based devices */ + +#ifdef CONFIG_SPI + ret = fmuk66_spi_bus_initialize(); + + if (ret != OK) { + board_autoled_on(LED_RED); + return ret; + } + +#endif + +#ifdef CONFIG_NETDEV_LATEINIT + +# ifdef CONFIG_KINETIS_ENET + kinetis_netinitialize(0); +# endif + +# ifdef CONFIG_KINETIS_FLEXCAN0 + kinetis_caninitialize(0); +# endif + +# ifdef CONFIG_KINETIS_FLEXCAN1 + kinetis_caninitialize(1); +# endif + +#endif + + return OK; +} diff --git a/boards/nxp/fmuk66-e/src/led.c b/boards/nxp/fmuk66-e/src/led.c new file mode 100644 index 0000000000..360f8b017d --- /dev/null +++ b/boards/nxp/fmuk66-e/src/led.c @@ -0,0 +1,115 @@ +/**************************************************************************** + * + * 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 led.c + * + * NXP fmuk66-e LED backend. + */ + +#include + +#include + +#include "kinetis.h" +#include "chip.h" +#include "board_config.h" + +#include + +/* + * Ideally we'd be able to get these from up_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + + +static uint32_t g_ledmap[] = { + 0, // Indexed by LED_BLUE + GPIO_LED_1, // Indexed by LED_RED, LED_AMBER + GPIO_LED_SAFETY, // Indexed by LED_SAFETY + GPIO_LED_2, // Indexed by LED_GREEN +}; + +__EXPORT void led_init(void) +{ + /* Configure LED GPIOs for output */ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + kinetis_pinconfig(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive High to switch on */ + + if (g_ledmap[led] != 0) { + kinetis_gpiowrite(g_ledmap[led], state); + } +} + +static bool phy_get_led(int led) +{ + + if (g_ledmap[led] != 0) { + return kinetis_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(led, true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(led, false); +} + +__EXPORT void led_toggle(int led) +{ + + phy_set_led(led, !phy_get_led(led)); +} diff --git a/boards/nxp/fmuk66-e/src/sdhc.c b/boards/nxp/fmuk66-e/src/sdhc.c new file mode 100644 index 0000000000..2236104b5c --- /dev/null +++ b/boards/nxp/fmuk66-e/src/sdhc.c @@ -0,0 +1,270 @@ +/**************************************************************************** + * + * Copyright (C) 2016-2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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. + * + ****************************************************************************/ +/* A micro Secure Digital (SD) card slot is available on the board connected to + * the SD Host Controller (SDHC) signals of the MCU. This slot will accept micro + * format SD memory cards. The SD card detect pin (PTE6) is an open switch that + * shorts with VDD when card is inserted. + * + * ------------ ------------- -------- + * SD Card Slot Board Signal K66 Pin + * ------------ ------------- -------- + * DAT0 SDHC0_D0 PTE1 + * DAT1 SDHC0_D1 PTE0 + * DAT2 SDHC0_D2 PTE5 + * CD/DAT3 SDHC0_D3 PTE4 + * CMD SDHC0_CMD PTE3 + * CLK SDHC0_DCLK PTE2 + * SWITCH D_CARD_DETECT PTE6 + * ------------ ------------- -------- + * + * There is no Write Protect pin available to the K66. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include "kinetis.h" + +#include "board_config.h" + +#ifdef CONFIG_KINETIS_SDHC + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ +/* This structure holds static information unique to one SDHC peripheral */ + +struct fmuk66_sdhc_state_s { + struct sdio_dev_s *sdhc; /* R/W device handle */ + bool inserted; /* TRUE: card is inserted */ +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* HSCMI device state */ + +static struct fmuk66_sdhc_state_s g_sdhc; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +#if defined(GPIO_SD_CARDDETECT) +/**************************************************************************** + * Name: fmuk66_mediachange + ****************************************************************************/ + +static void fmuk66_mediachange(struct fmuk66_sdhc_state_s *sdhc) +{ + bool inserted; + + /* Get the current value of the card detect pin. This pin is pulled up on + * board. So low means that a card is present. + */ + + inserted = !kinetis_gpioread(GPIO_SD_CARDDETECT); + mcinfo("inserted: %s\n", inserted ? "Yes" : "No"); + + /* Has the pin changed state? */ + + if (inserted != sdhc->inserted) { + mcinfo("Media change: %d->%d\n", sdhc->inserted, inserted); + + /* Yes.. perform the appropriate action (this might need some debounce). */ + + sdhc->inserted = inserted; + sdhc_mediachange(sdhc->sdhc, inserted); + +#ifdef CONFIG_FMUK66_SDHC_AUTOMOUNT + /* Let the automounter know about the insertion event */ + + fmuk66_automount_event(fmuk66_cardinserted()); +#endif + } +} + +/**************************************************************************** + * Name: fmuk66_cdinterrupt + ****************************************************************************/ + +static int fmuk66_cdinterrupt(int irq, FAR void *context, FAR void *args) +{ + /* All of the work is done by fmuk66_mediachange() */ + + fmuk66_mediachange((struct fmuk66_sdhc_state_s *) args); + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fmuk66_sdhc_initialize + * + * Description: + * Inititialize the SDHC SD card slot + * + ****************************************************************************/ + +int fmuk66_sdhc_initialize(void) +{ + int ret; + struct fmuk66_sdhc_state_s *sdhc = &g_sdhc; + /* Configure GPIO pins */ + + VDD_3V3_SD_CARD_EN(true); + +#if defined(GPIO_SD_CARDDETECT) + kinetis_pinconfig(GPIO_SD_CARDDETECT); + + /* Attached the card detect interrupt (but don't enable it yet) */ + + kinetis_pinirqattach(GPIO_SD_CARDDETECT, fmuk66_cdinterrupt, sdhc); +#endif + /* Configure the write protect GPIO -- None */ + + /* Mount the SDHC-based MMC/SD block driver */ + /* First, get an instance of the SDHC interface */ + + mcinfo("Initializing SDHC slot %d\n", CONFIG_NSH_MMCSDSLOTNO); + + sdhc->sdhc = sdhc_initialize(CONFIG_NSH_MMCSDSLOTNO); + + if (!sdhc->sdhc) { + mcerr("ERROR: Failed to initialize SDHC slot %d\n", CONFIG_NSH_MMCSDSLOTNO); + return -ENODEV; + } + +// Testing done on SanDISK HC all failed sd_bench with Drive/Slew other than default and _PIN_OUTPUT_FAST|_PIN_OUTPUT_HIGHDRIVE +// _PIN_OUTPUT_FAST|_PIN_OUTPUT_HIGHDRIVE Square noisy, pass SanDISK HC +// _PIN_OUTPUT_FAST|_PIN_OUTPUT_LOWDRIVE Square noisy, pass SanDISK HC +// _PIN_OUTPUT_HIGHDRIVE|_PIN_OUTPUT_SLOW sinusoidal fail SanDISK HC pass SanDISK HC1 +// _PIN_OUTPUT_LOWDRIVE|_PIN_OUTPUT_SLOW sinusoidal fail SanDISK HC pass SanDISK HC1 +// _PIN_OUTPUT_SLOW sinusoidal fail SanDISK HC pass SanDISK HC1 + + // This up dating of the driver setting is for EMI issue with GPS and FCC + // With this setting the clock is sinusoidal N.B. sd_bench fails on SanDISK HC, but + // Passes SanDISK **HC1** - use HC1 or Kingston cards! + + kinetis_pinconfig(PIN_SDHC0_DCLK | _PIN_OUTPUT_HIGHDRIVE | _PIN_OUTPUT_SLOW); + + /* Now bind the SDHC interface to the MMC/SD driver */ + + mcinfo("Bind SDHC to the MMC/SD driver, minor=%d\n", CONFIG_NSH_MMCSDMINOR); + + ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdhc->sdhc); + + if (ret != OK) { + syslog(LOG_ERR, "ERROR: Failed to bind SDHC to the MMC/SD driver: %d\n", ret); + return ret; + } + + syslog(LOG_ERR, "Successfully bound SDHC to the MMC/SD driver\n"); + +#if defined(GPIO_SD_CARDDETECT) + /* Handle the initial card state */ + + fmuk66_mediachange(sdhc); + + /* Enable CD interrupts to handle subsequent media changes */ + + kinetis_pinirqenable(GPIO_SD_CARDDETECT); +#else + sdhc_mediachange(sdhc->sdhc, true); +#endif + return OK; +} + +/**************************************************************************** + * Name: fmuk66_cardinserted + * + * Description: + * Check if a card is inserted into the SDHC slot + * + ****************************************************************************/ + +#ifdef HAVE_AUTOMOUNTER +bool fmuk66_cardinserted(void) +{ + bool inserted; + + /* Get the current value of the card detect pin. This pin is pulled up on + * board. So low means that a card is present. + */ + + inserted = !kinetis_gpioread(GPIO_SD_CARDDETECT); + mcinfo("inserted: %s\n", inserted ? "Yes" : "No"); + return inserted; +} +#endif + +/**************************************************************************** + * Name: fmuk66_writeprotected + * + * Description: + * Check if a card is inserted into the SDHC slot + * + ****************************************************************************/ + +#ifdef HAVE_AUTOMOUNTER +bool fmuk66_writeprotected(void) +{ + /* There are no write protect pins */ + + return false; +} +#endif + +#endif /* HAVE_MMCSD */ diff --git a/boards/nxp/fmuk66-e/src/spi.cpp b/boards/nxp/fmuk66-e/src/spi.cpp new file mode 100644 index 0000000000..8a7f0d7b05 --- /dev/null +++ b/boards/nxp/fmuk66-e/src/spi.cpp @@ -0,0 +1,313 @@ +/************************************************************************************ + * + * Copyright (C) 2016, 2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * 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. + * + ************************************************************************************/ + +#include +#include +#include + +#include + +#include +#include +#include +//#include + +#include +#include + +#include "up_arch.h" +#include "chip.h" +#include +#include "board_config.h" +#include + +#if defined(CONFIG_KINETIS_SPI0) || defined(CONFIG_KINETIS_SPI1) || defined(CONFIG_KINETIS_SPI2) + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI0, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortC, GPIO::Pin2}) + }), + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortB, GPIO::Pin10}, SPI::DRDY{GPIO::PortE, GPIO::Pin9}), + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortB, GPIO::Pin9}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortE, GPIO::Pin6}), + initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortA, GPIO::Pin19}), // CAL Memory + }, {GPIO::PortB, GPIO::Pin8}), + initSPIBusExternal(SPI::Bus::SPI2, { + initSPIConfigExternal(SPI::CS{GPIO::PortB, GPIO::Pin20}), + initSPIConfigExternal(SPI::CS{GPIO::PortD, GPIO::Pin15}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); + + +#define PX4_MK_GPIO(pin_ftmx, io) ((((uint32_t)(pin_ftmx)) & ~(_PIN_MODE_MASK | _PIN_OPTIONS_MASK)) |(io)) + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +__EXPORT void board_spi_reset(int ms, int bus_mask) +{ + /* Goal not to back feed the chips on the bus via IO lines */ + + /* Next Change CS to inputs with pull downs */ + for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) { + if (px4_spi_buses[bus].bus == PX4_BUS_NUMBER_TO_PX4(1)) { + for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) { + if (px4_spi_buses[bus].devices[i].cs_gpio != 0) { + kinetis_pinconfig(PX4_MK_GPIO(px4_spi_buses[bus].devices[i].cs_gpio, GPIO_PULLDOWN)); + } + } + } + } + + /* Turn all the int inputs to inputs with pull down */ + + kinetis_pinconfig(PX4_MK_GPIO(GPIO_nSPI1_DRDY1_BMI1088_ACCEL_INT1, GPIO_PULLDOWN)); + kinetis_pinconfig(PX4_MK_GPIO(GPIO_nSPI1_DRDY2_BMI1088_GYRO_INT2, GPIO_PULLDOWN)); + kinetis_pinconfig(PX4_MK_GPIO(GPIO_nSPI1_DRDY3_ICM42688_INT1, GPIO_PULLDOWN)); + + /* Power Down The Sensors */ + + VDD_3V3_SENSORS_EN(false); + up_mdelay(ms); + + /* Power Up The Sensors */ + VDD_3V3_SENSORS_EN(true); + up_mdelay(2); + + /* Restore all the CS to ouputs inactive */ + + for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) { + if (px4_spi_buses[bus].bus == PX4_BUS_NUMBER_TO_PX4(1)) { + for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) { + if (px4_spi_buses[bus].devices[i].cs_gpio != 0) { + kinetis_pinconfig(px4_spi_buses[bus].devices[i].cs_gpio); + } + } + } + } + + /* Restore all the int inputs to inputs */ + + kinetis_pinconfig(GPIO_nSPI1_DRDY1_BMI1088_ACCEL_INT1); + kinetis_pinconfig(GPIO_nSPI1_DRDY2_BMI1088_GYRO_INT2); + kinetis_pinconfig(GPIO_nSPI1_DRDY3_ICM42688_INT1); +} + +/************************************************************************************ + * Name: fmuk66_spidev_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the NXP FMUK66-E board. + * + ************************************************************************************/ + +void fmuk66_spidev_initialize(void) +{ + board_spi_reset(10, 0xffff); + + for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) { + for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) { + if (px4_spi_buses[bus].devices[i].cs_gpio != 0) { + kinetis_pinconfig(px4_spi_buses[bus].devices[i].cs_gpio); + } + } + } +} + +/************************************************************************************ + * Name: kinetis_spi_bus_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the NXP FMUK66 v3 board. + * + ************************************************************************************/ +static const px4_spi_bus_t *_spi_bus0; +static const px4_spi_bus_t *_spi_bus1; +static const px4_spi_bus_t *_spi_bus2; + +__EXPORT int fmuk66_spi_bus_initialize(void) +{ + for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) { + switch (px4_spi_buses[i].bus) { + case PX4_BUS_NUMBER_TO_PX4(0): _spi_bus0 = &px4_spi_buses[i]; break; + + case PX4_BUS_NUMBER_TO_PX4(1): _spi_bus1 = &px4_spi_buses[i]; break; + + case PX4_BUS_NUMBER_TO_PX4(2): _spi_bus2 = &px4_spi_buses[i]; break; + } + } + + /* Configure SPI-based devices */ + + struct spi_dev_s *spi_sensors = px4_spibus_initialize(PX4_BUS_NUMBER_TO_PX4(1)); + + if (!spi_sensors) { + syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 1); + return -ENODEV; + } + + /* Default bus 1 to 1MHz and de-assert the known chip selects. + */ + + SPI_SETFREQUENCY(spi_sensors, 1 * 1000 * 1000); + SPI_SETBITS(spi_sensors, 8); + SPI_SETMODE(spi_sensors, SPIDEV_MODE0); + + /* Get the SPI port for the Memory */ + + struct spi_dev_s *spi_memory = px4_spibus_initialize(PX4_BUS_NUMBER_TO_PX4(0)); + + if (!spi_memory) { + syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 0); + return -ENODEV; + } + + /* Default bus 0 to 12MHz and de-assert the known chip selects. + */ + + SPI_SETFREQUENCY(spi_memory, 12 * 1000 * 1000); + SPI_SETBITS(spi_memory, 8); + SPI_SETMODE(spi_memory, SPIDEV_MODE3); + + /* Configure EXTERNAL SPI-based devices */ + + struct spi_dev_s *spi_ext = px4_spibus_initialize(PX4_BUS_NUMBER_TO_PX4(2)); + + if (!spi_ext) { + syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 2); + return -ENODEV; + } + + /* Default external bus to 1MHz and de-assert the known chip selects. + */ + + SPI_SETFREQUENCY(spi_ext, 8 * 1000 * 1000); + SPI_SETBITS(spi_ext, 8); + SPI_SETMODE(spi_ext, SPIDEV_MODE3); + + /* deselect all */ + for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) { + for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) { + if (px4_spi_buses[bus].devices[i].cs_gpio != 0) { + SPI_SELECT(spi_ext, px4_spi_buses[bus].devices[i].devid, false); + } + } + } + + return OK; + +} + +/************************************************************************************ + * Name: kinetis_spi[n]select, kinetis_spi[n]status, and kinetis_spi[n]cmddata + * + * Description: + * These external functions must be provided by board-specific logic. They are + * implementations of the select, status, and cmddata methods of the SPI interface + * defined by struct spi_ops_s (see include/nuttx/spi/spi.h). All other methods + * including kinetis_spibus_initialize()) are provided by common Kinetis logic. + * To use this common SPI logic on your board: + * + * 1. Provide logic in kinetis_boardinitialize() to configure SPI chip select + * pins. + * 2. Provide kinetis_spi[n]select() and kinetis_spi[n]status() functions + * in your board-specific logic. These functions will perform chip selection + * and status operations using GPIOs in the way your board is configured. + * 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide + * kinetis_spi[n]cmddata() functions in your board-specific logic. These + * functions will perform cmd/data selection operations using GPIOs in the way + * your board is configured. + * 3. Add a call to kinetis_spibus_initialize() in your low level application + * initialization logic + * 4. The handle returned by kinetis_spibus_initialize() may then be used to bind the + * SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ************************************************************************************/ + +static inline void kinetis_spixselect(const px4_spi_bus_t *bus, struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) { + if (bus->devices[i].cs_gpio == 0) { + break; + } + + if (devid == bus->devices[i].devid) { + // SPI select is active low, so write !selected to select the device + kinetis_gpiowrite(bus->devices[i].cs_gpio, !selected); + } + } +} + +void kinetis_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + kinetis_spixselect(_spi_bus0, dev, devid, selected); +} + +uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return SPI_STATUS_PRESENT; +} + +void kinetis_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + kinetis_spixselect(_spi_bus1, dev, devid, selected); +} + +uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return SPI_STATUS_PRESENT; +} + +void kinetis_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected) +{ + spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + kinetis_spixselect(_spi_bus2, dev, devid, selected); +} + +uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, uint32_t devid) +{ + return SPI_STATUS_PRESENT; +} + + +#endif /* CONFIG_KINETIS_SPI0 || CONFIG_KINETIS_SPI1 || CONFIG_KINETIS_SPI2 */ diff --git a/boards/nxp/fmuk66-e/src/timer_config.cpp b/boards/nxp/fmuk66-e/src/timer_config.cpp new file mode 100644 index 0000000000..aa6362d34f --- /dev/null +++ b/boards/nxp/fmuk66-e/src/timer_config.cpp @@ -0,0 +1,188 @@ +/**************************************************************************** + * + * 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 kinetis pwm_servo, input capture and pwm input driver. + * + * Note that these arrays must always be fully-sized. + */ + +// TODO:Stubbed out for now +#include + +#include +#include "hardware/kinetis_sim.h" +#include "hardware/kinetis_ftm.h" + +#include +#include + +#include "board_config.h" + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::FTM0), + initIOTimer(Timer::FTM3), + initIOTimer(Timer::FTM2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel0}, {GPIO::PortC, GPIO::Pin1}), + initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel3}, {GPIO::PortA, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel4}, {GPIO::PortD, GPIO::Pin4}), + initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel5}, {GPIO::PortD, GPIO::Pin5}), + initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel6}, {GPIO::PortD, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel7}, {GPIO::PortD, GPIO::Pin7}), + initIOTimerChannel(io_timers, {Timer::FTM3, Timer::Channel6}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::FTM3, Timer::Channel7}, {GPIO::PortE, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::FTM3, Timer::Channel0}, {GPIO::PortD, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::FTM2, Timer::Channel0}, {GPIO::PortA, GPIO::Pin10}), +}; + +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] = { + { + .base = KINETIS_FTM3_BASE, + .clock_register = KINETIS_SIM_SCGC3, + .clock_bit = SIM_SCGC3_FTM3, + .vectorno = 0, + }, +}; + +const struct timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = { + { + .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, + }, +}; + +#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_SRC_CLOCK_FREQ) +#define BOARD_PWM_SRC_CLOCK_FREQ 16000000 +#endif + + +void fmuk66_timer_initialize(void) +{ + + + /* Y1 is 16 Mhz used to driver the FTM_CLKIN0 (PCT12) */ + + + /* Enable PCT12 as FTM_CLKIN0 */ + + kinetis_pinconfig(PIN_FTM_CLKIN0_3); + + /* Select FTM_CLKIN0 as source for FTM0, FTM2, and FTM3 */ + + uint32_t regval = _REG(KINETIS_SIM_SOPT4); + regval &= ~(SIM_SOPT4_FTM0CLKSEL | SIM_SOPT4_FTM2CLKSEL | 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; + +} diff --git a/boards/nxp/fmuk66-e/src/usb.c b/boards/nxp/fmuk66-e/src/usb.c new file mode 100644 index 0000000000..c4943f9f37 --- /dev/null +++ b/boards/nxp/fmuk66-e/src/usb.c @@ -0,0 +1,113 @@ +/**************************************************************************** + * + * 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 usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: kinetis_usbpullup + * + * Description: + * If USB is supported and the board supports a pullup via GPIO (for USB software + * connect and disconnect), then the board software must provide kinetis_usbpullup. + * See include/nuttx/usb/usbdev.h for additional description of this method. + * Alternatively, if no pull-up GPIO the following EXTERN can be redefined to be + * NULL. + * + ************************************************************************************/ + +__EXPORT +int kinetis_usbpullup(FAR struct usbdev_s *dev, bool enable) +{ + usbtrace(TRACE_DEVPULLUP, (uint16_t)enable); + + if (enable) { + putreg8(USB_CONTROL_DPPULLUPNONOTG, KINETIS_USB0_CONTROL); + + } else { + putreg8(0, KINETIS_USB0_CONTROL); + } + + return OK; +} + +/************************************************************************************ + * Name: kinetis_usbsuspend + * + * Description: + * Board logic must provide the kinetis_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT +void kinetis_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index dc10293feb..e48308ad33 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit dc10293feb724d50f6a0a64a068b47cb8cdae631 +Subproject commit e48308ad338b60ded6b34a4faa85589cf970cec2