Adding NXP fmurt1062-v1

Add nxp_fmurt1062-v1 to CI
This commit is contained in:
David Sidrane
2019-12-04 10:59:47 -08:00
committed by Daniel Agar
parent 490fe8256f
commit 59693dc48e
30 changed files with 8989 additions and 0 deletions

View File

@@ -37,6 +37,7 @@ pipeline {
"modalai_fc-v1_default", "modalai_fc-v1_default",
"mro_x21_default", "mro_ctrl-zero-f7_default", "mro_x21-777_default", "mro_x21_default", "mro_ctrl-zero-f7_default", "mro_x21-777_default",
"nxp_fmuk66-v3_default", "nxp_fmuk66-v3_default",
"nxp_fmurt1062-v1_default",
"omnibus_f4sd_default", "omnibus_f4sd_default",
"px4_fmu-v2_default", "px4_fmu-v2_fixedwing", "px4_fmu-v2_lpe", "px4_fmu-v2_multicopter", "px4_fmu-v2_rover", "px4_fmu-v2_test", "px4_fmu-v2_default", "px4_fmu-v2_fixedwing", "px4_fmu-v2_lpe", "px4_fmu-v2_multicopter", "px4_fmu-v2_rover", "px4_fmu-v2_test",
"px4_fmu-v3_default", "px4_fmu-v3_default",

View File

@@ -253,6 +253,7 @@ px4fmu_firmware: \
misc_qgc_extra_firmware: \ misc_qgc_extra_firmware: \
check_nxp_fmuk66-v3_default \ check_nxp_fmuk66-v3_default \
check_nxp_fmurt1062-v1_default \
check_intel_aerofc-v1_default \ check_intel_aerofc-v1_default \
check_mro_x21_default \ check_mro_x21_default \
check_bitcraze_crazyflie_default \ check_bitcraze_crazyflie_default \

View File

@@ -0,0 +1,129 @@
px4_add_board(
PLATFORM nuttx
VENDOR nxp
MODEL fmurt1062-v1
LABEL default
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
TESTING
# UAVCAN_INTERFACES 2
SERIAL_PORTS
# GPS1:/dev/ttyS0
# TEL1:/dev/ttyS1
# TEL2:/dev/ttyS2
# GPS2:/dev/ttyS3
# ON EVK
GPS1:/dev/ttyS1
TEL2:/dev/ttyS2
DRIVERS
adc
barometer # all available barometer drivers
batt_smbus
camera_capture
camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
# dshot not ported
gps
#heater
imu/adis16448
imu/adis16497
#imu # all available imu drivers
imu/bma180
imu/bmi055
imu/bmi160
imu/mpu6000
imu/mpu9250
irlock
lights/blinkm
lights/rgbled
lights/rgbled_ncp5623c
lights/rgbled_pwm
magnetometer # all available magnetometer drivers
mkblctrl
optical_flow # all available optical flow drivers
#osd
pca9685
power_monitor/ina226
#protocol_splitter
pwm_out_sim
px4fmu
# rc_input needs serial DMA driver
roboclaw
safety_button
tap_esc
telemetry # all available telemetry drivers
# test_ppm not portable
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_pos_control
mc_rate_control
#micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih
vmount
vtol_att_control
SYSTEMCMDS
bl_update
config
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
shutdown
tests # tests and test runner
top
topic_listener
tune_control
usb_connected
ver
work_queue
EXAMPLES
bottle_drop # OBC challenge
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
)

View File

@@ -0,0 +1,13 @@
{
"board_id": 28,
"magic": "PX4FWv1",
"description": "Firmware for the NXPFMURT1062v1 board",
"image": "",
"build_time": 0,
"summary": "NXPFMURT1062v1",
"version": "0.1",
"image_size": 0,
"image_maxsize": 8388608,
"git_identity": "",
"board_revision": 0
}

View File

@@ -0,0 +1,14 @@
#!/bin/sh
#
# PX4 FMUv5 specific board defaults
#------------------------------------------------------------------------------
if [ $AUTOCNF = yes ]
then
fi
set LOGGER_BUF 64
safety_button start

View File

@@ -0,0 +1,7 @@
#!/bin/sh
#
# PX4 FMUv5 specific board MAVLink startup script.
#------------------------------------------------------------------------------
# Start MAVLink on the USB port
mavlink start -d /dev/ttyACM0

View File

@@ -0,0 +1,58 @@
#!/bin/sh
#
# PX4 FMUv5 specific board sensors init
#------------------------------------------------------------------------------
#
# UART mapping on NXP FMURT1062:
#
# LPUART2 /dev/ttyS0 GPS
# LPUART3 /dev/ttyS2 TELEM2 (GPIO flow control)
# LPUART4 /dev/ttyS1 TELEM1 (UART flow control)
# LPUART5 /dev/ttyS3 TELEM4 GPS2
# LPUART6 /dev/ttyS4 TELEM3 (RC_INPUT)
# LPUART7 /dev/ttyS5 CONSOLE
# LPUART8 /dev/ttyS6 PX4IO
#
#------------------------------------------------------------------------------
adc start
# Internal SPI bus ICM-20602
mpu6000 -R 8 -s -T 20602 start
# Internal SPI bus ICM-20689
mpu6000 -R 8 -z -T 20689 start
# Internal SPI bus BMI055 accel
bmi055 -A -R 10 start
# Internal SPI bus BMI055 gyro
bmi055 -G -R 10 start
# Possible external compasses
ist8310 -C -b 1 start
ist8310 -C -b 2 start
hmc5883 -C -T -X start
qmc5883 -X start
lis3mdl -X start
# ICM20948 as external magnetometer on I2C (e.g. Here GPS)
if ! icm20948 -X -M -R 6 start
then
# external emulated AK09916 (Here2) is rotated 270 degrees yaw
ak09916 -X -R 6 start
fi
# Possible internal compass
ist8310 -C -b 5 start
# Baro on internal SPI
ms5611 -s start
# External RM3100 (I2C or SPI)
rm3100 start
# Possible pmw3901 optical flow sensor
pmw3901 start
px4flow start &

View File

@@ -0,0 +1,16 @@
#
# For a description of the syntax of this configuration file,
# see the file kconfig-language.txt in the NuttX tools repository.
#
choice
prompt "Boot Flash"
default NXP_FMURT1062_V3_QSPI_FLASH
config NXP_FMURT1062_V3_HYPER_FLASH
bool "HYPER Flash"
config NXP_FMURT1062_V3_QSPI_FLASH
bool "QSPI Flash"
endchoice # Boot Flash

View File

@@ -0,0 +1,392 @@
/************************************************************************************
* nuttx-configs/nxp_fmurt1062-v1/include/board.h
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* 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 __NUTTX_CONFIG_NXP_FMURT1062_V1_INCLUDE_BOARD_H
#define __NUTTX_CONFIG_NXP_FMURT1062_V1_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
#define ON_EVK // For Board Bring up before BIG Board on IMXRT1060-EVK
/* Clocking *************************************************************************/
/* Set VDD_SOC to 1.3V */
#define IMXRT_VDD_SOC (0x14)
/* Set Arm PLL (PLL1) to fOut = (24Mhz * ARM_PLL_DIV_SELECT/2) / ARM_PODF_DIVISOR
* 576Mhz = (24Mhz * ARM_PLL_DIV_SELECT/2) / ARM_PODF_DIVISOR
* ARM_PLL_DIV_SELECT = 96
* ARM_PODF_DIVISOR = 2
* 576Mhz = (24Mhz * 96/2) / 2
*
* AHB_CLOCK_ROOT = PLL1fOut / IMXRT_AHB_PODF_DIVIDER
* 1Hz to 600 Mhz = 576Mhz / IMXRT_ARM_CLOCK_DIVIDER
* IMXRT_ARM_CLOCK_DIVIDER = 1
* 576Mhz = 576Mhz / 1
*
* PRE_PERIPH_CLK_SEL = PRE_PERIPH_CLK_SEL_PLL1
* PERIPH_CLK_SEL = 1 (0 select PERIPH_CLK2_PODF, 1 select PRE_PERIPH_CLK_SEL_PLL1)
* PERIPH_CLK = 576Mhz
*
* IPG_CLOCK_ROOT = AHB_CLOCK_ROOT / IMXRT_IPG_PODF_DIVIDER
* IMXRT_IPG_PODF_DIVIDER = 4
* 144Mhz = 576Mhz / 4
*
* PRECLK_CLOCK_ROOT = IPG_CLOCK_ROOT / IMXRT_PERCLK_PODF_DIVIDER
* IMXRT_PERCLK_PODF_DIVIDER = 1
* 16Mhz = 144Mhz / 9
*
* SEMC_CLK_ROOT = 576Mhz / IMXRT_SEMC_PODF_DIVIDER (labeled AIX_PODF in 18.2)
* IMXRT_SEMC_PODF_DIVIDER = 8
* 72Mhz = 576Mhz / 8
*
* Set Sys PLL (PLL2) to fOut = (24Mhz * (20+(2*(DIV_SELECT)))
* 528Mhz = (24Mhz * (20+(2*(1)))
*
* Set USB1 PLL (PLL3) to fOut = (24Mhz * 20)
* 480Mhz = (24Mhz * 20)
*
* Set LPSPI PLL3 PFD0 to fOut = (480Mhz / 12 * 18)
* 720Mhz = (480Mhz / 12 * 18)
* 90Mhz = (720Mhz / LSPI_PODF_DIVIDER)
*
* Set USDHC1 PLL2 PFD2 to fOut = (528Mhz / 24 * 18)
* 396Mhz = (528Mhz / 24 * 18)
* 198Mhz = (396Mhz / IMXRT_USDHC1_PODF_DIVIDER)
*/
#define BOARD_XTAL_FREQUENCY 24000000
#define IMXRT_PRE_PERIPH_CLK_SEL CCM_CBCMR_PRE_PERIPH_CLK_SEL_PLL1
#define IMXRT_PERIPH_CLK_SEL CCM_CBCDR_PERIPH_CLK_SEL_PRE_PERIPH
#define IMXRT_ARM_PLL_DIV_SELECT 96
#define IMXRT_ARM_PODF_DIVIDER 2
#define IMXRT_AHB_PODF_DIVIDER 1
#define IMXRT_IPG_PODF_DIVIDER 4
#define IMXRT_PERCLK_CLK_SEL CCM_CSCMR1_PERCLK_CLK_SEL_IPG_CLK_ROOT
#define IMXRT_PERCLK_PODF_DIVIDER 9
#define IMXRT_SEMC_PODF_DIVIDER 8
#define IMXRT_LPSPI_CLK_SELECT CCM_CBCMR_LPSPI_CLK_SEL_PLL3_PFD0
#define IMXRT_LSPI_PODF_DIVIDER 8
#define IMXRT_USDHC1_CLK_SELECT CCM_CSCMR1_USDHC1_CLK_SEL_PLL2_PFD0
#define IMXRT_USDHC1_PODF_DIVIDER 2
#define IMXRT_SYS_PLL_SELECT CCM_ANALOG_PLL_SYS_DIV_SELECT_22
#define BOARD_CPU_FREQUENCY \
(BOARD_XTAL_FREQUENCY * (IMXRT_ARM_PLL_DIV_SELECT / 2)) / IMXRT_ARM_PODF_DIVIDER
#define BOARD_GPT_FREQUENCY \
(BOARD_CPU_FREQUENCY / IMXRT_IPG_PODF_DIVIDER) / IMXRT_PERCLK_PODF_DIVIDER
/* Define this to enable tracing */
#if CONFIG_USE_TRACE
# define IMXRT_TRACE_PODF_DIVIDER 1
# define IMXRT_TRACE_CLK_SELECT CCM_CBCMR_TRACE_CLK_SEL_PLL2_PFD0
#endif
/* SDIO *****************************************************************************/
/* Pin drive characteristics */
#define USDHC1_DATAX_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | \
IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER)
#define USDHC1_CMD_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | \
IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER)
#define USDHC1_CLK_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_SPEED_MAX)
#define USDHC1_CD_IOMUX (0)
#define PIN_USDHC1_D0 (GPIO_USDHC1_DATA0_1 | USDHC1_DATAX_IOMUX)
#define PIN_USDHC1_D1 (GPIO_USDHC1_DATA1_1 | USDHC1_DATAX_IOMUX)
#define PIN_USDHC1_D2 (GPIO_USDHC1_DATA2_1 | USDHC1_DATAX_IOMUX)
#define PIN_USDHC1_D3 (GPIO_USDHC1_DATA3_1 | USDHC1_DATAX_IOMUX)
#define PIN_USDHC1_DCLK (GPIO_USDHC1_CLK_1 | USDHC1_CLK_IOMUX)
#define PIN_USDHC1_CMD (GPIO_USDHC1_CMD_1 | USDHC1_CMD_IOMUX)
#define PIN_USDHC1_CD (GPIO_USDHC1_CD_2 | USDHC1_CD_IOMUX)
/* Ideal 400Khz for initial inquiry.
* Given input clock 198 Mhz.
* 386.71875 KHz = 198 Mhz / (256 * 2)
*/
#define BOARD_USDHC_IDMODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV256
#define BOARD_USDHC_IDMODE_DIVISOR USDHC_SYSCTL_DVS_DIV(2)
/* Ideal 25 Mhz for other modes
* Given input clock 198 Mhz.
* 24.75 MHz = 198 Mhz / (8 * 1)
*/
#define BOARD_USDHC_MMCMODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8
#define BOARD_USDHC_MMCMODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1)
#define BOARD_USDHC_SD1MODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8
#define BOARD_USDHC_SD1MODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1)
#define BOARD_USDHC_SD4MODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8
#define BOARD_USDHC_SD4MODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1)
/* LED definitions ******************************************************************/
/* The nxp fmutr1062 board has numerous LEDs but only three, LED_GREEN a Green LED,
* LED_BLUE a Blue LED and LED_RED a Red LED, that can be controlled by software.
*
* 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_LED1 0
#define BOARD_LED2 1
#define BOARD_LED3 2
#define BOARD_NLEDS 3
#define BOARD_LED_RED BOARD_LED1
#define BOARD_LED_GREEN BOARD_LED2
#define BOARD_LED_BLUE BOARD_LED3
/* LED bits for use with board_userled_all() */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
#define BOARD_LED2_BIT (1 << BOARD_LED2)
#define BOARD_LED3_BIT (1 << BOARD_LED3)
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
* events as follows:
*
*
* SYMBOL Meaning LED state
* Red Green Blue
* ---------------------- -------------------------- ------ ------ ----*/
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */
/* Thus if the Green LED is statically on, NuttX has successfully booted and
* is, apparently, running normally. If the Red LED is flashing at
* approximately 2Hz, then a fatal error has been detected and the system
* has halted.
*/
/* PIO Disambiguation ***************************************************************/
/* LPUARTs
*/
/* GPS 1 */
#define GPIO_LPUART2_RX (GPIO_LPUART2_RX_1 | IOMUX_UART_DEFAULT) /* EVK J22-8 */ /* GPIO_AD_B1_03 */
#define GPIO_LPUART2_TX (GPIO_LPUART2_TX_1 | IOMUX_UART_DEFAULT) /* EVK J22-7 */ /* GPIO_AD_B1_02 */
/* Telem 2 */
#define HS_INPUT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_SLEW_SLOW | IOMUX_DRIVE_HIZ | IOMUX_SPEED_MEDIUM | IOMUX_PULL_UP_47K)
#define HS_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_PULL_KEEP)
#if defined(ON_EVK)
#define GPIO_LPUART1_RX (GPIO_LPUART1_RX_1 | IOMUX_UART_DEFAULT) /* GPIO_AD_B0_13 EVK J46-2 */
#define GPIO_LPUART1_TX (GPIO_LPUART1_TX_1 | IOMUX_UART_DEFAULT) /* GPIO_AD_B0_12 EVK J46-2 */
#define GPIO_LPUART3_RX (GPIO_LPUART3_RX_1 | IOMUX_UART_DEFAULT) /* GPIO_AD_B1_07 EVK J22-1 */
#define GPIO_LPUART3_TX (GPIO_LPUART3_TX_1 | IOMUX_UART_DEFAULT) /* GPIO_AD_B1_06 EVK J22-2 */
#else
#define GPIO_LPUART3_RX (GPIO_LPUART3_RX_3 | IOMUX_UART_DEFAULT) /* GPIO_B0_09 */
#define GPIO_LPUART3_TX (GPIO_LPUART3_TX_3 | IOMUX_UART_DEFAULT) /* GPIO_B0_08 */
#define GPIO_LPUART3_CTS /* GPIO_AD_B0_08 GPIO1 Pin 8 (GPIO only, no HW Flow control) */ (GPIO_PORT1 | GPIO_PIN8 | GPIO_INPUT | HS_INPUT_IOMUX)
#define GPIO_LPUART3_RTS /* GPIO_EMC_24 GPIO4 Pin 24 (GPIO only, no HW Flow control) */ (GPIO_PORT4 | GPIO_PIN14 | GPIO_OUTPUT | HS_OUTPUT_IOMUX)
#endif
/* Telem 1 */
#define GPIO_LPUART4_RX GPIO_LPUART4_RX_1 /* GPIO_EMC_20 */
#define GPIO_LPUART4_TX GPIO_LPUART4_TX_1 /* GPIO_EMC_19 */
/* GPIO_LPUART4_CTS GPIO_EMC_17 No Alternate */
/* GPIO_LPUART4_RTS GPIO_EMC_18 No Alternate */
/* GPS2 */
#define GPIO_LPUART5_RX GPIO_LPUART5_RX_1 /* GPIO_B1_13 */
#define GPIO_LPUART5_TX GPIO_LPUART5_TX_1 /* GPIO_B1_12 */
/* RC INPUT single wire mode on TX, RX is not used */
#define GPIO_LPUART6_RX GPIO_LPUART6_RX_1 /* GPIO_EMC_26 */
#define GPIO_LPUART6_TX GPIO_LPUART6_TX_1 /* GPIO_EMC_25 */
#define GPIO_LPUART7_RX GPIO_LPUART7_RX_1 /* GPIO_EMC_32 */
#define GPIO_LPUART7_TX GPIO_LPUART7_TX_1 /* GPIO_EMC_31 */
#define GPIO_LPUART8_RX GPIO_LPUART3_RX_1 /* GPIO_EMC_39 */
#define GPIO_LPUART8_TX GPIO_LPUART3_TX_1 /* GPIO_EMC_38 */
/* CAN
*
* CAN1 is routed to transceiver.
* CAN2 is routed to transceiver.
* CAN3 is routed to transceiver.
*/
#define GPIO_FLEXCAN1_RX GPIO_FLEXCAN1_RX_2 /* GPIO_B0_03 */
#define GPIO_FLEXCAN1_TX GPIO_FLEXCAN1_TX_2 /* GPIO_B0_02 */
#define GPIO_FLEXCAN2_RX GPIO_FLEXCAN2_RX_1 /* GPIO_AD_B0_03 */
#define GPIO_FLEXCAN2_TX GPIO_FLEXCAN2_TX_1 /* GPIO_AD_B0_02 */
#define GPIO_FLEXCAN3_RX GPIO_FLEXCAN3_RX_1 /* GPIO_AD_B0_11 */
#define GPIO_FLEXCAN3_TX GPIO_FLEXCAN3_TX_3 /* GPIO_EMC_36 */
/* LPSPI */
#define GPIO_LPSPI1_SCK GPIO_LPSPI1_SCK_1 /* GPIO_EMC_27 */
#define GPIO_LPSPI1_MISO GPIO_LPSPI1_SDI_1 /* GPIO_EMC_29 */
#define GPIO_LPSPI1_MOSI GPIO_LPSPI1_SDO_1 /* GPIO_EMC_28 */
#if defined(ON_EVK)
#define GPIO_LPSPI2_SCK GPIO_LPSPI2_SCK_2 /* EVK J24-6 POP R280 GPIO_SD_B0_00 */
#define GPIO_LPSPI2_MISO GPIO_LPSPI1_SDI_2 /* EVK J24-5 POP R278 GPIO_SD_B0_03 */
#define GPIO_LPSPI2_MOSI GPIO_LPSPI1_SDO_2 /* EVK J24-4 POP R279 GPIO_SD_B0_02 */
#else
#define GPIO_LPSPI2_SCK GPIO_LPSPI2_SCK_1 /* GPIO_EMC_00 */
#define GPIO_LPSPI2_MISO GPIO_LPSPI2_SDI_1 /* GPIO_EMC_03 */
#define GPIO_LPSPI2_MOSI GPIO_LPSPI2_SDO_1 /* GPIO_EMC_02 */
#endif
#define GPIO_LPSPI3_SCK GPIO_LPSPI3_SCK_1 /* GPIO_AD_B1_15 */
#define GPIO_LPSPI3_MISO GPIO_LPSPI3_SDI_1 /* GPIO_AD_B1_13 */
#define GPIO_LPSPI3_MOSI GPIO_LPSPI3_SDO_1 /* GPIO_AD_B1_14 */
#define GPIO_LPSPI4_SCK GPIO_LPSPI4_SCK_1 /* GPIO_B1_07 */
#define GPIO_LPSPI4_MISO GPIO_LPSPI4_SDI_1 /* GPIO_B1_05 */
#define GPIO_LPSPI4_MOSI GPIO_LPSPI4_SDO_1 /* GPIO_B1_06 */
/* LPI2Cs */
#define LPI2C_IOMUX (GPIO_OUTPUT | IOMUX_SPEED_MAX | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_OPENDRAIN | IOMUX_PULL_NONE)
#define GPIO_LPI2C1_SDA GPIO_LPI2C1_SDA_2 /* EVK J24-9 R276 */ /* GPIO_AD_B1_01 */
#define GPIO_LPI2C1_SCL GPIO_LPI2C1_SCL_2 /* EVK J24-10 R277 */ /* GPIO_AD_B1_00 */
#define GPIO_LPI2C1_SDA_GPIO (GPIO_PORT1 | GPIO_PIN17 | LPI2C_IOMUX)
#define GPIO_LPI2C1_SCL_GPIO (GPIO_PORT1 | GPIO_PIN16 | LPI2C_IOMUX)
#define GPIO_LPI2C2_SDA GPIO_LPI2C2_SDA_1 /* EVK J8-A25 */ /* GPIO_B0_05 */
#define GPIO_LPI2C2_SCL GPIO_LPI2C2_SCL_1 /* EVK J8-A24 */ /* GPIO_B0_04 */
#define GPIO_LPI2C2_SDA_GPIO (GPIO_PORT2 | GPIO_PIN5 | LPI2C_IOMUX)
#define GPIO_LPI2C2_SCL_GPIO (GPIO_PORT2 | GPIO_PIN4 | LPI2C_IOMUX)
#define GPIO_LPI2C3_SDA GPIO_LPI2C3_SDA_2 /* GPIO_EMC_21 */
#define GPIO_LPI2C3_SCL GPIO_LPI2C3_SCL_2 /* GPIO_EMC_22 */
#define GPIO_LPI2C3_SDA_GPIO (GPIO_PORT4 | GPIO_PIN21 | LPI2C_IOMUX)
#define GPIO_LPI2C3_SCL_GPIO (GPIO_PORT4 | GPIO_PIN22 | LPI2C_IOMUX)
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
#if defined(CONFIG_BOARD_USE_PROBES)
#define PROBE_IOMUX (GPIO_OUTPUT | IOMUX_SPEED_MAX | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE)
# define PROBE_N(n) (1<<((n)-1))
# define PROBE_1 (GPIO_PORT2 | GPIO_PIN6 | PROBE_IOMUX)
# define PROBE_2 (GPIO_PORT4 | GPIO_PIN8 | PROBE_IOMUX)
# define PROBE_3 (GPIO_PORT4 | GPIO_PIN10 | PROBE_IOMUX)
# define PROBE_4 (GPIO_PORT1 | GPIO_PIN9 | PROBE_IOMUX)
# define PROBE_5 (GPIO_PORT3 | GPIO_PIN19 | PROBE_IOMUX)
# define PROBE_6 (GPIO_PORT4 | GPIO_PIN30 | PROBE_IOMUX)
# define PROBE_7 (GPIO_PORT4 | GPIO_PIN4 | PROBE_IOMUX)
# define PROBE_8 (GPIO_PORT4 | GPIO_PIN1 | PROBE_IOMUX)
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { imxrt_config_gpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { imxrt_config_gpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { imxrt_config_gpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { imxrt_config_gpio(PROBE_4); } \
if ((mask)& PROBE_N(5)) { imxrt_config_gpio(PROBE_5); } \
if ((mask)& PROBE_N(6)) { imxrt_config_gpio(PROBE_6); } \
if ((mask)& PROBE_N(7)) { imxrt_config_gpio(PROBE_7); } \
if ((mask)& PROBE_N(8)) { imxrt_config_gpio(PROBE_8); } \
} while(0)
# define PROBE(n,s) do {stm32_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 Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __NUTTX_CONFIG_NXP_FMURT1062_V1_INCLUDE_BOARD_H */

View File

@@ -0,0 +1,181 @@
#
# 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_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_TIME 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="imxrt"
CONFIG_ARCH_CHIP_IMXRT=y
CONFIG_ARCH_CHIP_MIMXRT1062DVL6A=y
CONFIG_ARCH_INTERRUPTSTACK=750
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_CUSTOM_LEDS=y
CONFIG_BOARD_LOOPSPERMSEC=104926
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_PRODUCTID=0x001d
CONFIG_CDCACM_PRODUCTSTR="PX4 FMURT1062 v1.x"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
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_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_EXCLUDE_BLOCKS=y
CONFIG_FS_PROCFS_EXCLUDE_MOUNT=y
CONFIG_FS_PROCFS_EXCLUDE_MOUNTS=y
CONFIG_FS_PROCFS_EXCLUDE_USAGE=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=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_IMXRT_EDMA=y
CONFIG_IMXRT_LPSPI3=y
CONFIG_IMXRT_LPUART1=y
CONFIG_IMXRT_LPUART2=y
CONFIG_IMXRT_LPUART3=y
CONFIG_IMXRT_LPUART_INVERT=y
CONFIG_IMXRT_RTC_MAGIC_REG=1
CONFIG_IMXRT_SNVS_LPSRTC=y
CONFIG_IMXRT_USDHC1=y
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_LPUART2_RXBUFSIZE=600
CONFIG_LPUART2_TXBUFSIZE=1500
CONFIG_LPUART3_BAUD=57600
CONFIG_LPUART3_RXBUFSIZE=600
CONFIG_LPUART3_SERIAL_CONSOLE=y
CONFIG_LPUART3_TXBUFSIZE=3000
CONFIG_MAX_WDOGPARMS=2
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_NFILE_DESCRIPTORS=54
CONFIG_NFILE_STREAMS=8
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARCHROMFS=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_IFCONFIG=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
CONFIG_NSH_DISABLE_MB=y
CONFIG_NSH_DISABLE_MH=y
CONFIG_NSH_DISABLE_PSSTACKUSAGE=y
CONFIG_NSH_DISABLE_TELNETD=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=12
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_NXFONTS_DISABLE_16BPP=y
CONFIG_NXFONTS_DISABLE_1BPP=y
CONFIG_NXFONTS_DISABLE_24BPP=y
CONFIG_NXFONTS_DISABLE_2BPP=y
CONFIG_NXFONTS_DISABLE_32BPP=y
CONFIG_NXFONTS_DISABLE_4BPP=y
CONFIG_NXFONTS_DISABLE_8BPP=y
CONFIG_PIPES=y
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_PREALLOC_TIMERS=50
CONFIG_PREALLOC_WDOGS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=1048576
CONFIG_RAM_START=0x20200000
CONFIG_RAW_BINARY=y
CONFIG_RTC=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1800
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1800
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDIO_BLOCKSETUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SERIAL_TERMIOS=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_SPI=y
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=32
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_SYSTEM_SPITOOL=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TIME_EXTENDED=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2500
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,178 @@
/****************************************************************************
* configs/nxp_fmurt1062-v1/scripts/flash.ld
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* 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 FMURT1062 has 8MiB of QSPI FLASH beginning at address,
* 0x0060:0000, Upto 512Kb of DTCM RAM beginning at 0x2000:0000, and 1MiB OCRAM
* beginning at 0x2020:0000. Neither DTCM or SDRAM are used in this
* configuratin.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x60000000, LENGTH = 8M
sram (rwx) : ORIGIN = 0x20200000, LENGTH = 512M
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 128K
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
EXTERN(flash_config)
EXTERN(image_vector_table)
EXTERN(boot_data)
ENTRY(_stext)
SECTIONS
{
/* Image Vector Table and Boot Data for booting from external flash */
.boot_hdr : ALIGN(4)
{
FILL(0xff)
__boot_hdr_start__ = ABSOLUTE(.) ;
KEEP(*(.boot_hdr.conf))
. = 0x1000 ;
KEEP(*(.boot_hdr.ivt))
. = 0x1020 ;
KEEP(*(.boot_hdr.boot_data))
. = 0x1030 ;
KEEP(*(.boot_hdr.dcd_data))
__boot_hdr_end__ = ABSOLUTE(.) ;
. = 0x2000 ;
} >flash
.text :
{
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.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;
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section :
{
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
/*
* Construction data for parameters.
*/
__param ALIGN(4):
{
__param_start = ABSOLUTE(.);
KEEP(*(__param*))
__param_end = ABSOLUTE(.);
} > flash
.ARM.extab :
{
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx :
{
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data :
{
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.ramfunc ALIGN(4):
{
_sramfuncs = ABSOLUTE(.);
*(.ramfunc .ramfunc.*)
_eramfuncs = ABSOLUTE(.);
} > sram AT > flash
_framfuncs = LOADADDR(.ramfunc);
.bss :
{
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* 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) }
}

View File

@@ -0,0 +1,57 @@
############################################################################
#
# Copyright (c) 2016, 2019 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(drivers_board
autoleds.c
automount.c
can.c
init.c
led.c
sdhc.c
spi.c
timer_config.c
usb.c
manifest.c
imxrt_flexspi_nor_boot.c
imxrt_flexspi_nor_flash.c
)
add_dependencies(drivers_board arch_board_hw_info)
target_link_libraries(drivers_board
PRIVATE
arch_board_hw_info
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio
px4_layer
)

View File

@@ -0,0 +1,191 @@
/****************************************************************************
*
* Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* 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-V3 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 fmurt1062-v1. 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 <px4_platform_common/px4_config.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/board.h>
#include <arch/board/board.h>
#include "chip.h"
#include "imxrt_gpio.h"
#include "board_config.h"
#ifdef CONFIG_ARCH_LEDS
__BEGIN_DECLS
extern void led_init(void);
__END_DECLS
/****************************************************************************
* Public Functions
****************************************************************************/
bool nuttx_owns_leds = true;
/****************************************************************************
* Name: board_autoled_initialize
****************************************************************************/
void board_autoled_initialize(void)
{
led_init();
}
/****************************************************************************
* Name: board_autoled_on
****************************************************************************/
void phy_set_led(int l, bool s)
{
}
void board_autoled_on(int led)
{
if (!nuttx_owns_leds) {
return;
}
switch (led) {
default:
break;
case LED_HEAPALLOCATE:
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_IRQSENABLED:
phy_set_led(BOARD_LED_BLUE, false);
phy_set_led(BOARD_LED_GREEN, true);
break;
case LED_STACKCREATED:
phy_set_led(BOARD_LED_GREEN, true);
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_INIRQ:
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_SIGNAL:
phy_set_led(BOARD_LED_GREEN, true);
break;
case LED_ASSERTION:
phy_set_led(BOARD_LED_RED, true);
phy_set_led(BOARD_LED_BLUE, true);
break;
case LED_PANIC:
phy_set_led(BOARD_LED_RED, true);
break;
case LED_IDLE : /* IDLE */
phy_set_led(BOARD_LED_RED, true);
break;
}
}
/****************************************************************************
* Name: board_autoled_off
****************************************************************************/
void board_autoled_off(int led)
{
if (!nuttx_owns_leds) {
return;
}
switch (led) {
default:
break;
case LED_SIGNAL:
phy_set_led(BOARD_LED_GREEN, false);
break;
case LED_INIRQ:
phy_set_led(BOARD_LED_BLUE, false);
break;
case LED_ASSERTION:
phy_set_led(BOARD_LED_RED, false);
phy_set_led(BOARD_LED_BLUE, false);
break;
case LED_PANIC:
phy_set_led(BOARD_LED_RED, false);
break;
case LED_IDLE : /* IDLE */
phy_set_led(BOARD_LED_RED, false);
break;
}
}
#endif /* CONFIG_ARCH_LEDS */

View File

@@ -0,0 +1,304 @@
/************************************************************************************
*
* Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* 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 <px4_platform_common/px4_config.h>
#if defined(CONFIG_FS_AUTOMOUNTER_DEBUG) && !defined(CONFIG_DEBUG_FS)
# define CONFIG_DEBUG_FS 1
#endif
#include <debug.h>
#include <stddef.h>
#include <nuttx/irq.h>
#include <nuttx/clock.h>
#include <nuttx/fs/automount.h>
#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 */

View File

@@ -0,0 +1,697 @@
/****************************************************************************
*
* Copyright (c) 2018-2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file board_config.h
*
* NXP fmukrt1062-v1 internal definitions
*/
#pragma once
#define ON_EVK // For Board Bring up before BIG Board on IMXRT1060-EVK
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include "imxrt_gpio.h"
#include "imxrt_iomuxc.h"
#include "hardware/imxrt_pinmux.h"
#include <arch/board/board.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
#if defined(ON_EVK)
//#define ON_EVK_SPI // Uses SDHC pins and requires R278-R281
#define ON_EVK_SDIO // SPI2 is mapped on Pins and requires
//#define ON_EVK_I2C // I2C2 is mapped on Pins and requires R278-R281
#endif
/* PX4IO connection configuration */
#if 0 // There is no PX4 Support on first out
// This requires serial DMA driver
#define BOARD_USES_PX4IO_VERSION 2
#define PX4IO_SERIAL_DEVICE "/dev/ttyS6"
#define PX4IO_SERIAL_TX_GPIO GPIO_LPUART8_TX_2
#define PX4IO_SERIAL_RX_GPIO GPIO_LPUART8_RX_2
#define PX4IO_SERIAL_BASE IMXRT_LPUART8_BASE
#define PX4IO_SERIAL_VECTOR IMXRT_IRQ_LPUART8
#define PX4IO_SERIAL_TX_DMAMAP
#define PX4IO_SERIAL_RX_DMAMAP
#define PX4IO_SERIAL_RCC_REG
#define PX4IO_SERIAL_RCC_EN
#define PX4IO_SERIAL_CLOCK
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
#endif
/* Configuration ************************************************************************************/
/* FMURT1062 GPIOs ***********************************************************************************/
/* LEDs */
/* An RGB LED is connected through GPIO as shown below:
*/
#define LED_IOMUX (IOMUX_OPENDRAIN | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_SLOW)
#define GPIO_nLED_RED (GPIO_PORT2 | GPIO_PIN0 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX)
#define GPIO_nLED_GREEN (GPIO_PORT2 | GPIO_PIN1 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX)
#define GPIO_nLED_BLUE (GPIO_PORT2 | GPIO_PIN24 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | LED_IOMUX)
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
#define BOARD_OVERLOAD_LED LED_RED
#define BOARD_ARMED_STATE_LED LED_BLUE
/* SENSORS are on SPI1, 3
* MEMORY is on bus SPI2
* MS5611 is on bus SPI4
*/
#define PX4_SPI_BUS_SENSORS 1
#define PX4_SPI_BUS_MEMORY 2
#define PX4_SPI_BUS_BARO 3
#define PX4_SPI_BUS_EXTERNAL1 4
/*
* Define the ability to shut off off the sensor signals
* by changing the signals to inputs
*/
#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT | IOMUX_PULL_DOWN_100K | IOMUX_CMOS_INPUT))
/* Define the Chip Selects, Data Ready and Control signals per SPI bus */
#define CS_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_33OHM | IOMUX_SPEED_LOW | IOMUX_SLEW_FAST)
#define OUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_50OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST)
/* SPI 1 CS */
#if defined(ON_EVK) && defined(ON_EVK_SPI)
#define GPIO_SPI1_CS1_ICM20689 /* J24-3 POP R280 GPIO_SD_B0_01 */ (GPIO_PORT3 | GPIO_PIN13 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX)
#else
#define GPIO_SPI1_CS1_ICM20689 (GPIO_PORT3 | GPIO_PIN26 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX)
#define GPIO_SPI1_CS2_ICM20602 (GPIO_PORT3 | GPIO_PIN27 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX)
#define GPIO_SPI1_CS3_BMI055_GYRO (GPIO_PORT2 | GPIO_PIN26 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX)
#define GPIO_SPI1_CS4_BMI055_ACC (GPIO_PORT2 | GPIO_PIN31 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX)
#endif
/* Define the SPI1 Data Ready interrupts */
#define DRDY_IOMUX (IOMUX_SCHMITT_TRIGGER | IOMUX_PULL_UP_47K | IOMUX_DRIVE_HIZ)
// todo add IRQ-ness!
#define GPIO_SPI1_DRDY1_ICM20689 (GPIO_PORT4 | GPIO_PIN15 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI1_DRDY2_BMI055_GYRO (GPIO_PORT4 | GPIO_PIN16 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI1_DRDY3_BMI055_ACC (GPIO_PORT3 | GPIO_PIN23 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI1_DRDY4_ICM20602 (GPIO_PORT3 | GPIO_PIN27 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI1_DRDY5_BMI055_GYRO (GPIO_PORT4 | GPIO_PIN13 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPI1_DRDY6_BMI055_ACC (GPIO_PORT2 | GPIO_PIN7 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_SPIAUX_CS_MEM (GPIO_PORT5 | GPIO_PIN0 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX)
/* SPI1 off */
#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_LPSPI1_SCK)
#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_LPSPI1_MISO)
#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_LPSPI1_MOSI)
#define GPIO_DRDY_OFF_SPI1_DRDY1_ICM20689 _PIN_OFF(GPIO_SPI1_DRDY1_ICM20689)
#define GPIO_DRDY_OFF_SPI1_DRDY2_BMI055_GYRO _PIN_OFF(GPIO_SPI1_DRDY2_BMI055_GYRO)
#define GPIO_DRDY_OFF_SPI1_DRDY3_BMI055_ACC _PIN_OFF(GPIO_SPI1_DRDY3_BMI055_ACC)
#define GPIO_DRDY_OFF_SPI1_DRDY4_ICM20602 _PIN_OFF(GPIO_SPI1_DRDY4_ICM20602)
#define GPIO_DRDY_OFF_SPI1_DRDY5_BMI055_GYRO _PIN_OFF(GPIO_SPI1_DRDY5_BMI055_GYRO)
#define GPIO_DRDY_OFF_SPI1_DRDY6_BMI055_ACC _PIN_OFF(GPIO_SPI1_DRDY6_BMI055_ACC)
/* SPI 2 CS */
#define GPIO_SPI2_CS_FRAM (GPIO_PORT3 | GPIO_PIN20 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX)
/* SPI 3 CS */
#define GPIO_SPI3_CS1_MS5611 (GPIO_PORT4 | GPIO_PIN14 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX)
/* SPI 4 CS */
#define SPI4_CS1_EXTERNAL1 (GPIO_PORT4 | GPIO_PIN7 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX)
#define SPI4_CS2_EXTERNAL1 (GPIO_PORT2 | GPIO_PIN30 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX)
#define SPI4_CS3_EXTERNAL1 (GPIO_PORT4 | GPIO_PIN11 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | CS_IOMUX)
/* Define the SPI4 Data Ready and Control signals */
#define GPIO_SPI4_DRDY7_EXTERNAL1 (GPIO_PORT3 | GPIO_PIN21 | GPIO_INPUT | DRDY_IOMUX)
#define GPIO_nSPI4_RESET_EXTERNAL1 (GPIO_PORT2 | GPIO_PIN16 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | OUT_IOMUX)
#define GPIO_SPI4_SYNC_EXTERNAL1 (GPIO_PORT4 | GPIO_PIN5 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | OUT_IOMUX)
#define GPIO_DRDY_OFF_SPI4_DRDY7_EXTERNAL1 _PIN_OFF(GPIO_SPI4_DRDY7_EXTERNAL1)
#define GPIO_nSPI4_RESET_EXTERNAL1_OFF _PIN_OFF(GPIO_nSPI4_RESET_EXTERNAL1)
#define GPIO_SPI4_SYNC_EXTERNAL1_OFF _PIN_OFF(GPIO_SPI4_SYNC_EXTERNAL1)
/* v BEGIN Legacy SPI defines TODO: fix this with enumeration */
#define PX4_SPI_BUS_RAMTRON PX4_SPI_BUS_MEMORY
#define PX4_SPIDEV_BMA 0
#define PX4_SPIDEV_BMI 0
/* ^ END Legacy SPI defines TODO: fix this with enumeration */
#define PX4_SPIDEV_ICM_20689 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,0)
#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,1)
#define PX4_SPIDEV_BMI055_GYR PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,2)
#define PX4_SPIDEV_BMI055_ACC PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,3)
#define PX4_SPIDEV_AUX_MEM PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS,4)
#define PX4_SENSOR_BUS_CS_GPIO {GPIO_SPI1_CS1_ICM20689, GPIO_SPI1_CS2_ICM20602, GPIO_SPI1_CS3_BMI055_GYRO, GPIO_SPI1_CS4_BMI055_ACC, GPIO_SPIAUX_CS_MEM}
#define PX4_SENSORS_BUS_FIRST_CS PX4_SPIDEV_ICM_20689
#define PX4_SENSORS_BUS_LAST_CS PX4_SPIDEV_AUX_MEM
#define PX4_SPIDEV_MEMORY PX4_MK_SPI_SEL(PX4_SPI_BUS_MEMORY,0)
#define PX4_MEMORY_BUS_CS_GPIO {GPIO_SPI2_CS_FRAM}
#define PX4_MEMORY_BUS_FIRST_CS PX4_SPIDEV_MEMORY
#define PX4_MEMORY_BUS_LAST_CS PX4_SPIDEV_MEMORY
#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_BARO,0)
#define PX4_BARO_BUS_CS_GPIO {GPIO_SPI3_CS1_MS5611}
#define PX4_BARO_BUS_FIRST_CS PX4_SPIDEV_BARO
#define PX4_BARO_BUS_LAST_CS PX4_SPIDEV_BARO
#define PX4_SPIDEV_EXTERNAL1_1 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1,0)
#define PX4_SPIDEV_EXTERNAL1_2 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1,1)
#define PX4_SPIDEV_EXTERNAL1_3 PX4_MK_SPI_SEL(PX4_SPI_BUS_EXTERNAL1,2)
#define PX4_EXTERNAL1_BUS_CS_GPIO {SPI4_CS1_EXTERNAL1, SPI4_CS2_EXTERNAL1, SPI4_CS3_EXTERNAL1}
#define PX4_EXTERNAL1_BUS_FIRST_CS PX4_SPIDEV_EXTERNAL1_1
#define PX4_EXTERNAL1_BUS_LAST_CS PX4_SPIDEV_EXTERNAL1_3
/* I2C busses */
/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 1
#define PX4_I2C_BUS_EXPANSION1 2
#define PX4_I2C_BUS_ONBOARD 3
#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION
#define BOARD_NUMBER_I2C_BUSES 3
#define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000}
#define ADC_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ)
#define ADC1_CH(n) (n)
#define ADC1_GPIO(n, p) (GPIO_PORT1 | GPIO_PIN##p | ADC_IOMUX) //
/* Define GPIO pins used as ADC N.B. Channel numbers are for reference, */
#if defined(ON_EVK)
#define PX4_ADC_GPIO \
/* J23-2 BATTERY1_VOLTAGE GPIO_AD_B1_11 GPIO1 Pin 27 */ ADC1_GPIO(0, 27), \
/* J23-3 HW_VER_SENSE GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_GPIO(9, 20), \
/* J23-4 SCALED_V5 GPIO_AD_B1_05 GPIO1 Pin 21 */ ADC1_GPIO(10, 21), \
/* J22-4 HW_REV_SENSE GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_GPIO(13, 24), \
/* J23-1 RSSI_IN GPIO_AD_B1_10 GPIO1 Pin 26 */ ADC1_GPIO(15, 26)
#else
#define PX4_ADC_GPIO \
/* BATTERY1_VOLTAGE GPIO_AD_B1_11 GPIO1 Pin 27 */ ADC1_GPIO(0, 27), \
/* BATTERY1_CURRENT GPIO_AD_B0_12 GPIO1 Pin 12 */ ADC1_GPIO(1, 12), \
/* BATTERY2_VOLTAGE GPIO_AD_B0_13 GPIO1 Pin 13 */ ADC1_GPIO(2, 13), \
/* BATTERY2_CURRENT GPIO_AD_B0_14 GPIO1 Pin 14 */ ADC1_GPIO(3, 14), \
/* SPARE_2_CHANNEL GPIO_AD_B0_15 GPIO1 Pin 15 */ ADC1_GPIO(4, 15), \
/* HW_VER_SENSE GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_GPIO(9, 20), \
/* SCALED_V5 GPIO_AD_B1_05 GPIO1 Pin 21 */ ADC1_GPIO(10, 21), \
/* SCALED_VDD_3V3_SENSORS GPIO_AD_B1_06 GPIO1 Pin 22 */ ADC1_GPIO(11, 22), \
/* HW_REV_SENSE GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_GPIO(13, 24), \
/* SPARE_1 GPIO_AD_B1_09 GPIO1 Pin 25 */ ADC1_GPIO(14, 25), \
/* RSSI_IN GPIO_AD_B1_10 GPIO1 Pin 26 */ ADC1_GPIO(15, 26)
#endif // defined(ON_EVK)
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_BATTERY1_VOLTAGE_CHANNEL /* GPIO_AD_B1_11 GPIO1 Pin 27 */ ADC1_CH(0)
#define ADC_BATTERY1_CURRENT_CHANNEL /* GPIO_AD_B0_12 GPIO1 Pin 12 */ ADC1_CH(1)
#define ADC_BATTERY2_VOLTAGE_CHANNEL /* GPIO_AD_B0_13 GPIO1 Pin 13 */ ADC1_CH(2)
#define ADC_BATTERY2_CURRENT_CHANNEL /* GPIO_AD_B0_14 GPIO1 Pin 14 */ ADC1_CH(3)
#define ADC1_SPARE_2_CHANNEL /* GPIO_AD_B0_15 GPIO1 Pin 15 */ ADC1_CH(4)
#define ADC_HW_VER_SENSE_CHANNEL /* GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_CH(9)
#define ADC_SCALED_V5_CHANNEL /* GPIO_AD_B1_05 GPIO1 Pin 21 */ ADC1_CH(10)
#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL /* GPIO_AD_B1_06 GPIO1 Pin 22 */ ADC1_CH(11)
#define ADC_HW_REV_SENSE_CHANNEL /* GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_CH(13)
#define ADC1_SPARE_1_CHANNEL /* GPIO_AD_B1_09 GPIO1 Pin 25 */ ADC1_CH(14)
#define ADC_RSSI_IN_CHANNEL /* GPIO_AD_B1_10 GPIO1 Pin 26 */ ADC1_CH(15)
#if defined(ON_EVK)
#define ADC_CHANNELS \
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
(1 << ADC_RSSI_IN_CHANNEL) | \
(1 << ADC_SCALED_V5_CHANNEL) | \
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
(1 << ADC_HW_REV_SENSE_CHANNEL))
#else
#define ADC_CHANNELS \
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY1_CURRENT_CHANNEL) | \
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
(1 << ADC1_SPARE_2_CHANNEL) | \
(1 << ADC_RSSI_IN_CHANNEL) | \
(1 << ADC_SCALED_V5_CHANNEL) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
(1 << ADC1_SPARE_1_CHANNEL))
#endif
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (18.1f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* HW Version and Revision drive signals Default to 1 to detect */
#define BOARD_HAS_HW_VERSIONING
#define HW_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MAX | IOMUX_SLEW_FAST)
#define GPIO_HW_REV_DRIVE /* GPIO_AD_B0_00 GPIO1_IO00 */ (GPIO_PORT1 | GPIO_PIN0 | GPIO_OUTPUT | GPIO_OUTPUT_SET | HW_IOMUX)
#define GPIO_HW_REV_SENSE /* GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_GPIO(13, 24)
#define GPIO_HW_VER_DRIVE /* GPIO_AD_B0_04 GPIO1_IO04 */ (GPIO_PORT1 | GPIO_PIN4 | GPIO_OUTPUT | GPIO_OUTPUT_SET | HW_IOMUX)
#define GPIO_HW_VER_SENSE /* GPIO_AD_B1_04 GPIO1 Pin 20 */ ADC1_GPIO(9, 20)
#define HW_INFO_INIT {'V','5','x', 'x',0}
#define HW_INFO_INIT_VER 2
#define HW_INFO_INIT_REV 3
/* CAN Silence
*
* Silent mode control \ ESC Mux select
*/
#define SILENT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MAX | IOMUX_SLEW_FAST)
#define GPIO_CAN1_SILENT_S0 /* GPIO_AD_B0_10 GPIO1_IO10 */ (GPIO_PORT1 | GPIO_PIN10 | GPIO_OUTPUT | GPIO_OUTPUT_CLEAR | SILENT_IOMUX)
#define GPIO_CAN2_SILENT_S1 /* GPIO_EMC_06 GPIO4_IO06 */ (GPIO_PORT4 | GPIO_PIN6 | GPIO_OUTPUT | GPIO_OUTPUT_CLEAR | SILENT_IOMUX)
#define GPIO_CAN3_SILENT_S2 /* GPIO_EMC_09 GPIO4_IO09 */ (GPIO_PORT4 | GPIO_PIN9 | GPIO_OUTPUT | GPIO_OUTPUT_CLEAR | SILENT_IOMUX)
/* HEATER
* PWM in future
*/
#define GPIO_HEATER_OUTPUT /* GPIO_B1_09 QTIMER2_TIMER3 GPIO2 Pin 25 */ GPIO_QTIMER2_TIMER3_1
/* PWM Capture
*
* 3 PWM Capture inputs are not supported
*/
#define DIRECT_PWM_CAPTURE_CHANNELS 0
/* PWM
*
* 8 PWM outputs are configured.
*
* Pins:
*
* FMU_CH1 : GPIO_B0_06 GPIO2 Pin 6 FLEXPWM2_PWMA0
* FMU_CH2 : GPIO_EMC_08 GPIO4 Pin 8 FLEXPWM2_PWMA1
* FMU_CH3 : GPIO_EMC_10 GPIO4 Pin 10 FLEXPWM2_PWMA2
* FMU_CH4 : GPIO_AD_B0_09 GPIO1 Pin 9 FLEXPWM2_PWMA3
* FMU_CH5 : GPIO_EMC_33 GPIO3 Pin 19 FLEXPWM3_PWMA2
* FMU_CH6 : GPIO_EMC_30 GPIO4 Pin 30 FLEXPWM3_PWMB0
* FMU_CH7 : GPIO_EMC_04 GPIO4 Pin 4 FLEXPWM4_PWMA2
* FMU_CH8 : GPIO_EMC_01 GPIO4 Pin 1 FLEXPWM4_PWMB0
*
*/
#define PWM_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_50OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST)
#define PIN_FLEXPWM2_PWMA00 /* P2:6 PWM2 A0 FMU1 */ (PWM_IOMUX | GPIO_FLEXPWM2_PWMA00_2)
#define PIN_FLEXPWM2_PWMA01 /* P4:8 PWM2 A1 FMU2 */ (PWM_IOMUX | GPIO_FLEXPWM2_PWMA01_1)
#define PIN_FLEXPWM2_PWMA02 /* P4:10 PWM2 A2 FMU3 */ (PWM_IOMUX | GPIO_FLEXPWM2_PWMA02_1)
#define PIN_FLEXPWM2_PWMA03 /* P1:9 PWM2 A3 FMU4 */ (PWM_IOMUX | GPIO_FLEXPWM2_PWMA03_2)
#define PIN_FLEXPWM3_PWMA02 /* P3:19 PWM3 A2 FMU5 */ (PWM_IOMUX | GPIO_FLEXPWM3_PWMA02_1)
#define PIN_FLEXPWM3_PWMB00 /* P4:30 PWM3 B0 FMU6 */ (PWM_IOMUX | GPIO_FLEXPWM3_PWMB00_1)
#define PIN_FLEXPWM4_PWMA02 /* P4:4 PWM4 A2 FMU7 */ (PWM_IOMUX | GPIO_FLEXPWM4_PWMA02_2)
#define PIN_FLEXPWM4_PWMB00 /* P4:1 PWM4 B0 FMU8 */ (PWM_IOMUX | GPIO_FLEXPWM4_PWMB00_1)
#define DIRECT_PWM_OUTPUT_CHANNELS 8
// Input Capture not supported on MVP
#define DIRECT_INPUT_TIMER_CHANNELS 0
#define BOARD_HAS_LED_PWM 1
#define BOARD_LED_PWM_DRIVE_ACTIVE_LOW 1
/* UI LEDs are driven by timer 4 the pins have no alternates
*
* nUI_LED_RED GPIO_B0_10 QTIMER4_TIMER1
* nUI_LED_GREEN GPIO_B0_11 QTIMER4_TIMER2
* nUI_LED_BLUE GPIO_B1_11 QTIMER4_TIMER3
*/
/* User GPIOs
*
* GPIO-
* Define as GPIO input / GPIO outputs
*/
#define FMU_INPUT_IOMUX (IOMUX_SCHMITT_TRIGGER | IOMUX_PULL_UP_47K | IOMUX_DRIVE_HIZ)
#define _MK_GPIO_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|FMU_INPUT_IOMUX))
#define GPIO_GPIO0_INPUT /* P2:6 PWM2 A0 FMU1 */ (GPIO_PORT2 | GPIO_PIN6 | GPIO_INPUT | FMU_INPUT_IOMUX)
#define GPIO_GPIO1_INPUT /* P4:8 PWM2 A1 FMU2 */ (GPIO_PORT4 | GPIO_PIN8 | GPIO_INPUT | FMU_INPUT_IOMUX)
#define GPIO_GPIO2_INPUT /* P4:10 PWM2 A2 FMU3 */ (GPIO_PORT4 | GPIO_PIN10 | GPIO_INPUT | FMU_INPUT_IOMUX)
#define GPIO_GPIO3_INPUT /* P1:9 PWM2 A3 FMU4 */ (GPIO_PORT1 | GPIO_PIN9 | GPIO_INPUT | FMU_INPUT_IOMUX)
#define GPIO_GPIO4_INPUT /* P3:19 PWM3 A2 FMU5 */ (GPIO_PORT3 | GPIO_PIN19 | GPIO_INPUT | FMU_INPUT_IOMUX)
#define GPIO_GPIO5_INPUT /* P4:30 PWM3 B0 FMU6 */ (GPIO_PORT4 | GPIO_PIN30 | GPIO_INPUT | FMU_INPUT_IOMUX)
#define GPIO_GPIO6_INPUT /* P4:4 PWM4 A2 FMU7 */ (GPIO_PORT4 | GPIO_PIN4 | GPIO_INPUT | FMU_INPUT_IOMUX)
#define GPIO_GPIO7_INPUT /* P4:1 PWM4 B0 FMU8 */ (GPIO_PORT1 | GPIO_PIN1 | GPIO_INPUT | FMU_INPUT_IOMUX)
#define FMU_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_KEEP | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST)
#define _MK_GPIO_OUTPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_OUTPUT|GPIO_OUTPUT_CLEAR|FMU_OUTPUT_IOMUX))
#define GPIO_GPIO0_OUTPUT /* P2:6 PWM2 A0 FMU1 */ (GPIO_PORT2 | GPIO_PIN6 | GPIO_OUTPUT | FMU_OUTPUT_IOMUX)
#define GPIO_GPIO1_OUTPUT /* P4:8 PWM2 A1 FMU2 */ (GPIO_PORT4 | GPIO_PIN8 | GPIO_OUTPUT | FMU_OUTPUT_IOMUX)
#define GPIO_GPIO2_OUTPUT /* P4:10 PWM2 A2 FMU3 */ (GPIO_PORT4 | GPIO_PIN10 | GPIO_OUTPUT | FMU_OUTPUT_IOMUX)
#define GPIO_GPIO3_OUTPUT /* P1:9 PWM2 A3 FMU4 */ (GPIO_PORT1 | GPIO_PIN9 | GPIO_OUTPUT | FMU_OUTPUT_IOMUX)
#define GPIO_GPIO4_OUTPUT /* P3:19 PWM3 A2 FMU5 */ (GPIO_PORT3 | GPIO_PIN19 | GPIO_OUTPUT | FMU_OUTPUT_IOMUX)
#define GPIO_GPIO5_OUTPUT /* P4:30 PWM3 B0 FMU6 */ (GPIO_PORT4 | GPIO_PIN30 | GPIO_OUTPUT | FMU_OUTPUT_IOMUX)
#define GPIO_GPIO6_OUTPUT /* P4:4 PWM4 A2 FMU7 */ (GPIO_PORT4 | GPIO_PIN4 | GPIO_OUTPUT | FMU_OUTPUT_IOMUX)
#define GPIO_GPIO7_OUTPUT /* P4:1 PWM4 B0 FMU8 */ (GPIO_PORT1 | GPIO_PIN1 | GPIO_OUTPUT | FMU_OUTPUT_IOMUX)
/* Power supply control and monitoring GPIOs */
#define GENERAL_INPUT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_UP_47K | IOMUX_DRIVE_HIZ)
#define GENERAL_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_KEEP | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST)
#define GPIO_nPOWER_IN_A /* GPIO_B0_12 GPIO2_IO12 */ (GPIO_PORT2 | GPIO_PIN12 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_nPOWER_IN_B /* GPIO_B0_13 GPIO2_IO13 */ (GPIO_PORT2 | GPIO_PIN13 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_nPOWER_IN_C /* GPIO_B0_14 GPIO2_IO14 */ (GPIO_PORT2 | GPIO_PIN14 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */
#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */
#define BOARD_NUMBER_BRICKS 2
#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */
#define GPIO_nVDD_5V_PERIPH_EN /* GPIO_B1_03 GPIO2_IO19 */ (GPIO_PORT2 | GPIO_PIN19 | GPIO_OUTPUT | GENERAL_OUTPUT_IOMUX)
#define GPIO_nVDD_5V_PERIPH_OC /* GPIO_B1_04 GPIO2_IO20 */ (GPIO_PORT2 | GPIO_PIN20 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_nVDD_5V_HIPOWER_EN /* GPIO_B1_01 GPIO2_IO17 */ (GPIO_PORT2 | GPIO_PIN17 | GPIO_OUTPUT | GENERAL_OUTPUT_IOMUX)
#define GPIO_nVDD_5V_HIPOWER_OC /* GPIO_B1_02 GPIO2_IO18 */ (GPIO_PORT2 | GPIO_PIN18 | GPIO_INPUT | GENERAL_INPUT_IOMUX)
#define GPIO_VDD_3V3_SENSORS_EN /* PMIC_STBY_REQ GPIO5_IO02 */ (GPIO_PORT5 | GPIO_PIN2 | GPIO_OUTPUT | GENERAL_OUTPUT_IOMUX)
#define GPIO_VDD_3V3_SD_CARD_EN /* PMIC_ON_REQ GPIO5_IO01 */ (GPIO_PORT5 | GPIO_PIN1 | GPIO_OUTPUT | GENERAL_OUTPUT_IOMUX)
/* Define True logic Power Control in arch agnostic form */
#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, !(on_true))
#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_VDD_3V3_SENSORS_EN, (on_true))
#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true))
/* Tone alarm output */
#if !defined(ON_EVK)
#define TONE_ALARM_TIMER 2 /* GPT 2 */
#define TONE_ALARM_CHANNEL 3 /* GPIO_AD_B1_07 GPT2_COMPARE3 */
#define GPIO_BUZZER_1 /* GPIO_AD_B1_07 GPIO1 Pin 23 */ (GPIO_PORT1 | GPIO_PIN23 | GPIO_OUTPUT | GENERAL_OUTPUT_IOMUX)
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
#define GPIO_TONE_ALARM GPIO_GPT2_COMPARE3
#endif
/* USB OTG FS
*
* VBUS_VALID is detected in USB_ANALOG_USB1_VBUS_DETECT_STAT
*/
/* High-resolution timer */
#define HRT_TIMER 1 /* use GPT1 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
#define HRT_PPM_CHANNEL /* GPT1_CAPTURE2 */ 2 /* use capture/compare channel 2 */
#define GPIO_PPM_IN /* GPT1_CAPTURE2 */ (GPIO_GPT1_CAPTURE2_1 | GENERAL_INPUT_IOMUX)
#if defined(ON_EVK)
#define BOARD_HAS_SINGLE_WIRE 1 /* HW is capable of Single Wire */
#else
#define RC_UXART_BASE IMXRT_LPUART6_BASE
#define RC_SERIAL_PORT "/dev/ttyS4"
#define BOARD_HAS_SINGLE_WIRE 1 /* HW is capable of Single Wire */
#define BOARD_HAS_SINGLE_WIRE_ON_TX 1 /* HW default is wired as Single Wire On TX pin */
#define BOARD_HAS_RX_TX_SWAP 0 /* HW Can swap TX and RX */
#define RC_SERIAL_PORT_IS_SWAPED 0 /* Board wired with RC's TX is on cpu RX */
#endif
/* PWM input driver. Use FMU AUX5 pins attached to GPIO_EMC_33 GPIO3 Pin 19 FLEXPWM3_PWMA2 */
#define PWMIN_TIMER /* FLEXPWM3_PWMA2 */ 3
#define PWMIN_TIMER_CHANNEL /* FLEXPWM3_PWMA2 */ 2
#define GPIO_PWM_IN /* GPIO_EMC_33 GPIO3 Pin 19 */ FLEXPWM3_PWMA2
/* Shared pins Both FMU and PX4IO control/monitor
* FMU Initializes these pins to passive input until it is known
* if we have and PX4IO on board
*/
#define GPIO_RSSI_IN /* GPIO_AD_B1_10 GPIO1 Pin 26 */ (GPIO_PORT1 | GPIO_PIN26 | GPIO_INPUT | ADC_IOMUX)
#define GPIO_RSSI_IN_INIT /* GPIO1 Pin 26 */ 0 /* Using 0 will Leave as ADC RSSI_IN */
/* Safety Switch is HW version dependent on having an PX4IO
* So we init to a benign state with the _INIT definition
* and provide the the non _INIT one for the driver to make a run time
* decision to use it.
*/
#define SAFETY_INIT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ)
#define SAFETY_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_SLOW)
#define SAFETY_SW_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_UP_22K | IOMUX_DRIVE_HIZ)
#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* GPIO_B0_15 GPIO2_IO15 */ (GPIO_PORT2 | GPIO_PIN15 | GPIO_INPUT | SAFETY_INIT_IOMUX)
#define GPIO_nSAFETY_SWITCH_LED_OUT /* GPIO_B0_15 GPIO2_IO15 */ (GPIO_PORT2 | GPIO_PIN15 | GPIO_OUTPUT | SAFETY_IOMUX)
/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */
#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT
#define GPIO_SAFETY_SWITCH_IN /* GPIO_AD_B1_12 GPIO1_IO28 */ (GPIO_PORT1 | GPIO_PIN28 | GPIO_INPUT | SAFETY_SW_IOMUX)
/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */
#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */
/*
* FMUv5 has a separate RC_IN
*
* GPIO PPM_IN on GPIO_EMC_23 GPIO4 Pin 23 GPT1_CAPTURE2
* Inversion is possible in the UART and can drive GPIO PPM_IN as an output
*/
#define GPIO_PPM_IN_AS_OUT /* GPIO_EMC_23 GPIO4 Pin 23 GPT1_CAPTURE2 */ (GPIO_PORT4 | GPIO_PIN23 | GPIO_OUTPUT | GENERAL_OUTPUT_IOMUX)
#define SDIO_SLOTNO 0 /* Only one slot */
#define SDIO_MINOR 0
/* SD card bringup does not work if performed on the IDLE thread because it
* will cause waiting. Use either:
*
* CONFIG_LIB_BOARDCTL=y, OR
* CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y
*/
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && \
!defined(CONFIG_BOARD_INITTHREAD)
# warning SDIO initialization cannot be perfomed on the IDLE thread
#endif
/* 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_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID))
#define BOARD_ADC_USB_CONNECTED (board_read_VBUS_state() == 0)
/* FMUv5 never powers odd the Servo rail */
#define BOARD_ADC_SERVO_VALID (1)
#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
#define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID))
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_PERIPH_OC))
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_HIPOWER_OC))
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/* 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
/* The list of GPIO that will be initialized */
#define PX4_GPIO_PWM_INIT_LIST { \
GPIO_GPIO7_INPUT, \
GPIO_GPIO6_INPUT, \
GPIO_GPIO5_INPUT, \
GPIO_GPIO4_INPUT, \
GPIO_GPIO3_INPUT, \
GPIO_GPIO2_INPUT, \
GPIO_GPIO1_INPUT, \
GPIO_GPIO0_INPUT, \
}
#if defined(ON_EVK)
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
}
#else
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_HW_REV_DRIVE, \
GPIO_HW_VER_DRIVE, \
GPIO_FLEXCAN1_TX, \
GPIO_FLEXCAN1_RX, \
GPIO_FLEXCAN2_TX, \
GPIO_FLEXCAN2_RX, \
GPIO_FLEXCAN3_TX, \
GPIO_FLEXCAN3_RX, \
GPIO_CAN1_SILENT_S0, \
GPIO_CAN2_SILENT_S1, \
GPIO_CAN3_SILENT_S2, \
GPIO_HEATER_OUTPUT, \
GPIO_nPOWER_IN_A, \
GPIO_nPOWER_IN_B, \
GPIO_nPOWER_IN_C, \
GPIO_nVDD_5V_PERIPH_EN, \
GPIO_nVDD_5V_PERIPH_OC, \
GPIO_nVDD_5V_HIPOWER_EN, \
GPIO_nVDD_5V_HIPOWER_OC, \
GPIO_VDD_3V3_SENSORS_EN, \
GPIO_VDD_3V3_SD_CARD_EN, \
GPIO_TONE_ALARM_IDLE, \
GPIO_RSSI_IN_INIT, \
GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \
GPIO_SAFETY_SWITCH_IN \
}
#endif //defined(ON_EVK)
#define BOARD_ENABLE_CONSOLE_BUFFER
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: fmurt1062_usdhc_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int fmurt1062_usdhc_initialize(void);
/****************************************************************************************************
* Name: imxrt_spidev_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
*
****************************************************************************************************/
extern void imxrt_spidev_initialize(void);
/************************************************************************************
* Name: imxrt_spi_bus_initialize
*
* Description:
* Called to configure SPI Buses.
*
************************************************************************************/
extern int imxrt1062_spi_bus_initialize(void);
/************************************************************************************
* Name: imxrt_usb_initialize
*
* Description:
* Called to configure USB.
*
************************************************************************************/
extern int imxrt_usb_initialize(void);
void board_spi_reset(int ms);
extern void imxrt_usbinitialize(void);
extern void board_peripheral_reset(int ms);
extern void fmurt1062_timer_initialize(void);
/****************************************************************************
* Name: nsh_archinitialize
*
* Description:
* Perform architecture specific initialization for NSH.
*
* CONFIG_NSH_ARCHINIT=y :
* Called from the NSH library
*
* CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
* CONFIG_NSH_ARCHINIT=n :
* Called from board_initialize().
*
****************************************************************************/
#ifdef CONFIG_NSH_LIBRARY
int nsh_archinitialize(void);
#endif
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS

