mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Add support for NXP MR-VMU-Tropic board (#25845)
* rt106x: Use platform SPI hal layer * rt106x: Add romapi support and reboot to isp/bootloader * bootloader: imxrt_common: Add rt106x support * NXP MR-Tropic initial commit * Add missing file for mr-tropic bootloader * nxp-mr-tropic:Bootloader Alow Assertion debugging & Keep Ram Vectors * nxp-mr-tropic: Firmware Boot from bootloader * nxp-mr-tropic:Add Bootloader bin file * mr-tropic: Update config and linker Fixes enet issues with write-back and some code cleanup. Furthermore increase NOR LittleFS to 256kB to reflect on linker * Update NuttX * mr-tropic: fix itcm apping and add mr-tropic to itcm check --------- Co-authored-by: David Sidrane <David.Sidrane@NscDg.com>
This commit is contained in:
parent
5f0d222e1b
commit
1250563ed1
4
.github/workflows/itcm_check.yml
vendored
4
.github/workflows/itcm_check.yml
vendored
@ -41,6 +41,10 @@ jobs:
|
||||
scripts: >
|
||||
boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld
|
||||
boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld
|
||||
- target: nxp_mr-tropic
|
||||
scripts: >
|
||||
boards/nxp/mr-tropic/nuttx-config/scripts/itcm_functions_includes.ld
|
||||
boards/nxp/mr-tropic/nuttx-config/scripts/itcm_static_functions.ld
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
with:
|
||||
|
||||
10
.vscode/cmake-variants.yaml
vendored
10
.vscode/cmake-variants.yaml
vendored
@ -481,6 +481,16 @@ CONFIG:
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: nxp_mr-canhubk3_fmu
|
||||
nxp_mr-tropic_default:
|
||||
short: nxp_mr-tropic_default
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: nxp_mr-tropic_default
|
||||
nxp_mr-tropic_bootloader:
|
||||
short: nxp_mr-tropic_bootloader
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: nxp_mr-tropic_bootloader
|
||||
nxp_tropic-community_default:
|
||||
short: nxp_tropic-community_default
|
||||
buildType: MinSizeRel
|
||||
|
||||
3
boards/nxp/mr-tropic/bootloader.px4board
Normal file
3
boards/nxp/mr-tropic/bootloader.px4board
Normal file
@ -0,0 +1,3 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_ROMFSROOT=""
|
||||
44
boards/nxp/mr-tropic/cmake/upload.cmake
Normal file
44
boards/nxp/mr-tropic/cmake/upload.cmake
Normal file
@ -0,0 +1,44 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2024 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
|
||||
set(PX4_FW_NAME ${PX4_BINARY_DIR}/${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_${PX4_BOARD_LABEL}.hex)
|
||||
|
||||
add_custom_target(upload_teensy
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/teensy_uploader.py --port ${serial_ports} ${PX4_FW_NAME} --vendor-id 0x1FC9 --product-id 0x0024
|
||||
DEPENDS ${PX4_FW_NAME}
|
||||
COMMENT "uploading px4"
|
||||
VERBATIM
|
||||
USES_TERMINAL
|
||||
WORKING_DIRECTORY ${PX4_BINARY_DIR}
|
||||
)
|
||||
109
boards/nxp/mr-tropic/default.px4board
Normal file
109
boards/nxp/mr-tropic/default.px4board
Normal file
@ -0,0 +1,109 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_ETHERNET=y
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS6"
|
||||
CONFIG_BOARD_PARAM_FILE="/fs/nor/mtd_params"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y
|
||||
CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
|
||||
CONFIG_COMMON_INS=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM350=y
|
||||
CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_DRIVERS_OSD_MSP_OSD=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
CONFIG_BOARD_UAVCAN_INTERFACES=1
|
||||
CONFIG_COMMON_UWB=y
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_ESC_BATTERY=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
CONFIG_MODULES_LAND_DETECTOR=y
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
|
||||
CONFIG_MODULES_LOAD_MON=y
|
||||
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
|
||||
CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
|
||||
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_MODULES_ZENOH=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BSONDUMP=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||
CONFIG_SYSTEMCMDS_I2C_LAUNCHER=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_NETMAN=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_SD_BENCH=y
|
||||
CONFIG_SYSTEMCMDS_SD_STRESS=y
|
||||
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
|
||||
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
|
||||
CONFIG_SYSTEMCMDS_VER=y
|
||||
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||
BIN
boards/nxp/mr-tropic/extras/nxp_mr-tropic_bootloader.bin
Executable file
BIN
boards/nxp/mr-tropic/extras/nxp_mr-tropic_bootloader.bin
Executable file
Binary file not shown.
13
boards/nxp/mr-tropic/firmware.prototype
Normal file
13
boards/nxp/mr-tropic/firmware.prototype
Normal file
@ -0,0 +1,13 @@
|
||||
{
|
||||
"board_id": 37,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the MR-TROPIC board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "MR-TROPIC",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 3932160,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
38
boards/nxp/mr-tropic/init/rc.board_defaults
Normal file
38
boards/nxp/mr-tropic/init/rc.board_defaults
Normal file
@ -0,0 +1,38 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Mavlink ethernet (CFG 1000)
|
||||
param set-default MAV_2_CONFIG 1000
|
||||
param set-default MAV_2_BROADCAST 1
|
||||
param set-default MAV_2_MODE 0
|
||||
param set-default MAV_2_RADIO_CTL 0
|
||||
param set-default MAV_2_RATE 100000
|
||||
param set-default MAV_2_REMOTE_PRT 14550
|
||||
param set-default MAV_2_UDP_PRT 14550
|
||||
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
param set-default RC_CRSF_PRT_CFG 300
|
||||
param set-default RC_CRSF_TEL_EN 1
|
||||
param set-default RC_SBUS_PRT_CFG 0
|
||||
|
||||
if [ -f "/fs/microsd/ipcfg-eth0" ]
|
||||
then
|
||||
else
|
||||
netman update -i eth0
|
||||
fi
|
||||
|
||||
rgbled_pwm start
|
||||
safety_button start
|
||||
|
||||
if param greater -s UAVCAN_ENABLE 0
|
||||
then
|
||||
ifup can0
|
||||
fi
|
||||
|
||||
# Start the ESC telemetry
|
||||
dshot telemetry -d /dev/ttyS5 -x
|
||||
4
boards/nxp/mr-tropic/init/rc.board_mavlink
Normal file
4
boards/nxp/mr-tropic/init/rc.board_mavlink
Normal file
@ -0,0 +1,4 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# Tropic Community specific board MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
68
boards/nxp/mr-tropic/init/rc.board_sensors
Normal file
68
boards/nxp/mr-tropic/init/rc.board_sensors
Normal file
@ -0,0 +1,68 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# PX4 board sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
#
|
||||
# UART mapping on Tropic Community:
|
||||
#
|
||||
# LPUART5 /dev/ttyS0 CONSOLE
|
||||
# LPUART3 /dev/ttyS1 GPS
|
||||
# LPUART2 /dev/ttyS2 TELEM1
|
||||
# LPUART4 /dev/ttyS3 TELEM2
|
||||
# LPUART8 /dev/ttyS4 RC
|
||||
#
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
set INA_CONFIGURED no
|
||||
|
||||
board_adc start
|
||||
|
||||
if param compare SENS_EN_INA226 1
|
||||
then
|
||||
# Start Digital power monitors
|
||||
ina226 -X -b 3 -t 1 -k start
|
||||
set INA_CONFIGURED yes
|
||||
fi
|
||||
|
||||
if param compare SENS_EN_INA228 1
|
||||
then
|
||||
# Start Digital power monitors
|
||||
ina228 -X -b 3 -t 1 -k start
|
||||
set INA_CONFIGURED yes
|
||||
fi
|
||||
|
||||
if param compare SENS_EN_INA238 1
|
||||
then
|
||||
# Start Digital power monitors
|
||||
ina238 -X -b 3 -t 1 -k start
|
||||
set INA_CONFIGURED yes
|
||||
fi
|
||||
|
||||
if [ $INA_CONFIGURED = no ]
|
||||
then
|
||||
# INA226, INA228, INA238 auto-start
|
||||
i2c_launcher start -b 3 -t 1
|
||||
fi
|
||||
|
||||
# Internal SPI bus icm45686
|
||||
icm45686 -R 2 -b 3 -s start
|
||||
|
||||
# Internal on IMU SPI BMI088
|
||||
bmi088 -A -R 2 -b 4 -s start
|
||||
bmi088 -G -R 2 -b 4 -s start
|
||||
|
||||
# Internal magnetometer on I2c
|
||||
bmm350 -I -b 4 -R 6 start
|
||||
|
||||
# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer)
|
||||
ist8310 -X -b 1 -R 10 start
|
||||
|
||||
# Possible internal Baro
|
||||
|
||||
# Disable startup of internal baros if param is set to false
|
||||
if param compare SENS_INT_BARO_EN 1
|
||||
then
|
||||
bmp388 -I -b 4 start
|
||||
fi
|
||||
|
||||
unset INA_CONFIGURED
|
||||
4
boards/nxp/mr-tropic/nuttx-config/Kconfig
Normal file
4
boards/nxp/mr-tropic/nuttx-config/Kconfig
Normal file
@ -0,0 +1,4 @@
|
||||
#
|
||||
# For a description of the syntax of this configuration file,
|
||||
# see the file kconfig-language.txt in the NuttX tools repository.
|
||||
#
|
||||
107
boards/nxp/mr-tropic/nuttx-config/bootloader/defconfig
Normal file
107
boards/nxp/mr-tropic/nuttx-config/bootloader/defconfig
Normal file
@ -0,0 +1,107 @@
|
||||
#
|
||||
# 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_DEV_CONSOLE is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_DISABLE_PTHREAD is not set
|
||||
# CONFIG_SPI_EXCHANGE is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/nxp/mr-tropic/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_MIMXRT1064DVL6A=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=4096
|
||||
CONFIG_ARCH_RAMVECTORS=y
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_ITCM=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU=y
|
||||
CONFIG_ARM_MPU_RESET=y
|
||||
CONFIG_BOARDCTL=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
CONFIG_BOARD_INITTHREAD_PRIORITY=254
|
||||
CONFIG_BOARD_LATE_INITIALIZE=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=115000
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_BULKIN_REQLEN=96
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0025
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 BL MR-TROPIC"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x1FC9
|
||||
CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS"
|
||||
CONFIG_DEBUG_ASSERTIONS=y
|
||||
CONFIG_DEBUG_ERROR=y
|
||||
CONFIG_DEBUG_FEATURES=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEBUG_USAGEFAULT=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FDCLONE_DISABLE=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=2048
|
||||
CONFIG_IMXRT_EDMA=y
|
||||
CONFIG_IMXRT_EDMA_EDBG=y
|
||||
CONFIG_IMXRT_EDMA_ELINK=y
|
||||
CONFIG_IMXRT_EDMA_NTCD=64
|
||||
CONFIG_IMXRT_ITCM=384
|
||||
CONFIG_IMXRT_LPUART3=y
|
||||
CONFIG_IMXRT_SNVS_LPSRTC=y
|
||||
CONFIG_IMXRT_USBDEV=y
|
||||
CONFIG_INIT_ENTRYPOINT="bootloader_main"
|
||||
CONFIG_INIT_STACKSIZE=3194
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_LPUART3_BAUD=57600
|
||||
CONFIG_LPUART3_IFLOWCONTROL=y
|
||||
CONFIG_LPUART3_OFLOWCONTROL=y
|
||||
CONFIG_LPUART3_RXBUFSIZE=600
|
||||
CONFIG_LPUART3_RXDMA=y
|
||||
CONFIG_LPUART3_TXBUFSIZE=1500
|
||||
CONFIG_LPUART3_TXDMA=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAM_SIZE=1048576
|
||||
CONFIG_RAM_START=0x20200000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SPI=y
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_SYSTEMTICK_HOOK=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_DMA=y
|
||||
CONFIG_USBDEV_DUALSPEED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
416
boards/nxp/mr-tropic/nuttx-config/include/board.h
Normal file
416
boards/nxp/mr-tropic/nuttx-config/include/board.h
Normal file
@ -0,0 +1,416 @@
|
||||
/************************************************************************************
|
||||
* nuttx-configs/nxp/nxp_mr-tropic/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_TROPIC_INCLUDE_BOARD_H
|
||||
#define __NUTTX_CONFIG_NXP_TROPIC_INCLUDE_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
|
||||
/* Set VDD_SOC to 1.25V */
|
||||
|
||||
#define IMXRT_VDD_SOC (0x12)
|
||||
|
||||
/* 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 LPI2C PLL3 / 8 to fOut = (480Mhz / 8)
|
||||
* 60Mhz = (480Mhz / 8)
|
||||
* 12Mhz = (60Mhz / 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_CAN_CLK_SELECT CCM_CSCMR2_CAN_CLK_SEL_PLL3_SW_80
|
||||
#define IMXRT_CAN_PODF_DIVIDER 1
|
||||
|
||||
#define IMXRT_LPSPI_CLK_SELECT CCM_CBCMR_LPSPI_CLK_SEL_PLL3_PFD0
|
||||
#define IMXRT_LSPI_PODF_DIVIDER 8
|
||||
|
||||
#define IMXRT_LPI2C_CLK_SELECT CCM_CSCDR2_LPI2C_CLK_SEL_PLL3_60M
|
||||
#define IMXRT_LSI2C_PODF_DIVIDER 5
|
||||
|
||||
#define IMXRT_USDHC1_CLK_SELECT CCM_CSCMR1_USDHC1_CLK_SEL_PLL2_PFD0
|
||||
#define IMXRT_USDHC1_PODF_DIVIDER 2
|
||||
|
||||
#define IMXRT_USB1_PLL_DIV_SELECT CCM_ANALOG_PLL_USB1_DIV_SELECT_20
|
||||
|
||||
#define IMXRT_SYS_PLL_SELECT CCM_ANALOG_PLL_SYS_DIV_SELECT_22
|
||||
|
||||
#define IMXRT_USB1_PLL_DIV_SELECT CCM_ANALOG_PLL_USB1_DIV_SELECT_20
|
||||
|
||||
#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
|
||||
|
||||
|
||||
/* 108Mhz clock for FlexIO using PLL3 PFD2 @ 520 */
|
||||
#define CONFIG_FLEXIO1_CLK 1
|
||||
#define CONFIG_FLEXIO1_PRED_DIVIDER 5
|
||||
#define CONFIG_FLEXIO1_PODF_DIVIDER 1
|
||||
#define CONFIG_PLL3_PFD2_FRAC 16
|
||||
#define BOARD_FLEXIO_PREQ 108000000
|
||||
|
||||
/* 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 (IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER)
|
||||
|
||||
#define PIN_USDHC1_D0 (GPIO_USDHC1_DATA0_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_02 */
|
||||
#define PIN_USDHC1_D1 (GPIO_USDHC1_DATA1_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_03 */
|
||||
#define PIN_USDHC1_D2 (GPIO_USDHC1_DATA2_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_04 */
|
||||
#define PIN_USDHC1_D3 (GPIO_USDHC1_DATA3_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_05 */
|
||||
#define PIN_USDHC1_DCLK (GPIO_USDHC1_CLK_1 | USDHC1_CLK_IOMUX) /* GPIO_SD_B0_01 */
|
||||
#define PIN_USDHC1_CMD (GPIO_USDHC1_CMD_1 | USDHC1_CMD_IOMUX) /* GPIO_SD_B0_00 */
|
||||
#define PIN_USDHC1_CD (PIN_USDHC1_D3)
|
||||
|
||||
/* #define PIN_USDHC1_CD (GPIO_USDHC1_CD_3 | USDHC1_CD_IOMUX)
|
||||
* CD_B Pin works fine but somehow the driver has a timing issue with
|
||||
* Thus use D3 instead
|
||||
*/
|
||||
|
||||
/* 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)
|
||||
|
||||
/* ETH Disambiguation *******************************************************/
|
||||
|
||||
/* Ethernet Interrupt: GPIO_B0_15
|
||||
*
|
||||
* This pin has a week pull-up within the PHY, is open-drain, and requires
|
||||
* an external 1k ohm pull-up resistor (present on the EVK). A falling
|
||||
* edge then indicates a change in state of the PHY.
|
||||
*/
|
||||
|
||||
#define GPIO_ENET_INT (IOMUX_ENET_INT_DEFAULT | \
|
||||
GPIO_PORT2 | GPIO_PIN15) /* B0_15 */
|
||||
#define GPIO_ENET_IRQ IMXRT_IRQ_GPIO2_15
|
||||
|
||||
/* Ethernet Reset: GPIO_B0_14
|
||||
*
|
||||
* The #RST uses inverted logic. The initial value of zero will put the
|
||||
* PHY into the reset state.
|
||||
*/
|
||||
|
||||
#define GPIO_ENET_RST (GPIO_OUTPUT | GPIO_OUTPUT_ZERO | \
|
||||
GPIO_PORT2 | GPIO_PIN14 | IOMUX_ENET_RST_DEFAULT) /* B0_14 */
|
||||
|
||||
#define GPIO_ENET_TX_DATA00 (GPIO_ENET_TX_DATA00_1| \
|
||||
IOMUX_ENET_DATA_DEFAULT) /* GPIO_B1_07 */
|
||||
#define GPIO_ENET_TX_DATA01 (GPIO_ENET_TX_DATA01_1| \
|
||||
IOMUX_ENET_DATA_DEFAULT) /* GPIO_B1_08 */
|
||||
#define GPIO_ENET_RX_DATA00 (GPIO_ENET_RX_DATA00_1| \
|
||||
IOMUX_ENET_DATA_DEFAULT) /* GPIO_B1_04 */
|
||||
#define GPIO_ENET_RX_DATA01 (GPIO_ENET_RX_DATA01_1| \
|
||||
IOMUX_ENET_DATA_DEFAULT) /* GPIO_B1_05 */
|
||||
#define GPIO_ENET_MDIO (GPIO_ENET_MDIO_1|IOMUX_ENET_MDIO_DEFAULT) /* GPIO_B1_15 */
|
||||
#define GPIO_ENET_MDC (GPIO_ENET_MDC_1|IOMUX_ENET_MDC_DEFAULT) /* GPIO_B1_14 */
|
||||
#define GPIO_ENET_RX_EN (GPIO_ENET_RX_EN_1|IOMUX_ENET_EN_DEFAULT) /* GPIO_B1_06 */
|
||||
#define GPIO_ENET_RX_ER (GPIO_ENET_RX_ER_1|IOMUX_ENET_RXERR_DEFAULT) /* GPIO_B1_11 */
|
||||
#define GPIO_ENET_TX_CLK (GPIO_ENET_REF_CLK_2|\
|
||||
IOMUX_ENET_TX_CLK_DEFAULT) /* GPIO_B1_10 */
|
||||
#define GPIO_ENET_TX_EN (GPIO_ENET_TX_EN_1|IOMUX_ENET_EN_DEFAULT) /* GPIO_B1_09 */
|
||||
|
||||
/* 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
|
||||
*/
|
||||
#define LPUART_IOMUX (IOMUX_PULL_UP_22K | IOMUX_DRIVE_40OHM | IOMUX_SLEW_SLOW | IOMUX_SPEED_LOW | IOMUX_SCHMITT_TRIGGER)
|
||||
#define IOMUX_UART_CTS_DEFAULT (IOMUX_PULL_DOWN_100K | IOMUX_DRIVE_40OHM | IOMUX_SLEW_SLOW)
|
||||
|
||||
/* Debug */
|
||||
|
||||
#define GPIO_LPUART6_RX (GPIO_LPUART6_RX_2 | LPUART_IOMUX) /* GPIO_EMC_26 */
|
||||
#define GPIO_LPUART6_TX (GPIO_LPUART6_TX_2 | LPUART_IOMUX) /* GPIO_EMC_25 */
|
||||
|
||||
|
||||
/* Telem 2 */
|
||||
|
||||
#define GPIO_LPUART5_RX (GPIO_LPUART5_RX_1 | LPUART_IOMUX) /* GPIO_B1_13 */
|
||||
#define GPIO_LPUART5_TX (GPIO_LPUART5_TX_1 | LPUART_IOMUX) /* GPIO_B1_12 */
|
||||
#define GPIO_LPUART5_CTS (GPIO_LPUART5_CTS_1 | IOMUX_UART_CTS_DEFAULT | PADMUX_SION) /* GPIO_EMC_28 GPIO4_IO27 */
|
||||
#define GPIO_LPUART5_RTS (GPIO_PORT4 | GPIO_PIN27 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | IOMUX_UART_DEFAULT) /* GPIO_EMC_27 GPIO4_IO27 (GPIO only, no HW Flow control) */
|
||||
|
||||
/* AUX */
|
||||
|
||||
#define GPIO_LPUART4_RX (GPIO_LPUART4_RX_1 | LPUART_IOMUX) /* GPIO_B1_01 */
|
||||
#define GPIO_LPUART4_TX (GPIO_LPUART4_TX_1 | LPUART_IOMUX) /* GPIO_B1_00 */
|
||||
#define GPIO_LPUART4_CTS (GPIO_PORT1 | GPIO_PIN15 | GPIO_INPUT | PADMUX_SION | IOMUX_UART_CTS_DEFAULT) /* GPIO_AD_B0_15 GPIO1_IO14 (Fixme Add GPIO Flow support in LPUART) */
|
||||
#define GPIO_LPUART4_RTS (GPIO_PORT1 | GPIO_PIN14 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | IOMUX_UART_DEFAULT) /* GPIO_AD_B0_14 GPIO1_IO14 (GPIO only, no HW Flow control) */
|
||||
|
||||
/* GPS 1 */
|
||||
|
||||
#define GPIO_LPUART2_RX (GPIO_LPUART2_RX_1 | LPUART_IOMUX) /* GPIO_AD_B1_03 */
|
||||
#define GPIO_LPUART2_TX (GPIO_LPUART2_TX_1 | LPUART_IOMUX) /* GPIO_AD_B1_02 */
|
||||
|
||||
/* Telem 1 */
|
||||
|
||||
#define GPIO_LPUART3_RX (GPIO_LPUART3_RX_1 | LPUART_IOMUX) /* GPIO_AD_B1_07 */
|
||||
#define GPIO_LPUART3_TX (GPIO_LPUART3_TX_1 | LPUART_IOMUX) /* GPIO_AD_B1_06 */
|
||||
#define GPIO_LPUART3_CTS (GPIO_LPUART3_CTS_1 | IOMUX_UART_CTS_DEFAULT | PADMUX_SION) /* GPIO_AD_B1_04 GPIO1_IO20 */
|
||||
#define GPIO_LPUART3_RTS (GPIO_PORT1 | GPIO_PIN21 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | IOMUX_UART_DEFAULT) /* GPIO_AD_B1_05 GPIO1_IO21 (GPIO only, no HW Flow control) */
|
||||
//TODO check RT7 partial HW handshake
|
||||
|
||||
/* ESC ONEWIRE */
|
||||
#define GPIO_LPUART7_RX (GPIO_LPUART7_TX_1 | LPUART_IOMUX) /* GPIO_EMC_31 */
|
||||
#define GPIO_LPUART7_TX (GPIO_LPUART7_TX_1 | LPUART_IOMUX) /* GPIO_EMC_31 */
|
||||
|
||||
|
||||
/* RC INPUT single wire mode on Input on TX, for CRSF use TX and RX */
|
||||
|
||||
#define GPIO_LPUART8_RX (GPIO_LPUART8_RX_1 | LPUART_IOMUX) /* GPIO_AD_B1_11 */
|
||||
#define GPIO_LPUART8_TX (GPIO_LPUART8_TX_1 | LPUART_IOMUX) /* GPIO_AD_B1_10 */
|
||||
|
||||
/* CAN
|
||||
*
|
||||
* CAN1 is routed to transceiver.
|
||||
* CAN2 is routed to transceiver.
|
||||
* CAN3 is routed to transceiver.
|
||||
*/
|
||||
#define FLEXCAN_IOMUX (IOMUX_PULL_UP_100K | IOMUX_DRIVE_40OHM | IOMUX_SLEW_FAST | IOMUX_SPEED_MEDIUM)
|
||||
|
||||
#define GPIO_FLEXCAN3_RX (GPIO_FLEXCAN3_RX_3 | FLEXCAN_IOMUX) /* GPIO_EMC_37 */
|
||||
#define GPIO_FLEXCAN3_TX (GPIO_FLEXCAN3_TX_3 | FLEXCAN_IOMUX) /* GPIO_EMC_36 */
|
||||
|
||||
/* LPSPI */
|
||||
#define LPSPI_IOMUX (IOMUX_PULL_UP_100K | IOMUX_DRIVE_33OHM | IOMUX_SLEW_FAST | IOMUX_SPEED_MAX)
|
||||
|
||||
|
||||
#define GPIO_LPSPI3_SCK (GPIO_LPSPI3_SCK_1 | LPSPI_IOMUX) /* GPIO_AD_B1_15 */
|
||||
#define GPIO_LPSPI3_MISO (GPIO_LPSPI3_SDI_1 | LPSPI_IOMUX) /* GPIO_AD_B1_13 */
|
||||
#define GPIO_LPSPI3_MOSI (GPIO_LPSPI3_SDO_1 | LPSPI_IOMUX) /* GPIO_AD_B1_14 */
|
||||
|
||||
#define GPIO_LPSPI4_SCK (GPIO_LPSPI4_SCK_2 | LPSPI_IOMUX) /* GPIO_B0_03 */
|
||||
#define GPIO_LPSPI4_MISO (GPIO_LPSPI4_SDI_2 | LPSPI_IOMUX) /* GPIO_B0_01 */
|
||||
#define GPIO_LPSPI4_MOSI (GPIO_LPSPI4_SDO_2 | LPSPI_IOMUX) /* GPIO_B0_02 */
|
||||
|
||||
#define BOARD_SPI_BUS_MAX_BUS_ITEMS 2
|
||||
|
||||
/* LPI2Cs */
|
||||
|
||||
#define LPI2C_IOMUX (IOMUX_SPEED_MEDIUM | IOMUX_DRIVE_33OHM | IOMUX_OPENDRAIN | GPIO_SION_ENABLE)
|
||||
#define LPI2C_IO_IOMUX (IOMUX_SPEED_MAX | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_OPENDRAIN | IOMUX_PULL_NONE)
|
||||
|
||||
#define GPIO_LPI2C1_SDA (GPIO_LPI2C1_SDA_2 | LPI2C_IOMUX) /* EVK J24-9 R276 */ /* GPIO_AD_B1_01 */
|
||||
#define GPIO_LPI2C1_SCL (GPIO_LPI2C1_SCL_2 | LPI2C_IOMUX) /* EVK J24-10 R277 */ /* GPIO_AD_B1_00 */
|
||||
|
||||
#define GPIO_LPI2C1_SDA_RESET (GPIO_PORT1 | GPIO_PIN17 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B1_01 GPIO1_IO17 */
|
||||
#define GPIO_LPI2C1_SCL_RESET (GPIO_PORT1 | GPIO_PIN16 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B1_00 GPIO1_IO16 */
|
||||
|
||||
#define GPIO_LPI2C3_SDA (GPIO_LPI2C3_SDA_2 | LPI2C_IOMUX) /* GPIO_EMC_21 */
|
||||
#define GPIO_LPI2C3_SCL (GPIO_LPI2C3_SCL_2 | LPI2C_IOMUX) /* GPIO_EMC_22 */
|
||||
|
||||
#define GPIO_LPI2C3_SDA_RESET (GPIO_PORT4 | GPIO_PIN21 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_EMC_21 */
|
||||
#define GPIO_LPI2C3_SCL_RESET (GPIO_PORT4 | GPIO_PIN22 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_EMC_22 */
|
||||
|
||||
#define GPIO_LPI2C4_SDA (GPIO_LPI2C4_SDA_1 | LPI2C_IOMUX) /* GPIO_AD_B0_13 */
|
||||
#define GPIO_LPI2C4_SCL (GPIO_LPI2C4_SCL_1 | LPI2C_IOMUX) /* GPIO_AD_B0_12 */
|
||||
|
||||
#define GPIO_LPI2C4_SDA_RESET (GPIO_PORT1 | GPIO_PIN13 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B0_13 */
|
||||
#define GPIO_LPI2C4_SCL_RESET (GPIO_PORT1 | GPIO_PIN12 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B0_12 */
|
||||
|
||||
#define BOARD_PHY_ADDR (18)
|
||||
|
||||
/* Board doesn't provide GPIO or other Hardware for signaling to timing analyzer */
|
||||
|
||||
#define PROBE_INIT(mask)
|
||||
#define PROBE(n,s)
|
||||
#define PROBE_MARK(n)
|
||||
|
||||
/************************************************************************************
|
||||
* 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_TROPIC_INCLUDE_BOARD_H */
|
||||
270
boards/nxp/mr-tropic/nuttx-config/nsh/defconfig
Normal file
270
boards/nxp/mr-tropic/nuttx-config/nsh/defconfig
Normal file
@ -0,0 +1,270 @@
|
||||
#
|
||||
# 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_NSH_DISABLE_MB is not set
|
||||
# CONFIG_NSH_DISABLE_MH is not set
|
||||
# CONFIG_NSH_DISABLE_MW is not set
|
||||
# CONFIG_SPI_CALLBACK is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/nxp/mr-tropic/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_MIMXRT1064DVL6A=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=2048
|
||||
CONFIG_ARCH_RAMVECTORS=y
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_ITCM=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU=y
|
||||
CONFIG_ARM_MPU_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
CONFIG_BOARD_LOOPSPERMSEC=115000
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_BULKIN_REQLEN=96
|
||||
CONFIG_CDCACM_PRODUCTID=0x0025
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 MR-TROPIC"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x1FC9
|
||||
CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS"
|
||||
CONFIG_DEBUG_ERROR=y
|
||||
CONFIG_DEBUG_FEATURES=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_MEMFAULT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_DEV_URANDOM=y
|
||||
CONFIG_ETH0_PHY_TJA1103=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FSUTILS_IPCFG=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_LITTLEFS=y
|
||||
CONFIG_FS_LITTLEFS_CACHE_SIZE_FACTOR=2
|
||||
CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=64
|
||||
CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
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=2048
|
||||
CONFIG_IMXRT_DTCM_HEAP=y
|
||||
CONFIG_IMXRT_DTCM_HEAP_SIZE=127
|
||||
CONFIG_IMXRT_EDMA=y
|
||||
CONFIG_IMXRT_EDMA_EDBG=y
|
||||
CONFIG_IMXRT_EDMA_ELINK=y
|
||||
CONFIG_IMXRT_EDMA_NTCD=64
|
||||
CONFIG_IMXRT_ENET=y
|
||||
CONFIG_IMXRT_ENET_NTXBUFFERS=8
|
||||
CONFIG_IMXRT_ENET_PHYINIT=y
|
||||
CONFIG_IMXRT_FLEXCAN3=y
|
||||
CONFIG_IMXRT_FLEXCAN_TXMB=1
|
||||
CONFIG_IMXRT_GPIO1_0_15_IRQ=y
|
||||
CONFIG_IMXRT_GPIO1_16_31_IRQ=y
|
||||
CONFIG_IMXRT_GPIO2_0_15_IRQ=y
|
||||
CONFIG_IMXRT_GPIO2_16_31_IRQ=y
|
||||
CONFIG_IMXRT_GPIO_IRQ=y
|
||||
CONFIG_IMXRT_INIT_FLEXRAM=y
|
||||
CONFIG_IMXRT_ITCM=384
|
||||
CONFIG_IMXRT_LPI2C1=y
|
||||
CONFIG_IMXRT_LPI2C3=y
|
||||
CONFIG_IMXRT_LPI2C4=y
|
||||
CONFIG_IMXRT_LPI2C_DMA=y
|
||||
CONFIG_IMXRT_LPI2C_DMA_MAXMSG=16
|
||||
CONFIG_IMXRT_LPI2C_DYNTIMEO=y
|
||||
CONFIG_IMXRT_LPI2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_IMXRT_LPSPI3=y
|
||||
CONFIG_IMXRT_LPSPI3_DMA=y
|
||||
CONFIG_IMXRT_LPSPI4=y
|
||||
CONFIG_IMXRT_LPSPI4_DMA=y
|
||||
CONFIG_IMXRT_LPSPI_DMA=y
|
||||
CONFIG_IMXRT_LPUART2=y
|
||||
CONFIG_IMXRT_LPUART3=y
|
||||
CONFIG_IMXRT_LPUART4=y
|
||||
CONFIG_IMXRT_LPUART5=y
|
||||
CONFIG_IMXRT_LPUART6=y
|
||||
CONFIG_IMXRT_LPUART7=y
|
||||
CONFIG_IMXRT_LPUART8=y
|
||||
CONFIG_IMXRT_LPUART_INVERT=y
|
||||
CONFIG_IMXRT_LPUART_SINGLEWIRE=y
|
||||
CONFIG_IMXRT_PHY_POLLING=y
|
||||
CONFIG_IMXRT_SNVS_LPSRTC=y
|
||||
CONFIG_IMXRT_USBDEV=y
|
||||
CONFIG_IMXRT_USDHC1=y
|
||||
CONFIG_IMXRT_USDHC1_INVERT_CD=y
|
||||
CONFIG_IMXRT_USDHC1_WIDTH_D1_D4=y
|
||||
CONFIG_INIT_ENTRYPOINT="nsh_main"
|
||||
CONFIG_INIT_STACKSIZE=2944
|
||||
CONFIG_IOB_NBUFFERS=24
|
||||
CONFIG_IOB_THROTTLE=0
|
||||
CONFIG_IPCFG_BINARY=y
|
||||
CONFIG_IPCFG_PATH="/fs/nor"
|
||||
CONFIG_LIBC_MAX_EXITFUNS=1
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_LPI2C1_DMA=y
|
||||
CONFIG_LPI2C3_DMA=y
|
||||
CONFIG_LPI2C4_DMA=y
|
||||
CONFIG_LPUART2_RXDMA=y
|
||||
CONFIG_LPUART2_TXDMA=y
|
||||
CONFIG_LPUART3_BAUD=57600
|
||||
CONFIG_LPUART3_IFLOWCONTROL=y
|
||||
CONFIG_LPUART3_OFLOWCONTROL=y
|
||||
CONFIG_LPUART3_RXBUFSIZE=600
|
||||
CONFIG_LPUART3_RXDMA=y
|
||||
CONFIG_LPUART3_TXBUFSIZE=3000
|
||||
CONFIG_LPUART3_TXDMA=y
|
||||
CONFIG_LPUART4_BAUD=57600
|
||||
CONFIG_LPUART4_IFLOWCONTROL=y
|
||||
CONFIG_LPUART4_RXBUFSIZE=600
|
||||
CONFIG_LPUART4_RXDMA=y
|
||||
CONFIG_LPUART4_TXBUFSIZE=3000
|
||||
CONFIG_LPUART4_TXDMA=y
|
||||
CONFIG_LPUART5_BAUD=57600
|
||||
CONFIG_LPUART5_IFLOWCONTROL=y
|
||||
CONFIG_LPUART5_OFLOWCONTROL=y
|
||||
CONFIG_LPUART5_RXBUFSIZE=600
|
||||
CONFIG_LPUART5_RXDMA=y
|
||||
CONFIG_LPUART5_TXBUFSIZE=3000
|
||||
CONFIG_LPUART5_TXDMA=y
|
||||
CONFIG_LPUART6_BAUD=57600
|
||||
CONFIG_LPUART6_SERIAL_CONSOLE=y
|
||||
CONFIG_LPUART7_RXDMA=y
|
||||
CONFIG_LPUART7_TXBUFSIZE=128
|
||||
CONFIG_LPUART8_BAUD=420000
|
||||
CONFIG_LPUART8_RXBUFSIZE=600
|
||||
CONFIG_LPUART8_RXDMA=y
|
||||
CONFIG_LPUART8_TXDMA=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NET=y
|
||||
CONFIG_NETDB_DNSCLIENT=y
|
||||
CONFIG_NETDB_DNSSERVER_NOADDR=y
|
||||
CONFIG_NETDEV_CAN_BITRATE_IOCTL=y
|
||||
CONFIG_NETDEV_CAN_FILTER_IOCTL=y
|
||||
CONFIG_NETDEV_LATEINIT=y
|
||||
CONFIG_NETDEV_PHY_IOCTL=y
|
||||
CONFIG_NETINIT_DHCPC=y
|
||||
CONFIG_NETINIT_DNS=y
|
||||
CONFIG_NETINIT_DNSIPADDR=0XC0A800FE
|
||||
CONFIG_NETINIT_DRIPADDR=0XC0A800FE
|
||||
CONFIG_NETINIT_MONITOR=y
|
||||
CONFIG_NETINIT_RETRY_MOUNTPATH=10
|
||||
CONFIG_NETINIT_THREAD=y
|
||||
CONFIG_NETINIT_THREAD_PRIORITY=49
|
||||
CONFIG_NETUTILS_TELNETD=y
|
||||
CONFIG_NET_ARP_IPIN=y
|
||||
CONFIG_NET_ARP_SEND=y
|
||||
CONFIG_NET_BROADCAST=y
|
||||
CONFIG_NET_CAN=y
|
||||
CONFIG_NET_CAN_EXTID=y
|
||||
CONFIG_NET_CAN_NOTIFIER=y
|
||||
CONFIG_NET_CAN_RAW_TX_DEADLINE=y
|
||||
CONFIG_NET_CAN_SOCK_OPTS=y
|
||||
CONFIG_NET_ETH_PKTSIZE=1518
|
||||
CONFIG_NET_ICMP=y
|
||||
CONFIG_NET_ICMP_SOCKET=y
|
||||
CONFIG_NET_IGMP=y
|
||||
CONFIG_NET_SOLINGER=y
|
||||
CONFIG_NET_TCP=y
|
||||
CONFIG_NET_TCPBACKLOG=y
|
||||
CONFIG_NET_TCP_DELAYED_ACK=y
|
||||
CONFIG_NET_TCP_KEEPALIVE=y
|
||||
CONFIG_NET_TCP_WRITE_BUFFERS=y
|
||||
CONFIG_NET_TIMESTAMP=y
|
||||
CONFIG_NET_UDP=y
|
||||
CONFIG_NET_UDP_CHECKSUMS=y
|
||||
CONFIG_NET_UDP_WRITE_BUFFERS=y
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_READLINE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_TELNET_LOGIN=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_TYPES=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAM_SIZE=1048576
|
||||
CONFIG_RAM_START=0x20200000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_RTC=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1800
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=2032
|
||||
CONFIG_SDIO_BLOCKSETUP=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=32
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
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=256
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_CLE=y
|
||||
CONFIG_SYSTEM_DHCPC_RENEW=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYSTEM_PING=y
|
||||
CONFIG_SYSTEM_SYSTEM=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_DUALSPEED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_WATCHDOG=y
|
||||
177
boards/nxp/mr-tropic/nuttx-config/scripts/bootloader_script.ld
Normal file
177
boards/nxp/mr-tropic/nuttx-config/scripts/bootloader_script.ld
Normal file
@ -0,0 +1,177 @@
|
||||
/****************************************************************************
|
||||
* boards/nxp/mr-tropic/nuttx-config/scripts/bootloader_script.ld
|
||||
*
|
||||
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||
* contributor license agreements. See the NOTICE file distributed with
|
||||
* this work for additional information regarding copyright ownership. The
|
||||
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||
* "License"); you may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||
* License for the specific language governing permissions and limitations
|
||||
* under the License.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* Specify the memory areas */
|
||||
|
||||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x70000000, LENGTH = 128K
|
||||
sram (rwx) : ORIGIN = 0x20200000, LENGTH = 512K
|
||||
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 384K
|
||||
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
EXTERN(_vectors)
|
||||
EXTERN(g_flash_config)
|
||||
EXTERN(g_image_vector_table)
|
||||
EXTERN(g_boot_data)
|
||||
EXTERN(board_get_manifest)
|
||||
EXTERN(_bootdelay_signature)
|
||||
|
||||
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
|
||||
|
||||
.vectors :
|
||||
{
|
||||
KEEP(*(.vectors))
|
||||
*(.text .text.__start)
|
||||
} >flash
|
||||
|
||||
.itcmfunc :
|
||||
{
|
||||
. = ALIGN(8);
|
||||
_sitcmfuncs = ABSOLUTE(.);
|
||||
FILL(0xFF)
|
||||
. = 0x40 ;
|
||||
*(.ram_vectors)
|
||||
. = ALIGN(8);
|
||||
_eitcmfuncs = ABSOLUTE(.);
|
||||
} > itcm AT > flash
|
||||
|
||||
_fitcmfuncs = LOADADDR(.itcmfunc);
|
||||
|
||||
.text : ALIGN(4)
|
||||
{
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
. = ALIGN(32);
|
||||
/*
|
||||
This signature provides the bootloader with a way to delay booting
|
||||
*/
|
||||
_bootdelay_signature = ABSOLUTE(.);
|
||||
FILL(0xffecc2925d7d05c5)
|
||||
. += 8;
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
. = ALIGN(4096);
|
||||
_etext = ABSOLUTE(.);
|
||||
_srodata = ABSOLUTE(.);
|
||||
*(.rodata .rodata.*)
|
||||
. = ALIGN(4096);
|
||||
_erodata = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
.init_section :
|
||||
{
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab*)
|
||||
} > flash
|
||||
|
||||
.ARM.exidx :
|
||||
{
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data :
|
||||
{
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
. = ALIGN(4);
|
||||
_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)
|
||||
. = ALIGN(4);
|
||||
_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) }
|
||||
|
||||
_boot_loadaddr = ORIGIN(flash);
|
||||
_boot_size = LENGTH(flash);
|
||||
_ram_size = LENGTH(sram);
|
||||
_sdtcm = ORIGIN(dtcm);
|
||||
_edtcm = ORIGIN(dtcm) + LENGTH(dtcm);
|
||||
}
|
||||
@ -0,0 +1,719 @@
|
||||
*(.text._ZN4uORB7Manager27orb_add_internal_subscriberE6ORB_IDhPj)
|
||||
*(.text._ZN13MavlinkStream6updateERKy)
|
||||
*(.text._ZN7Mavlink16update_rate_multEv)
|
||||
*(.text._ZN3sym17PredictCovarianceIfEEN6matrix6MatrixIT_Lj23ELj23EEERKNS2_IS3_Lj24ELj1EEERKS4_RKNS2_IS3_Lj3ELj1EEES3_SC_SC_S3_S3_) /* itcm-check-ignore */
|
||||
*(.text._ZN13MavlinkStream12get_size_avgEv)
|
||||
*(.text._ZN16ControlAllocator3RunEv)
|
||||
*(.text._ZN22MulticopterRateControl3RunEv.part.0)
|
||||
*(.text._ZN7Mavlink9task_mainEiPPc)
|
||||
*(.text._ZN7sensors22VehicleAngularVelocity3RunEv)
|
||||
*(.text._ZN4uORB12Subscription9subscribeEv.part.0)
|
||||
*(.text._ZN4uORB7Manager13orb_data_copyEPvS1_Rjb)
|
||||
*(.text._ZN4uORB10DeviceNode5writeEP4filePKcj)
|
||||
*(.text._ZN4uORB10DeviceNode7publishEPK12orb_metadataPvPKv)
|
||||
*(.text._ZN4uORB12DeviceMaster19getDeviceNodeLockedEPK12orb_metadatah)
|
||||
*(.text._Z12get_orb_meta6ORB_ID)
|
||||
*(.text._ZN9ICM42688P12ProcessAccelERKyPKN20InvenSense_ICM42688P4FIFO4DATAEh)
|
||||
*(.text._ZN3px49WorkQueue3RunEv)
|
||||
*(.text._ZN9ICM42688P11ProcessGyroERKyPKN20InvenSense_ICM42688P4FIFO4DATAEh)
|
||||
*(.text._ZN4EKF23RunEv)
|
||||
*(.text._ZN7sensors10VehicleIMU7PublishEv)
|
||||
*(.text._ZN4math17WelfordMeanVectorIfLj3EE6updateERKN6matrix6VectorIfLj3EEE)
|
||||
*(.text._ZN7sensors10VehicleIMU10UpdateGyroEv)
|
||||
*(.text._ZN9ICM42688P8FIFOReadERKyh)
|
||||
*(.text._ZN3Ekf20controlGravityFusionERKN9estimator9imuSampleE)
|
||||
*(.text._ZN16PX4Accelerometer10updateFIFOER19sensor_accel_fifo_s)
|
||||
*(.text._ZN7sensors22VehicleAngularVelocity19CalibrateAndPublishERKyRKN6matrix7Vector3IfEES7_)
|
||||
*(.text._ZN4uORB12Subscription10advertisedEv)
|
||||
*(.text._ZNK15AttitudeControl6updateERKN6matrix10QuaternionIfEE)
|
||||
*(.text._ZN7sensors10VehicleIMU11UpdateAccelEv)
|
||||
*(.text.perf_set_elapsed.part.0)
|
||||
*(.text._ZN4uORB12Subscription6updateEPv)
|
||||
*(.text._ZN12PX4Gyroscope10updateFIFOER18sensor_gyro_fifo_s)
|
||||
*(.text._ZN7sensors10VehicleIMU3RunEv)
|
||||
*(.text.__aeabi_l2f)
|
||||
*(.text._ZN39ControlAllocationSequentialDesaturation23computeDesaturationGainERKN6matrix6VectorIfLj16EEES4_)
|
||||
*(.text.pthread_mutex_timedlock)
|
||||
*(.text._ZN7sensors22VehicleAngularVelocity21FilterAngularVelocityEiPfi)
|
||||
*(.text._ZN26MulticopterAttitudeControl3RunEv.part.0)
|
||||
*(.text._ZN6device3SPI9_transferEPhS1_j)
|
||||
*(.text._ZN15OutputPredictor21calculateOutputStatesEyRKN6matrix7Vector3IfEEfS4_f)
|
||||
*(.text._ZN7sensors18VotedSensorsUpdate7imuPollER17sensor_combined_s)
|
||||
*(.text._Z9rotate_3i8RotationRsS0_S0_)
|
||||
*(.text.fs_getfilep)
|
||||
*(.text.MEM_DataCopy0_1)
|
||||
*(.text._ZN7sensors19VehicleAcceleration3RunEv)
|
||||
*(.text.uart_ioctl)
|
||||
*(.text._ZN26MulticopterPositionControl3RunEv.part.0)
|
||||
*(.text.pthread_mutex_take)
|
||||
*(.text._ZN14ImuDownSampler6updateERKN9estimator9imuSampleE)
|
||||
*(.text._ZN39ControlAllocationSequentialDesaturation6mixYawEv)
|
||||
*(.text._ZN16ControlAllocator25publish_actuator_controlsEv.part.0)
|
||||
*(.text._ZN9ICM42688P7RunImplEv)
|
||||
*(.text._ZN4uORB12Subscription9subscribeEv)
|
||||
*(.text.param_get)
|
||||
*(.text._ZN7sensors22VehicleAngularVelocity21SensorSelectionUpdateERKyb)
|
||||
*(.text._ZN3px49WorkQueue3AddEPNS_8WorkItemE)
|
||||
*(.text._ZN4EKF220PublishLocalPositionERKy)
|
||||
*(.text._mav_finalize_message_chan_send)
|
||||
*(.text._ZN7sensors22VehicleAngularVelocity16ParametersUpdateEb)
|
||||
*(.text._ZN6events12SendProtocol6updateERKy)
|
||||
*(.text._ZN6device3SPI8transferEPhS1_j)
|
||||
*(.text._ZN27MavlinkStreamDistanceSensor4sendEv)
|
||||
*(.text.hrt_call_internal)
|
||||
*(.text._ZN39ControlAllocationSequentialDesaturation18mixAirmodeDisabledEv)
|
||||
*(.text._ZN7Mavlink15get_free_tx_bufEv)
|
||||
*(.text.nx_poll)
|
||||
*(.text._ZN15MavlinkReceiver3runEv)
|
||||
*(.text._ZN9ICM42688P18ProcessTemperatureEPKN20InvenSense_ICM42688P4FIFO4DATAEh)
|
||||
*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEERK9LatLonAltS8_S8_)
|
||||
*(.text._ZN3Ekf12predictStateERKN9estimator9imuSampleE)
|
||||
*(.text._ZN3px46logger6Logger3runEv)
|
||||
*(.text._ZN4uORB20SubscriptionInterval7updatedEv)
|
||||
*(.text._ZN24MavlinkStreamCommandLong4sendEv)
|
||||
*(.text._ZN9Commander3runEv)
|
||||
*(.text._ZN3Ekf17predictCovarianceERKN9estimator9imuSampleE)
|
||||
*(.text.wd_cancel)
|
||||
*(.text._ZN7Sensors3RunEv)
|
||||
*(.text.perf_end)
|
||||
*(.text._ZN4uORB12Subscription7updatedEv)
|
||||
*(.text._ZN13land_detector12LandDetector3RunEv)
|
||||
*(.text.sched_idletask)
|
||||
*(.text.atanf)
|
||||
*(.text.uart_write)
|
||||
*(.text.pthread_mutex_unlock)
|
||||
*(.text.__ieee754_asinf)
|
||||
*(.text.MEM_DataCopy0_2)
|
||||
*(.text._ZN20MavlinkCommandSender13check_timeoutE17mavlink_channel_t)
|
||||
*(.text._ZN16ControlAllocator32publish_control_allocator_statusEi)
|
||||
*(.text.__ieee754_atan2f)
|
||||
*(.text._ZNK18DynamicSparseLayer3getEt)
|
||||
*(.text.__udivmoddi4)
|
||||
*(.text._ZN8Failsafe17checkStateAndModeERKyRKN12FailsafeBase5StateERK16failsafe_flags_s)
|
||||
*(.text._ZN29MavlinkStreamHygrometerSensor4sendEv)
|
||||
*(.text.pthread_mutex_give)
|
||||
*(.text._ZN3Ekf18controlFusionModesERKN9estimator9imuSampleE)
|
||||
*(.text._ZN4cdev4CDev11poll_notifyEm)
|
||||
*(.text.file_vioctl)
|
||||
*(.text._ZN7sensors18VotedSensorsUpdate11sensorsPollER17sensor_combined_s)
|
||||
*(.text.nxsig_nanosleep)
|
||||
*(.text.sem_wait)
|
||||
*(.text.perf_count_interval.part.0)
|
||||
*(.text._ZN16ControlAllocator37update_effectiveness_matrix_if_neededE25EffectivenessUpdateReason)
|
||||
*(.text.MEM_LongCopyJump)
|
||||
*(.text.px4_arch_adc_sample)
|
||||
*(.text._ZN31MulticopterHoverThrustEstimator3RunEv)
|
||||
*(.text._ZNK17ControlAllocation20clipActuatorSetpointERN6matrix6VectorIfLj16EEE)
|
||||
*(.text._ZN4uORB7Manager17get_device_masterEv)
|
||||
*(.text._ZN13DataValidator3putEyPKfmh)
|
||||
*(.text.cdcuart_ioctl)
|
||||
*(.text.cdcacm_sndpacket)
|
||||
*(.text._ZN7sensors22VehicleAngularVelocity16SensorBiasUpdateEb)
|
||||
*(.text._ZN13MavlinkStream11update_dataEv)
|
||||
*(.text._ZN7sensors18VotedSensorsUpdate21calcGyroInconsistencyEv)
|
||||
*(.text.param_set_used)
|
||||
*(.text._ZN18EstimatorInterface10setIMUDataERKN9estimator9imuSampleE)
|
||||
*(.text._ZN18DataValidatorGroup8get_bestEyPi)
|
||||
*(.text._ZN4EKF218PublishInnovationsERKy)
|
||||
*(.text._ZN21MavlinkMissionManager4sendEv)
|
||||
*(.text._ZN22MulticopterRateControl28updateActuatorControlsStatusERK25vehicle_torque_setpoint_sf)
|
||||
*(.text._ZN11RateControl6updateERKN6matrix7Vector3IfEES4_S4_fb)
|
||||
*(.text._ZN39ControlAllocationSequentialDesaturation19desaturateActuatorsERN6matrix6VectorIfLj16EEERKS2_b)
|
||||
*(.text.imxrt_lpi2c_transfer)
|
||||
*(.text.uart_putxmitchar)
|
||||
*(.text.clock_nanosleep)
|
||||
*(.text.up_release_pending)
|
||||
*(.text.MEM_DataCopy0)
|
||||
*(.text._ZN22MavlinkStreamGPSRawInt4sendEv)
|
||||
*(.text.dq_rem)
|
||||
*(.text._ZN15GyroCalibration3RunEv.part.0)
|
||||
*(.text._ZN7sensors18VotedSensorsUpdate22calcAccelInconsistencyEv)
|
||||
*(.text._ZN24MavlinkStreamADSBVehicle4sendEv)
|
||||
*(.text.sinf)
|
||||
*(.text.hrt_call_after)
|
||||
*(.text._ZN39ControlAllocationSequentialDesaturation8allocateEv)
|
||||
*(.text.up_invalidate_dcache)
|
||||
*(.text._ZN15PositionControl16_velocityControlEf)
|
||||
*(.text._ZN4EKF222PublishAidSourceStatusERKy)
|
||||
*(.text._ZN4ListIP13MavlinkStreamE8IteratorppEv)
|
||||
*(.text._ZN20MavlinkStreamESCInfo4sendEv)
|
||||
*(.text.sem_post)
|
||||
*(.text._ZN3px417ScheduledWorkItem15ScheduleDelayedEm)
|
||||
*(.text._ZN10FlightTaskC1Ev)
|
||||
*(.text.usleep)
|
||||
*(.text._ZN14FlightTaskAutoC1Ev)
|
||||
*(.text.sem_getvalue)
|
||||
*(.text._ZN23MavlinkStreamHighresIMU4sendEv)
|
||||
*(.text.imxrt_gpio_write)
|
||||
*(.text._ZN3Ekf6updateEv)
|
||||
*(.text.__ieee754_acosf)
|
||||
*(.text._ZN3Ekf20updateIMUBiasInhibitERKN9estimator9imuSampleE)
|
||||
*(.text._ZN9Commander13dataLinkCheckEv)
|
||||
*(.text._ZN17FlightModeManager10switchTaskE15FlightTaskIndex)
|
||||
*(.text._ZN12PX4Gyroscope9set_scaleEf)
|
||||
*(.text._ZN12FailsafeBase6updateERKyRKNS_5StateEbbRK16failsafe_flags_s)
|
||||
*(.text._ZN18MavlinkStreamDebug4sendEv)
|
||||
*(.text._ZN27MavlinkStreamServoOutputRawILi0EE4sendEv)
|
||||
*(.text.asinf)
|
||||
*(.text._ZN6matrix5EulerIfEC1ERKNS_3DcmIfEE)
|
||||
*(.text._ZN4EKF227PublishInnovationTestRatiosERKy)
|
||||
*(.text._ZN4EKF213PublishStatusERKy)
|
||||
*(.text._ZN4EKF226PublishInnovationVariancesERKy)
|
||||
*(.text._ZN13land_detector23MulticopterLandDetector25_get_ground_contact_stateEv)
|
||||
*(.text.imxrt_dmach_start)
|
||||
*(.text._ZN3ADC19update_system_powerEy)
|
||||
*(.text._ZNK3Ekf19get_ekf_soln_statusEv)
|
||||
*(.text._ZN3px46logger15watchdog_updateERNS0_15watchdog_data_tEb)
|
||||
*(.text.imxrt_gpio_read)
|
||||
*(.text._ZN32MavlinkStreamNavControllerOutput4sendEv)
|
||||
*(.text._ZN39MavlinkStreamGimbalDeviceAttitudeStatus4sendEv)
|
||||
*(.text._ZNK10ConstLayer3getEt)
|
||||
*(.text.__aeabi_uldivmod)
|
||||
*(.text.up_udelay)
|
||||
*(.text.up_idle)
|
||||
*(.text._ZN20MavlinkStreamGPS2Raw4sendEv)
|
||||
*(.text._ZN4EKF217UpdateCalibrationERKyRNS_19InFlightCalibrationERKN6matrix7Vector3IfEES8_fbb)
|
||||
*(.text._ZN28MavlinkStreamGpsGlobalOrigin4sendEv)
|
||||
*(.text._ZN11ControlMath15bodyzToAttitudeEN6matrix7Vector3IfEEfR27vehicle_attitude_setpoint_s)
|
||||
*(.text._ZN4EKF217UpdateRangeSampleER17ekf2_timestamps_s)
|
||||
*(.text._ZN3Ekf24controlOpticalFlowFusionERKN9estimator9imuSampleE)
|
||||
*(.text._ZN19MavlinkStreamRawRpm4sendEv)
|
||||
*(.text._ZN13MavlinkStream10const_rateEv)
|
||||
*(.text._ZN4EKF215PublishOdometryERKyRKN9estimator9imuSampleE)
|
||||
*(.text._ZN15FailureDetector20updateAttitudeStatusERK16vehicle_status_s)
|
||||
*(.text._ZN7Mavlink19configure_sik_radioEv)
|
||||
*(.text._ZN13BatteryStatus8adc_pollEv)
|
||||
*(.text.getpid)
|
||||
*(.text._ZN13DataValidator10confidenceEy)
|
||||
*(.text._ZN22MavlinkStreamGPSStatus4sendEv)
|
||||
*(.text._ZN4EKF220UpdateAirspeedSampleER17ekf2_timestamps_s)
|
||||
*(.text._ZN23MavlinkStreamStatustext4sendEv)
|
||||
*(.text.uart_poll)
|
||||
*(.text._ZN24MavlinkParametersManager4sendEv)
|
||||
*(.text._ZN26MulticopterPositionControl18set_vehicle_statesERK24vehicle_local_position_sf)
|
||||
*(.text.file_poll)
|
||||
*(.text.hrt_elapsed_time)
|
||||
*(.text._ZN7Mavlink11send_finishEv)
|
||||
*(.text._ZNK3Ekf36estimateInertialNavFallingLikelihoodEv)
|
||||
*(.text._ZN15PositionControl16_positionControlEv)
|
||||
*(.text._ZN28MavlinkStreamDebugFloatArray4sendEv)
|
||||
*(.text._ZN11ControlMath9limitTiltERN6matrix7Vector3IfEERKS2_f)
|
||||
*(.text.pthread_mutex_lock)
|
||||
*(.text._ZN21MavlinkStreamAltitude8get_sizeEv)
|
||||
*(.text._ZN7Mavlink29check_requested_subscriptionsEv)
|
||||
*(.text.imxrt_lpspi_setmode)
|
||||
*(.text._ZN3Ekf34controlZeroInnovationHeadingUpdateEv)
|
||||
*(.text.perf_begin)
|
||||
*(.text.imxrt_lpspi_setfrequency)
|
||||
*(.text._ZN17FlightModeManager9_initTaskE15FlightTaskIndex)
|
||||
*(.text._ZN22MulticopterRateControl3RunEv)
|
||||
*(.text.cosf)
|
||||
*(.text._ZN22MavlinkStreamESCStatus4sendEv)
|
||||
*(.text._ZN26MavlinkStreamCameraTrigger4sendEv)
|
||||
*(.text._ZN36MavlinkStreamPositionTargetGlobalInt4sendEv)
|
||||
*(.text._ZN4uORB12Subscription4copyEPv)
|
||||
*(.text._ZN7sensors19VehicleAcceleration21SensorSelectionUpdateEb)
|
||||
*(.text.crc_accumulate)
|
||||
*(.text._ZN3px46logger6Logger13update_paramsEv)
|
||||
*(.text._ZN11calibration14DeviceExternalEm)
|
||||
*(.text._ZN25MavlinkStreamHomePosition8get_sizeEv)
|
||||
*(.text.imxrt_lpspi_modifyreg32)
|
||||
*(.text._ZN7sensors19VehicleAcceleration16SensorBiasUpdateEb)
|
||||
*(.text.modifyreg32)
|
||||
*(.text._ZNK6matrix6MatrixIfLj3ELj1EEmlEf)
|
||||
*(.text._ZN6matrix5EulerIfEC1ERKNS_10QuaternionIfEE)
|
||||
*(.text.imxrt_queuedtd)
|
||||
*(.text._ZN27MavlinkStreamDistanceSensor8get_sizeEv)
|
||||
*(.text._ZN3Ekf23controlBaroHeightFusionERKN9estimator9imuSampleE)
|
||||
*(.text._ZN16PX4Accelerometer9set_scaleEf)
|
||||
*(.text._ZN11ControlMath11constrainXYERKN6matrix7Vector2IfEES4_RKf)
|
||||
*(.text._ZN22MavlinkStreamEfiStatus4sendEv)
|
||||
*(.text._ZN22MavlinkStreamDebugVect4sendEv)
|
||||
*(.text._ZN4EKF217PublishSensorBiasERKy)
|
||||
*(.text._ZN17FlightModeManager3RunEv)
|
||||
*(.text._ZN15PositionControl11_inputValidEv)
|
||||
*(.text._ZN7sensors14VehicleAirData3RunEv)
|
||||
*(.text.perf_count)
|
||||
*(.text._ZN3Ekf16controlMagFusionERKN9estimator9imuSampleE)
|
||||
*(.text.pthread_sem_give)
|
||||
*(.text._ZN7sensors10VehicleIMU16ParametersUpdateEb)
|
||||
*(.text._ZN4uORB20SubscriptionInterval4copyEPv)
|
||||
*(.text._ZN12I2CSPIDriverI9ICM42688PE3RunEv)
|
||||
*(.text.imxrt_epcomplete.constprop.0)
|
||||
*(.text._ZNK6matrix6MatrixIfLj3ELj1EEmiERKS1_)
|
||||
*(.text._ZN9Commander30handleModeIntentionAndFailsafeEv)
|
||||
*(.text.perf_event_count)
|
||||
*(.text._ZN4EKF215PublishAttitudeERKy)
|
||||
*(.text._ZN19MavlinkStreamRawRpm8get_sizeEv)
|
||||
*(.text._ZNK3px46atomicIbE4loadEv)
|
||||
*(.text._ZN29MavlinkStreamHygrometerSensor8get_sizeEv)
|
||||
*(.text.pthread_mutex_add)
|
||||
*(.text._ZN12HomePosition6updateEbb)
|
||||
*(.text.poll_fdsetup)
|
||||
*(.text._ZN15PositionControl20_accelerationControlEv)
|
||||
*(.text._ZN3Ekf19controlHeightFusionERKN9estimator9imuSampleE)
|
||||
*(.text._ZN9Commander19control_status_ledsEbh)
|
||||
*(.text._ZN6device3I2C8transferEPKhjPhj)
|
||||
*(.text.orb_publish)
|
||||
*(.text._ZN7sensors19VehicleAcceleration16ParametersUpdateEb)
|
||||
*(.text._ZN22MavlinkStreamVibration8get_sizeEv)
|
||||
*(.text._ZN15MavlinkReceiver15CheckHeartbeatsERKyb)
|
||||
*(.text._ZNK6matrix7Vector3IfEmiES1_)
|
||||
*(.text.__aeabi_f2ulz)
|
||||
*(.text._ZN9ICM42688P26DataReadyInterruptCallbackEiPvS0_)
|
||||
*(.text._ZN13land_detector23MulticopterLandDetector23_get_maybe_landed_stateEv)
|
||||
*(.text.acosf)
|
||||
*(.text._ZN14ImuDownSampler5resetEv)
|
||||
*(.text._ZN3Ekf31checkVerticalAccelerationHealthERKN9estimator9imuSampleE)
|
||||
*(.text._ZN6matrix6MatrixIfLj3ELj1EEC1ERKS1_)
|
||||
*(.text.udp_pollsetup)
|
||||
*(.text._ZL14timer_callbackPv)
|
||||
*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj24EEEf)
|
||||
*(.text._ZN13land_detector23MulticopterLandDetector22_set_hysteresis_factorEi)
|
||||
*(.text.nxsem_wait_irq)
|
||||
*(.text._ZN20MavlinkCommandSender4lockEv)
|
||||
*(.text.MEM_LongCopyEnd)
|
||||
*(.text._ZThn24_N16ControlAllocator3RunEv)
|
||||
*(.text._ZN15TimestampedListIN20MavlinkCommandSender14command_item_sELi3EE8get_nextEv)
|
||||
*(.text._ZNK3Ekf21get_ekf_lpos_accuracyEPfS0_)
|
||||
*(.text._ZN17FlightModeManager17start_flight_taskEv)
|
||||
*(.text.MEM_DataCopyBytes)
|
||||
*(.text._ZN29MavlinkStreamLocalPositionNED8get_sizeEv)
|
||||
*(.text._ZN6SticksC1EP12ModuleParams)
|
||||
*(.text._ZN27MavlinkStreamServoOutputRawILi1EE4sendEv)
|
||||
*(.text._ZN3Ekf35updateHorizontalDeadReckoningstatusEv)
|
||||
*(.text._ZN3Ekf20controlAirDataFusionERKN9estimator9imuSampleE)
|
||||
*(.text._ZN24FlightTaskManualAltitudeC1Ev)
|
||||
*(.text._ZN25MavlinkStreamHomePosition4sendEv)
|
||||
*(.text._ZN24MavlinkParametersManager8send_oneEv)
|
||||
*(.text._ZN15OutputPredictor29applyCorrectionToOutputBufferERKN6matrix7Vector3IfEES4_)
|
||||
*(.text._ZN21HealthAndArmingChecks6updateEbb)
|
||||
*(.text._ZThn24_N22MulticopterRateControl3RunEv)
|
||||
*(.text._ZN26MavlinkStreamManualControl4sendEv)
|
||||
*(.text._ZN27MavlinkStreamOpticalFlowRad4sendEv)
|
||||
*(.text._ZN18mag_bias_estimator16MagBiasEstimator3RunEv)
|
||||
*(.text._ZN4uORB7Manager11orb_publishEPK12orb_metadataPvPKv)
|
||||
*(.text._ZN24MavlinkParametersManager18send_untransmittedEv)
|
||||
*(.text._ZN10MavlinkFTP4sendEv)
|
||||
*(.text._ZN3Ekf27controlExternalVisionFusionERKN9estimator9imuSampleE)
|
||||
*(.text.clock_gettime)
|
||||
*(.text._ZN3ADC17update_adc_reportEy)
|
||||
*(.text._ZN32MavlinkStreamGimbalManagerStatus4sendEv)
|
||||
*(.text._ZN9LockGuardD1Ev) /* itcm-check-ignore */
|
||||
*(.text._ZN4EKF213PublishStatesERKy)
|
||||
*(.text._ZN3ADC3RunEv)
|
||||
*(.text._ZN6BMP38815compensate_dataEhPK16bmp3_uncomp_dataP9bmp3_data)
|
||||
*(.text._ZN3Ekf20controlFakePosFusionEv)
|
||||
*(.text._ZN11calibration9Gyroscope13set_device_idEm)
|
||||
*(.text._ZN24MavlinkStreamOrbitStatus8get_sizeEv)
|
||||
*(.text.imxrt_progressep)
|
||||
*(.text.imxrt_gpio_configinput)
|
||||
*(.text._ZN17FlightModeManager26generateTrajectorySetpointEfRK24vehicle_local_position_s)
|
||||
*(.text._ZN7Sensors14diff_pres_pollEv)
|
||||
*(.text._ZN21MavlinkStreamAttitude4sendEv)
|
||||
*(.text._ZN4EKF220UpdateMagCalibrationERKy)
|
||||
*(.text._ZN22MavlinkStreamEfiStatus8get_sizeEv)
|
||||
*(.text._ZN9ICM42688P9DataReadyEv)
|
||||
*(.text._ZN21MavlinkMissionManager20check_active_missionEv)
|
||||
*(.text._ZNK3Ekf20get_ekf_vel_accuracyEPfS0_)
|
||||
*(.text._ZN4EKF216UpdateBaroSampleER17ekf2_timestamps_s)
|
||||
*(.text._ZN4EKF223UpdateSystemFlagsSampleER17ekf2_timestamps_s)
|
||||
*(.text._ZThn16_N7sensors22VehicleAngularVelocity3RunEv)
|
||||
*(.text._ZN29MavlinkStreamObstacleDistance4sendEv)
|
||||
*(.text._ZN24MavlinkStreamOrbitStatus4sendEv)
|
||||
*(.text._ZN9Navigator3runEv)
|
||||
*(.text._ZN24MavlinkParametersManager11send_paramsEv)
|
||||
*(.text._ZN17MavlinkLogHandler4sendEv)
|
||||
*(.text._ZN7control10SuperBlock5setDtEf)
|
||||
*(.text._ZN29MavlinkStreamMountOrientation8get_sizeEv)
|
||||
*(.text._ZN26MulticopterAttitudeControl3RunEv)
|
||||
*(.text._ZThn16_N31ActuatorEffectivenessMultirotor22getEffectivenessMatrixERN21ActuatorEffectiveness13ConfigurationE25EffectivenessUpdateReason)
|
||||
*(.text._ZN4EKF218PublishStatusFlagsERKy)
|
||||
*(.text._ZN11WeatherVaneC1EP12ModuleParams)
|
||||
*(.text._ZN15FailureDetector6updateERK16vehicle_status_sRK22vehicle_control_mode_s)
|
||||
*(.text._ZN7Mavlink10send_startEi)
|
||||
*(.text.imxrt_lpspi_setbits)
|
||||
*(.text._ZN15OutputPredictor37applyCorrectionToVerticalOutputBufferEff)
|
||||
*(.text._ZN4EKF222UpdateAccelCalibrationERKy)
|
||||
*(.text._ZN7sensors19VehicleMagnetometer3RunEv)
|
||||
*(.text._ZN29MavlinkStreamMountOrientation4sendEv)
|
||||
*(.text._ZN13land_detector12LandDetector19UpdateVehicleAtRestEv)
|
||||
*(.text._ZN10FlightTask29_evaluateVehicleLocalPositionEv)
|
||||
*(.text.__aeabi_f2lz)
|
||||
*(.text._ZN32MavlinkStreamCameraImageCaptured4sendEv)
|
||||
*(.text._ZN21MavlinkStreamOdometry8get_sizeEv)
|
||||
*(.text._ZN28MavlinkStreamNamedValueFloat4sendEv)
|
||||
*(.text.__aeabi_ul2f)
|
||||
*(.text.poll)
|
||||
*(.text._ZN14FlightTaskAutoD1Ev)
|
||||
*(.text._ZN4uORB10DeviceNode22get_initial_generationEv)
|
||||
*(.text._ZN3Ekf23controlGnssHeightFusionERKN9estimator10gnssSampleE)
|
||||
*(.text._ZN3Ekf40updateOnGroundMotionForOpticalFlowChecksEv)
|
||||
*(.text._ZN6matrix6MatrixIfLj3ELj1EEC1Ev)
|
||||
*(.text._ZN14ZeroGyroUpdate6updateER3EkfRKN9estimator9imuSampleE)
|
||||
*(.text._ZN30MavlinkStreamOpenDroneIdSystem4sendEv)
|
||||
*(.text._ZN22MavlinkStreamScaledIMU4sendEv)
|
||||
*(.text.imxrt_ioctl)
|
||||
*(.text._ZN36MavlinkStreamGimbalDeviceSetAttitude4sendEv)
|
||||
*(.text._ZN4math13expo_deadzoneIfEEKT_RS2_S3_S3_.isra.0)
|
||||
*(.text._ZN19StickAccelerationXYC1EP12ModuleParams)
|
||||
*(.text.imxrt_epsubmit)
|
||||
*(.text._ZN15PositionControl6updateEf)
|
||||
*(.text._ZN23MavlinkStreamScaledIMU24sendEv)
|
||||
*(.text.imxrt_dma_send)
|
||||
*(.text._ZN20MavlinkStreamWindCov4sendEv)
|
||||
*(.text._ZN7sensors18VotedSensorsUpdate13checkFailoverERNS0_10SensorDataEPKcN6events3px45enums13sensor_type_tE)
|
||||
*(.text._ZN21MavlinkStreamOdometry4sendEv)
|
||||
*(.text.vsprintf_internal.constprop.0)
|
||||
*(.text.udp_pollteardown)
|
||||
*(.text._ZN12MixingOutput6updateEv)
|
||||
*(.text.clock_abstime2ticks)
|
||||
*(.text._ZN13BatteryStatus3RunEv)
|
||||
*(.text._ZN32MavlinkStreamGimbalManagerStatus8get_sizeEv)
|
||||
*(.text._ZN10FlightTask15_resetSetpointsEv)
|
||||
*(.text._ZN9systemlib10Hysteresis20set_state_and_updateEbRKy)
|
||||
*(.text.devif_callback_free.part.0)
|
||||
*(.text._ZN6Sticks25checkAndUpdateStickInputsEv)
|
||||
*(.text.atan2f)
|
||||
*(.text._ZN23MavlinkStreamRCChannels4sendEv)
|
||||
*(.text._ZN4EKF221UpdateExtVisionSampleER17ekf2_timestamps_s)
|
||||
*(.text.imxrt_dmach_stop)
|
||||
*(.text._ZN9Commander16handleAutoDisarmEv)
|
||||
*(.text._ZN9Commander11updateTunesEv)
|
||||
*(.text._ZN4EKF215UpdateMagSampleER17ekf2_timestamps_s)
|
||||
*(.text._ZN18DataValidatorGroup3putEjyPKfmh)
|
||||
*(.text._ZNK3Ekf19get_ekf_ctrl_limitsEPfS0_S0_S0_S0_)
|
||||
*(.text._ZN12FailsafeBase13checkFailsafeEibbRKNS_13ActionOptionsE)
|
||||
*(.text._ZN17FlightTaskDescendD1Ev)
|
||||
*(.text._ZN30MavlinkStreamOpenDroneIdSystem8get_sizeEv)
|
||||
*(.text._ZNK3px46logger9LogWriter10is_startedENS0_7LogTypeE)
|
||||
*(.text._ZN24FlightTaskManualAltitudeD1Ev)
|
||||
*(.text._Z35px4_indicate_external_reset_lockout16LockoutComponentb)
|
||||
*(.text.uart_pollnotify)
|
||||
*(.text._ZN4EKF215PublishBaroBiasERKy)
|
||||
*(.text._ZN4EKF221UpdateGyroCalibrationERKy)
|
||||
*(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_)
|
||||
*(.text._ZN4uORB22SubscriptionMultiArrayI16battery_status_sLh3EE16advertised_countEv)
|
||||
*(.text._ZN23MavlinkStreamScaledIMU34sendEv)
|
||||
*(.text.__aeabi_ldivmod)
|
||||
*(.text._ZN15PositionControl16setInputSetpointERK21trajectory_setpoint_s)
|
||||
*(.text.nxsig_pendingset)
|
||||
*(.text.psock_poll)
|
||||
*(.text._ZN15FailureInjector6updateEv)
|
||||
*(.text.imxrt_writedtd)
|
||||
*(.text.cdcacm_wrcomplete)
|
||||
*(.text.cdcuart_txint)
|
||||
*(.text._ZN3Ekf33updateVerticalDeadReckoningStatusEv)
|
||||
*(.text._ZN33FlightTaskManualAltitudeSmoothVelC1Ev)
|
||||
*(.text.powf)
|
||||
*(.text._ZN4EKF217PublishEventFlagsERKy)
|
||||
*(.text._ZN17FlightTaskDescend6updateEv)
|
||||
*(.text.imxrt_iomux_configure)
|
||||
*(.text.hrt_store_absolute_time)
|
||||
*(.text.nxsem_set_protocol)
|
||||
*(.text.write)
|
||||
*(.text._ZN22MavlinkStreamSysStatus4sendEv)
|
||||
*(.text._ZN4EKF216UpdateFlowSampleER17ekf2_timestamps_s)
|
||||
*(.text._ZN4cdevL10cdev_ioctlEP4fileim)
|
||||
*(.text._ZN7Mavlink10send_bytesEPKhj)
|
||||
*(.text._ZNK8Failsafe17checkModeFallbackERK16failsafe_flags_sh)
|
||||
*(.text.clock_systime_timespec)
|
||||
*(.text._ZN4uORB10DeviceNode26remove_internal_subscriberEv)
|
||||
*(.text._ZThn16_N4EKF23RunEv)
|
||||
*(.text._ZNK3Ekf22computeYawInnovVarAndHEfRfRN6matrix6VectorIfLj24EEE)
|
||||
*(.text._ZN12ActuatorTest6updateEif)
|
||||
*(.text._ZN17VelocitySmoothingC1Efff)
|
||||
*(.text._ZN13AnalogBattery19get_voltage_channelEv)
|
||||
*(.text._ZN10FlightTask37_evaluateVehicleLocalPositionSetpointEv)
|
||||
*(.text._ZN4uORB12Subscription11unsubscribeEv)
|
||||
*(.text.net_lock)
|
||||
*(.text.clock_time2ticks)
|
||||
*(.text._ZN12FailsafeBase16updateStartDelayERKyb)
|
||||
*(.text._ZN23MavlinkStreamStatustext8get_sizeEv)
|
||||
*(.text._ZN11calibration13Accelerometer13set_device_idEm)
|
||||
*(.text._ZN3px46logger6Logger18start_stop_loggingEv)
|
||||
*(.text._ZN14FlightTaskAuto17_evaluateTripletsEv)
|
||||
*(.text._ZN11calibration9Gyroscope23SensorCorrectionsUpdateEb)
|
||||
*(.text._ZN25MavlinkStreamMagCalReport4sendEv)
|
||||
*(.text.imxrt_config_gpio)
|
||||
*(.text.nxsig_timeout)
|
||||
*(.text._ZN11RateControl19setSaturationStatusERKN6matrix7Vector3IbEES4_)
|
||||
*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj24EEERKS2_ff)
|
||||
*(.text.dq_addlast)
|
||||
*(.text._ZN19MavlinkStreamVFRHUD4sendEv)
|
||||
*(.text.hrt_call_reschedule)
|
||||
*(.text.nxsem_boost_priority)
|
||||
*(.text._ZN4EKF215UpdateGpsSampleER17ekf2_timestamps_s)
|
||||
*(.text._ZN8StickYawC1EP12ModuleParams)
|
||||
*(.text._ZN7control12BlockLowPass6updateEf)
|
||||
*(.text._ZN15FailureDetector26updateImbalancedPropStatusEv)
|
||||
*(.text._ZN9systemlib10Hysteresis6updateERKy)
|
||||
*(.text.nxsem_tickwait_uninterruptible)
|
||||
*(.text._ZN12HomePosition31hasMovedFromCurrentHomeLocationEv)
|
||||
*(.text.devif_callback_alloc)
|
||||
*(.text._ZN28MavlinkStreamNamedValueFloat8get_sizeEv)
|
||||
*(.text._ZN24MavlinkStreamADSBVehicle8get_sizeEv)
|
||||
*(.text._ZN26MavlinkStreamBatteryStatus8get_sizeEv)
|
||||
*(.text._ZN26MulticopterPositionControl17parameters_updateEb)
|
||||
*(.text._ZN3px46logger6Logger29handle_vehicle_command_updateEv)
|
||||
*(.text.imxrt_lpspi_send)
|
||||
*(.text._ZN4uORB10DeviceNode23add_internal_subscriberEv)
|
||||
*(.text._ZN6matrix6MatrixIfLj3ELj1EEaSERKS1_)
|
||||
*(.text._ZNK6matrix6MatrixIfLj3ELj1EE5emultERKS1_)
|
||||
*(.text.mallinfo_handler)
|
||||
*(.text._ZN13land_detector23MulticopterLandDetector14_update_topicsEv)
|
||||
*(.text._ZN24ManualVelocitySmoothingZC1Ev) /* itcm-check-ignore */
|
||||
*(.text._ZN3ADC6sampleEj)
|
||||
*(.text._ZNK3Ekf22isTerrainEstimateValidEv)
|
||||
*(.text._ZN15EstimatorChecks23setModeRequirementFlagsERK7ContextbbbRK24vehicle_local_position_sRK12sensor_gps_sR16failsafe_flags_sR6Report)
|
||||
*(.text._ZN11ControlMath11addIfNotNanERff)
|
||||
*(.text._ZN9Commander21checkForMissionUpdateEv)
|
||||
*(.text._Z8set_tunei)
|
||||
*(.text._ZNK6matrix7Vector3IfE5crossERKNS_6MatrixIfLj3ELj1EEE)
|
||||
*(.text._ZN10FlightTask22_checkEkfResetCountersEv)
|
||||
*(.text._ZNK6matrix6MatrixIfLj3ELj1EE11isAllFiniteEv)
|
||||
*(.text._ZN14FlightTaskAuto24_evaluateGlobalReferenceEv)
|
||||
*(.text._ZN6matrix9constrainIfLj2ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_)
|
||||
*(.text._ZN3px46logger6Logger23handle_file_write_errorEv)
|
||||
*(.text._ZN10FlightTask16updateInitializeEv)
|
||||
*(.text._ZN11calibration9Gyroscope10set_offsetERKN6matrix7Vector3IfEE)
|
||||
*(.text._ZNK6matrix6VectorIfLj3EE4normEv)
|
||||
*(.text._ZN14FlightTaskAuto16updateInitializeEv)
|
||||
*(.text.fabsf)
|
||||
*(.text._ZN27MavlinkStreamAttitudeTarget8get_sizeEv)
|
||||
*(.text.nxsem_get_value)
|
||||
*(.text._ZN13AnalogBattery8is_validEv)
|
||||
*(.text._ZN4uORB16SubscriptionDataI15home_position_sEC1EPK12orb_metadatah)
|
||||
*(.text._ZN22MavlinkStreamGPSStatus8get_sizeEv)
|
||||
*(.text.nxsem_destroyholder)
|
||||
*(.text.psock_udp_cansend)
|
||||
*(.text.MEM_DataCopy2_2)
|
||||
*(.text._ZN10FlightTask8activateERK21trajectory_setpoint_s)
|
||||
*(.text.sock_file_poll)
|
||||
*(.text._ZN10Ringbuffer9pop_frontEPhj)
|
||||
*(.text.nx_write)
|
||||
*(.text._ZN9Commander18manualControlCheckEv)
|
||||
*(.text._ZN31MavlinkStreamAttitudeQuaternion4sendEv)
|
||||
*(.text.nxsem_canceled)
|
||||
*(.text._ZN10FlightTask21getTrajectorySetpointEv)
|
||||
*(.text.imxrt_dmach_getcount)
|
||||
*(.text.sem_clockwait)
|
||||
*(.text.inet_poll)
|
||||
*(.text._ZN6BMP3887collectEv)
|
||||
*(.text._ZNK15PositionControl24getLocalPositionSetpointER33vehicle_local_position_setpoint_s)
|
||||
*(.text._ZN3Ekf16controlGpsFusionERKN9estimator9imuSampleE)
|
||||
*(.text._ZN23MavlinkStreamRCChannels8get_sizeEv)
|
||||
*(.text._ZN20MavlinkStreamESCInfo8get_sizeEv)
|
||||
*(.text._ZNK6matrix6VectorIfLj2EE4normEv)
|
||||
*(.text._Z15arm_auth_updateyb)
|
||||
*(.text._ZN3LED5ioctlEP4fileim) /* itcm-check-ignore */
|
||||
*(.text._ZNK3px46logger9LogWriter20had_file_write_errorEv)
|
||||
*(.text._ZN29MavlinkStreamLocalPositionNED4sendEv)
|
||||
*(.text._ZNK6matrix6VectorIfLj3EE3dotERKNS_6MatrixIfLj3ELj1EEE)
|
||||
*(.text.imxrt_lpi2c_setclock)
|
||||
*(.text._ZN6matrix12typeFunction9constrainIfEET_S2_S2_S2_.part.0)
|
||||
*(.text._ZN13MapProjection13initReferenceEddy)
|
||||
*(.text._ZN11calibration13Accelerometer23SensorCorrectionsUpdateEb)
|
||||
*(.text._ZN31MavlinkStreamAttitudeQuaternion8get_sizeEv)
|
||||
*(.text._ZN30MavlinkStreamGlobalPositionInt4sendEv)
|
||||
*(.text._ZN6SticksD1Ev)
|
||||
*(.text._ZN13NavigatorMode3runEb)
|
||||
*(.text._ZL19param_find_internalPKcb)
|
||||
*(.text.uart_datasent)
|
||||
*(.text._ZN4EKF221PublishOpticalFlowVelERKy)
|
||||
*(.text.nxsem_destroy)
|
||||
*(.text.file_write)
|
||||
*(.text._ZN21MavlinkStreamAltitude4sendEv)
|
||||
*(.text._ZN7sensors14VehicleAirData12UpdateStatusEv)
|
||||
*(.text.imxrt_padmux_map)
|
||||
*(.text._ZN6BMP38815get_sensor_dataEhP9bmp3_data)
|
||||
*(.text._ZN18MavlinkRateLimiter5checkERKy)
|
||||
*(.text._ZThn24_N26MulticopterAttitudeControl3RunEv)
|
||||
*(.text.imxrt_periphclk_configure)
|
||||
*(.text._ZN4EKF218UpdateAuxVelSampleER17ekf2_timestamps_s)
|
||||
*(.text._ZN3RTL11on_inactiveEv)
|
||||
*(.text._ZN12FailsafeBase10modeCanRunERK16failsafe_flags_sh)
|
||||
*(.text._ZN4EKF216PublishEvPosBiasERKy)
|
||||
*(.text._ZN21MavlinkStreamAttitude8get_sizeEv)
|
||||
*(.text._ZThn16_N7sensors19VehicleAcceleration3RunEv)
|
||||
*(.text._ZN33MavlinkStreamTimeEstimateToTarget4sendEv)
|
||||
*(.text._ZN6matrix6MatrixIfLj3ELj1EE6setAllEf)
|
||||
*(.text._ZN12ModuleParamsD1Ev)
|
||||
*(.text._ZN3Ekf20controlFakeHgtFusionEv)
|
||||
*(.text.imxrt_reqcomplete)
|
||||
*(.text._ZNK6matrix7Vector3IfEmlEf)
|
||||
*(.text._ZN18ZeroVelocityUpdate6updateER3EkfRKN9estimator9imuSampleE)
|
||||
*(.text._ZN11ControlMath19addIfNotNanVector3fERN6matrix7Vector3IfEERKS2_)
|
||||
*(.text._ZN11ControlMath16thrustToAttitudeERKN6matrix7Vector3IfEEfR27vehicle_attitude_setpoint_s)
|
||||
*(.text.cos)
|
||||
*(.text.net_unlock)
|
||||
*(.text._ZN7sensors18VotedSensorsUpdate21setRelativeTimestampsER17sensor_combined_s)
|
||||
*(.text._ZN12FailsafeBase13ActionOptionsC1ENS_6ActionE)
|
||||
*(.text._ZN24FlightTaskManualAltitude16updateInitializeEv)
|
||||
*(.text._ZN26MulticopterPositionControl3RunEv)
|
||||
*(.text._ZN8Failsafe21fromQuadchuteActParamEi)
|
||||
*(.text._ZN24VariableLengthRingbuffer9pop_frontEPhj)
|
||||
*(.text._ZN7control15BlockDerivative6updateEf) /* itcm-check-ignore */
|
||||
*(.text._ZN9Commander18safetyButtonUpdateEv)
|
||||
*(.text._ZN13BatteryChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text._ZN18DataValidatorGroup16get_sensor_stateEj)
|
||||
*(.text.uart_xmitchars_done)
|
||||
*(.text._ZN4EKF225PublishYawEstimatorStatusERKy)
|
||||
*(.text.sin)
|
||||
*(.text._ZN6Safety19safetyButtonHandlerEv)
|
||||
*(.text._ZN3Ekf19controlAuxVelFusionERKN9estimator9imuSampleE)
|
||||
*(.text._ZNK6matrix6MatrixIfLj2ELj1EEplERKS1_)
|
||||
*(.text._ZThn24_N7Sensors3RunEv)
|
||||
*(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ERKS1_)
|
||||
*(.text._ZN10FlightTask10reActivateEv)
|
||||
*(.text._ZNK15PositionControl19getAttitudeSetpointER27vehicle_attitude_setpoint_s)
|
||||
*(.text._ZN4cdev4CDev4pollEP4fileP6pollfdb)
|
||||
*(.text._ZN9Commander20offboardControlCheckEv)
|
||||
*(.text._ZN4EKF216PublishGpsStatusERKy)
|
||||
*(.text._ZN4uORB12SubscriptionaSEOS0_)
|
||||
*(.text._ZN15TakeoffHandling18updateTakeoffStateEbbbfbRKy)
|
||||
*(.text._ZN10ModeChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text._ZN14FlightTaskAuto24_updateInternalWaypointsEv)
|
||||
*(.text._ZN8Failsafe17updateArmingStateERKybRK16failsafe_flags_s)
|
||||
*(.text.imxrt_lpi2c_modifyreg)
|
||||
*(.text.up_flush_dcache)
|
||||
*(.text._ZN15GyroCalibration3RunEv)
|
||||
*(.text.mavlink_start_uart_send)
|
||||
*(.text.MEM_DataCopy2)
|
||||
*(.text._ZNK9Commander14getPrearmStateEv)
|
||||
*(.text._ZN15EstimatorChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text._ZN28FlightTaskManualAccelerationD1Ev)
|
||||
*(.text._ZN11RateControl20getRateControlStatusER18rate_ctrl_status_s)
|
||||
*(.text._ZN4uORB10DeviceNode15poll_notify_oneEP6pollfdm)
|
||||
*(.text._ZN3GPS21handleInjectDataTopicEv.part.0)
|
||||
*(.text._ZN9Commander17systemPowerUpdateEv)
|
||||
*(.text._ZN4EKF221PublishGlobalPositionERKy)
|
||||
*(.text._ZNK12FailsafeBase17getSelectedActionERKNS_5StateERK16failsafe_flags_sbbRNS_19SelectedActionStateE)
|
||||
*(.text.imxrt_padctl_address)
|
||||
*(.text._ZNK6matrix6VectorIfLj2EE4unitEv)
|
||||
*(.text._ZN19RcCalibrationChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text.devif_conn_callback_free)
|
||||
*(.text._ZN13InnovationLpf6updateEfff.isra.0)
|
||||
*(.text._ZN9Commander18landDetectorUpdateEv)
|
||||
*(.text._ZN3Ekf18updateGroundEffectEv)
|
||||
*(.text.nxsem_init)
|
||||
*(.text._ZN9Commander16vtolStatusUpdateEv)
|
||||
*(.text._ZN6matrix6MatrixIfLj4ELj1EEC1EPKf)
|
||||
*(.text._ZN11ControlMath20setZeroIfNanVector3fERN6matrix7Vector3IfEE)
|
||||
*(.text._ZThn8_N3ADC3RunEv)
|
||||
*(.text._ZN11StickTiltXYC1EP12ModuleParams)
|
||||
*(.text._ZN12SafetyButton3RunEv)
|
||||
*(.text._ZN6BMP38811set_op_modeEh)
|
||||
*(.text._ZN3GPS8callbackE15GPSCallbackTypePviS1_)
|
||||
*(.text._ZN13AnalogBattery19get_current_channelEv)
|
||||
*(.text._ZN15EstimatorChecks20checkEstimatorStatusERK7ContextR6ReportRK18estimator_status_s8NavModes)
|
||||
*(.text._ZN12FailsafeBase11updateDelayERKy)
|
||||
*(.text._ZN10FlightTask25_evaluateDistanceToGroundEv)
|
||||
*(.text._ZN4EKF218PublishGnssHgtBiasERKy)
|
||||
*(.text._ZN6matrix6VectorIfLj3EE9normalizeEv)
|
||||
*(.text._ZThn16_N7sensors10VehicleIMU3RunEv)
|
||||
*(.text.__kernel_cos)
|
||||
*(.text._ZN12SafetyButton19CheckPairingRequestEb)
|
||||
*(.text.imxrt_dma_txavailable)
|
||||
*(.text.perf_set_elapsed)
|
||||
*(.text.pthread_sem_take)
|
||||
*(.text._ZN8StickYawD1Ev)
|
||||
*(.text._Z15blink_msg_statev)
|
||||
*(.text._ZN19AccelerometerChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text._ZN8Failsafe14fromGfActParamEi)
|
||||
*(.text._ZN3Ekf17controlBetaFusionERKN9estimator9imuSampleE)
|
||||
*(.text._ZN36do_not_explicitly_use_this_namespace5ParamIfLN3px46paramsE919EEC1Ev) /* itcm-check-ignore */
|
||||
*(.text._ZN22MavlinkStreamHeartbeat8get_sizeEv)
|
||||
*(.text._ZN6matrix6MatrixIfLj3ELj1EEdVEf)
|
||||
*(.text._ZN17FlightTaskDescendC1Ev)
|
||||
*(.text._ZN26MavlinkStreamCameraTrigger8get_sizeEv)
|
||||
*(.text.iob_navail)
|
||||
*(.text._ZN12FailsafeBase25removeNonActivatedActionsEv)
|
||||
*(.text._ZN15TakeoffHandling10updateRampEff)
|
||||
*(.text._Z7led_offi)
|
||||
*(.text.led_off)
|
||||
*(.text.udp_wrbuffer_test)
|
||||
*(.text._ZNK4math17WelfordMeanVectorIfLj3EE8varianceEv)
|
||||
*(.text._ZN27MavlinkStreamAttitudeTarget4sendEv)
|
||||
*(.text._ZN12MixingOutput19updateSubscriptionsEb)
|
||||
*(.text._ZN10FlightTaskD1Ev)
|
||||
*(.text._ZThn24_N13land_detector12LandDetector3RunEv)
|
||||
*(.text._ZN18MavlinkStreamDebug8get_sizeEv)
|
||||
*(.text._ZN12GPSDriverUBX7receiveEj)
|
||||
*(.text._ZN13BatteryStatus21parameter_update_pollEb)
|
||||
*(.text._ZN3RTL18updateDatamanCacheEv)
|
||||
*(.text.__ieee754_sqrtf)
|
||||
*(.text._ZThn24_N18mag_bias_estimator16MagBiasEstimator3RunEv)
|
||||
*(.text.__kernel_sin)
|
||||
*(.text._ZN11MissionBase17parameters_updateEv)
|
||||
*(.text.nx_start)
|
||||
*(.text._ZN3Ekf17controlDragFusionERKN9estimator9imuSampleE)
|
||||
*(.text._ZNK8Failsafe22modifyUserIntendedModeEN12FailsafeBase6ActionES1_h)
|
||||
*(.text._ZN3px417ScheduledWorkItem19schedule_trampolineEPv)
|
||||
*(.text.uart_xmitchars_dma)
|
||||
*(.text._ZN13land_detector23MulticopterLandDetector19_get_freefall_stateEv)
|
||||
*(.text._ZThn24_N31MulticopterHoverThrustEstimator3RunEv)
|
||||
*(.text._ZN11MissionBase11on_inactiveEv)
|
||||
*(.text._ZN21FailureDetectorChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text._ZN12SystemChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text._ZN6matrix6MatrixIfLj3ELj1EEC1EPKf)
|
||||
*(.text.imxrt_padmux_address)
|
||||
*(.text._ZN19MavlinkStreamVFRHUD8get_sizeEv)
|
||||
*(.text._ZN15EstimatorChecks15checkSensorBiasERK7ContextR6Report8NavModes)
|
||||
*(.text._ZN20ImuConsistencyChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text._ZN28MavlinkStreamGpsGlobalOrigin8get_sizeEv)
|
||||
*(.text.MEM_DataCopy2_1)
|
||||
*(.text._ZN6BMP3887measureEv)
|
||||
*(.text._ZN4EKF217PublishRngHgtBiasERKy)
|
||||
*(.text._ZN36MavlinkStreamPositionTargetGlobalInt8get_sizeEv)
|
||||
*(.text._ZN28MavlinkStreamEstimatorStatus8get_sizeEv)
|
||||
*(.text.up_clean_dcache)
|
||||
*(.text._ZThn24_N26MulticopterPositionControl3RunEv)
|
||||
*(.text._ZN16FlightTimeChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text._ZN13ManualControl12processInputEy)
|
||||
*(.text._ZN17CpuResourceChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text._ZN10GyroChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text._ZN8Failsafe26fromImbalancedPropActParamEi)
|
||||
*(.text._ZThn24_N13BatteryStatus3RunEv)
|
||||
*(.text.mm_foreach)
|
||||
*(.text._ZN35MavlinkStreamPositionTargetLocalNed8get_sizeEv)
|
||||
*(.text._ZN32MavlinkStreamNavControllerOutput8get_sizeEv)
|
||||
*(.text._ZN6matrix8wrap_2piIfEET_S1_)
|
||||
*(.text._ZN4uORB7Manager30orb_remove_internal_subscriberEPv)
|
||||
*(.text._ZN10BMP388_I2C7get_regEhPh)
|
||||
*(.text._ZN4math17WelfordMeanVectorIfLj3EE5resetEv)
|
||||
*(.text._ZN27MavlinkStreamScaledPressure8get_sizeEv)
|
||||
*(.text._ZN3RTL17parameters_updateEv)
|
||||
*(.text._ZN18EstimatorInterface11setBaroDataERKN9estimator10baroSampleE.part.0)
|
||||
*(.text._ZN32MavlinkStreamOpenDroneIdLocation8get_sizeEv)
|
||||
*(.text._ZN21MavlinkStreamTimesync4sendEv)
|
||||
*(.text._ZN9Navigator23reset_position_setpointER19position_setpoint_s)
|
||||
*(.text._ZN19RcAndDataLinkChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text.imxrt_dma_txcallback)
|
||||
*(.text._ZN24MavlinkParametersManager11send_uavcanEv)
|
||||
*(.text._ZN4uORB10DeviceNode4readEP4filePcj)
|
||||
*(.text._ZN4uORB10DeviceNode10poll_stateEP4file)
|
||||
*(.text._ZN4uORB7Manager8orb_copyEPK12orb_metadataiPv)
|
||||
*(.text._ZN27MavlinkStreamServoOutputRawILi0EE8get_sizeEv)
|
||||
*(.text._ZN8Geofence3runEv)
|
||||
*(.text._ZN15EstimatorChecks25checkEstimatorStatusFlagsERK7ContextR6ReportRK18estimator_status_sRK24vehicle_local_position_s)
|
||||
*(.text._ZN18MagnetometerChecks14checkAndReportERK7ContextR6Report)
|
||||
*(.text._ZN6events9SendEvent3RunEv)
|
||||
*(.text._ZN30MavlinkStreamGlobalPositionInt8get_sizeEv)
|
||||
*(.text._ZN22MavlinkStreamESCStatus8get_sizeEv)
|
||||
*(.text._Z20px4_spi_bus_externalRK13px4_spi_bus_t)
|
||||
*(.text.read)
|
||||
*(.text._ZN4uORB15PublicationBaseD1Ev)
|
||||
*(.text._ZN22MavlinkStreamDebugVect8get_sizeEv)
|
||||
*(.text._ZN7Mission11on_inactiveEv)
|
||||
*(.text._ZN7sensors19VehicleMagnetometer20UpdateMagCalibrationEv)
|
||||
*(.text._ZN11calibration27FindCurrentCalibrationIndexEPKcm)
|
||||
*(.text._ZN4cdevL9cdev_readEP4filePcj)
|
||||
*(.text.sem_timedwait)
|
||||
*(.text.snprintf)
|
||||
*(.text._ZN27MavlinkStreamOpticalFlowRad8get_sizeEv)
|
||||
*(.text._ZNK6matrix6MatrixIfLj3ELj1EE6copyToEPf)
|
||||
*(.text._ZN6Report13healthFailureIJhEEEv8NavModes20HealthComponentIndexmRKN6events9LogLevelsEPKcDpT_.isra.0.constprop.0)
|
||||
*(.text._ZN13BatteryChecks16rtlEstimateCheckERK7ContextR6Reportf)
|
||||
*(.text.sigemptyset)
|
||||
*(.text.nx_read)
|
||||
@ -0,0 +1,163 @@
|
||||
/* Static */
|
||||
*(.text.arm_ack_irq)
|
||||
*(.text.arm_doirq)
|
||||
*(.text.arm_svcall)
|
||||
*(.text.arm_switchcontext)
|
||||
*(.text.clock_timer)
|
||||
*(.text.exception_common)
|
||||
*(.text.flexio_irq_handler)
|
||||
*(.text.hrt_absolute_time)
|
||||
*(.text.hrt_call_enter)
|
||||
*(.text.hrt_tim_isr)
|
||||
*(.text.imxrt_configwaitints)
|
||||
*(.text.imxrt_dma_callback)
|
||||
*(.text.imxrt_dmach_interrupt)
|
||||
*(.text.imxrt_dmach_xfrsetup)
|
||||
*(.text.imxrt_dmaterminate)
|
||||
*(.text.imxrt_dispatch)
|
||||
*(.text.imxrt_edma_interrupt)
|
||||
*(.text.imxrt_endwait)
|
||||
*(.text.imxrt_enet_interrupt)
|
||||
*(.text.imxrt_enet_interrupt_work)
|
||||
*(.text.imxrt_interrupt)
|
||||
*(.text.imxrt_gpio1_16_31_interrupt)
|
||||
*(.text.imxrt_gpio2_0_15_interrupt)
|
||||
*(.text.imxrt_lpi2c_isr)
|
||||
*(.text.imxrt_lpspi3select)
|
||||
*(.text.imxrt_lpspi4select)
|
||||
*(.text.imxrt_lpspi_exchange)
|
||||
*(.text.imxrt_recvdma)
|
||||
*(.text.imxrt_tcd_free)
|
||||
*(.text.imxrt_timerisr)
|
||||
*(.text.imxrt_transmit)
|
||||
*(.text.imxrt_txdone)
|
||||
*(.text.imxrt_txtimeout_work)
|
||||
*(.text.imxrt_txtimeout_expiry)
|
||||
*(.text.imxrt_txpoll)
|
||||
*(.text.imxrt_txringfull)
|
||||
*(.text.imxrt_txavail_work)
|
||||
*(.text.imxrt_txavail)
|
||||
*(.text.imxrt_usbinterrupt)
|
||||
*(.text.irq_dispatch)
|
||||
*(.text.ioctl)
|
||||
*(.text.memcpy)
|
||||
*(.text.memset)
|
||||
*(.text.nxsched_add_blocked)
|
||||
*(.text.nxsched_add_prioritized)
|
||||
*(.text.nxsched_add_readytorun)
|
||||
*(.text.nxsched_get_files)
|
||||
*(.text.nxsched_get_tcb)
|
||||
*(.text.nxsched_merge_pending)
|
||||
*(.text.nxsched_process_timer)
|
||||
*(.text.nxsched_remove_blocked)
|
||||
*(.text.nxsched_remove_readytorun)
|
||||
*(.text.nxsched_resume_scheduler)
|
||||
*(.text.nxsched_suspend_scheduler)
|
||||
*(.text.nxsem_add_holder)
|
||||
*(.text.nxsem_add_holder_tcb)
|
||||
*(.text.nxsem_clockwait)
|
||||
*(.text.nxsem_foreachholder)
|
||||
*(.text.nxsem_freecount0holder)
|
||||
*(.text.nxsem_freeholder)
|
||||
*(.text.nxsem_post)
|
||||
*(.text.nxsem_release_holder)
|
||||
*(.text.nxsem_restore_baseprio)
|
||||
*(.text.nxsem_tickwait)
|
||||
*(.text.nxsem_timeout)
|
||||
*(.text.nxsem_trywait)
|
||||
*(.text.nxsem_wait)
|
||||
*(.text.nxsem_wait_uninterruptible)
|
||||
*(.text.nxsig_timedwait)
|
||||
*(.text.sched_lock)
|
||||
*(.text.sched_note_resume)
|
||||
*(.text.sched_note_suspend)
|
||||
*(.text.sched_unlock)
|
||||
*(.text.strcmp)
|
||||
*(.text.sq_addafter)
|
||||
*(.text.sq_addlast)
|
||||
*(.text.sq_rem)
|
||||
*(.text.sq_remafter)
|
||||
*(.text.sq_remfirst)
|
||||
*(.text.uart_connected)
|
||||
*(.text.up_block_task)
|
||||
*(.text.up_unblock_task)
|
||||
*(.text.wd_timer)
|
||||
*(.text.wd_start)
|
||||
*(.text.work_thread)
|
||||
*(.text.work_queue)
|
||||
*(.text._do_memcpy)
|
||||
|
||||
/* Tropic Eth tune */
|
||||
*(.text.devif_poll)
|
||||
*(.text.devif_poll_tcp_connections)
|
||||
*(.text.tcp_poll)
|
||||
*(.text.devif_poll_udp_connections)
|
||||
*(.text.udp_nextconn)
|
||||
*(.text.udp_poll)
|
||||
*(.text.udp_ipv4_select)
|
||||
*(.text.udp_callback)
|
||||
*(.text.udp_datahandler)
|
||||
*(.text.udp_send)
|
||||
*(.text.udp_active)
|
||||
*(.text.udp_ipv4_active)
|
||||
*(.text.psock_udp_sendto)
|
||||
*(.text.sendto_eventhandler)
|
||||
*(.text.net_dataevent)
|
||||
*(.text.devif_conn_event)
|
||||
*(.text.devif_event_trigger)
|
||||
*(.text.devif_poll_icmp)
|
||||
*(.text.icmp_poll)
|
||||
*(.text.arp_out)
|
||||
*(.text.arp_find)
|
||||
*(.text.arp_format)
|
||||
*(.text.net_ipv4addr_hdrcmp) /* itcm-check-ignore */
|
||||
*(.text.net_ipv4addr_copy) /* itcm-check-ignore */
|
||||
*(.text.net_ipv4addr_broadcast) /* itcm-check-ignore */
|
||||
*(.text.wd_start)
|
||||
*(.text.arp_arpin)
|
||||
*(.text.ipv4_input)
|
||||
*(.text.work_thread)
|
||||
*(.text.work_queue)
|
||||
|
||||
/* ICM45686 */
|
||||
*(.text._ZN8ICM4568612ProcessAccelERKyPKN19InvenSense_ICM456864FIFO4DATAEh)
|
||||
*(.text._ZN8ICM4568611ProcessGyroERKyPKN19InvenSense_ICM456864FIFO4DATAEh)
|
||||
*(.text._ZN8ICM456868FIFOReadERKy)
|
||||
*(.text._ZN8ICM456867RunImplEv)
|
||||
*(.text._ZN8ICM4568618ProcessTemperatureEPKN19InvenSense_ICM456864FIFO4DATAEh)
|
||||
*(.text._ZN12I2CSPIDriverI8ICM45686E3RunEv)
|
||||
*(.text._ZN8ICM4568613FIFOReadCountEv)
|
||||
|
||||
/* BMI088 */
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer12RegisterReadENS1_8RegisterE)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer13FIFOReadCountEv)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer8FIFOReadERKyh)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer13RegisterCheckERKNS2_17register_config_tE)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer13RegisterWriteENS1_8RegisterEh)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer17UpdateTemperatureEv)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer23RegisterSetAndClearBitsENS1_8RegisterEhh)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer26DataReadyInterruptCallbackEiPvS3_)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer7RunImplEv)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer9DataReadyEv)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_AccelerometerD0Ev)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_AccelerometerD1Ev)
|
||||
*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_AccelerometerD2Ev)
|
||||
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope12RegisterReadENS1_8RegisterE)
|
||||
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope13RegisterCheckERKNS2_17register_config_tE)
|
||||
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope13RegisterWriteENS1_8RegisterEh)
|
||||
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope23RegisterSetAndClearBitsENS1_8RegisterEhh)
|
||||
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope26DataReadyInterruptCallbackEiPvS3_)
|
||||
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope7RunImplEv)
|
||||
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope8FIFOReadERKyh)
|
||||
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope9DataReadyEv)
|
||||
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_GyroscopeD0Ev)
|
||||
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_GyroscopeD1Ev)
|
||||
*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_GyroscopeD2Ev)
|
||||
*(.text._ZN12I2CSPIDriverI6BMI088E3RunEv)
|
||||
|
||||
/* BMM350 */
|
||||
*(.text._ZN12I2CSPIDriverI6BMM350E3RunEv)
|
||||
*(.text._ZN6BMM3507RunImplEv)
|
||||
*(.text._ZN6BMM35013RegisterWriteEN12Bosch_BMM3508RegisterEh)
|
||||
*(.text._ZN6BMM35012RegisterReadEN12Bosch_BMM3508RegisterEPh)
|
||||
*(.text._ZN6BMM35014ReadOutRawDataEPf)
|
||||
187
boards/nxp/mr-tropic/nuttx-config/scripts/script.ld
Normal file
187
boards/nxp/mr-tropic/nuttx-config/scripts/script.ld
Normal file
@ -0,0 +1,187 @@
|
||||
/****************************************************************************
|
||||
* boards/nxp/mr-tropic/nuttx-config/scripts/script.ld
|
||||
*
|
||||
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||
* contributor license agreements. See the NOTICE file distributed with
|
||||
* this work for additional information regarding copyright ownership. The
|
||||
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||
* "License"); you may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||
* License for the specific language governing permissions and limitations
|
||||
* under the License.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* Specify the memory areas */
|
||||
|
||||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x70020000, LENGTH = 4194304 - 256K
|
||||
sram (rwx) : ORIGIN = 0x20200000, LENGTH = 512K
|
||||
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 384K
|
||||
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 127K
|
||||
dtcm_nocache (rwx) : ORIGIN = 0x2001FC00, LENGTH = 1K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
EXTERN(_vectors)
|
||||
EXTERN(g_flash_config)
|
||||
EXTERN(g_image_vector_table)
|
||||
EXTERN(g_boot_data)
|
||||
EXTERN(board_get_manifest)
|
||||
EXTERN(_bootdelay_signature)
|
||||
|
||||
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
|
||||
|
||||
/* Workaround for ethernet issue, by placing g_desc_pool into DTCM,
|
||||
which effectively puts it into a no-cache region */
|
||||
.dtcm_nocache : {
|
||||
*(.bss.g_desc_pool)
|
||||
} > dtcm_nocache
|
||||
|
||||
.vectors :
|
||||
{
|
||||
KEEP(*(.vectors))
|
||||
*(.text .text.__start)
|
||||
} >flash
|
||||
|
||||
.itcmfunc :
|
||||
{
|
||||
. = ALIGN(8);
|
||||
_sitcmfuncs = ABSOLUTE(.);
|
||||
FILL(0xFF)
|
||||
. = 0x40 ;
|
||||
*(.ram_vectors)
|
||||
INCLUDE "itcm_static_functions.ld"
|
||||
INCLUDE "itcm_functions_includes.ld"
|
||||
. = ALIGN(8);
|
||||
_eitcmfuncs = ABSOLUTE(.);
|
||||
} > itcm AT > flash
|
||||
|
||||
_fitcmfuncs = LOADADDR(.itcmfunc);
|
||||
|
||||
.text :
|
||||
{
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
. = ALIGN(32);
|
||||
/*
|
||||
This signature provides the bootloader with a way to delay booting
|
||||
*/
|
||||
_bootdelay_signature = ABSOLUTE(.);
|
||||
FILL(0xffecc2925d7d05c5)
|
||||
. += 8;
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
. = ALIGN(4096);
|
||||
_etext = ABSOLUTE(.);
|
||||
_srodata = ABSOLUTE(.);
|
||||
*(.rodata .rodata.*)
|
||||
. = ALIGN(4096);
|
||||
_erodata = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
.init_section :
|
||||
{
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*)))
|
||||
KEEP(*(.init_array .ctors))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab*)
|
||||
} > flash
|
||||
|
||||
.ARM.exidx :
|
||||
{
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data :
|
||||
{
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
. = ALIGN(4);
|
||||
_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)
|
||||
. = ALIGN(4);
|
||||
_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) }
|
||||
|
||||
_boot_loadaddr = ORIGIN(flash);
|
||||
_boot_size = LENGTH(flash);
|
||||
_ram_size = LENGTH(sram);
|
||||
_sdtcm = ORIGIN(dtcm);
|
||||
_edtcm = ORIGIN(dtcm) + LENGTH(dtcm);
|
||||
}
|
||||
86
boards/nxp/mr-tropic/src/CMakeLists.txt
Normal file
86
boards/nxp/mr-tropic/src/CMakeLists.txt
Normal file
@ -0,0 +1,86 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2024 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.
|
||||
#
|
||||
############################################################################
|
||||
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
|
||||
add_compile_definitions(BOOTLOADER)
|
||||
add_library(drivers_board
|
||||
bootloader_main.c
|
||||
init.c
|
||||
usb.c
|
||||
imxrt_flexspi_nor_boot.c
|
||||
imxrt_flexspi_nor_flash.c
|
||||
timer_config.cpp
|
||||
)
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
nuttx_arch # sdio
|
||||
nuttx_drivers # sdio
|
||||
px4_layer #gpio
|
||||
arch_io_pins # iotimer
|
||||
arch_board_romapi
|
||||
bootloader
|
||||
)
|
||||
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common)
|
||||
|
||||
else()
|
||||
|
||||
px4_add_library(drivers_board
|
||||
i2c.cpp
|
||||
init.c
|
||||
sdhc.c
|
||||
spi.cpp
|
||||
timer_config.cpp
|
||||
tropic_led_pwm.cpp
|
||||
usb.c
|
||||
imxrt_flexspi_nor_boot.c
|
||||
imxrt_flexspi_nor_flash.c
|
||||
imxrt_flexspi_storage.c
|
||||
imxrt_ocram_initialize.c
|
||||
hw_rev_ver_tropic.c
|
||||
manifest.c
|
||||
)
|
||||
|
||||
|
||||
# Force compiler not to use builtin functions (like memcpy)
|
||||
# to optimize for loops in init.c (imxrt_ocram_initialize)
|
||||
set_source_files_properties(imxrt_ocram_initialize.c PROPERTIES COMPILE_FLAGS -fno-builtin)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
arch_board_romapi
|
||||
arch_spi
|
||||
nuttx_arch # sdio
|
||||
nuttx_drivers # sdio
|
||||
px4_layer
|
||||
)
|
||||
|
||||
endif()
|
||||
355
boards/nxp/mr-tropic/src/board_config.h
Normal file
355
boards/nxp/mr-tropic/src/board_config.h
Normal file
@ -0,0 +1,355 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 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
|
||||
*
|
||||
* Tropic Community internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_arch/io_timer.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "imxrt_gpio.h"
|
||||
#include "imxrt_iomuxc.h"
|
||||
#include "hardware/imxrt_pinmux.h"
|
||||
#include "hardware/imxrt_usb_analog.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <arm_internal.h>
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
/* 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_EMC_33 GPIO3_IO19 */ (GPIO_PORT3 | GPIO_PIN19 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LED_IOMUX)
|
||||
#define GPIO_nLED_BLUE /* GPIO_EMC_34 GPIO3_IO20 */ (GPIO_PORT3 | GPIO_PIN20 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LED_IOMUX)
|
||||
#define GPIO_nLED_GREEN /* GPIO_EMC_38 GPIO3_IO24 */ (GPIO_PORT3 | GPIO_PIN24 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LED_IOMUX)
|
||||
|
||||
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
|
||||
#define BOARD_OVERLOAD_LED LED_RED
|
||||
#define BOARD_ARMED_STATE_LED LED_BLUE
|
||||
|
||||
/*
|
||||
* 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)
|
||||
|
||||
|
||||
/* SPI1 off */
|
||||
|
||||
#define _GPIO_LPSPI1_SCK /* GPIO_EMC_27 GPIO4_IO27 */ (GPIO_PORT4 | GPIO_PIN27 | CS_IOMUX)
|
||||
#define _GPIO_LPSPI1_MISO /* GPIO_EMC_29 GPIO4_IO29 */ (GPIO_PORT4 | GPIO_PIN29 | CS_IOMUX)
|
||||
#define _GPIO_LPSPI1_MOSI /* GPIO_EMC_28 GPIO4_IO28 */ (GPIO_PORT4 | GPIO_PIN28 | CS_IOMUX)
|
||||
|
||||
#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_LPSPI3_SCK /* GPIO_AD_B1_15 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN31 | CS_IOMUX)
|
||||
#define _GPIO_LPSPI3_MISO /* GPIO_AD_B1_13 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN29 | CS_IOMUX)
|
||||
#define _GPIO_LPSPI3_MOSI /* GPIO_AD_B1_14 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN30 | CS_IOMUX)
|
||||
|
||||
#define GPIO_SPI3_SCK_OFF _PIN_OFF(_GPIO_LPSPI3_SCK)
|
||||
#define GPIO_SPI3_MISO_OFF _PIN_OFF(_GPIO_LPSPI3_MISO)
|
||||
#define GPIO_SPI3_MOSI_OFF _PIN_OFF(_GPIO_LPSPI3_MOSI)
|
||||
|
||||
/* Define the SPI4 Data Ready and Control signals */
|
||||
|
||||
#define GPIO_SPI4_DRDY7_EXTERNAL1 /* GPIO_EMC_35 GPIO3_IO21*/ (GPIO_PORT3 | GPIO_PIN21 | GPIO_INPUT | DRDY_IOMUX)
|
||||
|
||||
#define GPIO_DRDY_OFF_SPI4_DRDY7_EXTERNAL1 _PIN_OFF(GPIO_SPI4_DRDY7_EXTERNAL1)
|
||||
|
||||
#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, */
|
||||
|
||||
#define PX4_ADC_GPIO \
|
||||
/* ADC_5V_RAIL_SENSE GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_GPIO(0, 24)
|
||||
|
||||
/* Define Channel numbers must match above GPIO pin IN(n)*/
|
||||
|
||||
#define ADC_5V_RAIL_SENSE /* GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_CH(13)
|
||||
|
||||
#define ADC_CHANNELS (1 << ADC_5V_RAIL_SENSE)
|
||||
|
||||
/* 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)
|
||||
|
||||
|
||||
/* PWM
|
||||
*/
|
||||
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
#define BOARD_NUM_IO_TIMERS 4
|
||||
|
||||
// Input Capture not supported on MVP
|
||||
|
||||
#define BOARD_HAS_NO_CAPTURE
|
||||
|
||||
//#define BOARD_HAS_UI_LED_PWM 1 Not ported yet (Still Kinetis driver)
|
||||
#define BOARD_HAS_LED_PWM 1
|
||||
#define BOARD_LED_PWM_DRIVE_ACTIVE_LOW 1
|
||||
#define BOARD_HAS_CUSTOM_LED_PWM 1
|
||||
|
||||
#define PWM_LED_RED /* GPIO_EMC_33 */ (GPIO_FLEXPWM3_PWMA02_1 | GENERAL_OUTPUT_IOMUX)
|
||||
#define PWM_LED_BLUE /* GPIO_EMC_34 */ (GPIO_FLEXPWM3_PWMB02_1 | GENERAL_OUTPUT_IOMUX)
|
||||
#define PWM_LED_GREEN /* GPIO_EMC_38 */ (GPIO_FLEXPWM1_PWMA03_2 | GENERAL_OUTPUT_IOMUX)
|
||||
|
||||
|
||||
/* ETHERNET GPIO */
|
||||
|
||||
#define GPIO_ENET_RX_ER_CONFIG1 /* GPIO_B1_11 GPIO2_IO27 PHYAD18 Open */ (GPIO_PORT2 | GPIO_PIN27 | GPIO_INPUT | IOMUX_PULL_NONE)
|
||||
#define GPIO_ENET_RX_DATA01_CONFIG4 /* GPIO_B1_05 GPIO2_IO21 (RMII-clkmode) High */ (GPIO_PORT2 | GPIO_PIN21 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | GENERAL_OUTPUT_IOMUX)
|
||||
#define GPIO_ENET_RX_DATA00_CONFIG5 /* GPIO_B1_04 GPIO2_IO20 SLAVE:Auto Open */ (GPIO_PORT2 | GPIO_PIN20 | GPIO_INPUT | IOMUX_PULL_NONE)
|
||||
#define GPIO_ENET_CRS_DV_CONFIG6 /* GPIO_B1_06 GPIO4_IO22 SLAVE:POl Corr Low */ (GPIO_PORT2 | GPIO_PIN22 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
|
||||
|
||||
/* Tone alarm output */
|
||||
|
||||
//FIXME FlexPWM TONE DRIVER
|
||||
#define TONE_ALARM_FLEXPWM PWMA_VAL
|
||||
#define TONE_ALARM_TIMER 1 /* FlexPWM 3 */
|
||||
#define TONE_ALARM_CHANNEL 0 /* GPIO_EMC_23 PWM1_PWMA00 */
|
||||
|
||||
#define GPIO_BUZZER_1 /* GPIO_EMC_23 GPIO4_IO23 */ (GPIO_PORT4 | GPIO_PIN23 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX)
|
||||
|
||||
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
|
||||
#define GPIO_TONE_ALARM (GPIO_FLEXPWM1_PWMA00_1 | GENERAL_OUTPUT_IOMUX)
|
||||
|
||||
/* 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 RC_SERIAL_PORT "/dev/ttyS6"
|
||||
//#define RC_SERIAL_SINGLEWIRE 1 // Suport Single wire wiring
|
||||
//#define RC_SERIAL_SWAP_RXTX 1 // Set Swap (but not supported in HW) to use Single wire
|
||||
//#define RC_SERIAL_SWAP_USING_SINGLEWIRE 1 // Set to use Single wire swap as HW does not support swap
|
||||
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
|
||||
|
||||
/* 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)
|
||||
|
||||
/* 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 GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* EMC_39 */ (GPIO_PORT3 | GPIO_PIN25 | GPIO_INPUT | SAFETY_INIT_IOMUX)
|
||||
#define GPIO_nSAFETY_SWITCH_LED_OUT /* EMC_39 */ (GPIO_PORT3 | GPIO_PIN25 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | 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_B0_12 GPIO2_IO12 */ (GPIO_PORT2 | GPIO_PIN12 | 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 */
|
||||
|
||||
#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_BOARDCTL=y, OR
|
||||
* CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_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_NUMBER_BRICKS 1
|
||||
#define BOARD_NUMBER_DIGITAL_BRICKS 1
|
||||
|
||||
#define BOARD_ADC_BRICK_VALID 1
|
||||
|
||||
#define BOARD_ADC_USB_CONNECTED (board_read_VBUS_state() == 0)
|
||||
|
||||
/* FMUv5 never powers odd the Servo rail */
|
||||
|
||||
#define BOARD_ADC_SERVO_VALID (1)
|
||||
|
||||
|
||||
/* This board provides a DMA pool and APIs */
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||
|
||||
/* This board provides the board_on_reset interface */
|
||||
|
||||
#define BOARD_HAS_ON_RESET 1
|
||||
#define BOARD_HAS_ISP_BOOTLOADER 1
|
||||
|
||||
#define PX4_GPIO_INIT_LIST { \
|
||||
GPIO_FLEXCAN3_TX, \
|
||||
GPIO_FLEXCAN3_RX, \
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_SAFETY_SWITCH_IN, \
|
||||
GPIO_ENET_RX_ER_CONFIG1, \
|
||||
GPIO_ENET_RX_DATA01_CONFIG4, \
|
||||
GPIO_ENET_RX_DATA00_CONFIG5, \
|
||||
GPIO_ENET_CRS_DV_CONFIG6, \
|
||||
GPIO_ENET_RST \
|
||||
}
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
/* To detect IMU */
|
||||
#define BOARD_HAS_HW_VERSIONING 1
|
||||
#define BOARD_HAS_HW_SPLIT_VERSIONING 1
|
||||
#define HW_INFO_INIT_PREFIX "TROPIC"
|
||||
|
||||
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 3
|
||||
// Base/FMUM
|
||||
#define TROPIC_0 HW_FMUM_ID(0x0) // ICM45686
|
||||
#define TROPIC_1 HW_FMUM_ID(0x1) // ICM42688
|
||||
#define TROPIC_2 HW_FMUM_ID(0x2) // ICM42686
|
||||
|
||||
/* Flash instance for storage */
|
||||
#define NOR_INSTANCE 1
|
||||
|
||||
__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 void imxrt_spiinitialize(void);
|
||||
|
||||
extern int imxrt_usb_initialize(void);
|
||||
|
||||
extern void imxrt_usbinitialize(void);
|
||||
|
||||
extern void board_peripheral_reset(int ms);
|
||||
|
||||
extern void fmurt1062_timer_initialize(void);
|
||||
|
||||
#include <px4_platform_common/board_common.h>
|
||||
|
||||
void imxrt_flash_romapi_initialize(void);
|
||||
|
||||
int imxrt_flexspi_storage_initialize(void);
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
||||
61
boards/nxp/mr-tropic/src/bootloader_main.c
Normal file
61
boards/nxp/mr-tropic/src/bootloader_main.c
Normal file
@ -0,0 +1,61 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2023 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 bootloader_main.c
|
||||
*
|
||||
* FMU-specific early startup code for bootloader
|
||||
*/
|
||||
|
||||
#include "board_config.h"
|
||||
#include "bl.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <chip.h>
|
||||
#include <arch/board/board.h>
|
||||
#include "arm_internal.h"
|
||||
#include <px4_platform_common/init.h>
|
||||
|
||||
extern int sercon_main(int c, char **argv);
|
||||
|
||||
void board_late_initialize(void)
|
||||
{
|
||||
sercon_main(0, NULL);
|
||||
}
|
||||
|
||||
extern void sys_tick_handler(void);
|
||||
void board_timerhook(void)
|
||||
{
|
||||
sys_tick_handler();
|
||||
}
|
||||
130
boards/nxp/mr-tropic/src/hw_config.h
Normal file
130
boards/nxp/mr-tropic/src/hw_config.h
Normal file
@ -0,0 +1,130 @@
|
||||
/*
|
||||
* hw_config.h
|
||||
*
|
||||
* Created on: May 17, 2015
|
||||
* Author: david_s5
|
||||
*/
|
||||
|
||||
#ifndef HW_CONFIG_H_
|
||||
#define HW_CONFIG_H_
|
||||
|
||||
/****************************************************************************
|
||||
* 10-8--2016:
|
||||
* To simplify the ripple effect on the tools, we will be using
|
||||
* /dev/serial/by-id/<asterisk>PX4<asterisk> to locate PX4 devices. Therefore
|
||||
* moving forward all Bootloaders must contain the prefix "PX4 BL "
|
||||
* in the USBDEVICESTRING
|
||||
* This Change will be made in an upcoming BL release
|
||||
****************************************************************************/
|
||||
/*
|
||||
* Define usage to configure a bootloader
|
||||
*
|
||||
*
|
||||
* Constant example Usage
|
||||
* APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed
|
||||
* BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request
|
||||
* BOARD_FMUV2
|
||||
* INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading
|
||||
* INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading
|
||||
* USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string
|
||||
* USBPRODUCTID 0x0011 - PID Should match defconfig
|
||||
* BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom
|
||||
* delay provided by an APP FW
|
||||
* BOARD_TYPE 9 - Must match .prototype boad_id
|
||||
* _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection
|
||||
* BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector
|
||||
* BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector
|
||||
* BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time.
|
||||
* (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted
|
||||
* programmatically
|
||||
*
|
||||
* BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing.
|
||||
* This is to allow sectors to be reserved for app fw usage. That will NOT be erased
|
||||
* during a FW upgrade.
|
||||
* The default is 0, and selects the first sector to be erased, as the 0th entry in the
|
||||
* flash_sectors table. Which is the second physical sector of FLASH in the device.
|
||||
* The first physical sector of FLASH is used by the bootloader, and is not defined
|
||||
* in the table.
|
||||
*
|
||||
* APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus
|
||||
* BOOTLOADER_RESERVATION_SIZE will be deducted from
|
||||
* BOARD_FLASH_SIZE to determine the size of the App FW
|
||||
* and hence the address space of FLASH to erase and program.
|
||||
* USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.)
|
||||
* SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL
|
||||
*
|
||||
* * Other defines are somewhat self explanatory.
|
||||
*/
|
||||
|
||||
/* Boot device selection list*/
|
||||
#define USB0_DEV 0x01
|
||||
#define SERIAL0_DEV 0x02
|
||||
#define SERIAL1_DEV 0x04
|
||||
|
||||
#define APP_LOAD_ADDRESS 0x70020000
|
||||
#define APP_VECTOR_OFFSET 0x2000
|
||||
#define BOOTLOADER_DELAY 5000
|
||||
#define INTERFACE_USB 1
|
||||
#define INTERFACE_USB_CONFIG "/dev/ttyACM0"
|
||||
|
||||
//#define USE_VBUS_PULL_DOWN
|
||||
#define INTERFACE_USART 1
|
||||
#define INTERFACE_USART_CONFIG "/dev/ttyS0,1500000"
|
||||
#define BOOT_DELAY_ADDRESS 0x00039FA0
|
||||
#define BOARD_TYPE 37
|
||||
// The board has a 64 Mb part with 16384, 4K secors, but we artificialy limit it to 4 Mb
|
||||
// as 1024, 4K sectors
|
||||
#define BOARD_FLASH_SECTORS 960 // 1024 * 4k sectors, 128k for bootloader, 128k for storage
|
||||
#define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 32 // We resreve 128K for the bootloader
|
||||
#define BOARD_FLASH_SIZE (BOARD_FLASH_SECTORS * 4096)
|
||||
|
||||
#define OSC_FREQ 24
|
||||
|
||||
#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE
|
||||
#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN
|
||||
#define BOARD_LED_ON 0
|
||||
#define BOARD_LED_OFF 1
|
||||
|
||||
#define SERIAL_BREAK_DETECT_DISABLED 1
|
||||
|
||||
/*
|
||||
* Uncommenting this allows to force the bootloader through
|
||||
* a PWM output pin. As this can accidentally initialize
|
||||
* an ESC prematurely, it is not recommended. This feature
|
||||
* has not been used and hence defaults now to off.
|
||||
*
|
||||
* # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14)
|
||||
* # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11)
|
||||
*
|
||||
* # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
|
||||
* # define BOARD_POWER_ON 1
|
||||
* # define BOARD_POWER_OFF 0
|
||||
* # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power)
|
||||
*
|
||||
*/
|
||||
|
||||
#if !defined(ARCH_SN_MAX_LENGTH)
|
||||
# define ARCH_SN_MAX_LENGTH 12
|
||||
#endif
|
||||
|
||||
#if !defined(APP_RESERVATION_SIZE)
|
||||
# define APP_RESERVATION_SIZE 0
|
||||
#endif
|
||||
|
||||
#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE)
|
||||
# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1
|
||||
#endif
|
||||
|
||||
#if !defined(USB_DATA_ALIGN)
|
||||
# define USB_DATA_ALIGN
|
||||
#endif
|
||||
|
||||
#ifndef BOOT_DEVICES_SELECTION
|
||||
# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
|
||||
#endif
|
||||
|
||||
#ifndef BOOT_DEVICES_FILTER_ONUSB
|
||||
# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV
|
||||
#endif
|
||||
|
||||
#endif /* HW_CONFIG_H_ */
|
||||
165
boards/nxp/mr-tropic/src/hw_rev_ver_tropic.c
Normal file
165
boards/nxp/mr-tropic/src/hw_rev_ver_tropic.c
Normal file
@ -0,0 +1,165 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2023 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 hw_rev_ver_canhubk3.c
|
||||
* CANHUBK3 Hardware Revision and Version ID API
|
||||
*/
|
||||
#include <drivers/drv_adc.h>
|
||||
#include <px4_arch/adc.h>
|
||||
#include <px4_platform_common/micro_hal.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform/board_determine_hw_info.h>
|
||||
#include <stdio.h>
|
||||
#include <board_config.h>
|
||||
#include <drivers/drv_sensor.h>
|
||||
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
#if defined(BOARD_HAS_HW_VERSIONING)
|
||||
|
||||
#define HW_INFO_SIZE HW_INFO_VER_DIGITS + HW_INFO_REV_DIGITS
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
static int hw_revision = 0;
|
||||
static char hw_info[HW_INFO_SIZE] = {0};
|
||||
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
|
||||
static char hw_base_info[HW_INFO_SIZE] = {0};
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
/************************************************************************************
|
||||
* Name: board_get_hw_type
|
||||
*
|
||||
* Description:
|
||||
* Optional returns a 0 terminated string defining the HW type.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* a 0 terminated string defining the HW type. This my be a 0 length string ""
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT const char *board_get_hw_type_name()
|
||||
{
|
||||
return (const char *) hw_info;
|
||||
}
|
||||
|
||||
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
|
||||
/************************************************************************************
|
||||
* Name: board_get_hw_base_type_name
|
||||
*
|
||||
* Description:
|
||||
* Optional returns a 0 terminated string defining the base type.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* a 0 terminated string defining the HW type. This my be a 0 length string ""
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT const char *board_get_hw_base_type_name()
|
||||
{
|
||||
return (const char *) hw_base_info;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_get_hw_version
|
||||
*
|
||||
* Description:
|
||||
* Optional returns a integer HW version
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* An integer value of this boards hardware version.
|
||||
* A value of -1 is the default for boards not supporting the BOARD_HAS_VERSIONING API.
|
||||
* A value of 0 is the default for boards supporting the API but not having version.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT int board_get_hw_version()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_get_hw_revision
|
||||
*
|
||||
* Description:
|
||||
* Optional returns a integer HW revision
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* An integer value of this boards hardware revision.
|
||||
* A value of -1 is the default for boards not supporting the BOARD_HAS_VERSIONING API.
|
||||
* A value of 0 is the default for boards supporting the API but not having revision.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT int board_get_hw_revision()
|
||||
{
|
||||
return hw_revision;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_determine_hw_info
|
||||
*
|
||||
* Description:
|
||||
* Uses GPIO to detect MR-CANHUBK3-ADAP
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int board_determine_hw_info()
|
||||
{
|
||||
hw_revision = 0; //TODO Read fuses
|
||||
|
||||
sprintf(hw_info, "%03d", hw_revision);
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
40
boards/nxp/mr-tropic/src/i2c.cpp
Normal file
40
boards/nxp/mr-tropic/src/i2c.cpp
Normal file
@ -0,0 +1,40 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/i2c_hw_description.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusExternal(1),
|
||||
initI2CBusExternal(3),
|
||||
initI2CBusInternal(4),
|
||||
};
|
||||
55
boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.c
Normal file
55
boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.c
Normal file
@ -0,0 +1,55 @@
|
||||
/****************************************************************************
|
||||
* boards/arm/imxrt/imxrt1064-evk/src/imxrt_flexspi_nor_boot.c
|
||||
*
|
||||
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||
* contributor license agreements. See the NOTICE file distributed with
|
||||
* this work for additional information regarding copyright ownership. The
|
||||
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||
* "License"); you may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||
* License for the specific language governing permissions and limitations
|
||||
* under the License.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include "imxrt_flexspi_nor_boot.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
locate_data(".boot_hdr.ivt")
|
||||
const struct ivt_s g_image_vector_table = {
|
||||
IVT_HEADER, /* IVT Header */
|
||||
IMAGE_ENTRY_ADDRESS, /* 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)IMAG_VECTOR_TABLE, /* Pointer to IVT Self (absolute address */
|
||||
(uint32_t)CSF_ADDRESS, /* Address where CSF file is stored */
|
||||
IVT_RSVD /* Reserved = 0 */
|
||||
};
|
||||
|
||||
locate_data(".boot_hdr.boot_data")
|
||||
const struct boot_data_s g_boot_data = {
|
||||
IMAGE_DEST, /* boot start location */
|
||||
(IMAGE_DEST_END - IMAGE_DEST), /* size */
|
||||
PLUGIN_FLAG, /* Plugin flag */
|
||||
0xffffffff /* empty - extra data word */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/* None */
|
||||
166
boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.h
Normal file
166
boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.h
Normal file
@ -0,0 +1,166 @@
|
||||
/****************************************************************************
|
||||
* boards/arm/imxrt/imxrt1064-evk/src/imxrt_flexspi_nor_boot.h
|
||||
*
|
||||
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||
* contributor license agreements. See the NOTICE file distributed with
|
||||
* this work for additional information regarding copyright ownership. The
|
||||
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||
* "License"); you may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||
* License for the specific language governing permissions and limitations
|
||||
* under the License.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H
|
||||
#define __BOARDS_ARM_IMXRT_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 0x70000000
|
||||
#define FLASH_END 0x70400000
|
||||
|
||||
/* This needs to take into account the memory configuration at boot
|
||||
* bootloader
|
||||
*/
|
||||
|
||||
#define ROM_BOOTLOADER_OCRAM_RES 0x8000
|
||||
#define OCRAM_BASE (0x20200000 + ROM_BOOTLOADER_OCRAM_RES)
|
||||
#define OCRAM_END (OCRAM_BASE + (512 * 1024) + (256 * 1024) \
|
||||
- ROM_BOOTLOADER_OCRAM_RES)
|
||||
|
||||
#define SCLK 1
|
||||
#if defined(CONFIG_BOOT_RUNFROMFLASH)
|
||||
# define IMAGE_DEST FLASH_BASE
|
||||
# define IMAGE_DEST_END FLASH_END
|
||||
# define IMAGE_DEST_OFFSET 0
|
||||
#else
|
||||
# define IMAGE_DEST OCRAM_BASE
|
||||
# define IMAGE_DEST_END OCRAM_END
|
||||
# define IMAGE_DEST_OFFSET IVT_SIZE
|
||||
#endif
|
||||
|
||||
#define LOCATE_IN_DEST(x) (((uint32_t)(x)) - FLASH_BASE + IMAGE_DEST)
|
||||
#define LOCATE_IN_SRC(x) (((uint32_t)(x)) - IMAGE_DEST + FLASH_BASE)
|
||||
|
||||
#ifdef CONFIG_IMXRT1064_EVK_SDRAM
|
||||
# define DCD_ADDRESS &g_dcd_data
|
||||
#else
|
||||
# define DCD_ADDRESS 0
|
||||
#endif
|
||||
#define BOOT_DATA_ADDRESS LOCATE_IN_DEST(&g_boot_data)
|
||||
#define CSF_ADDRESS 0
|
||||
#define PLUGIN_FLAG (uint32_t)0
|
||||
|
||||
/* Located in Destination Memory */
|
||||
|
||||
#define IMAGE_ENTRY_ADDRESS ((uint32_t)&_vectors)
|
||||
#define IMAG_VECTOR_TABLE LOCATE_IN_DEST(&g_image_vector_table)
|
||||
|
||||
/****************************************************************************
|
||||
* 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; /* placeholder to make even 0x10 size */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
extern const struct boot_data_s g_boot_data;
|
||||
#ifdef CONFIG_IMXRT1064_EVK_SDRAM
|
||||
extern const uint8_t g_dcd_data[];
|
||||
#endif
|
||||
extern const uint32_t _vectors[];
|
||||
|
||||
#endif /* __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H */
|
||||
107
boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.c
Normal file
107
boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.c
Normal file
@ -0,0 +1,107 @@
|
||||
/****************************************************************************
|
||||
* boards/arm/imxrt/teensy-4.x/src/imxrt_flexspi_nor_flash.c
|
||||
*
|
||||
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||
* contributor license agreements. See the NOTICE file distributed with
|
||||
* this work for additional information regarding copyright ownership. The
|
||||
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||
* "License"); you may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||
* License for the specific language governing permissions and limitations
|
||||
* under the License.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include "imxrt_flexspi_nor_flash.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
enum {
|
||||
/* SPI instructions */
|
||||
|
||||
READ_FAST = 0,
|
||||
READ_STATUS_REG = 1,
|
||||
WRITE_ENABLE = 3,
|
||||
SECTOR_ERASE_4K = 5,
|
||||
READ_FAST_QUAD_OUTPUT = 6,
|
||||
PAGE_PROGRAM_QUAD_INPUT = 7,
|
||||
ERASE_BLOCK = 8,
|
||||
PAGE_PROGRAM = 9,
|
||||
CHIP_ERASE = 11,
|
||||
};
|
||||
|
||||
locate_data(".boot_hdr.conf")
|
||||
const struct flexspi_nor_config_s g_flash_config = {
|
||||
.mem_config =
|
||||
{
|
||||
.tag = FLEXSPI_CFG_BLK_TAG,
|
||||
.version = FLEXSPI_CFG_BLK_VERSION,
|
||||
.read_sample_clksrc = FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_DQSPAD,
|
||||
.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_133MHz,
|
||||
.sflash_a1size = 4u * 1024u * 1024u,
|
||||
.lookup_table =
|
||||
{
|
||||
[4 * READ_FAST] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xeb,
|
||||
RADDR_SDR, FLEXSPI_4PAD, 0x18),
|
||||
[4 * READ_FAST + 1] = FLEXSPI_LUT_SEQ(DUMMY_SDR, FLEXSPI_4PAD, 0x06,
|
||||
READ_SDR, FLEXSPI_4PAD, 0x04),
|
||||
|
||||
[4 * READ_STATUS_REG] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x05,
|
||||
READ_SDR, FLEXSPI_1PAD, 0x04),
|
||||
|
||||
[4 * WRITE_ENABLE] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x06,
|
||||
STOP, FLEXSPI_1PAD, 0),
|
||||
|
||||
[4 * SECTOR_ERASE_4K] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x20,
|
||||
RADDR_SDR, FLEXSPI_1PAD, 0x18),
|
||||
|
||||
[4 * CHIP_ERASE] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x60,
|
||||
STOP, FLEXSPI_1PAD, 0),
|
||||
|
||||
[4 * ERASE_BLOCK] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xd8,
|
||||
RADDR_SDR, FLEXSPI_1PAD, 0x18),
|
||||
|
||||
[4 * PAGE_PROGRAM] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x02,
|
||||
RADDR_SDR, FLEXSPI_1PAD, 0x18),
|
||||
[4 * PAGE_PROGRAM + 1] = FLEXSPI_LUT_SEQ(WRITE_SDR, FLEXSPI_1PAD, 0x04,
|
||||
STOP, FLEXSPI_1PAD, 0x0),
|
||||
|
||||
[4 * READ_FAST_QUAD_OUTPUT] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x6b,
|
||||
RADDR_SDR, FLEXSPI_1PAD, 0x18),
|
||||
[4 * READ_FAST_QUAD_OUTPUT + 1] = FLEXSPI_LUT_SEQ(DUMMY_SDR, FLEXSPI_4PAD, 0x08,
|
||||
READ_SDR, FLEXSPI_4PAD, 0x04),
|
||||
|
||||
[4 * PAGE_PROGRAM_QUAD_INPUT] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x32,
|
||||
RADDR_SDR, FLEXSPI_1PAD, 0x18),
|
||||
[4 * PAGE_PROGRAM_QUAD_INPUT + 1] = FLEXSPI_LUT_SEQ(WRITE_SDR, FLEXSPI_4PAD, 0x04,
|
||||
STOP, FLEXSPI_1PAD, 0),
|
||||
|
||||
},
|
||||
},
|
||||
|
||||
.page_size = 256u,
|
||||
.sector_size = 4u * 1024u,
|
||||
.blocksize = 64u * 1024u,
|
||||
.is_uniform_blocksize = false,
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
349
boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.h
Normal file
349
boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.h
Normal file
@ -0,0 +1,349 @@
|
||||
/****************************************************************************
|
||||
* boards/arm/imxrt/imxrt1064-evk/src/imxrt_flexspi_nor_flash.h
|
||||
*
|
||||
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||
* contributor license agreements. See the NOTICE file distributed with
|
||||
* this work for additional information regarding copyright ownership. The
|
||||
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||
* "License"); you may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||
* License for the specific language governing permissions and limitations
|
||||
* under the License.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __BOARDS_ARM_IMXRT_IMXRT1064_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H
|
||||
#define __BOARDS_ARM_IMXRT_IMXRT1064_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* FLEXSPI memory config block related definitions */
|
||||
|
||||
#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 definitions */
|
||||
|
||||
#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 LUT 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 LUT 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 LUT 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 LUT 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_120MHz = 7,
|
||||
FLEXSPI_SERIAL_CLKFREQ_133MHz = 8,
|
||||
FLEXSPI_SERIAL_CLKFREQ_166MHz = 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_EXT_INPUT_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 device 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
|
||||
* command execution
|
||||
*/
|
||||
|
||||
uint32_t blocksize; /* Block size */
|
||||
uint32_t reserve2[11]; /* Reserved for future use */
|
||||
};
|
||||
|
||||
extern const struct flexspi_nor_config_s g_flash_config;
|
||||
|
||||
#endif /* __BOARDS_ARM_IMXRT_IMXRT1064_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H */
|
||||
411
boards/nxp/mr-tropic/src/imxrt_flexspi_storage.c
Normal file
411
boards/nxp/mr-tropic/src/imxrt_flexspi_storage.c
Normal file
@ -0,0 +1,411 @@
|
||||
/****************************************************************************
|
||||
* boards/nxp/mr-tropic/src/imxrt_flexspi_storage.c
|
||||
*
|
||||
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||
* contributor license agreements. See the NOTICE file distributed with
|
||||
* this work for additional information regarding copyright ownership. The
|
||||
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||
* "License"); you may not use this file except in compliance with the
|
||||
* License. You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||
* License for the specific language governing permissions and limitations
|
||||
* under the License.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/signal.h>
|
||||
#include <nuttx/fs/fs.h>
|
||||
#include <nuttx/mtd/mtd.h>
|
||||
|
||||
#include <px4_platform_common/px4_mtd.h>
|
||||
#include "px4_log.h"
|
||||
|
||||
#include <px4_arch/imxrt_flexspi_nor_flash.h>
|
||||
#include <px4_arch/imxrt_romapi.h>
|
||||
#include "board_config.h"
|
||||
#include "hardware/imxrt_pinmux.h"
|
||||
#include "barriers.h"
|
||||
|
||||
/* Used sectors must be multiple of the flash block size
|
||||
* i.e. W25Q32JV has a block size of 64KB
|
||||
*/
|
||||
|
||||
#define NOR_USED_SECTORS (0x40U) /* 64 * 4KB = 256KB */
|
||||
#define NOR_TOTAL_SECTORS (0x0400U)
|
||||
#define NOR_PAGE_SIZE (0x0100U) /* 256 bytes */
|
||||
#define NOR_SECTOR_SIZE (0x1000U) /* 4KB */
|
||||
#define NOR_START_SECTOR (NOR_TOTAL_SECTORS - NOR_USED_SECTORS)
|
||||
#define NOR_START_PAGE ((NOR_START_SECTOR * NOR_SECTOR_SIZE) / NOR_PAGE_SIZE)
|
||||
#define NOR_STORAGE_ADDR (IMXRT_FLEX2CIPHER_BASE + NOR_START_SECTOR * NOR_SECTOR_SIZE)
|
||||
#define NOR_STORAGE_END (IMXRT_FLEX2CIPHER_BASE + (NOR_START_SECTOR + NOR_TOTAL_SECTORS) * NOR_SECTOR_SIZE)
|
||||
|
||||
#define MIN(a, b) (((a) < (b)) ? (a) : (b))
|
||||
|
||||
extern struct flexspi_nor_config_s g_bootConfig;
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/* FlexSPI NOR device private data */
|
||||
|
||||
struct imxrt_flexspi_storage_dev_s {
|
||||
struct mtd_dev_s mtd;
|
||||
uint8_t *ahb_base;
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/* MTD driver methods */
|
||||
|
||||
static int imxrt_flexspi_storage_erase(struct mtd_dev_s *dev,
|
||||
off_t startblock,
|
||||
size_t nblocks);
|
||||
static ssize_t imxrt_flexspi_storage_read(struct mtd_dev_s *dev,
|
||||
off_t offset,
|
||||
size_t nbytes,
|
||||
uint8_t *buffer);
|
||||
static ssize_t imxrt_flexspi_storage_bread(struct mtd_dev_s *dev,
|
||||
off_t startblock,
|
||||
size_t nblocks,
|
||||
uint8_t *buffer);
|
||||
static ssize_t imxrt_flexspi_storage_bwrite(struct mtd_dev_s *dev,
|
||||
off_t startblock,
|
||||
size_t nblocks,
|
||||
const uint8_t *buffer);
|
||||
static int imxrt_flexspi_storage_ioctl(struct mtd_dev_s *dev,
|
||||
int cmd,
|
||||
unsigned long arg);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
static struct imxrt_flexspi_storage_dev_s g_flexspi_nor = {
|
||||
.mtd =
|
||||
{
|
||||
.erase = imxrt_flexspi_storage_erase,
|
||||
.bread = imxrt_flexspi_storage_bread,
|
||||
.bwrite = imxrt_flexspi_storage_bwrite,
|
||||
.read = imxrt_flexspi_storage_read,
|
||||
.ioctl = imxrt_flexspi_storage_ioctl,
|
||||
#ifdef CONFIG_MTD_BYTE_WRITE
|
||||
.write = NULL,
|
||||
#endif
|
||||
.name = "imxrt_flexspi_storage"
|
||||
},
|
||||
.ahb_base = (uint8_t *) NOR_STORAGE_ADDR,
|
||||
};
|
||||
|
||||
/* Ensure exclusive access to the driver */
|
||||
|
||||
static sem_t g_exclsem = SEM_INITIALIZER(1);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
static int imxrt_flexspi_storage_erase_chip(
|
||||
const struct imxrt_flexspi_storage_dev_s *dev)
|
||||
{
|
||||
/* We can't erase the chip we're executing from */
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
static ssize_t imxrt_flexspi_storage_read(struct mtd_dev_s *dev,
|
||||
off_t offset,
|
||||
size_t nbytes,
|
||||
uint8_t *buffer)
|
||||
{
|
||||
ssize_t ret;
|
||||
struct imxrt_flexspi_storage_dev_s *priv =
|
||||
(struct imxrt_flexspi_storage_dev_s *)dev;
|
||||
uint8_t *src;
|
||||
|
||||
finfo("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes);
|
||||
|
||||
if (offset < 0) {
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
src = priv->ahb_base + offset;
|
||||
|
||||
if (src + nbytes > (uint8_t *)NOR_STORAGE_END) {
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
ret = nxsem_wait(&g_exclsem);
|
||||
|
||||
if (ret < 0) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
memcpy(buffer, src, nbytes);
|
||||
|
||||
nxsem_post(&g_exclsem);
|
||||
|
||||
finfo("return nbytes: %d\n", (int)nbytes);
|
||||
return (ssize_t)nbytes;
|
||||
}
|
||||
|
||||
static ssize_t imxrt_flexspi_storage_bread(struct mtd_dev_s *dev,
|
||||
off_t startblock,
|
||||
size_t nblocks,
|
||||
uint8_t *buffer)
|
||||
{
|
||||
ssize_t nbytes;
|
||||
|
||||
finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
|
||||
|
||||
/* On this device, we can handle the block read just like the byte-oriented
|
||||
* read
|
||||
*/
|
||||
|
||||
nbytes = imxrt_flexspi_storage_read(dev, startblock * NOR_PAGE_SIZE,
|
||||
nblocks * NOR_PAGE_SIZE, buffer);
|
||||
|
||||
if (nbytes > 0) {
|
||||
nbytes /= NOR_PAGE_SIZE;
|
||||
}
|
||||
|
||||
return nbytes;
|
||||
}
|
||||
|
||||
locate_code(".ramfunc")
|
||||
static ssize_t imxrt_flexspi_storage_bwrite(struct mtd_dev_s *dev,
|
||||
off_t startblock,
|
||||
size_t nblocks,
|
||||
const uint8_t *buffer)
|
||||
{
|
||||
ssize_t ret;
|
||||
struct flexspi_nor_config_s *pConfig = &g_bootConfig;
|
||||
size_t len = nblocks * NOR_PAGE_SIZE;
|
||||
off_t offset = (startblock + NOR_START_PAGE) * NOR_PAGE_SIZE;
|
||||
uint8_t *src = (uint8_t *) buffer;
|
||||
#ifdef CONFIG_ARMV7M_DCACHE
|
||||
struct imxrt_flexspi_storage_dev_s *priv =
|
||||
(struct imxrt_flexspi_storage_dev_s *)dev;
|
||||
uint8_t *dst = priv->ahb_base + startblock * NOR_PAGE_SIZE;
|
||||
#endif
|
||||
int i;
|
||||
|
||||
if (((uintptr_t)buffer % 4) != 0) {
|
||||
return -EINVAL; // Byte aligned write not supported
|
||||
}
|
||||
|
||||
finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
|
||||
|
||||
ret = nxsem_wait(&g_exclsem);
|
||||
|
||||
if (ret < 0) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
while (len) {
|
||||
i = MIN(NOR_PAGE_SIZE, len);
|
||||
cpsid(); // Disable interrupts
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wcast-align"
|
||||
volatile uint32_t status = ROM_FLEXSPI_NorFlash_ProgramPage(NOR_INSTANCE, pConfig, offset, (const uint32_t *)src);
|
||||
#pragma GCC diagnostic pop
|
||||
cpsie(); // Enable interrupts
|
||||
usleep(0); // Yield to scheduler
|
||||
UNUSED(status);
|
||||
|
||||
offset += i;
|
||||
src += i;
|
||||
len -= i;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_ARMV7M_DCACHE
|
||||
up_invalidate_dcache((uintptr_t)dst,
|
||||
(uintptr_t)dst + nblocks * NOR_PAGE_SIZE);
|
||||
#endif
|
||||
|
||||
nxsem_post(&g_exclsem);
|
||||
|
||||
return nblocks;
|
||||
}
|
||||
|
||||
locate_code(".ramfunc")
|
||||
static int imxrt_flexspi_storage_erase(struct mtd_dev_s *dev,
|
||||
off_t startblock,
|
||||
size_t nblocks)
|
||||
{
|
||||
struct flexspi_nor_config_s *pConfig = &g_bootConfig;
|
||||
size_t blocksleft = nblocks;
|
||||
#ifdef CONFIG_ARMV7M_DCACHE
|
||||
struct imxrt_flexspi_storage_dev_s *priv =
|
||||
(struct imxrt_flexspi_storage_dev_s *)dev;
|
||||
uint8_t *dst = priv->ahb_base + startblock * NOR_SECTOR_SIZE;
|
||||
#endif
|
||||
ssize_t ret;
|
||||
|
||||
startblock += NOR_START_SECTOR;
|
||||
|
||||
finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
|
||||
|
||||
ret = nxsem_wait(&g_exclsem);
|
||||
|
||||
if (ret < 0) {
|
||||
return ret;
|
||||
}
|
||||
|
||||
while (blocksleft-- > 0) {
|
||||
/* Erase each sector */
|
||||
cpsid(); // Disable interrupts
|
||||
volatile uint32_t status = ROM_FLEXSPI_NorFlash_Erase(NOR_INSTANCE, pConfig,
|
||||
(startblock * NOR_SECTOR_SIZE), NOR_SECTOR_SIZE);
|
||||
cpsie(); // Enable interrupts
|
||||
usleep(0); // Yield to scheduler
|
||||
UNUSED(status);
|
||||
startblock++;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_ARMV7M_DCACHE
|
||||
up_invalidate_dcache((uintptr_t)dst,
|
||||
(uintptr_t)dst + nblocks * NOR_SECTOR_SIZE);
|
||||
#endif
|
||||
nxsem_post(&g_exclsem);
|
||||
|
||||
return (int)nblocks;
|
||||
}
|
||||
|
||||
static int imxrt_flexspi_storage_ioctl(struct mtd_dev_s *dev,
|
||||
int cmd,
|
||||
unsigned long arg)
|
||||
{
|
||||
struct imxrt_flexspi_storage_dev_s *priv =
|
||||
(struct imxrt_flexspi_storage_dev_s *)dev;
|
||||
int ret = -EINVAL; /* Assume good command with bad parameters */
|
||||
|
||||
finfo("cmd: %d\n", cmd);
|
||||
|
||||
switch (cmd) {
|
||||
case MTDIOC_GEOMETRY: {
|
||||
struct mtd_geometry_s *geo =
|
||||
(struct mtd_geometry_s *)((uintptr_t)arg);
|
||||
|
||||
if (geo) {
|
||||
/* Populate the geometry structure with information need to
|
||||
* know the capacity and how to access the device.
|
||||
*
|
||||
* NOTE:
|
||||
* that the device is treated as though it where just an array
|
||||
* of fixed size blocks. That is most likely not true, but the
|
||||
* client will expect the device logic to do whatever is
|
||||
* necessary to make it appear so.
|
||||
*/
|
||||
|
||||
geo->blocksize = (NOR_PAGE_SIZE);
|
||||
geo->erasesize = (NOR_SECTOR_SIZE);
|
||||
geo->neraseblocks = (NOR_USED_SECTORS);
|
||||
|
||||
ret = OK;
|
||||
|
||||
finfo("blocksize: %lu erasesize: %lu neraseblocks: %lu\n",
|
||||
geo->blocksize, geo->erasesize, geo->neraseblocks);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case BIOC_PARTINFO: {
|
||||
struct partition_info_s *info =
|
||||
(struct partition_info_s *)arg;
|
||||
|
||||
if (info != NULL) {
|
||||
info->numsectors = (NOR_USED_SECTORS * NOR_SECTOR_SIZE) / NOR_PAGE_SIZE;
|
||||
info->sectorsize = NOR_PAGE_SIZE;
|
||||
info->startsector = 0;
|
||||
info->parent[0] = '\0';
|
||||
ret = OK;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case MTDIOC_BULKERASE: {
|
||||
/* Erase the entire device */
|
||||
|
||||
imxrt_flexspi_storage_erase_chip(priv);
|
||||
ret = OK;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
ret = -ENOTTY; /* Bad/unsupported command */
|
||||
break;
|
||||
}
|
||||
|
||||
finfo("return %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Name: imxrt_flexspi_storage_initialize
|
||||
*
|
||||
* Description:
|
||||
* This function is called by board-bringup logic to configure the
|
||||
* flash device.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero is returned on success. Otherwise, a negated errno value is
|
||||
* returned to indicate the nature of the failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int imxrt_flexspi_storage_initialize(void)
|
||||
{
|
||||
struct mtd_dev_s *mtd_dev = &g_flexspi_nor.mtd;
|
||||
int ret = -ENODEV;
|
||||
|
||||
/* Register the MTD driver so that it can be accessed from the
|
||||
* VFS.
|
||||
*/
|
||||
|
||||
ret = register_mtddriver("/dev/nor", mtd_dev, 0755, NULL);
|
||||
|
||||
if (ret < 0) {
|
||||
syslog(LOG_ERR, "ERROR: Failed to register MTD driver: %d\n",
|
||||
ret);
|
||||
}
|
||||
|
||||
#ifdef CONFIG_FS_LITTLEFS
|
||||
|
||||
/* Mount the LittleFS file system */
|
||||
|
||||
ret = nx_mount("/dev/nor", "/fs/nor", "littlefs", 0,
|
||||
"autoformat");
|
||||
|
||||
if (ret < 0) {
|
||||
syslog(LOG_ERR,
|
||||
"ERROR: Failed to mount LittleFS at /mnt/lfs: %d\n",
|
||||
ret);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
return ret;
|
||||
}
|
||||
102
boards/nxp/mr-tropic/src/imxrt_ocram_initialize.c
Normal file
102
boards/nxp/mr-tropic/src/imxrt_ocram_initialize.c
Normal file
@ -0,0 +1,102 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2018-2019, 2023 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 imxrt_ocram_initialize.c
|
||||
*
|
||||
* PX4 fmu-v6xrt RAM startup early startup code.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include "arm_internal.h"
|
||||
#include "imxrt_iomuxc.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
__BEGIN_DECLS
|
||||
extern const uint64_t _fitcmfuncs; /* Copy source address in FLASH */
|
||||
extern uint64_t _sitcmfuncs; /* Copy destination start address in ITCM */
|
||||
extern uint64_t _eitcmfuncs; /* Copy destination end address in ITCM */
|
||||
extern uint64_t _sdtcm; /* Copy destination start address in DTCM */
|
||||
extern uint64_t _edtcm; /* Copy destination end address in DTCM */
|
||||
__END_DECLS
|
||||
|
||||
/****************************************************************************
|
||||
* Name: imxrt_ocram_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called off reset vector to reconfigure the flexRAM
|
||||
* and finish the FLASH to RAM Copy.
|
||||
* CMakeLists.txt Forces compiler not to use builtin functions using -fno-builtin
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
__EXPORT void imxrt_ocram_initialize(void)
|
||||
{
|
||||
uint32_t regval;
|
||||
register uint64_t *src;
|
||||
register uint64_t *dest;
|
||||
|
||||
/* FlexRAM Configuration
|
||||
* F = 64K ITCM
|
||||
* A = 64K DTCM
|
||||
* 5 = 64K OCRAM
|
||||
* So 0xFFFFFFAA is
|
||||
* 384K FlexRAM ITCM
|
||||
* 128K FlexRAM DTCM
|
||||
* */
|
||||
|
||||
putreg32(0xFFFFFFAA, IMXRT_IOMUXC_GPR_GPR17);
|
||||
regval = getreg32(IMXRT_IOMUXC_GPR_GPR16);
|
||||
putreg32(regval | GPR_GPR16_FLEXRAM_BANK_CFG_SEL, IMXRT_IOMUXC_GPR_GPR16);
|
||||
|
||||
/* Copy any necessary code sections from FLASH to ITCM. The process is the
|
||||
* same as the code copying from FLASH to RAM above. */
|
||||
for (src = (uint64_t *)&_fitcmfuncs, dest = (uint64_t *)&_sitcmfuncs;
|
||||
dest < (uint64_t *)&_eitcmfuncs;) {
|
||||
*dest++ = *src++;
|
||||
}
|
||||
|
||||
/* Clear .dtcm. We'll do this inline (vs. calling memset) just to be
|
||||
* certain that there are no issues with the state of global variables.
|
||||
*/
|
||||
|
||||
for (dest = &_sdtcm; dest < &_edtcm;) {
|
||||
*dest++ = 0;
|
||||
}
|
||||
}
|
||||
400
boards/nxp/mr-tropic/src/init.c
Normal file
400
boards/nxp/mr-tropic/src/init.c
Normal file
@ -0,0 +1,400 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 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 <barriers.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
#include <syslog.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 "arm_internal.h"
|
||||
#include "imxrt_flexspi_nor_boot.h"
|
||||
#include <px4_arch/imxrt_flexspi_nor_flash.h>
|
||||
#include "imxrt_iomuxc.h"
|
||||
#include "imxrt_flexcan.h"
|
||||
#include "imxrt_enet.h"
|
||||
#include <chip.h>
|
||||
#include "board_config.h"
|
||||
|
||||
#include <hardware/imxrt_lpuart.h>
|
||||
#undef FLEXSPI_LUT_COUNT
|
||||
#include <hardware/imxrt_flexspi.h>
|
||||
#include <hardware/imxrt_ccm.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_board_led.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
#include <px4_arch/io_timer.h>
|
||||
#include <px4_arch/imxrt_romapi.h>
|
||||
#include <px4_platform_common/init.h>
|
||||
#include <px4_platform/gpio.h>
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
#include <px4_platform/board_determine_hw_info.h>
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from arm_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 uint32_t _srodata; /* Start of .rodata */
|
||||
extern uint32_t _erodata; /* End of .rodata */
|
||||
__END_DECLS
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_peripheral_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_peripheral_reset(int ms)
|
||||
{
|
||||
|
||||
}
|
||||
/************************************************************************************
|
||||
* 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)
|
||||
{
|
||||
for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
|
||||
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_gpio_output(i)));
|
||||
}
|
||||
|
||||
/*
|
||||
* On resets invoked from system (not boot) ensure we establish a low
|
||||
* output state on PWM pins to disarm the ESC and prevent the reset from potentially
|
||||
* spinning up the motors.
|
||||
*/
|
||||
if (status >= 0) {
|
||||
up_mdelay(100);
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: imxrt_flash_romapi_initialize
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
****************************************************************************/
|
||||
struct flexspi_nor_config_s g_bootConfig;
|
||||
|
||||
locate_code(".ramfunc")
|
||||
void imxrt_flash_romapi_initialize(void)
|
||||
{
|
||||
memcpy((struct flexspi_nor_config_s *)&g_bootConfig, &g_flash_config,
|
||||
sizeof(struct flexspi_nor_config_s));
|
||||
g_bootConfig.memConfig.tag = FLEXSPI_CFG_BLK_TAG;
|
||||
|
||||
ROM_API_Init();
|
||||
|
||||
ROM_FLEXSPI_NorFlash_Init(NOR_INSTANCE, (struct flexspi_nor_config_s *)&g_bootConfig);
|
||||
ROM_FLEXSPI_NorFlash_ClearCache(NOR_INSTANCE);
|
||||
|
||||
ARM_DSB();
|
||||
ARM_ISB();
|
||||
ARM_DMB();
|
||||
}
|
||||
|
||||
locate_code(".ramfunc")
|
||||
void imxrt_flash_setup_prefetch_partition(void)
|
||||
{
|
||||
//Prefetch tuning to be determined
|
||||
#if 0
|
||||
putreg32((uint32_t)&_srodata, IMXRT_FLEXSPI1_AHBBUFREGIONSTART0);
|
||||
putreg32((uint32_t)&_erodata, IMXRT_FLEXSPI1_AHBBUFREGIONEND0);
|
||||
/*putreg32((uint32_t)&_stext, IMXRT_FLEXSPI1_AHBBUFREGIONSTART1);
|
||||
putreg32((uint32_t)&_etext, IMXRT_FLEXSPI1_AHBBUFREGIONEND1);
|
||||
putreg32((uint32_t)&_stext, IMXRT_FLEXSPI1_AHBBUFREGIONSTART2);
|
||||
putreg32((uint32_t)&_etext, IMXRT_FLEXSPI1_AHBBUFREGIONEND2);
|
||||
putreg32((uint32_t)&_stext, IMXRT_FLEXSPI1_AHBBUFREGIONSTART3);
|
||||
putreg32((uint32_t)&_etext, IMXRT_FLEXSPI1_AHBBUFREGIONEND3);*/
|
||||
#endif
|
||||
#if 0
|
||||
struct flexspi_type_s *g_flexspi = (struct flexspi_type_s *)IMXRT_FLEXSPIC_BASE;
|
||||
/* RODATA */
|
||||
g_flexspi->AHBRXBUFCR0[0] = FLEXSPI_AHBRXBUFCR0_BUFSZ(48) |
|
||||
FLEXSPI_AHBRXBUFCR0_MSTRID(0) |
|
||||
FLEXSPI_AHBRXBUFCR0_PREFETCHEN(1) |
|
||||
FLEXSPI_AHBRXBUFCR0_REGIONEN(1);
|
||||
|
||||
|
||||
/* All Text */
|
||||
g_flexspi->AHBRXBUFCR0[1] = FLEXSPI_AHBRXBUFCR0_BUFSZ(80) |
|
||||
FLEXSPI_AHBRXBUFCR0_MSTRID(0) |
|
||||
FLEXSPI_AHBRXBUFCR0_PREFETCHEN(1) |
|
||||
FLEXSPI_AHBRXBUFCR0_REGIONEN(1);
|
||||
|
||||
/* Disable 2 */
|
||||
g_flexspi->AHBRXBUFCR0[2] = FLEXSPI_AHBRXBUFCR0_BUFSZ(0) |
|
||||
FLEXSPI_AHBRXBUFCR0_MSTRID(0) |
|
||||
FLEXSPI_AHBRXBUFCR0_PREFETCHEN(1) |
|
||||
FLEXSPI_AHBRXBUFCR0_REGIONEN(0);
|
||||
|
||||
/* Disable 3 */
|
||||
g_flexspi->AHBRXBUFCR0[3] = FLEXSPI_AHBRXBUFCR0_BUFSZ(0) |
|
||||
FLEXSPI_AHBRXBUFCR0_MSTRID(0) |
|
||||
FLEXSPI_AHBRXBUFCR0_PREFETCHEN(1) |
|
||||
FLEXSPI_AHBRXBUFCR0_REGIONEN(0);
|
||||
#endif
|
||||
|
||||
ARM_DSB();
|
||||
ARM_ISB();
|
||||
ARM_DMB();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* 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)
|
||||
{
|
||||
imxrt_flash_setup_prefetch_partition();
|
||||
|
||||
imxrt_flash_romapi_initialize();
|
||||
|
||||
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));
|
||||
|
||||
imxrt_usb_initialize();
|
||||
|
||||
fmurt1062_timer_initialize();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Function: imxrt_phy_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* Some boards require specialized initialization of the PHY before it can
|
||||
* be used. This may include such things as configuring GPIOs, resetting
|
||||
* the PHY, etc.
|
||||
* If CONFIG_IMXRT_ENET_PHYINIT is defined in the configuration then the
|
||||
* board specific logic must provide imxrt_phyinitialize();
|
||||
* The i.MX RT Ethernet driver will call this function one time before it
|
||||
* first uses the PHY.
|
||||
*
|
||||
* Input Parameters:
|
||||
* intf - Always zero for now.
|
||||
*
|
||||
* Returned Value:
|
||||
* OK on success; Negated errno on failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int imxrt_phy_boardinitialize(int intf)
|
||||
{
|
||||
#ifdef CONFIG_IMXRT_GPIO1_0_15_IRQ
|
||||
/* Configure the PHY interrupt pin */
|
||||
|
||||
printf("Configuring interrupt: %08x\n", GPIO_ENET_INT);
|
||||
imxrt_config_gpio(GPIO_ENET_INT);
|
||||
#endif
|
||||
return OK;
|
||||
}
|
||||
|
||||
void imxrt_flexio_clocking(void)
|
||||
{
|
||||
uint32_t reg;
|
||||
|
||||
/* Init USB PLL3 PFD2 */
|
||||
|
||||
reg = getreg32(IMXRT_CCM_ANALOG_PFD_480);
|
||||
|
||||
while ((getreg32(IMXRT_CCM_ANALOG_PLL_USB1) &
|
||||
CCM_ANALOG_PLL_USB1_LOCK) == 0) {
|
||||
}
|
||||
|
||||
reg &= ~CCM_ANALOG_PFD_480_PFD2_FRAC_MASK;
|
||||
|
||||
/* Set PLL3 PFD2 to 480 * 18 / CONFIG_PLL3_PFD2_FRAC */
|
||||
|
||||
reg |= ((uint32_t)(CONFIG_PLL3_PFD2_FRAC) << CCM_ANALOG_PFD_480_PFD3_FRAC_SHIFT);
|
||||
|
||||
putreg32(reg, IMXRT_CCM_ANALOG_PFD_480);
|
||||
|
||||
reg = getreg32(IMXRT_CCM_CDCDR);
|
||||
reg &= ~(CCM_CDCDR_FLEXIO1_CLK_SEL_MASK |
|
||||
CCM_CDCDR_FLEXIO1_CLK_PODF_MASK |
|
||||
CCM_CDCDR_FLEXIO1_CLK_PRED_MASK);
|
||||
reg |= CCM_CDCDR_FLEXIO1_CLK_SEL(CONFIG_FLEXIO1_CLK);
|
||||
reg |= CCM_CDCDR_FLEXIO1_CLK_PODF
|
||||
(CCM_PODF_FROM_DIVISOR(CONFIG_FLEXIO1_PODF_DIVIDER));
|
||||
reg |= CCM_CDCDR_FLEXIO1_CLK_PRED
|
||||
(CCM_PRED_FROM_DIVISOR(CONFIG_FLEXIO1_PRED_DIVIDER));
|
||||
putreg32(reg, IMXRT_CCM_CDCDR);
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* 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)
|
||||
{
|
||||
int ret = OK;
|
||||
|
||||
#if !defined(BOOTLOADER)
|
||||
|
||||
imxrt_flexio_clocking();
|
||||
|
||||
/* Power on Interfaces */
|
||||
|
||||
px4_platform_init();
|
||||
|
||||
imxrt_spiinitialize();
|
||||
|
||||
board_determine_hw_info();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
#if defined(SERIAL_HAVE_RXDMA)
|
||||
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
|
||||
static struct hrt_call serial_dma_call;
|
||||
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)imxrt_serial_dma_poll, NULL);
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_IMXRT_USDHC)
|
||||
ret = fmurt1062_usdhc_initialize();
|
||||
#endif
|
||||
|
||||
imxrt_spiinitialize();
|
||||
|
||||
board_spi_reset(10, 0xffff);
|
||||
|
||||
#ifdef CONFIG_IMXRT_ENET
|
||||
imxrt_gpio_write(GPIO_ENET_RST, true);
|
||||
|
||||
usleep(2000);
|
||||
|
||||
imxrt_netinitialize(0);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_IMXRT_FLEXCAN3
|
||||
imxrt_caninitialize(3);
|
||||
#endif
|
||||
|
||||
ret = imxrt_flexspi_storage_initialize();
|
||||
|
||||
if (ret < 0) {
|
||||
syslog(LOG_ERR,
|
||||
"ERROR: imxrt_flexspi_nor_initialize failed: %d\n", ret);
|
||||
}
|
||||
|
||||
#endif /* !defined(BOOTLOADER) */
|
||||
|
||||
return ret;
|
||||
}
|
||||
79
boards/nxp/mr-tropic/src/manifest.c
Normal file
79
boards/nxp/mr-tropic/src/manifest.c
Normal file
@ -0,0 +1,79 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2023 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 <syslog.h>
|
||||
|
||||
#include "systemlib/px4_macros.h"
|
||||
#include "px4_log.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* 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)
|
||||
{
|
||||
return px4_hw_mft_unsupported;
|
||||
}
|
||||
128
boards/nxp/mr-tropic/src/sdhc.c
Normal file
128
boards/nxp/mr-tropic/src/sdhc.c
Normal file
@ -0,0 +1,128 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
* CD USDHC1_CD GPIO_B1_12
|
||||
* ------------ ------------- --------
|
||||
*
|
||||
* There are no Write Protect 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 */
|
||||
95
boards/nxp/mr-tropic/src/spi.cpp
Normal file
95
boards/nxp/mr-tropic/src/spi.cpp
Normal file
@ -0,0 +1,95 @@
|
||||
/************************************************************************************
|
||||
*
|
||||
* 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_arch/spi_hw_description.h>
|
||||
#include <drivers/drv_sensor.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
#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 <arm_internal.h>
|
||||
#include <chip.h>
|
||||
#include "imxrt_lpspi.h"
|
||||
#include "imxrt_gpio.h"
|
||||
#include "board_config.h"
|
||||
#include <systemlib/err.h>
|
||||
|
||||
constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = {
|
||||
initSPIFmumID(TROPIC_0, {
|
||||
initSPIBus(SPI::Bus::LPSPI3, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::Port1, GPIO::Pin28}, SPI::DRDY{GPIO::Port3, GPIO::Pin18}), /* GPIO_AD_B1_12 GPIO1_IO28 */
|
||||
}),
|
||||
initSPIBus(SPI::Bus::LPSPI4, {
|
||||
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin18}, SPI::DRDY{GPIO::Port2, GPIO::Pin10}), /* GPIO_B1_02 GPIO2_IO18 */
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin0}, SPI::DRDY{GPIO::Port1, GPIO::Pin25}), /* GPIO_B0_00 GPIO2_IO00 */
|
||||
}),
|
||||
}),
|
||||
|
||||
initSPIFmumID(TROPIC_1, {
|
||||
initSPIBus(SPI::Bus::LPSPI3, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::Port1, GPIO::Pin28}), /* GPIO_AD_B1_12 GPIO1_IO28 */
|
||||
}),
|
||||
initSPIBus(SPI::Bus::LPSPI4, {
|
||||
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin18}), /* GPIO_B1_02 GPIO2_IO18 */
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin0}), /* GPIO_B0_00 GPIO2_IO00 */
|
||||
}),
|
||||
}),
|
||||
|
||||
initSPIFmumID(TROPIC_2, {
|
||||
initSPIBus(SPI::Bus::LPSPI3, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42686P, SPI::CS{GPIO::Port1, GPIO::Pin28}), /* GPIO_AD_B1_12 GPIO1_IO28 */
|
||||
}),
|
||||
initSPIBus(SPI::Bus::LPSPI4, {
|
||||
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin18}), /* GPIO_B1_02 GPIO2_IO18 */
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin0}), /* GPIO_B0_00 GPIO2_IO00 */
|
||||
}),
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw);
|
||||
152
boards/nxp/mr-tropic/src/timer_config.cpp
Normal file
152
boards/nxp/mr-tropic/src/timer_config.cpp
Normal file
@ -0,0 +1,152 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
#include <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_hw_description.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
/* 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)
|
||||
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule0), // PWM_1, PMW_2
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule1), // PWM_3, PWM_4
|
||||
initIOPWMDshot(PWM::FlexPWM4, PWM::Submodule1), // PWM_5, PWM_6
|
||||
initIOPWMDshot(PWM::FlexPWM4, PWM::Submodule2), // PWM_7, PWM_8
|
||||
};
|
||||
|
||||
#define FXIO_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER)
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_06, GPIO_FLEXIO1_FLEXIO06_1 | FXIO_IOMUX, 6),
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_B, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_07, GPIO_FLEXIO1_FLEXIO07_1 | FXIO_IOMUX, 7),
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_08, GPIO_FLEXIO1_FLEXIO08_1 | FXIO_IOMUX, 8),
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_B, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_09, GPIO_FLEXIO1_FLEXIO09_1 | FXIO_IOMUX, 9),
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_02, GPIO_FLEXIO1_FLEXIO02_1 | FXIO_IOMUX, 2),
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_B, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_03, GPIO_FLEXIO1_FLEXIO03_1 | FXIO_IOMUX, 3),
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_04, GPIO_FLEXIO1_FLEXIO04_1 | FXIO_IOMUX, 4),
|
||||
initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_B, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_05, GPIO_FLEXIO1_FLEXIO05_1 | FXIO_IOMUX, 5),
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
initIOTimerChannelMapping(io_timers, timer_io_channels);
|
||||
|
||||
constexpr io_timers_t led_pwm_timers[MAX_LED_TIMERS] = {
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = {
|
||||
};
|
||||
|
||||
#include <stdio.h>
|
||||
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);
|
||||
imxrt_xbar_connect(IMXRT_XBARA1_OUT_FLEXPWM1_EXT_CLK_SEL_OFFSET, IMXRT_XBARA1_IN_QTIMER3_TMR0_OUT);
|
||||
}
|
||||
182
boards/nxp/mr-tropic/src/tropic_led_pwm.cpp
Normal file
182
boards/nxp/mr-tropic/src/tropic_led_pwm.cpp
Normal file
@ -0,0 +1,182 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 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 Airmind 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 tropic_led_pwm.cpp
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/irq.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include <assert.h>
|
||||
#include <debug.h>
|
||||
#include <time.h>
|
||||
#include <queue.h>
|
||||
#include <errno.h>
|
||||
#include <string.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
|
||||
#include <px4_arch/io_timer.h>
|
||||
|
||||
#include <chip.h>
|
||||
#include "imxrt_xbar.h"
|
||||
#include "imxrt_periphclks.h"
|
||||
#include "hardware/imxrt_tmr.h"
|
||||
#include "hardware/imxrt_flexpwm.h"
|
||||
|
||||
#define LED_PWM_FREQ 1000
|
||||
#define FLEXPWM_FREQ 1000000
|
||||
#define QTMR_FREQ (144000000/128)
|
||||
|
||||
#define SM_SPACING (IMXRT_FLEXPWM_SM1CNT_OFFSET-IMXRT_FLEXPWM_SM0CNT_OFFSET)
|
||||
|
||||
#define FLEXPWM_TIMER_BASE IMXRT_FLEXPWM2_BASE
|
||||
|
||||
/* Register accessors */
|
||||
#define _REG(_addr) (*(volatile uint16_t *)(_addr))
|
||||
#define _REG16(_base, _reg) (*(volatile uint16_t *)(_base + _reg))
|
||||
#define FLEXPWMREG(_tmr, _sm, _reg) _REG16(_tmr + ((_sm) * SM_SPACING), (_reg))
|
||||
|
||||
/* FlexPWM Registers for LED_G */
|
||||
#define rINIT(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0INIT_OFFSET) /* Initial Count Register */
|
||||
#define rCTRL(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0CTRL_OFFSET) /* Control Register */
|
||||
#define rCTRL2(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0CTRL2_OFFSET) /* Control 2 Register */
|
||||
#define rFSTS0(_tim) FLEXPWMREG(_tim, 0, IMXRT_FLEXPWM_FSTS0_OFFSET) /* Fault Status Register */
|
||||
#define rVAL0(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL0_OFFSET) /* Value Register 0 */
|
||||
#define rVAL1(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL1_OFFSET) /* Value Register 1 */
|
||||
#define rVAL2(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL2_OFFSET) /* Value Register 2 */
|
||||
#define rVAL3(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL3_OFFSET) /* Value Register 3 */
|
||||
#define rVAL4(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL4_OFFSET) /* Value Register 4 */
|
||||
#define rVAL5(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL5_OFFSET) /* Value Register 5 */
|
||||
#define rFFILT0(_tim) FLEXPWMREG(_tim, 0, IMXRT_FLEXPWM_FFILT0_OFFSET) /* Fault Filter Register */
|
||||
#define rDISMAP0(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0DISMAP0_OFFSET) /* Fault Disable Mapping Register 0 */
|
||||
#define rDISMAP1(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0DISMAP1_OFFSET) /* Fault Disable Mapping Register 1 */
|
||||
#define rOUTEN(_tim) FLEXPWMREG(_tim, 0, IMXRT_FLEXPWM_OUTEN_OFFSET) /* Output Enable Register */
|
||||
#define rDTSRCSEL(_tim) FLEXPWMREG(_tim, 0, IMXRT_FLEXPWM_DTSRCSEL_OFFSET) /* PWM Source Select Register */
|
||||
#define rMCTRL(_tim) FLEXPWMREG(_tim, 0, IMXRT_FLEXPWM_MCTRL_OFFSET) /* Master Control Register */
|
||||
|
||||
#define OUTEN_A_MASK 0x1
|
||||
#define OUTEN_B_MASK 0x2
|
||||
|
||||
#define FREQ
|
||||
|
||||
static void flexpwm_led(uint32_t timer, uint32_t sm, uint16_t cvalue, uint32_t gpio_mux, uint32_t pwm_mux,
|
||||
uint32_t out_mask)
|
||||
{
|
||||
if (cvalue == 0) {
|
||||
//rMCTRL(timer) &= ~MCTRL_RUN(1 << sm);
|
||||
px4_arch_configgpio(gpio_mux);
|
||||
|
||||
} else {
|
||||
rMCTRL(timer) |= (1 << (sm + MCTRL_CLDOK_SHIFT));
|
||||
rVAL1(timer, sm) = (FLEXPWM_FREQ / LED_PWM_FREQ) - 1;
|
||||
|
||||
if (out_mask & OUTEN_A_MASK) {
|
||||
rVAL3(timer, sm) = (FLEXPWM_FREQ / LED_PWM_FREQ) - (cvalue);
|
||||
|
||||
} else if (out_mask & OUTEN_B_MASK) {
|
||||
rVAL5(timer, sm) = (FLEXPWM_FREQ / LED_PWM_FREQ) - (cvalue);
|
||||
}
|
||||
|
||||
rMCTRL(timer) |= MCTRL_LDOK(1 << sm) | MCTRL_RUN(1 << sm);
|
||||
px4_arch_configgpio(pwm_mux);
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
led_pwm_servo_set(unsigned channel, uint8_t cvalue)
|
||||
{
|
||||
if (channel == 0) {
|
||||
flexpwm_led(IMXRT_FLEXPWM3_BASE, 2, cvalue, GPIO_nLED_RED, PWM_LED_RED, OUTEN_A_MASK);
|
||||
|
||||
} else if (channel == 1) {
|
||||
flexpwm_led(IMXRT_FLEXPWM1_BASE, 3, cvalue, GPIO_nLED_GREEN, PWM_LED_GREEN, OUTEN_A_MASK);
|
||||
|
||||
} else if (channel == 2) {
|
||||
flexpwm_led(IMXRT_FLEXPWM3_BASE, 2, cvalue * 3, GPIO_nLED_BLUE, PWM_LED_BLUE, OUTEN_B_MASK);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void flexpwm_init(uint32_t timer, uint32_t sm, uint32_t out_mask)
|
||||
{
|
||||
/* Clear all Faults */
|
||||
rFSTS0(timer) = FSTS_FFLAG_MASK;
|
||||
rMCTRL(timer) |= (1 << (sm + MCTRL_CLDOK_SHIFT));
|
||||
|
||||
rCTRL2(timer, sm) = SMCTRL2_CLK_SEL_EXT_CLK | SMCTRL2_DBGEN | SMCTRL2_INDEP;
|
||||
rCTRL(timer, sm) = SMCTRL_PRSC_DIV16 | SMCTRL_FULL;
|
||||
/* Edge aligned at 0 */
|
||||
rINIT(timer, sm) = 0;
|
||||
rVAL0(timer, sm) = 0;
|
||||
rVAL2(timer, sm) = 0;
|
||||
rVAL4(timer, sm) = 0;
|
||||
rFFILT0(timer) &= ~FFILT_FILT_PER_MASK;
|
||||
rDISMAP0(timer, sm) = 0xf000;
|
||||
rDISMAP1(timer, sm) = 0xf000;
|
||||
|
||||
|
||||
if (out_mask & OUTEN_A_MASK) {
|
||||
rOUTEN(timer) |= OUTEN_PWMA_EN(1 << sm);
|
||||
}
|
||||
|
||||
if (out_mask & OUTEN_B_MASK) {
|
||||
rOUTEN(timer) |= OUTEN_PWMB_EN(1 << sm);
|
||||
}
|
||||
|
||||
rDTSRCSEL(timer) = 0;
|
||||
rMCTRL(timer) |= MCTRL_LDOK(1 << sm);
|
||||
}
|
||||
|
||||
int led_pwm_servo_init()
|
||||
{
|
||||
/* PWM_LED_GREEN - FLEXPWM2_PWMB03 */
|
||||
imxrt_clockall_pwm1();
|
||||
imxrt_clockall_pwm3();
|
||||
|
||||
flexpwm_init(IMXRT_FLEXPWM3_BASE, 2, OUTEN_A_MASK | OUTEN_B_MASK); // GPIO_FLEXPWM3_PWMA02_1
|
||||
flexpwm_init(IMXRT_FLEXPWM1_BASE, 3, OUTEN_A_MASK); // GPIO_FLEXPWM1_PWMA03_2
|
||||
|
||||
|
||||
|
||||
return OK;
|
||||
}
|
||||
129
boards/nxp/mr-tropic/src/usb.c
Normal file
129
boards/nxp/mr-tropic/src/usb.c
Normal file
@ -0,0 +1,129 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 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 <arm_internal.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;
|
||||
}
|
||||
@ -157,8 +157,13 @@
|
||||
#if BOARD_NUMBER_BRICKS == 0
|
||||
/* allow SITL to disable all bricks */
|
||||
#elif BOARD_NUMBER_BRICKS == 1
|
||||
# if defined(BOARD_NUMBER_DIGITAL_BRICKS)
|
||||
# define BOARD_BATT_V_LIST {-1}
|
||||
# define BOARD_BATT_I_LIST {-1}
|
||||
# else
|
||||
# define BOARD_BATT_V_LIST {ADC_BATTERY_VOLTAGE_CHANNEL}
|
||||
# define BOARD_BATT_I_LIST {ADC_BATTERY_CURRENT_CHANNEL}
|
||||
# endif
|
||||
# define BOARD_BRICK_VALID_LIST {BOARD_ADC_BRICK_VALID}
|
||||
#elif BOARD_NUMBER_BRICKS == 2
|
||||
# if defined(BOARD_NUMBER_DIGITAL_BRICKS)
|
||||
|
||||
@ -507,6 +507,9 @@ if(NOT NUTTX_DIR MATCHES "external")
|
||||
if(CONFIG_ARCH_CHIP_MIMXRT1062DVL6A)
|
||||
set(DEBUG_DEVICE "MIMXRT1062XXX6A")
|
||||
set(DEBUG_SVD_FILE "MIMXRT1062.xml")
|
||||
elseif(CONFIG_ARCH_CHIP_MIMXRT1064DVL6A)
|
||||
set(DEBUG_DEVICE "MIMXRT1064XXX6A")
|
||||
set(DEBUG_SVD_FILE "MIMXRT1064.xml")
|
||||
elseif(CONFIG_ARCH_CHIP_MIMXRT1176DVMAA)
|
||||
set(DEBUG_DEVICE "MIMXRT1176DVMAA")
|
||||
set(DEBUG_SVD_FILE "MIMXRT1176_cm7.xml")
|
||||
|
||||
@ -1 +1 @@
|
||||
Subproject commit d50ffd354495ce5d30814dba41d2eb70a32b8fa3
|
||||
Subproject commit fb2fadf6f599c1406f052db013efd00a2518e72c
|
||||
@ -158,6 +158,9 @@ function(px4_os_determine_build_chip)
|
||||
elseif(CONFIG_ARCH_CHIP_MIMXRT1062DVL6A)
|
||||
set(CHIP_MANUFACTURER "nxp")
|
||||
set(CHIP "rt106x")
|
||||
elseif(CONFIG_ARCH_CHIP_MIMXRT1064DVL6A)
|
||||
set(CHIP_MANUFACTURER "nxp")
|
||||
set(CHIP "rt106x")
|
||||
elseif(CONFIG_ARCH_CHIP_MIMXRT1176DVMAA)
|
||||
set(CHIP_MANUFACTURER "nxp")
|
||||
set(CHIP "rt117x")
|
||||
|
||||
@ -9,9 +9,19 @@
|
||||
#include "hw_config.h"
|
||||
#include <px4_arch/imxrt_flexspi_nor_flash.h>
|
||||
#include <px4_arch/imxrt_romapi.h>
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
# include <hardware/rt117x/imxrt117x_ocotp.h>
|
||||
# include <hardware/rt117x/imxrt117x_anadig.h>
|
||||
# include <hardware/rt117x/imxrt117x_snvs.h>
|
||||
#else
|
||||
# include <chip.h>
|
||||
# include <hardware/imxrt_usb_analog.h>
|
||||
# include <hardware/imxrt_snvs.h>
|
||||
# include <hardware/imxrt_ocotp.h>
|
||||
# include "hardware/imxrt_ccm.h"
|
||||
# include "imxrt_periphclks.h"
|
||||
# define SNVS_LPCR_GPR_Z_DIS (1 << 24) /* Bit 24: General Purpose Registers Zeroization Disable */
|
||||
#endif
|
||||
#include <hardware/imxrt_usb_analog.h>
|
||||
#include "imxrt_clockconfig.h"
|
||||
|
||||
@ -30,14 +40,31 @@
|
||||
|
||||
#define APP_SIZE_MAX (BOARD_FLASH_SIZE - (BOOTLOADER_RESERVATION_SIZE + APP_RESERVATION_SIZE))
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
#define CHIP_TAG "i.MX RT11?0,r??"
|
||||
#define CHIP_TAG_LEN sizeof(CHIP_TAG)-1
|
||||
|
||||
#define SI_REV(n) ((n & 0x7000000) >> 24)
|
||||
#define DIFPROG_TYPE(n) ((n & 0xF000) >> 12)
|
||||
#define DIFPROG_REV_MAJOR(n) ((n & 0xF0) >> 4)
|
||||
#define DIFPROG_REV_MINOR(n) ((n & 0xF))
|
||||
#elif defined(CONFIG_ARCH_FAMILY_IMXRT106x)
|
||||
#define CHIP_TAG "i.MX RT10?? r?.?"
|
||||
#define DIGPROG_MINOR_SHIFT 0
|
||||
#define DIGPROG_MINOR_MASK (0xff << DIGPROG_MINOR_SHIFT)
|
||||
#define DIGPROG_MINOR(info) (((info) & DIGPROG_MINOR_MASK) >> DIGPROG_MINOR_SHIFT)
|
||||
#define DIGPROG_MAJOR_LOWER_SHIFT 8
|
||||
#define DIGPROG_MAJOR_LOWER_MASK (0xff << DIGPROG_MAJOR_LOWER_SHIFT)
|
||||
#define DIGPROG_MAJOR_LOWER(info) (((info) & DIGPROG_MAJOR_LOWER_MASK) >> DIGPROG_MAJOR_LOWER_SHIFT)
|
||||
#define DIGPROG_MAJOR_UPPER_SHIFT 16
|
||||
#define DIGPROG_MAJOR_UPPER_MASK (0xff << DIGPROG_MAJOR_UPPER_SHIFT)
|
||||
#define DIGPROG_MAJOR_UPPER(info) (((info) & DIGPROG_MAJOR_UPPER_MASK) >> DIGPROG_MAJOR_UPPER_SHIFT)
|
||||
#endif
|
||||
#define CHIP_TAG_LEN sizeof(CHIP_TAG)-1
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
#define FLASH_BASE IMXRT_FLEXSPI1_CIPHER_BASE
|
||||
#elif defined(CONFIG_ARCH_CHIP_MIMXRT1064DVL6A)
|
||||
#define FLASH_BASE IMXRT_FLEX2CIPHER_BASE
|
||||
#endif
|
||||
|
||||
/* context passed to cinit */
|
||||
#if INTERFACE_USART
|
||||
@ -287,6 +314,27 @@ board_deinit(void)
|
||||
px4_arch_configgpio(MK_GPIO_INPUT(BOARD_PIN_LED_BOOTLOADER));
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT106x
|
||||
|
||||
// Restore CCM registers to ROM state
|
||||
putreg32(0x00000001, IMXRT_CCM_CACRR);
|
||||
putreg32(0x000A8200, IMXRT_CCM_CBCDR);
|
||||
putreg32(0x06490B03, IMXRT_CCM_CSCDR1);
|
||||
putreg32(0x75AE8104, IMXRT_CCM_CBCMR);
|
||||
putreg32(0x67930001, IMXRT_CCM_CSCMR1);
|
||||
|
||||
imxrt_clockoff_lpuart3();
|
||||
imxrt_clockoff_usboh3();
|
||||
imxrt_clockoff_timer3();
|
||||
imxrt_clockoff_xbar1();
|
||||
imxrt_clockoff_xbar3();
|
||||
|
||||
up_disable_icache();
|
||||
up_disable_dcache();
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
const uint32_t dnfw[] = {
|
||||
CCM_CR_M7,
|
||||
CCM_CR_BUS,
|
||||
@ -309,6 +357,8 @@ board_deinit(void)
|
||||
putreg32(CCM_CR_CTRL_OFF, IMXRT_CCM_CR_CTRL(i));
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
inline void arch_systic_init(void)
|
||||
@ -365,7 +415,7 @@ ssize_t arch_flash_write(uintptr_t address, const void *buffer, size_t buflen)
|
||||
j++;
|
||||
}
|
||||
|
||||
uintptr_t offset = ((uintptr_t) address) - IMXRT_FLEXSPI1_CIPHER_BASE;
|
||||
uintptr_t offset = ((uintptr_t) address) - FLASH_BASE;
|
||||
|
||||
volatile uint32_t status = ROM_FLEXSPI_NorFlash_ProgramPage(1, pConfig, offset, (const uint32_t *)buffer);
|
||||
up_invalidate_dcache((uintptr_t)address,
|
||||
@ -400,7 +450,7 @@ flash_func_sector_size(unsigned sector)
|
||||
ssize_t up_progmem_ispageerased(unsigned sector)
|
||||
{
|
||||
const uint32_t bytes_per_sector = flash_func_sector_size(sector);
|
||||
uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector));
|
||||
uint32_t *address = (uint32_t *)(FLASH_BASE + (sector * bytes_per_sector));
|
||||
const uint32_t uint32_per_sector = bytes_per_sector / sizeof(*address);
|
||||
|
||||
int blank = 0; /* Assume it is Bank */
|
||||
@ -437,9 +487,9 @@ flash_func_erase_sector(unsigned sector, bool force)
|
||||
struct flexspi_nor_config_s *pConfig = &g_bootConfig;
|
||||
|
||||
const uint32_t bytes_per_sector = flash_func_sector_size(sector);
|
||||
uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector));
|
||||
uint32_t *address = (uint32_t *)(FLASH_BASE + (sector * bytes_per_sector));
|
||||
|
||||
uintptr_t offset = ((uintptr_t) address) - IMXRT_FLEXSPI1_CIPHER_BASE;
|
||||
uintptr_t offset = ((uintptr_t) address) - FLASH_BASE;
|
||||
irqstate_t flags;
|
||||
flags = enter_critical_section();
|
||||
volatile uint32_t status = ROM_FLEXSPI_NorFlash_Erase(1, pConfig, (uintptr_t) offset, bytes_per_sector);
|
||||
@ -473,6 +523,8 @@ flash_func_read_otp(uintptr_t address)
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
|
||||
uint32_t get_mcu_id(void)
|
||||
{
|
||||
// ??? is DEBUGMCU get able
|
||||
@ -499,6 +551,36 @@ int get_mcu_desc(int max, uint8_t *revstr)
|
||||
return strp - revstr;
|
||||
}
|
||||
|
||||
#elif defined(CONFIG_ARCH_FAMILY_IMXRT106x)
|
||||
|
||||
uint32_t get_mcu_id(void)
|
||||
{
|
||||
return getreg32(IMXRT_OCOTP_UNIQUE_ID_LSB);
|
||||
}
|
||||
|
||||
int get_mcu_desc(int max, uint8_t *revstr)
|
||||
{
|
||||
uint32_t info = getreg32(IMXRT_USB_ANALOG_DIGPROG);
|
||||
// CHIP_TAG "i.MX RT10?? r?.?"
|
||||
static uint8_t chip[sizeof(CHIP_TAG) + 1] = CHIP_TAG;
|
||||
chip[CHIP_TAG_LEN - 1] = '0' + DIGPROG_MINOR(info);
|
||||
chip[CHIP_TAG_LEN - 3] = '1' + DIGPROG_MAJOR_LOWER(info);
|
||||
chip[CHIP_TAG_LEN - 6] = getreg32(0x401F867C) == 0x10 ? '4' : '2';
|
||||
chip[CHIP_TAG_LEN - 7] = DIGPROG_MAJOR_UPPER(info) == 0x6a ? '5' : '6';
|
||||
|
||||
uint8_t *endp = &revstr[max - 1];
|
||||
uint8_t *strp = revstr;
|
||||
uint8_t *des = chip;
|
||||
|
||||
while (strp < endp && *des) {
|
||||
*strp++ = *des++;
|
||||
}
|
||||
|
||||
return strp - revstr;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
int check_silicon(void)
|
||||
{
|
||||
@ -717,6 +799,7 @@ bootloader_main(void)
|
||||
* Returns - 0 if connected.
|
||||
*
|
||||
************************************************************************************/
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
#undef IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT
|
||||
#define USB1_VBUS_DET_STAT_OFFSET 0xd0
|
||||
#define IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT (IMXRT_USBPHY1_BASE + USB1_VBUS_DET_STAT_OFFSET)
|
||||
@ -727,6 +810,17 @@ bootloader_main(void)
|
||||
try_boot = false;
|
||||
}
|
||||
|
||||
#elif defined(CONFIG_ARCH_FAMILY_IMXRT106x)
|
||||
#undef IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT
|
||||
#define IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT (IMXRT_ANATOP_BASE + IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT_OFFSET)
|
||||
|
||||
if ((getreg32(IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT) & USB_ANALOG_USB_VBUS_DETECT_STAT_VBUS_VALID) != 0) {
|
||||
usb_connected = true;
|
||||
/* don't try booting before we set up the bootloader */
|
||||
try_boot = false;
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if INTERFACE_USART
|
||||
|
||||
34
platforms/nuttx/src/bootloader/nxp/rt106x/CMakeLists.txt
Normal file
34
platforms/nuttx/src/bootloader/nxp/rt106x/CMakeLists.txt
Normal file
@ -0,0 +1,34 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2023 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(../imxrt_common arch_bootloader)
|
||||
@ -35,9 +35,7 @@ px4_add_library(arch_board_reset
|
||||
board_reset.cpp
|
||||
)
|
||||
|
||||
if (CONFIG_ARCH_FAMILY_IMXRT117x)
|
||||
target_link_libraries(arch_board_reset PRIVATE arch_board_romapi)
|
||||
endif()
|
||||
|
||||
# up_systemreset
|
||||
if (NOT DEFINED CONFIG_BUILD_FLAT)
|
||||
|
||||
@ -45,6 +45,12 @@
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
#include <hardware/rt117x/imxrt117x_snvs.h>
|
||||
#elif defined CONFIG_ARCH_FAMILY_IMXRT106x
|
||||
# include <hardware/imxrt_snvs.h>
|
||||
# define SNVS_LPCR_GPR_Z_DIS (1 << 24) /* Bit 24: General Purpose Registers Zeroization Disable */
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_HAS_ISP_BOOTLOADER
|
||||
#include <px4_arch/imxrt_flexspi_nor_flash.h>
|
||||
#include <px4_arch/imxrt_romapi.h>
|
||||
#endif
|
||||
@ -59,13 +65,9 @@
|
||||
|
||||
static int board_reset_enter_bootloader()
|
||||
{
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
uint32_t regvalue = BOOT_RTC_SIGNATURE;
|
||||
modifyreg32(IMXRT_SNVS_LPCR, 0, SNVS_LPCR_GPR_Z_DIS);
|
||||
putreg32(regvalue, PX4_IMXRT_RTC_REBOOT_REG_ADDRESS);
|
||||
#elif defined(BOARD_HAS_TEENSY_BOOTLOADER)
|
||||
asm("BKPT #251"); /* Enter Teensy MKL02 bootloader */
|
||||
#endif
|
||||
return OK;
|
||||
}
|
||||
|
||||
@ -75,15 +77,16 @@ int board_reset(int status)
|
||||
board_reset_enter_bootloader();
|
||||
}
|
||||
|
||||
#if defined(BOARD_HAS_ISP_BOOTLOADER)
|
||||
|
||||
else if (status == REBOOT_TO_ISP) {
|
||||
#ifdef BOARD_HAS_TEENSY_BOOTLOADER
|
||||
asm("BKPT #251"); /* Enter Teensy MKL02 bootloader */
|
||||
#elif defined(BOARD_HAS_ISP_BOOTLOADER)
|
||||
uint32_t arg = 0xeb100000;
|
||||
ROM_API_Init();
|
||||
ROM_RunBootloader(&arg);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_HAS_ON_RESET)
|
||||
board_on_reset(status);
|
||||
|
||||
@ -138,6 +138,20 @@
|
||||
(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))
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT106x
|
||||
//!@brief Definitions for FlexSPI Serial Clock Frequency
|
||||
typedef enum _FlexSpiSerialClockFreq {
|
||||
kFlexSpiSerialClk_30MHz = 1,
|
||||
kFlexSpiSerialClk_50MHz = 2,
|
||||
kFlexSpiSerialClk_60MHz = 3,
|
||||
kFlexSpiSerialClk_75MHz = 4,
|
||||
kFlexSpiSerialClk_80MHz = 5,
|
||||
kFlexSpiSerialClk_100MHz = 6,
|
||||
kFlexSpiSerialClk_120MHz = 7,
|
||||
kFlexSpiSerialClk_133MHz = 8,
|
||||
kFlexSpiSerialClk_166MHz = 9,
|
||||
} flexspi_serial_clk_freq_t;
|
||||
#elif defined(CONFIG_ARCH_FAMILY_IMXRT117x)
|
||||
//!@brief Definitions for FlexSPI Serial Clock Frequency
|
||||
typedef enum _FlexSpiSerialClockFreq {
|
||||
kFlexSpiSerialClk_30MHz = 1,
|
||||
@ -150,6 +164,7 @@ typedef enum _FlexSpiSerialClockFreq {
|
||||
kFlexSpiSerialClk_166MHz = 8,
|
||||
kFlexSpiSerialClk_200MHz = 9,
|
||||
} flexspi_serial_clk_freq_t;
|
||||
#endif
|
||||
|
||||
//!@brief FlexSPI clock configuration type
|
||||
enum {
|
||||
|
||||
@ -239,7 +239,9 @@ status_t ROM_FLEXSPI_NorFlash_Erase(uint32_t instance, flexspi_nor_config_t *con
|
||||
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
|
||||
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout
|
||||
*/
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
status_t ROM_FLEXSPI_NorFlash_EraseSector(uint32_t instance, flexspi_nor_config_t *config, uint32_t start);
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* @brief Erase one block specified by address
|
||||
@ -259,7 +261,9 @@ status_t ROM_FLEXSPI_NorFlash_EraseSector(uint32_t instance, flexspi_nor_config_
|
||||
* @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout.
|
||||
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout
|
||||
*/
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
status_t ROM_FLEXSPI_NorFlash_EraseBlock(uint32_t instance, flexspi_nor_config_t *config, uint32_t start);
|
||||
#endif
|
||||
|
||||
/*!
|
||||
* @brief Erase all the Serial NOR devices connected on FLEXSPI.
|
||||
@ -342,10 +346,12 @@ status_t ROM_FLEXSPI_NorFlash_UpdateLut(uint32_t instance,
|
||||
* @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided.
|
||||
* @retval kStatus_ROM_FLEXSPI_DeviceTimeout Device timeout.
|
||||
*/
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
status_t ROM_FLEXSPI_NorFlash_WaitBusy(uint32_t instance,
|
||||
flexspi_nor_config_t *config,
|
||||
bool isParallelMode,
|
||||
uint32_t address);
|
||||
#endif
|
||||
/*@}*/
|
||||
|
||||
/*!
|
||||
|
||||
@ -52,8 +52,29 @@ typedef union _standard_version {
|
||||
#endif
|
||||
} standard_version_t;
|
||||
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT106x
|
||||
|
||||
/*!
|
||||
* @brief Interface for the ROM FLEXSPI NOR flash driver.
|
||||
* @brief Interface for the IMXRT106X ROM FLEXSPI NOR flash driver.
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t version;
|
||||
status_t (*init)(uint32_t instance, flexspi_nor_config_t *config);
|
||||
status_t (*page_program)(uint32_t instance, flexspi_nor_config_t *config, uint32_t dst_addr, const uint32_t *src);
|
||||
status_t (*erase_all)(uint32_t instance, flexspi_nor_config_t *config);
|
||||
status_t (*erase)(uint32_t instance, flexspi_nor_config_t *config, uint32_t start, uint32_t length);
|
||||
status_t (*read)(uint32_t instance, flexspi_nor_config_t *config, uint32_t *dst, uint32_t start, uint32_t bytes);
|
||||
void (*clear_cache)(uint32_t instance);
|
||||
status_t (*xfer)(uint32_t instance, flexspi_xfer_t *xfer);
|
||||
status_t (*update_lut)(uint32_t instance, uint32_t seqIndex, const uint32_t *lutBase, uint32_t numberOfSeq);
|
||||
status_t (*get_config)(uint32_t instance, flexspi_nor_config_t *config, serial_nor_config_option_t *option);
|
||||
} flexspi_nor_driver_interface_t;
|
||||
|
||||
#elif defined(CONFIG_ARCH_FAMILY_IMXRT117x)
|
||||
|
||||
/*!
|
||||
* @brief Interface for the IMXRT117X ROM FLEXSPI NOR flash driver.
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t version;
|
||||
@ -73,6 +94,33 @@ typedef struct {
|
||||
const uint32_t reserved1[2]; /*!< Reserved */
|
||||
} flexspi_nor_driver_interface_t;
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT106x
|
||||
|
||||
/*!
|
||||
* @brief Root of the bootloader api tree.
|
||||
*
|
||||
* An instance of this struct resides in read-only memory in the bootloader. It
|
||||
* provides a user application access to APIs exported by the bootloader.
|
||||
*
|
||||
* @note The order of existing fields must not be changed.
|
||||
*/
|
||||
typedef struct {
|
||||
const uint32_t version; //!< Bootloader version number
|
||||
const char *copyright; //!< Bootloader Copyright
|
||||
void (*runBootloader)(void *arg); //!< Function to start the bootloader executing
|
||||
const uint32_t *reserved0; //!< Reserved
|
||||
const flexspi_nor_driver_interface_t *flexSpiNorDriver; //!< FlexSPI NOR Flash API
|
||||
const uint32_t *reserved1; //!< Reserved
|
||||
const uint32_t *unused_rtwdogDriver;
|
||||
const uint32_t *unused_wdogDriver;
|
||||
const uint32_t *reserved2;
|
||||
} bootloader_api_entry_t;
|
||||
|
||||
#elif defined(CONFIG_ARCH_FAMILY_IMXRT117x)
|
||||
|
||||
/*!
|
||||
* @brief Root of the bootloader api tree.
|
||||
*
|
||||
@ -89,6 +137,8 @@ typedef struct {
|
||||
const uint32_t reserved[8]; /*!< Reserved */
|
||||
} bootloader_api_entry_t;
|
||||
|
||||
#endif
|
||||
|
||||
/*******************************************************************************
|
||||
* Variables
|
||||
******************************************************************************/
|
||||
@ -104,6 +154,9 @@ static bootloader_api_entry_t *g_bootloaderTree = NULL;
|
||||
locate_code(".ramfunc")
|
||||
void ROM_API_Init(void)
|
||||
{
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT106x
|
||||
g_bootloaderTree = ((bootloader_api_entry_t *) * (uint32_t *)0x0020001cU);
|
||||
#else
|
||||
|
||||
if ((getreg32(IMXRT_ANADIG_MISC_MISC_DIFPROG) & ANADIG_MISC_MISC_DIFPROG_CHIPID(0x10U)) != 0U) {
|
||||
g_bootloaderTree = ((bootloader_api_entry_t *) * (uint32_t *)0x0021001cU);
|
||||
@ -111,6 +164,8 @@ void ROM_API_Init(void)
|
||||
} else {
|
||||
g_bootloaderTree = ((bootloader_api_entry_t *) * (uint32_t *)0x0020001cU);
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
/*!
|
||||
@ -193,6 +248,8 @@ status_t ROM_FLEXSPI_NorFlash_Erase(uint32_t instance, flexspi_nor_config_t *con
|
||||
return g_bootloaderTree->flexSpiNorDriver->erase(instance, config, start, length);
|
||||
}
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
|
||||
/*!
|
||||
* @brief Erase one sector specified by address.
|
||||
*
|
||||
@ -219,6 +276,8 @@ status_t ROM_FLEXSPI_NorFlash_EraseBlock(uint32_t instance, flexspi_nor_config_t
|
||||
return g_bootloaderTree->flexSpiNorDriver->erase_block(instance, config, start);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/*! @brief Erase all the Serial NOR devices connected on FLEXSPI. */
|
||||
locate_code(".ramfunc")
|
||||
status_t ROM_FLEXSPI_NorFlash_EraseAll(uint32_t instance, flexspi_nor_config_t *config)
|
||||
@ -242,6 +301,19 @@ status_t ROM_FLEXSPI_NorFlash_UpdateLut(uint32_t instance,
|
||||
return g_bootloaderTree->flexSpiNorDriver->update_lut(instance, seqIndex, lutBase, seqNumber);
|
||||
}
|
||||
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT106x
|
||||
|
||||
/*! @brief Software reset for the FLEXSPI logic. */
|
||||
locate_code(".ramfunc")
|
||||
void ROM_FLEXSPI_NorFlash_ClearCache(uint32_t instance)
|
||||
{
|
||||
g_bootloaderTree->flexSpiNorDriver->clear_cache(instance);
|
||||
}
|
||||
|
||||
|
||||
#elif defined(CONFIG_ARCH_FAMILY_IMXRT117x)
|
||||
|
||||
/*! @brief Software reset for the FLEXSPI logic. */
|
||||
locate_code(".ramfunc")
|
||||
void ROM_FLEXSPI_NorFlash_ClearCache(uint32_t instance)
|
||||
@ -259,6 +331,9 @@ void ROM_FLEXSPI_NorFlash_ClearCache(uint32_t instance)
|
||||
MISRA_CAST(clearCacheCommand_t, clearCacheCommand, uint32_t, clearCacheFunctionAddress);
|
||||
(void)clearCacheCommand(instance);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_FAMILY_IMXRT117x
|
||||
|
||||
/*! @brief Wait until device is idle*/
|
||||
locate_code(".ramfunc")
|
||||
@ -269,3 +344,5 @@ status_t ROM_FLEXSPI_NorFlash_WaitBusy(uint32_t instance,
|
||||
{
|
||||
return g_bootloaderTree->flexSpiNorDriver->wait_busy(instance, config, isParallelMode, address);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
@ -90,7 +90,7 @@ int board_mcu_version(char *rev, const char **revstr, const char **errata)
|
||||
#define DIGPROG_MAJOR_UPPER_MASK (0xff << DIGPROG_MAJOR_UPPER_SHIFT)
|
||||
#define DIGPROG_MAJOR_UPPER(info) (((info) & DIGPROG_MAJOR_UPPER_MASK) >> DIGPROG_MAJOR_UPPER_SHIFT)
|
||||
// 876543210
|
||||
#define CHIP_TAG "i.MX RT10?2 r?.?"
|
||||
#define CHIP_TAG "i.MX RT10?? r?.?"
|
||||
#define CHIP_TAG_LEN sizeof(CHIP_TAG)-1
|
||||
|
||||
int board_mcu_version(char *rev, const char **revstr, const char **errata)
|
||||
@ -100,6 +100,7 @@ int board_mcu_version(char *rev, const char **revstr, const char **errata)
|
||||
|
||||
chip[CHIP_TAG_LEN - 1] = '0' + DIGPROG_MINOR(info);
|
||||
chip[CHIP_TAG_LEN - 3] = '1' + DIGPROG_MAJOR_LOWER(info);
|
||||
chip[CHIP_TAG_LEN - 6] = getreg32(0x401F867C) == 0x10 ? '4' : '2';
|
||||
chip[CHIP_TAG_LEN - 7] = DIGPROG_MAJOR_UPPER(info) == 0x6a ? '5' : '6';
|
||||
*revstr = chip;
|
||||
*rev = '0' + DIGPROG_MINOR(info);
|
||||
|
||||
@ -36,11 +36,13 @@ add_subdirectory(../imxrt/adc adc)
|
||||
add_subdirectory(../imxrt/board_critmon board_critmon)
|
||||
add_subdirectory(../imxrt/board_hw_info board_hw_info)
|
||||
add_subdirectory(../imxrt/board_reset board_reset)
|
||||
add_subdirectory(../imxrt/romapi romapi)
|
||||
add_subdirectory(../imxrt/dshot dshot)
|
||||
add_subdirectory(../imxrt/hrt hrt)
|
||||
add_subdirectory(../imxrt/led_pwm led_pwm)
|
||||
add_subdirectory(../imxrt/io_pins io_pins)
|
||||
add_subdirectory(../imxrt/tone_alarm tone_alarm)
|
||||
add_subdirectory(../imxrt/version version)
|
||||
add_subdirectory(../imxrt/spi spi)
|
||||
|
||||
add_subdirectory(px4io_serial)
|
||||
|
||||
@ -41,8 +41,8 @@
|
||||
#include <px4_platform_common/constexpr_util.h>
|
||||
|
||||
#include <board_config.h>
|
||||
#ifndef CONFIG_ARCH_CHIP_MIMXRT1062DVL6A
|
||||
# error "This code has only been validated with IMXRT1062. Make sure it is correct before using it on another board."
|
||||
#if !defined(CONFIG_ARCH_CHIP_MIMXRT1062DVL6A) && !defined(CONFIG_ARCH_CHIP_MIMXRT1064DVL6A)
|
||||
# error "This code has only been validated with IMXRT1062 and IMXRT1064. Make sure it is correct before using it on another board."
|
||||
#endif
|
||||
|
||||
/*
|
||||
|
||||
@ -0,0 +1,36 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
|
||||
#include "../../../imxrt/include/px4_arch/imxrt_flexspi_nor_flash.h"
|
||||
@ -0,0 +1,36 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
|
||||
|
||||
#include "../../../imxrt/include/px4_arch/imxrt_romapi.h"
|
||||
@ -47,8 +47,8 @@
|
||||
#include <hardware/imxrt_pinmux.h>
|
||||
|
||||
#include <board_config.h>
|
||||
#ifndef CONFIG_ARCH_CHIP_MIMXRT1062DVL6A
|
||||
# error "This code has only been validated with IMXRT1062. Make sure it is correct before using it on another board."
|
||||
#if !defined(CONFIG_ARCH_CHIP_MIMXRT1062DVL6A) && !defined(CONFIG_ARCH_CHIP_MIMXRT1064DVL6A)
|
||||
# error "This code has only been validated with IMXRT1062 and IMXRT1064. Make sure it is correct before using it on another board."
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
@ -46,6 +46,58 @@
|
||||
|
||||
#define GENERAL_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_KEEP | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST)
|
||||
|
||||
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
|
||||
{
|
||||
const bool nuttx_enabled_spi_buses[] = {
|
||||
#ifdef CONFIG_IMXRT_LPSPI1
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_IMXRT_LPSPI2
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_IMXRT_LPSPI3
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_IMXRT_LPSPI4
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_IMXRT_LPSPI5
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
#ifdef CONFIG_IMXRT_LPSPI6
|
||||
true,
|
||||
#else
|
||||
false,
|
||||
#endif
|
||||
};
|
||||
|
||||
for (unsigned i = 0; i < sizeof(nuttx_enabled_spi_buses) / sizeof(nuttx_enabled_spi_buses[0]); ++i) {
|
||||
bool found_bus = false;
|
||||
|
||||
for (int j = 0; j < SPI_BUS_MAX_BUS_ITEMS; ++j) {
|
||||
if (spi_busses_conf[j].bus == (int)i + 1) {
|
||||
found_bus = true;
|
||||
}
|
||||
}
|
||||
|
||||
// Either the bus is enabled in NuttX and configured in spi_busses_conf, or disabled and not configured
|
||||
constexpr_assert(found_bus == nuttx_enabled_spi_buses[i], "SPI bus config mismatch (CONFIG_STM32H7_SPIx)");
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
static inline constexpr px4_spi_bus_device_t initSPIDevice(uint32_t devid, SPI::CS cs_gpio, SPI::DRDY drdy_gpio = {})
|
||||
{
|
||||
px4_spi_bus_device_t ret{};
|
||||
@ -138,8 +190,57 @@ static inline constexpr SPI::bus_device_external_cfg_t initSPIConfigExternal(SPI
|
||||
return ret;
|
||||
}
|
||||
|
||||
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
|
||||
|
||||
struct px4_spi_bus_array_t {
|
||||
px4_spi_bus_t item[SPI_BUS_MAX_BUS_ITEMS];
|
||||
};
|
||||
#if defined(BOARD_HAS_HW_SPLIT_VERSIONING)
|
||||
static inline constexpr px4_spi_bus_all_hw_t initSPIFmumID(hw_fmun_id_t hw_fmun_id,
|
||||
const px4_spi_bus_array_t &bus_items)
|
||||
{
|
||||
return true;
|
||||
px4_spi_bus_all_hw_t ret{};
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) {
|
||||
ret.buses[i] = bus_items.item[i];
|
||||
}
|
||||
|
||||
ret.board_hw_fmun_id = hw_fmun_id;
|
||||
return ret;
|
||||
}
|
||||
#else
|
||||
static inline constexpr px4_spi_bus_all_hw_t initSPIHWVersion(int hw_version_revision,
|
||||
const px4_spi_bus_array_t &bus_items)
|
||||
{
|
||||
px4_spi_bus_all_hw_t ret{};
|
||||
|
||||
for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) {
|
||||
ret.buses[i] = bus_items.item[i];
|
||||
}
|
||||
|
||||
ret.board_hw_version_revision = hw_version_revision;
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_buses_conf[SPI_BUS_MAX_BUS_ITEMS]);
|
||||
|
||||
constexpr bool validateSPIConfig(const px4_spi_bus_all_hw_t spi_buses_conf[BOARD_NUM_SPI_CFG_HW_VERSIONS])
|
||||
{
|
||||
for (int ver = 0; ver < BOARD_NUM_SPI_CFG_HW_VERSIONS; ++ver) {
|
||||
validateSPIConfig(spi_buses_conf[ver].buses);
|
||||
}
|
||||
|
||||
for (int ver = 1; ver < BOARD_NUM_SPI_CFG_HW_VERSIONS; ++ver) {
|
||||
for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) {
|
||||
const bool equal_power_enable_gpio = spi_buses_conf[ver].buses[i].power_enable_gpio == spi_buses_conf[ver -
|
||||
1].buses[i].power_enable_gpio;
|
||||
// currently board_control_spi_sensors_power_configgpio() depends on that - this restriction can be removed
|
||||
// by ensuring board_control_spi_sensors_power_configgpio() is called after the hw version is determined
|
||||
// and SPI config is initialized.
|
||||
constexpr_assert(equal_power_enable_gpio, "All HW versions must define the same power enable GPIO");
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user