View File

@@ -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 <px4_platform_common/px4_config.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/can/can.h>
#include <arch/board/board.h>
#include <chip.h>
#include "up_arch.h"
#include "board_config.h"
#ifdef CONFIG_CAN
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Configuration ********************************************************************/
#if defined(CONFIG_IMXRT_FLEXCAN1) && defined(CONFIG_IMXRT_FLEXCAN2) \
&& defined(CONFIG_IMXRT_FLEXCAN3)
# warning "CAN1 and CAN2 and CAN2 are enabled. Assuming only CAN1."
#endif
#ifdef CONFIG_IMXRT_FLEXCAN1
# 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 imxrt_caninitialize() to get an instance of the CAN interface */
can = imxrt_can_initialize(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

View File

@@ -0,0 +1,64 @@
/****************************************************************************
* config/imxrt1060-evk/src/imxrt_flexspi_nor_boot.c
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Ivan Ucherdzhiev <ivanucherdjiev@gmail.com>
*
* 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 "imxrt_flexspi_nor_boot.h"
/****************************************************************************
* Public Data
****************************************************************************/
__attribute__((section(".boot_hdr.ivt")))
const struct ivt_s image_vector_table = {
IVT_HEADER, /* IVT Header */
0x60002000, /* Image Entry Function */
IVT_RSVD, /* Reserved = 0 */
(uint32_t)DCD_ADDRESS, /* Address where DCD information is stored */
(uint32_t)BOOT_DATA_ADDRESS, /* Address where BOOT Data Structure is stored */
(uint32_t) &image_vector_table, /* Pointer to IVT Self (absolute address */
(uint32_t)CSF_ADDRESS, /* Address where CSF file is stored */
IVT_RSVD /* Reserved = 0 */
};
__attribute__((section(".boot_hdr.boot_data")))
const struct boot_data_s boot_data = {
FLASH_BASE, /* boot start location */
(FLASH_END - FLASH_BASE), /* size */
PLUGIN_FLAG, /* Plugin flag*/
0xFFFFFFFF /* empty - extra data word */
};

View File

@@ -0,0 +1,147 @@
/****************************************************************************
* config/imxrt1060-evk/src/imxrt_flexspi_nor_boot.h
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Authors: Ivan Ucherdzhiev <ivanucherdjiev@gmail.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* 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 __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H
#define __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* IVT Data */
#define IVT_MAJOR_VERSION 0x4
#define IVT_MAJOR_VERSION_SHIFT 0x4
#define IVT_MAJOR_VERSION_MASK 0xf
#define IVT_MINOR_VERSION 0x1
#define IVT_MINOR_VERSION_SHIFT 0x0
#define IVT_MINOR_VERSION_MASK 0xf
#define IVT_VERSION(major, minor) \
((((major) & IVT_MAJOR_VERSION_MASK) << IVT_MAJOR_VERSION_SHIFT) | \
(((minor) & IVT_MINOR_VERSION_MASK) << IVT_MINOR_VERSION_SHIFT))
#define IVT_TAG_HEADER (0xd1) /* Image Vector Table */
#define IVT_SIZE 0x2000
#define IVT_PAR IVT_VERSION(IVT_MAJOR_VERSION, IVT_MINOR_VERSION)
#define IVT_HEADER (IVT_TAG_HEADER | (IVT_SIZE << 8) | (IVT_PAR << 24))
#define IVT_RSVD (uint32_t)(0x00000000)
/* DCD Data */
#define DCD_TAG_HEADER (0xd2)
#define DCD_TAG_HEADER_SHIFT (24)
#define DCD_VERSION (0x40)
#define DCD_ARRAY_SIZE 1
#define FLASH_BASE 0x60000000
#define FLASH_END 0x7f7fffff
#define SCLK 1
#define DCD_ADDRESS 0
#define BOOT_DATA_ADDRESS &boot_data
#define CSF_ADDRESS 0
#define PLUGIN_FLAG (uint32_t)0
/****************************************************************************
* Public Types
****************************************************************************/
/* IVT Data */
struct ivt_s {
/* Header with tag #HAB_TAG_IVT, length and HAB version fields
* (see data)
*/
uint32_t hdr;
/* Absolute address of the first instruction to execute from the
* image
*/
uint32_t entry;
/* Reserved in this version of HAB: should be NULL. */
uint32_t reserved1;
/* Absolute address of the image DCD: may be NULL. */
uint32_t dcd;
/* Absolute address of the Boot Data: may be NULL, but not interpreted
* any further by HAB
*/
uint32_t boot_data;
/* Absolute address of the IVT.*/
uint32_t self;
/* Absolute address of the image CSF.*/
uint32_t csf;
/* Reserved in this version of HAB: should be zero. */
uint32_t reserved2;
};
/* Boot Data */
struct boot_data_s {
uint32_t start; /* boot start location */
uint32_t size; /* size */
uint32_t plugin; /* plugin flag - 1 if downloaded application is plugin */
uint32_t placeholder; /* placehoder to make even 0x10 size */
};
/****************************************************************************
* Public Data
****************************************************************************/
extern const struct boot_data_s boot_data;
#endif /* __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H */

View File

@@ -0,0 +1,198 @@
/****************************************************************************
* config/imxrt1060-evk/src/imxrt_flexspi_nor_flash.c
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Authors: Ivan Ucherdzhiev <ivanucherdjiev@gmail.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* 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 "imxrt_flexspi_nor_flash.h"
/*******************************************************************************
* Public Data
******************************************************************************/
#if defined (CONFIG_NXP_FMURT1062_V3_HYPER_FLASH)
__attribute__((section(".boot_hdr.conf")))
const struct flexspi_nor_config_s flash_config = {
.mem_config =
{
.tag = FLEXSPI_CFG_BLK_TAG,
.version = FLEXSPI_CFG_BLK_VERSION,
.read_sample_clksrc = FLASH_READ_SAMPLE_CLK_EXTERNALINPUT_FROM_DQSPAD,
.cs_hold_time = 3u,
.cs_setup_time = 3u,
.column_address_width = 3u,
/* Enable DDR mode, Word addassable, Safe configuration, Differential clock */
.controller_misc_option = (1u << FLEXSPIMISC_OFFSET_DDR_MODE_EN) |
(1u << FLEXSPIMISC_OFFSET_WORD_ADDRESSABLE_EN) |
(1u << FLEXSPIMISC_OFFSET_SAFECONFIG_FREQ_EN) |
(1u << FLEXSPIMISC_OFFSET_DIFFCLKEN),
.sflash_pad_type = SERIAL_FLASH_8PADS,
.serial_clk_freq = FLEXSPI_SERIAL_CLKFREQ_133MHz,
.sflash_a1size = 64u * 1024u * 1024u,
.data_valid_time = {16u, 16u},
.lookup_table =
{
/* Read LUTs */
FLEXSPI_LUT_SEQ(CMD_DDR, FLEXSPI_8PAD, 0xA0, RADDR_DDR, FLEXSPI_8PAD, 0x18),
FLEXSPI_LUT_SEQ(CADDR_DDR, FLEXSPI_8PAD, 0x10, DUMMY_DDR, FLEXSPI_8PAD, 0x06),
FLEXSPI_LUT_SEQ(READ_DDR, FLEXSPI_8PAD, 0x04, STOP, FLEXSPI_1PAD, 0x0),
},
},
.page_size = 512u,
.sector_size = 256u * 1024u,
.blocksize = 256u * 1024u,
.is_uniform_blocksize = 1,
};
#elif defined (CONFIG_NXP_FMURT1062_V3_QSPI_FLASH)
__attribute__((section(".boot_hdr.conf")))
const struct flexspi_nor_config_s flash_config = {
.mem_config =
{
.tag = FLEXSPI_CFG_BLK_TAG,
.version = FLEXSPI_CFG_BLK_VERSION,
.read_sample_clksrc = FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_SCKPAD,
.cs_hold_time = 3u,
.cs_setup_time = 3u,
.column_address_width = 0u,
.device_type = FLEXSPI_DEVICE_TYPE_SERIAL_NOR,
.sflash_pad_type = SERIAL_FLASH_4PADS,
.serial_clk_freq = FLEXSPI_SERIAL_CLKFREQ_60MHz,
.sflash_a1size = 8u * 1024u * 1024u,
.data_valid_time = {16u, 16u},
.lookup_table =
{
/* LUTs */
/* 0 Fast read Quad IO DTR Mode Operation in SPI Mode (normal read)*/
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xED, RADDR_DDR, FLEXSPI_4PAD, 0x18),
FLEXSPI_LUT_SEQ(DUMMY_DDR, FLEXSPI_4PAD, 0x0C, READ_DDR, FLEXSPI_4PAD, 0x08),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
/* 1 Read Status */
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x05, READ_SDR, FLEXSPI_1PAD, 0x1),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
/* 2 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 3 */
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x06, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
/* 4 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 5 Erase Sector */
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xD7, RADDR_SDR, FLEXSPI_1PAD, 0x18),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
/* 6 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 7 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 8 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 9 Page Program */
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x02, RADDR_SDR, FLEXSPI_1PAD, 0x18),
FLEXSPI_LUT_SEQ(WRITE_SDR, FLEXSPI_1PAD, 0x8, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
/* 10 */
0x00000000,
0x00000000,
0x00000000,
0x00000000,
/* 11 Chip Erase */
FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xC7, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
FLEXSPI_LUT_SEQ(STOP, FLEXSPI_1PAD, 0x0, STOP, FLEXSPI_1PAD, 0x0),
},
},
.page_size = 256u,
.sector_size = 4u * 1024u,
.blocksize = 32u * 1024u,
.is_uniform_blocksize = false,
};
#else
# error Boot Flash type not chosen!
#endif

View File

@@ -0,0 +1,349 @@
/****************************************************************************
* config/imxrt1060-evk/src/imxrt_flexspi_nor_flash.h
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Authors: Ivan Ucherdzhiev <ivanucherdjiev@gmail.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* 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 __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H
#define __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdint.h>
#include <stdbool.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* FLEXSPI memory config block related defintions */
#define FLEXSPI_CFG_BLK_TAG (0x42464346ul)
#define FLEXSPI_CFG_BLK_VERSION (0x56010400ul)
#define FLEXSPI_CFG_BLK_SIZE (512)
/* FLEXSPI Feature related definitions */
#define FLEXSPI_FEATURE_HAS_PARALLEL_MODE 1
/* Lookup table related defintions */
#define CMD_INDEX_READ 0
#define CMD_INDEX_READSTATUS 1
#define CMD_INDEX_WRITEENABLE 2
#define CMD_INDEX_WRITE 4
#define CMD_LUT_SEQ_IDX_READ 0
#define CMD_LUT_SEQ_IDX_READSTATUS 1
#define CMD_LUT_SEQ_IDX_WRITEENABLE 3
#define CMD_LUT_SEQ_IDX_WRITE 9
#define CMD_SDR 0x01
#define CMD_DDR 0x21
#define RADDR_SDR 0x02
#define RADDR_DDR 0x22
#define CADDR_SDR 0x03
#define CADDR_DDR 0x23
#define MODE1_SDR 0x04
#define MODE1_DDR 0x24
#define MODE2_SDR 0x05
#define MODE2_DDR 0x25
#define MODE4_SDR 0x06
#define MODE4_DDR 0x26
#define MODE8_SDR 0x07
#define MODE8_DDR 0x27
#define WRITE_SDR 0x08
#define WRITE_DDR 0x28
#define READ_SDR 0x09
#define READ_DDR 0x29
#define LEARN_SDR 0x0a
#define LEARN_DDR 0x2a
#define DATSZ_SDR 0x0b
#define DATSZ_DDR 0x2b
#define DUMMY_SDR 0x0c
#define DUMMY_DDR 0x2c
#define DUMMY_RWDS_SDR 0x0d
#define DUMMY_RWDS_DDR 0x2d
#define JMP_ON_CS 0x1f
#define STOP 0
#define FLEXSPI_1PAD 0
#define FLEXSPI_2PAD 1
#define FLEXSPI_4PAD 2
#define FLEXSPI_8PAD 3
#define FLEXSPI_LUT_OPERAND0_MASK (0xffu)
#define FLEXSPI_LUT_OPERAND0_SHIFT (0U)
#define FLEXSPI_LUT_OPERAND0(x) (((uint32_t) \
(((uint32_t)(x)) << FLEXSPI_LUT_OPERAND0_SHIFT)) & \
FLEXSPI_LUT_OPERAND0_MASK)
#define FLEXSPI_LUT_NUM_PADS0_MASK (0x300u)
#define FLEXSPI_LUT_NUM_PADS0_SHIFT (8u)
#define FLEXSPI_LUT_NUM_PADS0(x) (((uint32_t) \
(((uint32_t)(x)) << FLEXSPI_LUT_NUM_PADS0_SHIFT)) & \
FLEXSPI_LUT_NUM_PADS0_MASK)
#define FLEXSPI_LUT_OPCODE0_MASK (0xfc00u)
#define FLEXSPI_LUT_OPCODE0_SHIFT (10u)
#define FLEXSPI_LUT_OPCODE0(x) (((uint32_t) \
(((uint32_t)(x)) << FLEXSPI_LUT_OPCODE0_SHIFT)) & \
FLEXSPI_LUT_OPCODE0_MASK)
#define FLEXSPI_LUT_OPERAND1_MASK (0xff0000u)
#define FLEXSPI_LUT_OPERAND1_SHIFT (16U)
#define FLEXSPI_LUT_OPERAND1(x) (((uint32_t) \
(((uint32_t)(x)) << FLEXSPI_LUT_OPERAND1_SHIFT)) & \
FLEXSPI_LUT_OPERAND1_MASK)
#define FLEXSPI_LUT_NUM_PADS1_MASK (0x3000000u)
#define FLEXSPI_LUT_NUM_PADS1_SHIFT (24u)
#define FLEXSPI_LUT_NUM_PADS1(x) (((uint32_t) \
(((uint32_t)(x)) << FLEXSPI_LUT_NUM_PADS1_SHIFT)) & \
FLEXSPI_LUT_NUM_PADS1_MASK)
#define FLEXSPI_LUT_OPCODE1_MASK (0xfc000000u)
#define FLEXSPI_LUT_OPCODE1_SHIFT (26u)
#define FLEXSPI_LUT_OPCODE1(x) (((uint32_t)(((uint32_t)(x)) << FLEXSPI_LUT_OPCODE1_SHIFT)) & \
FLEXSPI_LUT_OPCODE1_MASK)
#define FLEXSPI_LUT_SEQ(cmd0, pad0, op0, cmd1, pad1, op1) \
(FLEXSPI_LUT_OPERAND0(op0) | FLEXSPI_LUT_NUM_PADS0(pad0) | \
FLEXSPI_LUT_OPCODE0(cmd0) | FLEXSPI_LUT_OPERAND1(op1) | \
FLEXSPI_LUT_NUM_PADS1(pad1) | FLEXSPI_LUT_OPCODE1(cmd1))
/* */
#define NOR_CMD_INDEX_READ CMD_INDEX_READ
#define NOR_CMD_INDEX_READSTATUS CMD_INDEX_READSTATUS
#define NOR_CMD_INDEX_WRITEENABLE CMD_INDEX_WRITEENABLE
#define NOR_CMD_INDEX_ERASESECTOR 3
#define NOR_CMD_INDEX_PAGEPROGRAM CMD_INDEX_WRITE
#define NOR_CMD_INDEX_CHIPERASE 5
#define NOR_CMD_INDEX_DUMMY 6
#define NOR_CMD_INDEX_ERASEBLOCK 7
/* READ LUT sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_READ CMD_LUT_SEQ_IDX_READ
/* Read Status LUT sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_READSTATUS CMD_LUT_SEQ_IDX_READSTATUS
/* 2 Read status DPI/QPI/OPI sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_READSTATUS_XPI 2
/* 3 Write Enable sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_WRITEENABLE CMD_LUT_SEQ_IDX_WRITEENABLE
/* 4 Write Enable DPI/QPI/OPI sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_WRITEENABLE_XPI 4
/* 5 Erase Sector sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_ERASESECTOR 5
/* 8 Erase Block sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_ERASEBLOCK 8
/* 9 Program sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_PAGEPROGRAM CMD_LUT_SEQ_IDX_WRITE
/* 11 Chip Erase sequence in lookupTable id stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_CHIPERASE 11
/* 13 Read SFDP sequence in lookupTable id stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_READ_SFDP 13
/* 14 Restore 0-4-4/0-8-8 mode sequence id in lookupTable stored in config block */
#define NOR_CMD_LUT_SEQ_IDX_RESTORE_NOCMD 14
/* 15 Exit 0-4-4/0-8-8 mode sequence id in lookupTable stored in config blobk */
#define NOR_CMD_LUT_SEQ_IDX_EXIT_NOCMD 15
/****************************************************************************
* Public Types
****************************************************************************/
/* Definitions for FlexSPI Serial Clock Frequency */
enum flexspi_serial_clkfreq_e {
FLEXSPI_SERIAL_CLKFREQ_30MHz = 1,
FLEXSPI_SERIAL_CLKFREQ_50MHz = 2,
FLEXSPI_SERIAL_CLKFREQ_60MHz = 3,
FLEXSPI_SERIAL_CLKFREQ_75MHz = 4,
FLEXSPI_SERIAL_CLKFREQ_80MHz = 5,
FLEXSPI_SERIAL_CLKFREQ_100MHz = 6,
FLEXSPI_SERIAL_CLKFREQ_133MHz = 7,
FLEXSPI_SERIAL_CLKFREQ_166MHz = 8,
FLEXSPI_SERIAL_CLKFREQ_200MHz = 9,
};
/* FlexSPI clock configuration type*/
enum flexspi_serial_clockmode_e {
FLEXSPI_CLKMODE_SDR,
FLEXSPI_CLKMODE_DDR,
};
/* FlexSPI Read Sample Clock Source definition */
enum flash_read_sample_clk_e {
FLASH_READ_SAMPLE_CLK_LOOPBACK_INTERNELLY = 0,
FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_DQSPAD = 1,
FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_SCKPAD = 2,
FLASH_READ_SAMPLE_CLK_EXTERNALINPUT_FROM_DQSPAD = 3,
};
/* Misc feature bit definitions */
enum flash_misc_feature_e {
FLEXSPIMISC_OFFSET_DIFFCLKEN = 0, /* Bit for Differential clock enable */
FLEXSPIMISC_OFFSET_CK2EN = 1, /* Bit for CK2 enable */
FLEXSPIMISC_OFFSET_PARALLELEN = 2, /* Bit for Parallel mode enable */
FLEXSPIMISC_OFFSET_WORD_ADDRESSABLE_EN = 3, /* Bit for Word Addressable enable */
FLEXSPIMISC_OFFSET_SAFECONFIG_FREQ_EN = 4, /* Bit for Safe Configuration Frequency enable */
FLEXSPIMISC_OFFSET_PAD_SETTING_OVERRIDE_EN = 5, /* Bit for Pad setting override enable */
FLEXSPIMISC_OFFSET_DDR_MODE_EN = 6, /* Bit for DDR clock confiuration indication. */
};
/* Flash Type Definition */
enum flash_flash_type_e {
FLEXSPI_DEVICE_TYPE_SERIAL_NOR = 1, /* Flash devices are Serial NOR */
FLEXSPI_DEVICE_TYPE_SERIAL_NAND = 2, /* Flash devices are Serial NAND */
FLEXSPI_DEVICE_TYPE_SERIAL_RAM = 3, /* Flash devices are Serial RAM/HyperFLASH */
FLEXSPI_DEVICE_TYPE_MCP_NOR_NAND = 0x12, /* Flash device is MCP device, A1 is Serial NOR, A2 is Serial NAND */
FLEXSPI_DEVICE_TYPE_MCP_NOR_RAM = 0x13, /* Flash deivce is MCP device, A1 is Serial NOR, A2 is Serial RAMs */
};
/* Flash Pad Definitions */
enum flash_flash_pad_e {
SERIAL_FLASH_1PAD = 1,
SERIAL_FLASH_2PADS = 2,
SERIAL_FLASH_4PADS = 4,
SERIAL_FLASH_8PADS = 8,
};
/* Flash Configuration Command Type */
enum flash_config_cmd_e {
DEVICE_CONFIG_CMD_TYPE_GENERIC, /* Generic command, for example: configure dummy cycles, drive strength, etc */
DEVICE_CONFIG_CMD_TYPE_QUADENABLE, /* Quad Enable command */
DEVICE_CONFIG_CMD_TYPE_SPI2XPI, /* Switch from SPI to DPI/QPI/OPI mode */
DEVICE_CONFIG_CMD_TYPE_XPI2SPI, /* Switch from DPI/QPI/OPI to SPI mode */
DEVICE_CONFIG_CMD_TYPE_SPI2NO_CMD, /* Switch to 0-4-4/0-8-8 mode */
DEVICE_CONFIG_CMD_TYPE_RESET, /* Reset device command */
};
/* FlexSPI LUT Sequence structure */
struct flexspi_lut_seq_s {
uint8_t seq_num; /* Sequence Number, valid number: 1-16 */
uint8_t seq_id; /* Sequence Index, valid number: 0-15 */
uint16_t reserved;
};
/* FlexSPI Memory Configuration Block */
struct flexspi_mem_config_s {
uint32_t tag;
uint32_t version;
uint32_t reserved0;
uint8_t read_sample_clksrc;
uint8_t cs_hold_time;
uint8_t cs_setup_time;
uint8_t column_address_width; /* [0x00f-0x00f] Column Address with, for
* HyperBus protocol, it is fixed to 3, For
* Serial NAND, need to refer to datasheet */
uint8_t device_mode_cfg_enable;
uint8_t device_mode_type;
uint16_t wait_time_cfg_commands;
struct flexspi_lut_seq_s device_mode_seq;
uint32_t device_mode_arg;
uint8_t config_cmd_enable;
uint8_t config_mode_type[3];
struct flexspi_lut_seq_s config_cmd_seqs[3];
uint32_t reserved1;
uint32_t config_cmd_args[3];
uint32_t reserved2;
uint32_t controller_misc_option;
uint8_t device_type;
uint8_t sflash_pad_type;
uint8_t serial_clk_freq;
uint8_t lut_custom_seq_enable;
uint32_t reserved3[2];
uint32_t sflash_a1size;
uint32_t sflash_a2size;
uint32_t sflash_b1size;
uint32_t sflash_b2size;
uint32_t cspad_setting_override;
uint32_t sclkpad_setting_override;
uint32_t datapad_setting_override;
uint32_t dqspad_setting_override;
uint32_t timeout_in_ms;
uint32_t command_interval;
uint16_t data_valid_time[2];
uint16_t busy_offset;
uint16_t busybit_polarity;
uint32_t lookup_table[64];
struct flexspi_lut_seq_s lut_customseq[12];
uint32_t reserved4[4];
};
/* Serial NOR configuration block */
struct flexspi_nor_config_s {
struct flexspi_mem_config_s mem_config; /* Common memory configuration info via FlexSPI */
uint32_t page_size; /* Page size of Serial NOR */
uint32_t sector_size; /* Sector size of Serial NOR */
uint8_t ipcmd_serial_clkfreq; /* Clock frequency for IP command */
uint8_t is_uniform_blocksize; /* Sector/Block size is the same */
uint8_t reserved0[2]; /* Reserved for future use */
uint8_t serial_nor_type; /* Serial NOR Flash type: 0/1/2/3 */
uint8_t need_exit_nocmdmode; /* Need to exit NoCmd mode before other IP command */
uint8_t halfclk_for_nonreadcmd; /* Half the Serial Clock for non-read command: true/false */
uint8_t need_restore_nocmdmode; /* Need to Restore NoCmd mode after IP commmand execution */
uint32_t blocksize; /* Block size */
uint32_t reserve2[11]; /* Reserved for future use */
};
#endif /* __CONFIGS_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H */

View File

@@ -0,0 +1,348 @@
/****************************************************************************
*
* Copyright (c) 2018-2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file init.c
*
* NXP imxrt1062-v1 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 "board_config.h"
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/config.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
#include <nuttx/mm/gran.h>
#include "up_arch.h"
#include <chip.h>
#include "board_config.h"
#include <hardware/imxrt_lpuart.h>
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <px4_platform/board_determine_hw_info.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/*
* 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
/************************************************************************************
* Name: board_rc_input
*
* Description:
* All boards my optionally provide this API to invert the Serial RC input.
* This is needed on SoCs that support the notion RXINV or TXINV as apposed to
* and external XOR controlled by a GPIO
*
************************************************************************************/
__EXPORT void board_rc_input(bool invert_on, uint32_t uxart_base)
{
irqstate_t irqstate = px4_enter_critical_section();
uint32_t cr = getreg32(IMXRT_LPUART_CTRL_OFFSET + uxart_base);
uint32_t sr = getreg32(IMXRT_LPUART_STAT_OFFSET + uxart_base);
uint32_t regval = cr;
/* RXINV bit field can only be written when the receiver is disabled (RE=0). */
regval &= ~LPUART_CTRL_RE;
putreg32(regval, IMXRT_LPUART_CTRL_OFFSET + uxart_base);
if (invert_on) {
cr |= LPUART_CTRL_TXINV;
sr |= LPUART_STAT_RXINV;
} else {
cr &= ~LPUART_CTRL_TXINV;
sr &= ~LPUART_STAT_RXINV;
}
putreg32(sr, IMXRT_LPUART_STAT_OFFSET + uxart_base);
putreg32(cr, IMXRT_LPUART_CTRL_OFFSET + uxart_base);
leave_critical_section(irqstate);
}
/************************************************************************************
* Name: board_peripheral_reset
*
* Description:
*
************************************************************************************/
__EXPORT void board_peripheral_reset(int ms)
{
/* set the peripheral rails off */
VDD_5V_PERIPH_EN(false);
VDD_3V3_SENSORS_EN(false);
/* wait for the peripheral rail to reach GND */
usleep(ms * 1000);
syslog(LOG_DEBUG, "reset done, %d ms", ms);
/* re-enable power */
/* switch the peripheral rail back on */
VDD_3V3_SENSORS_EN(true);
VDD_5V_PERIPH_EN(true);
}
/************************************************************************************
* 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
*
************************************************************************************/
__EXPORT void board_on_reset(int status)
{
/* configure the GPIO pins to outputs and keep them low */
const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
if (status >= 0) {
up_mdelay(6);
}
}
/****************************************************************************
* Name: imxrt_boardinitialize
*
* Description:
* All i.MX RT architectures must provide the following entry point. This
* entry point is called early in the initialization -- after clocking and
* memory have been configured but before caches have been enabled and
* before any devices have been initialized.
*
****************************************************************************/
__EXPORT void imxrt_boardinitialize(void)
{
board_on_reset(-1); /* Reset PWM first thing */
/* configure LEDs */
board_autoled_initialize();
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */
imxrt_spidev_initialize();
imxrt_usb_initialize();
fmurt1062_timer_initialize();
}
/****************************************************************************
* 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)
{
/* Power on Interfaces */
VDD_3V3_SD_CARD_EN(true);
VDD_5V_PERIPH_EN(true);
VDD_5V_HIPOWER_EN(true);
VDD_3V3_SENSORS_EN(true);
if (OK == board_determine_hw_info()) {
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
board_get_hw_type_name());
} else {
syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n");
}
px4_platform_init();
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "[boot] 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)imxrt_serial_dma_poll,
NULL);
#endif
/* initial LED state */
drv_led_start();
led_off(LED_RED);
led_off(LED_GREEN);
led_off(LED_BLUE);
#if defined(ON_EVK_SDIO) && defined(CONFIG_IMXRT_USDHC)
int ret = fmurt1062_usdhc_initialize();
if (ret != OK) {
board_autoled_on(LED_RED);
return ret;
}
#endif
#if defined(ON_EVK_SPI)
/* Configure SPI-based devices */
ret = imxrt1062_spi_bus_initialize();
if (ret != OK) {
board_autoled_on(LED_RED);
return ret
}
#endif
return OK;
}
// USB Stubs
#include <nuttx/usb/usbdev.h>
void up_usbinitialize(void)
{
}
int usbdev_register(struct usbdevclass_driver_s *driver)
{
return -EINVAL;
}
int usbdev_unregister(struct usbdevclass_driver_s *driver)
{
return -EINVAL;
}
#if defined(ON_EVK)
# if !defined(CONFIG_IMXRT_LPI2C)
FAR struct i2c_master_s *imxrt_i2cbus_initialize(int port)
{
return 0;
}
int imxrt_i2cbus_uninitialize(FAR struct i2c_master_s *dev)
{
return 0;
}
# endif
#endif

View File

@@ -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 fmurt1062-v1 LED backend.
*/
#include <px4_platform_common/px4_config.h>
#include <stdbool.h>
#include "chip.h"
#include <hardware/imxrt_gpio.h>
#include "board_config.h"
#include <arch/board/board.h>
/*
* 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_nLED_RED, // Indexed by LED_RED, LED_AMBER
GPIO_LED_SAFETY, // Indexed by LED_SAFETY
GPIO_nLED_GREEN, // 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) {
imxrt_config_gpio(g_ledmap[l]);
}
}
}
static void phy_set_led(int led, bool state)
{
/* Drive High to switch on */
if (g_ledmap[led] != 0) {
imxrt_gpio_write(g_ledmap[led], state);
}
}
static bool phy_get_led(int led)
{
if (g_ledmap[led] != 0) {
return imxrt_gpio_read(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));
}

View File

@@ -0,0 +1,142 @@
/****************************************************************************
*
* Copyright (c) 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 manifest.c
*
* This module supplies the interface to the manifest of hardware that is
* optional and dependent on the HW REV and HW VER IDs
*
* The manifest allows the system to know whether a hardware option
* say for example the PX4IO is an no-pop option vs it is broken.
*
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <stdbool.h>
#include "systemlib/px4_macros.h"
#include "px4_log.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
typedef struct {
uint32_t hw_ver_rev; /* the version and revision */
const px4_hw_mft_item_t *mft; /* The first entry */
uint32_t entries; /* the lenght of the list */
} px4_hw_mft_list_entry_t;
typedef px4_hw_mft_list_entry_t *px4_hw_mft_list_entry;
#define px4_hw_mft_list_uninitialized (px4_hw_mft_list_entry) -1
static const px4_hw_mft_item_t device_unsupported = {0, 0, 0};
// List of components on a specific board configuration
// The index of those components is given by the enum (px4_hw_mft_item_id_t)
// declared in board_common.h
static const px4_hw_mft_item_t hw_mft_list_v0500[] = {
{
.present = 1,
.mandatory = 1,
.connection = px4_hw_con_onboard,
},
};
static const px4_hw_mft_item_t hw_mft_list_v0540[] = {
{
.present = 0,
.mandatory = 0,
.connection = px4_hw_con_unknown,
},
};
static px4_hw_mft_list_entry_t mft_lists[] = {
{0x0000, hw_mft_list_v0500, arraySize(hw_mft_list_v0500)},
{0x0400, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)},
#if defined(ON_EVK)
{0x0804, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)},
{0x0807, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)},
{0x0404, hw_mft_list_v0540, arraySize(hw_mft_list_v0540)},
#endif
};
/************************************************************************************
* Name: board_query_manifest
*
* Description:
* Optional returns manifest item.
*
* Input Parameters:
* manifest_id - the ID for the manifest item to retrieve
*
* Returned Value:
* 0 - item is not in manifest => assume legacy operations
* pointer to a manifest item
*
************************************************************************************/
__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
{
static px4_hw_mft_list_entry boards_manifest = px4_hw_mft_list_uninitialized;
if (boards_manifest == px4_hw_mft_list_uninitialized) {
uint32_t ver_rev = board_get_hw_version() << 8;
ver_rev |= board_get_hw_revision();
for (unsigned i = 0; i < arraySize(mft_lists); i++) {
if (mft_lists[i].hw_ver_rev == ver_rev) {
boards_manifest = &mft_lists[i];
break;
}
}
if (boards_manifest == px4_hw_mft_list_uninitialized) {
PX4_ERR("Board %4x is not supported!", ver_rev);
}
}
px4_hw_mft_item rv = &device_unsupported;
if (boards_manifest != px4_hw_mft_list_uninitialized &&
id < boards_manifest->entries) {
rv = &boards_manifest->mft[id];
}
return rv;
}

View File

@@ -0,0 +1,127 @@
/****************************************************************************
*
* Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* 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 (USDHC1) signals of the MCU. This slot will accept
* micro format SD memory cards.
*
* ------------ ------------- --------
* SD Card Slot Board Signal IMXRT Pin
* ------------ ------------- --------
* DAT0 USDHC1_DATA0 GPIO_SD_B0_02
* DAT1 USDHC1_DATA1 GPIO_SD_B0_03
* DAT2 USDHC1_DATA2 GPIO_SD_B0_04
* CD/DAT3 USDHC1_DATA3 GPIO_SD_B0_05
* CMD USDHC1_CMD GPIO_SD_B0_00
* CLK USDHC1_CLK GPIO_SD_B0_01
* ------------ ------------- --------
*
* There are no Write Protect or Card detection pins available to the IMXRT.
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <px4_log.h>
#include <stdbool.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include "chip.h"
#include "imxrt_usdhc.h"
#include "board_config.h"
#ifdef CONFIG_IMXRT_USDHC
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: fmurt1062_usdhc_initialize
*
* Description:
* Inititialize the SDHC SD card slot
*
****************************************************************************/
int fmurt1062_usdhc_initialize(void)
{
int ret;
/* Mount the SDHC-based MMC/SD block driver */
/* First, get an instance of the SDHC interface */
struct sdio_dev_s *sdhc = imxrt_usdhc_initialize(CONFIG_NSH_MMCSDSLOTNO);
if (!sdhc) {
PX4_ERR("ERROR: Failed to initialize SDHC slot %d\n", CONFIG_NSH_MMCSDSLOTNO);
return -ENODEV;
}
/* Now bind the SDHC interface to the MMC/SD driver */
ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdhc);
if (ret != OK) {
PX4_ERR("ERROR: Failed to bind SDHC to the MMC/SD driver: %d\n", ret);
return ret;
}
syslog(LOG_INFO, "Successfully bound SDHC to the MMC/SD driver\n");
return OK;
}
#endif /* CONFIG_IMXRT_USDHC */

View File

@@ -0,0 +1,414 @@
/************************************************************************************
*
* Copyright (C) 2016, 2018 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* 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.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <px4_log.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/spi/spi.h>
#include <arch/board/board.h>
#include <systemlib/px4_macros.h>
#include <px4_platform/gpio.h>
#include <up_arch.h>
#include <chip.h>
#include "imxrt_lpspi.h"
#include "imxrt_gpio.h"
#include "board_config.h"
#include <systemlib/err.h>
#if defined(CONFIG_IMXRT_LPSPI1) || defined(CONFIG_IMXRT_LPSPI2) || \
defined(CONFIG_IMXRT_LPSPI3) || defined(CONFIG_IMXRT_LPSPI4)
/* Define CS GPIO array */
#if defined(CONFIG_IMXRT_LPSPI1)
static const uint32_t spi1selects_gpio[] = PX4_SENSOR_BUS_CS_GPIO;
#endif
#if defined(CONFIG_IMXRT_LPSPI2)
static const uint32_t spi2selects_gpio[] = PX4_MEMORY_BUS_CS_GPIO;
#endif
#if defined(CONFIG_IMXRT_LPSPI3)
static const uint32_t spi3selects_gpio[] = PX4_BARO_BUS_CS_GPIO;
#endif
#if defined(CONFIG_IMXRT_LPSPI4)
static const uint32_t spi4selects_gpio[] = PX4_EXTERNAL1_BUS_CS_GPIO;
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: fmurt1062_spidev_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the NXP FMUKRT1062-V1 board.
*
************************************************************************************/
void imxrt_spidev_initialize(void)
{
#if defined(CONFIG_IMXRT_LPSPI1)
px4_gpio_init(spi1selects_gpio, arraySize(spi1selects_gpio));
#endif
#if defined(CONFIG_IMXRT_LPSPI2)
px4_gpio_init(spi2selects_gpio, arraySize(spi2selects_gpio));
#endif
#if defined(CONFIG_IMXRT_LPSPI3)
px4_gpio_init(spi3selects_gpio, arraySize(spi3selects_gpio));
#endif
#if defined(CONFIG_IMXRT_LPSPI4)
px4_gpio_init(spi4selects_gpio, arraySize(spi4selects_gpio));
#endif
}
/************************************************************************************
* Name: imxrt_spi_bus_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the NXP FMUKRT1062-V1 board.
*
************************************************************************************/
static struct spi_dev_s *spi_sensors;
static struct spi_dev_s *spi_memory;
static struct spi_dev_s *spi_baro;
static struct spi_dev_s *spi_ext;
__EXPORT int imxrt1062_spi_bus_initialize(void)
{
/* Configure SPI-based devices */
spi_sensors = px4_spibus_initialize(PX4_SPI_BUS_SENSORS);
if (!spi_sensors) {
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
return -ENODEV;
}
/* Default PX4_SPI_BUS_SENSORS 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_MODE3);
for (int cs = PX4_SENSORS_BUS_FIRST_CS; cs <= PX4_SENSORS_BUS_LAST_CS; cs++) {
SPI_SELECT(spi_sensors, cs, false);
}
/* Get the SPI port for the Memory */
spi_memory = px4_spibus_initialize(PX4_SPI_BUS_MEMORY);
if (!spi_memory) {
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_MEMORY);
return -ENODEV;
}
/* Default PX4_SPI_BUS_MEMORY 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);
for (int cs = PX4_MEMORY_BUS_FIRST_CS; cs <= PX4_MEMORY_BUS_LAST_CS; cs++) {
SPI_SELECT(spi_memory, cs, false);
}
/* Get the SPI port for the BARO */
spi_ext = px4_spibus_initialize(PX4_SPI_BUS_BARO);
if (!spi_baro) {
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_BARO);
return -ENODEV;
}
/* MS5611 has max SPI clock speed of 20MHz
*/
SPI_SETFREQUENCY(spi_baro, 20 * 1000 * 1000);
SPI_SETBITS(spi_baro, 8);
SPI_SETMODE(spi_baro, SPIDEV_MODE3);
for (int cs = PX4_BARO_BUS_FIRST_CS; cs <= PX4_BARO_BUS_LAST_CS; cs++) {
SPI_SELECT(spi_baro, cs, false);
}
/* Get the SPI port for the PX4_SPI_EXTERNAL1 */
spi_ext = px4_spibus_initialize(PX4_SPI_BUS_EXTERNAL1);
if (!spi_ext) {
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_EXTERNAL1);
return -ENODEV;
}
/* Default PX4_SPI_BUS_SENSORS 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);
for (int cs = PX4_EXTERNAL1_BUS_FIRST_CS; cs <= PX4_EXTERNAL1_BUS_LAST_CS; cs++) {
SPI_SELECT(spi_ext, cs, false);
}
return OK;
}
/****************************************************************************
* Name: imxrt_lpspi1/2/3select and imxrt_lpspi1/2/3status
*
* Description:
* The external functions, imxrt_lpspi1/2/3select and imxrt_lpspi1/2/3status must be
* provided by board-specific logic. They are implementations of the select
* and status methods of the SPI interface defined by struct spi_ops_s (see
* include/nuttx/spi/spi.h). All other methods (including imxrt_lpspibus_initialize())
* are provided by common STM32 logic. To use this common SPI logic on your
* board:
*
* 1. Provide logic in imxrt_boardinitialize() to configure SPI chip select
* pins.
* 2. Provide imxrt_lpspi1/2/3select() and imxrt_lpspi1/2/3status() functions in your
* board-specific logic. These functions will perform chip selection and
* status operations using GPIOs in the way your board is configured.
* 3. Add a calls to imxrt_lpspibus_initialize() in your low level application
* initialization logic
* 4. The handle returned by imxrt_lpspibus_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).
*
****************************************************************************/
#if defined(CONFIG_IMXRT_LPSPI1)
__EXPORT void imxrt_lpspi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
{
/* SPI select is active low, so write !selected to select the device */
int sel = (int) devid;
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_SENSORS);
/* Making sure the other peripherals are not selected */
for (size_t cs = 0; arraySize(spi1selects_gpio) > 1 && cs < arraySize(spi1selects_gpio); cs++) {
if (spi1selects_gpio[cs] != 0) {
imxrt_gpio_write(spi1selects_gpio[cs], 1);
}
}
uint32_t gpio = spi1selects_gpio[PX4_SPI_DEV_ID(sel)];
if (gpio) {
imxrt_gpio_write(gpio, !selected);
}
}
__EXPORT uint8_t imxrt_lpspi1status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return SPI_STATUS_PRESENT;
}
#endif
#if defined(CONFIG_IMXRT_LPSPI2)
__EXPORT void imxrt_lpspi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
{
/* SPI select is active low, so write !selected to select the device */
int sel = (int) devid;
if (devid == SPIDEV_FLASH(0)) {
sel = PX4_SPIDEV_MEMORY;
}
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_MEMORY);
/* Making sure the other peripherals are not selected */
for (int cs = 0; arraySize(spi2selects_gpio) > 1 && cs < arraySize(spi2selects_gpio); cs++) {
if (spi2selects_gpio[cs] != 0) {
imxrt_gpio_write(spi2selects_gpio[cs], 1);
}
}
uint32_t gpio = spi2selects_gpio[PX4_SPI_DEV_ID(sel)];
if (gpio) {
imxrt_gpio_write(gpio, !selected);
}
}
__EXPORT uint8_t imxrt_lpspi2status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return SPI_STATUS_PRESENT;
}
#endif
#if defined(CONFIG_IMXRT_LPSPI3)
__EXPORT void imxrt_lpspi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
{
/* SPI select is active low, so write !selected to select the device */
int sel = (int) devid;
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_BARO);
/* Making sure the other peripherals are not selected */
for (int cs = 0; arraySize(spi3selects_gpio) > 1 && cs < arraySize(spi3selects_gpio); cs++) {
if (spi3selects_gpio[cs] != 0) {
imxrt_gpio_write(spi3selects_gpio[cs], 1);
}
}
uint32_t gpio = spi3selects_gpio[PX4_SPI_DEV_ID(sel)];
if (gpio) {
imxrt_gpio_write(gpio, !selected);
}
}
__EXPORT uint8_t imxrt_lpspi3status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return SPI_STATUS_PRESENT;
}
#endif
#if defined(CONFIG_IMXRT_LPSPI4)
__EXPORT void imxrt_lpspi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
{
int sel = (int) devid;
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_BARO);
/* Making sure the other peripherals are not selected */
for (size_t cs = 0; arraySize(spi4selects_gpio) > 1 && cs < arraySize(spi4selects_gpio); cs++) {
imxrt_gpio_write(spi4selects_gpio[cs], 1);
}
uint32_t gpio = spi4selects_gpio[PX4_SPI_DEV_ID(sel)];
if (gpio) {
imxrt_gpio_write(gpio, !selected);
}
}
__EXPORT uint8_t imxrt_lpspi4status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return SPI_STATUS_PRESENT;
}
#endif
/************************************************************************************
* Name: board_spi_reset
*
* Description:
*
*
************************************************************************************/
__EXPORT void board_spi_reset(int ms)
{
#ifdef CONFIG_IMXRT_LPSPI1
/* Goal not to back feed the chips on the bus via IO lines */
for (size_t cs = 0; arraySize(spi1selects_gpio) > 1 && cs < arraySize(spi1selects_gpio); cs++) {
if (spi1selects_gpio[cs] != 0) {
imxrt_config_gpio(_PIN_OFF(spi1selects_gpio[cs]));
}
}
imxrt_config_gpio(GPIO_SPI1_SCK_OFF);
imxrt_config_gpio(GPIO_SPI1_MISO_OFF);
imxrt_config_gpio(GPIO_SPI1_MOSI_OFF);
# if BOARD_USE_DRDY
imxrt_config_gpio(GPIO_DRDY_OFF_SPI1_DRDY1_ICM20689);
imxrt_config_gpio(GPIO_DRDY_OFF_SPI1_DRDY2_BMI055_GYRO);
imxrt_config_gpio(GPIO_DRDY_OFF_SPI1_DRDY3_BMI055_ACC);
imxrt_config_gpio(GPIO_DRDY_OFF_SPI1_DRDY4_ICM20602);
imxrt_config_gpio(GPIO_DRDY_OFF_SPI1_DRDY5_BMI055_GYRO);
imxrt_config_gpio(GPIO_DRDY_OFF_SPI1_DRDY6_BMI055_ACC);
# endif
/* set the sensor rail off */
imxrt_gpio_write(GPIO_VDD_3V3_SENSORS_EN, 0);
/* wait for the sensor rail to reach GND */
usleep(ms * 1000);
warnx("reset done, %d ms", ms);
/* re-enable power */
/* switch the sensor rail back on */
imxrt_gpio_write(GPIO_VDD_3V3_SENSORS_EN, 1);
/* wait a bit before starting SPI, different times didn't influence results */
usleep(100);
/* reconfigure the SPI pins */
for (size_t cs = 0; arraySize(spi1selects_gpio) > 1 && cs < arraySize(spi1selects_gpio); cs++) {
if (spi1selects_gpio[cs] != 0) {
imxrt_config_gpio(spi1selects_gpio[cs]);
}
}
imxrt_config_gpio(GPIO_LPSPI1_SCK);
imxrt_config_gpio(GPIO_LPSPI1_MISO);
imxrt_config_gpio(GPIO_LPSPI1_MOSI);
# if BOARD_USE_DRDY
imxrt_config_gpio(GPIO_SPI1_DRDY1_ICM20689);
imxrt_config_gpio(GPIO_SPI1_DRDY2_BMI055_GYRO);
imxrt_config_gpio(GPIO_SPI1_DRDY3_BMI055_ACC);
imxrt_config_gpio(GPIO_SPI1_DRDY4_ICM20602);
imxrt_config_gpio(GPIO_SPI1_DRDY5_BMI055_GYRO);
imxrt_config_gpio(GPIO_SPI1_DRDY6_BMI055_ACC);
# endif
#endif /* CONFIG_IMXRT_LPSPI1 */
}
#endif /* CONFIG_IMXRT_LPSPI1 || CONFIG_IMXRT_LPSPI2 || CONFIG_IMXRT_LPSPI3 || CONFIG_IMXRT_LPSPI4 */

View File

@@ -0,0 +1,250 @@
/****************************************************************************
*
* Copyright (C) 2016, 2018-2019 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* @file timer_config.c
*
* Configuration data for the imxrt pwm_servo, input capture and pwm input driver.
*
* Note that these arrays must always be fully-sized.
*/
// TODO:Stubbed out for now
#include <stdint.h>
#include <chip.h>
#include "hardware/imxrt_tmr.h"
#include "hardware/imxrt_flexpwm.h"
#include "imxrt_gpio.h"
#include "imxrt_iomuxc.h"
#include "hardware/imxrt_pinmux.h"
#include "imxrt_xbar.h"
#include "imxrt_periphclks.h"
#include <drivers/drv_pwm_output.h>
#include <px4_arch/io_timer.h>
#include "board_config.h"
/****************************************************************************************************
* Definitions
****************************************************************************************************/
#if defined(ON_EVK)
//# define DEBUG_CLOCK_EVK 1
#endif
/* Register accessors */
#define _REG(_addr) (*(volatile uint16_t *)(_addr))
/* QTimer3 register accessors */
#define REG(_reg) _REG(IMXRT_QTIMER3_BASE + IMXRT_TMR_OFFSET(IMXRT_TMR_CH0,(_reg)))
#define rCOMP1 REG(IMXRT_TMR_COMP1_OFFSET)
#define rCOMP2 REG(IMXRT_TMR_COMP2_OFFSET)
#define rCAPT REG(IMXRT_TMR_CAPT_OFFSET)
#define rLOAD REG(IMXRT_TMR_LOAD_OFFSET)
#define rHOLD REG(IMXRT_TMR_HOLD_OFFSET)
#define rCNTR REG(IMXRT_TMR_CNTR_OFFSET)
#define rCTRL REG(IMXRT_TMR_CTRL_OFFSET)
#define rSCTRL REG(IMXRT_TMR_SCTRL_OFFSET)
#define rCMPLD1 REG(IMXRT_TMR_CMPLD1_OFFSET)
#define rCMPLD2 REG(IMXRT_TMR_CMPLD2_OFFSET)
#define rCSCTRL REG(IMXRT_TMR_CSCTRL_OFFSET)
#define rFILT REG(IMXRT_TMR_FILT_OFFSET)
#define rDMA REG(IMXRT_TMR_DMA_OFFSET)
#define rENBL REG(IMXRT_TMR_ENBL_OFFSET)
__EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
{
.base = IMXRT_FLEXPWM2_BASE,
.first_channel_index = 0,
.last_channel_index = 3,
},
{
.base = IMXRT_FLEXPWM3_BASE,
.first_channel_index = 4,
.last_channel_index = 5,
},
{
.base = IMXRT_FLEXPWM4_BASE,
.first_channel_index = 6,
.last_channel_index = 7,
},
};
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
{
/* FMU_CH1 : GPIO_B0_06 GPIO2 Pin 6 FLEXPWM2_PWMA0 */
.gpio_out = PIN_FLEXPWM2_PWMA00,
.timer_index = 0,
.val_offset = PWMA_VAL,
.sub_module = SM0,
.sub_module_bits = MCTRL_LDOK(1 << SM0),
},
{
/* FMU_CH2 : GPIO_EMC_08 GPIO4 Pin 8 FLEXPWM2_PWMA1 */
.gpio_out = PIN_FLEXPWM2_PWMA01,
.timer_index = 0,
.val_offset = PWMA_VAL,
.sub_module = SM1,
.sub_module_bits = MCTRL_LDOK(1 << SM1),
},
{
/* FMU_CH3 : GPIO_EMC_10 GPIO4 Pin 10 FLEXPWM2_PWMA2 */
.gpio_out = PIN_FLEXPWM2_PWMA02,
.timer_index = 0,
.val_offset = PWMA_VAL,
.sub_module = SM2,
.sub_module_bits = MCTRL_LDOK(1 << SM2),
},
{
/* FMU_CH4 : GPIO_AD_B0_09 GPIO1 Pin 9 FLEXPWM2_PWMA3 */
.gpio_out = PIN_FLEXPWM2_PWMA03,
.timer_index = 0,
.val_offset = PWMA_VAL,
.sub_module = SM3,
.sub_module_bits = MCTRL_LDOK(1 << SM3),
},
{
/* FMU_CH5 : GPIO_EMC_33 GPIO3 Pin 19 FLEXPWM3_PWMA2 */
.gpio_out = PIN_FLEXPWM3_PWMA02,
.timer_index = 1,
.val_offset = PWMA_VAL,
.sub_module = SM2,
.sub_module_bits = MCTRL_LDOK(1 << SM2),
},
{
/* FMU_CH6 : GPIO_EMC_30 GPIO4 Pin 30 FLEXPWM3_PWMB0 */
.gpio_out = PIN_FLEXPWM3_PWMB00,
.timer_index = 1,
.val_offset = PWMB_VAL,
.sub_module = SM0,
.sub_module_bits = MCTRL_LDOK(1 << SM0),
},
{
/* FMU_CH7 : GPIO_EMC_04 GPIO4 Pin 4 FLEXPWM4_PWMA2 */
.gpio_out = PIN_FLEXPWM4_PWMA02,
.timer_index = 2,
.val_offset = PWMA_VAL,
.sub_module = SM2,
.sub_module_bits = MCTRL_LDOK(1 << SM2),
},
{
/* FMU_CH8 : GPIO_EMC_01 GPIO4 Pin 1 FLEXPWM4_PWMB0 */
.gpio_out = PIN_FLEXPWM4_PWMB00,
.timer_index = 2,
.val_offset = PWMB_VAL,
.sub_module = SM0,
.sub_module_bits = MCTRL_LDOK(1 << SM0),
},
};
__EXPORT const struct io_timers_t led_pwm_timers[MAX_LED_TIMERS] = {
};
__EXPORT const struct timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = {
};
__EXPORT void fmurt1062_timer_initialize(void)
{
/* We must configure Qtimer 3 as the IPG divide by to yield 16 Mhz
* and deliver that clock to the eFlexPWM234 via XBAR
*
* IPG = 144 Mhz
* 16Mhz = 144 / 9
* COMP 1 = 5, COMP2 = 4
*
* */
/* Enable Block Clocks for Qtimer and XBAR1 */
imxrt_clockall_timer3();
imxrt_clockall_xbar1();
/* Disable Timer */
rCTRL = 0;
rCOMP1 = 5 - 1; // N - 1
rCOMP2 = 4 - 1;
rCAPT = 0;
rLOAD = 0;
rCNTR = 0;
rSCTRL = TMR_SCTRL_OEN;
rCMPLD1 = 0;
rCMPLD2 = 0;
rCSCTRL = 0;
rFILT = 0;
rDMA = 0;
/* Count rising edges of primary source,
* Prescaler is /1
* Count UP until compare, then re-initialize. a successful compare occurs when the counter reaches a COMP1 value.
* Toggle OFLAG output using alternating compare registers
*/
rCTRL = (TMR_CTRL_CM_MODE1 | TMR_CTRL_PCS_DIV1 | TMR_CTRL_LENGTH | TMR_CTRL_OUTMODE_TOG_ALT);
/* QTIMER3_TIMER0 -> Flexpwm234ExtClk */
imxrt_xbar_connect(IMXRT_XBARA1_OUT_FLEXPWM234_EXT_CLK_SEL_OFFSET, IMXRT_XBARA1_IN_QTIMER3_TMR0_OUT);
#if defined(DEBUG_CLOCK_EVK)
/* Make it Scope-able on J24-1 */
imxrt_xbar_connect(IMXRT_XBARA1_OUT_IOMUX_XBAR_IO17_SEL_OFFSET, IMXRT_XBARA1_IN_QTIMER3_TMR0_OUT);
imxrt_config_gpio(GPIO_XBAR1_INOUT17_1 | (IOMUX_CMOS_OUTPUT | IOMUX_DRIVE_60OHM | IOMUX_SPEED_MAX |
IOMUX_SLEW_FAST));
modifyreg32(IMXRT_IOMUXC_GPR_GPR6, 0, GPR_GPR6_IOMUXC_XBAR_DIR_SEL_17_MASK);
#endif /* DEBUG_CLOCK_EVK */
}

View File

@@ -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 usb.c
*
* Board-specific USB functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/usb/usbdev.h>
#include <nuttx/usb/usbdev_trace.h>
#include <up_arch.h>
#include <chip.h>
#include <hardware/imxrt_usb_analog.h>
#include "board_config.h"
#include "imxrt_periphclks.h"
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
int imxrt_usb_initialize(void)
{
imxrt_clockall_usboh3();
return 0;
}
/************************************************************************************
* Name: imxrt_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 imxrt_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 imxrt_usbpullup(FAR struct usbdev_s *dev, bool enable)
{
usbtrace(TRACE_DEVPULLUP, (uint16_t)enable);
return OK;
}
/************************************************************************************
* Name: imxrt_usbsuspend
*
* Description:
* Board logic must provide the imxrt_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 imxrt_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}
/************************************************************************************
* 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 (getreg32(IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT) & USB_ANALOG_USB_VBUS_DETECT_STAT_VBUS_VALID) ? 0 : 1;
}