mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 21:55:34 +08:00
nxp:Add support for rev E HW nxp_fmuk66-e
This commit is contained in:
committed by
Daniel Agar
parent
f8b6de24c7
commit
e67486d603
@@ -0,0 +1,118 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR nxp
|
||||
MODEL fmuk66-e
|
||||
LABEL default
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
ROMFSROOT px4fmu_common
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS4
|
||||
TEL2:/dev/ttyS1
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
barometer/mpl3115a2
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm42688p
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
mkblctrl
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
pca9685
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
safety_button
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
#test_ppm # NOT Portable YET
|
||||
tone_alarm
|
||||
uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
#hardfault_log # Needs bbsrm
|
||||
i2cdetect
|
||||
led_control
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
||||
@@ -0,0 +1,13 @@
|
||||
{
|
||||
"board_id": 30,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the NXPFMUK66E board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "NXPFMUK66E",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 2096112,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
@@ -0,0 +1,13 @@
|
||||
|
||||
#
|
||||
# NXP fmuk66-e specific board defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
|
||||
if [ $AUTOCNF = yes ]
|
||||
then
|
||||
|
||||
fi
|
||||
|
||||
rgbled_pwm start
|
||||
safety_button start
|
||||
@@ -0,0 +1,7 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# NXP fmuk66-e specific board MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# Start MAVLink on the USB port
|
||||
mavlink start -d /dev/ttyACM0
|
||||
@@ -0,0 +1,19 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# NXP fmuk66-e specific board defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
adc start
|
||||
|
||||
# Internal Mag I2C bus roll 180, yaw 90
|
||||
bmm150 -I -R 10 start
|
||||
|
||||
# Onboard I2C baros
|
||||
bmp280 -I start
|
||||
|
||||
# Internal SPI (accel + mag)
|
||||
bmi088 -A -R 4 -s start
|
||||
bmi088 -G -R 4 -s start
|
||||
|
||||
# Internal SPI bus ICM-42688
|
||||
icm42688p -R 12 -s start
|
||||
@@ -0,0 +1,47 @@
|
||||
#
|
||||
# For a description of the syntax of this configuration file,
|
||||
# see misc/tools/kconfig-language.txt.
|
||||
#
|
||||
|
||||
config FMUK66_SDHC_AUTOMOUNT
|
||||
bool "SDHC automounter"
|
||||
default n
|
||||
depends on FS_AUTOMOUNTER && KINETIS_SDHC
|
||||
|
||||
if FMUK66_SDHC_AUTOMOUNT
|
||||
|
||||
config FMUK66_SDHC_AUTOMOUNT_FSTYPE
|
||||
string "SDHC file system type"
|
||||
default "vfat"
|
||||
|
||||
config FMUK66_SDHC_AUTOMOUNT_BLKDEV
|
||||
string "SDHC block device"
|
||||
default "/dev/mmcsd0"
|
||||
|
||||
config FMUK66_SDHC_AUTOMOUNT_MOUNTPOINT
|
||||
string "SDHC mount point"
|
||||
default "/fs/microsd"
|
||||
|
||||
config FMUK66_SDHC_AUTOMOUNT_DDELAY
|
||||
int "SDHC debounce delay (milliseconds)"
|
||||
default 1000
|
||||
|
||||
config FMUK66_SDHC_AUTOMOUNT_UDELAY
|
||||
int "SDHC unmount retry delay (milliseconds)"
|
||||
default 2000
|
||||
|
||||
endif # FMUK66_SDHC_AUTOMOUNT
|
||||
|
||||
config BOARD_HAS_PROBES
|
||||
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
|
||||
default y
|
||||
---help---
|
||||
This board provides GPIO FMU-CH1-6 as PROBE_1-6 to provide timing signals from selected drivers.
|
||||
|
||||
config BOARD_USE_PROBES
|
||||
bool "Enable the use the board provided GPIO FMU-CH1-6 as PROBE_1-6 to provide timing signals from selected drivers"
|
||||
default n
|
||||
depends on BOARD_HAS_PROBES
|
||||
|
||||
---help---
|
||||
Select to use GPIO FMU-CH1-6 to provide timing signals from selected drivers.
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,224 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_OS_API is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="kinetis"
|
||||
CONFIG_ARCH_CHIP_KINETIS=y
|
||||
CONFIG_ARCH_CHIP_MK66FN2M0VMD18=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=15175
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_BULKIN_REQLEN=96
|
||||
CONFIG_CDCACM_PRODUCTID=0x001c
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMUK66 v3.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=8000
|
||||
CONFIG_CDCACM_VENDORID=0x1FC9
|
||||
CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS"
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_ETH0_PHY_TJA1100=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_AUTOMOUNTER=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_IOB_NBUFFERS=24
|
||||
CONFIG_IOB_THROTTLE=0
|
||||
CONFIG_KINETIS_ADC0=y
|
||||
CONFIG_KINETIS_ADC1=y
|
||||
CONFIG_KINETIS_CRC=y
|
||||
CONFIG_KINETIS_DMA=y
|
||||
CONFIG_KINETIS_EMAC_RMIICLK1588CLKIN=y
|
||||
CONFIG_KINETIS_ENET=y
|
||||
CONFIG_KINETIS_FLEXCAN0=y
|
||||
CONFIG_KINETIS_FLEXCAN1=y
|
||||
CONFIG_KINETIS_GPIOIRQ=y
|
||||
CONFIG_KINETIS_I2C0=y
|
||||
CONFIG_KINETIS_I2C1=y
|
||||
CONFIG_KINETIS_LPTMR0=y
|
||||
CONFIG_KINETIS_LPUART0=y
|
||||
CONFIG_KINETIS_MERGE_TTY=y
|
||||
CONFIG_KINETIS_PDB=y
|
||||
CONFIG_KINETIS_PIT=y
|
||||
CONFIG_KINETIS_PORTAINTS=y
|
||||
CONFIG_KINETIS_PORTBINTS=y
|
||||
CONFIG_KINETIS_PORTCINTS=y
|
||||
CONFIG_KINETIS_PORTDINTS=y
|
||||
CONFIG_KINETIS_PORTEINTS=y
|
||||
CONFIG_KINETIS_RTC=y
|
||||
CONFIG_KINETIS_SDHC=y
|
||||
CONFIG_KINETIS_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_KINETIS_SPI0=y
|
||||
CONFIG_KINETIS_SPI1=y
|
||||
CONFIG_KINETIS_SPI2=y
|
||||
CONFIG_KINETIS_UART0=y
|
||||
CONFIG_KINETIS_UART0_RXDMA=y
|
||||
CONFIG_KINETIS_UART1=y
|
||||
CONFIG_KINETIS_UART1_RXDMA=y
|
||||
CONFIG_KINETIS_UART2=y
|
||||
CONFIG_KINETIS_UART2_RXDMA=y
|
||||
CONFIG_KINETIS_UART4=y
|
||||
CONFIG_KINETIS_UART4_RXDMA=y
|
||||
CONFIG_KINETIS_UARTFIFOS=y
|
||||
CONFIG_KINETIS_UART_BREAKS=y
|
||||
CONFIG_KINETIS_UART_EXTEDED_BREAK=y
|
||||
CONFIG_KINETIS_UART_INVERT=y
|
||||
CONFIG_KINETIS_USBDCD=y
|
||||
CONFIG_KINETS_LPUART_LOWEST=y
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_LPUART0_BAUD=57600
|
||||
CONFIG_LPUART0_SERIAL_CONSOLE=y
|
||||
CONFIG_MAX_WDOGPARMS=2
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_MULTIBLOCK_DISABLE=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NETDB_DNSCLIENT=y
|
||||
CONFIG_NETDB_DNSSERVER_NOADDR=y
|
||||
CONFIG_NETDEV_PHY_IOCTL=y
|
||||
CONFIG_NETINIT_THREAD=y
|
||||
CONFIG_NETINIT_THREAD_PRIORITY=49
|
||||
CONFIG_NETUTILS_TELNETD=y
|
||||
CONFIG_NET_ARP_IPIN=y
|
||||
CONFIG_NET_ARP_SEND=y
|
||||
CONFIG_NET_BROADCAST=y
|
||||
CONFIG_NET_ICMP=y
|
||||
CONFIG_NET_ICMP_SOCKET=y
|
||||
CONFIG_NET_SOCKOPTS=y
|
||||
CONFIG_NET_SOLINGER=y
|
||||
CONFIG_NET_TCP=y
|
||||
CONFIG_NET_TCPBACKLOG=y
|
||||
CONFIG_NET_TCP_WRITE_BUFFERS=y
|
||||
CONFIG_NET_UDP=y
|
||||
CONFIG_NET_UDP_CHECKSUMS=y
|
||||
CONFIG_NFILE_DESCRIPTORS=15
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_BASENAME=y
|
||||
CONFIG_NSH_DISABLE_DIRNAME=y
|
||||
CONFIG_NSH_DISABLE_EXPORT=y
|
||||
CONFIG_NSH_DISABLE_HEXDUMP=y
|
||||
CONFIG_NSH_DISABLE_LOSETUP=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_DISABLE_MKFIFO=y
|
||||
CONFIG_NSH_DISABLE_MKRD=y
|
||||
CONFIG_NSH_DISABLE_PUT=y
|
||||
CONFIG_NSH_DISABLE_REBOOT=y
|
||||
CONFIG_NSH_DISABLE_TELNETD=y
|
||||
CONFIG_NSH_DISABLE_UNAME=y
|
||||
CONFIG_NSH_DISABLE_WGET=y
|
||||
CONFIG_NSH_DISABLE_XD=y
|
||||
CONFIG_NSH_FILEIOSIZE=512
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_READLINE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PREALLOC_WDOGS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x1fff0000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_CUTERM=y
|
||||
CONFIG_SYSTEM_CUTERM_DEFAULT_BAUD=57600
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYSTEM_PING=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TIME_EXTENDED=y
|
||||
CONFIG_UART0_IFLOWCONTROL=y
|
||||
CONFIG_UART0_OFLOWCONTROL=y
|
||||
CONFIG_UART1_RXBUFSIZE=600
|
||||
CONFIG_UART1_TXBUFSIZE=1100
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_IFLOWCONTROL=y
|
||||
CONFIG_UART4_OFLOWCONTROL=y
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_TXBUFSIZE=1100
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_DUALSPEED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
||||
@@ -0,0 +1,179 @@
|
||||
/****************************************************************************
|
||||
* configs/nxp_fmuk66-e/scripts/flash.ld
|
||||
*
|
||||
* Copyright (C) 2016, 2017 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The MK66FN2M0VLQ18 has 2 MiB of FLASH beginning at address 0x0000:0000 and
|
||||
* 256 KiB of SRAM beginning at address 0x1fff:0000- (SRAM_L) (64Kib) and
|
||||
* 0x2000:0000 196 Kib (SRAM_U).
|
||||
*
|
||||
* NOTE: that the first part of the K66 FLASH region is reserved for
|
||||
* interrupt vectflash and, following that, is a region from 0x0000:0400
|
||||
* to 0x0000:040f that is reserved for the FLASH control fields (FCF).
|
||||
*
|
||||
* NOTE: The on-chip RAM is split evenly among SRAM_L and SRAM_U. The RAM is
|
||||
* also implemented such that the SRAM_L and SRAM_U ranges form a
|
||||
* contiguous block in the memory map.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
vectflash (rx) : ORIGIN = 0x00006000, LENGTH = 1K
|
||||
cfmprotect (rx) : ORIGIN = 0x00006400, LENGTH = 16
|
||||
progflash (rx) : ORIGIN = 0x00006410, LENGTH = 2M - ((6*4K) + 1K + 16)
|
||||
datasram (rwx) : ORIGIN = 0x1fff0000, LENGTH = 256K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
ENTRY(__start)
|
||||
EXTERN(__flashconfigbytes)
|
||||
SECTIONS
|
||||
{
|
||||
.vectors : {
|
||||
_svectors = ABSOLUTE(.);
|
||||
KEEP(*(.vectors))
|
||||
_evectors = ABSOLUTE(.);
|
||||
} > vectflash
|
||||
|
||||
.cfmprotect : {
|
||||
KEEP(*(.cfmconfig))
|
||||
} > cfmprotect
|
||||
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
|
||||
/*
|
||||
* This is a hack to make the newlib libm __errno() call
|
||||
* use the NuttX get_errno_ptr() function.
|
||||
*/
|
||||
__errno = get_errno_ptr;
|
||||
. = ALIGN(8);
|
||||
FILL(0xff)
|
||||
. += 8;
|
||||
} > progflash =0xff
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
. = ALIGN(8);
|
||||
FILL(0xff)
|
||||
. += 8;
|
||||
} > progflash
|
||||
|
||||
/*
|
||||
* Construction data for parameters.
|
||||
*/
|
||||
__param ALIGN(4): {
|
||||
__param_start = ABSOLUTE(.);
|
||||
KEEP(*(__param*))
|
||||
__param_end = ABSOLUTE(.);
|
||||
. = ALIGN(8);
|
||||
FILL(0xff)
|
||||
. += 8;
|
||||
} > progflash
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
. = ALIGN(8);
|
||||
FILL(0xff)
|
||||
. += 8;
|
||||
} > progflash
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > progflash
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
. = ALIGN(8);
|
||||
FILL(0xff)
|
||||
. += 8;
|
||||
} > datasram AT > progflash
|
||||
|
||||
.ramfunc ALIGN(4): {
|
||||
_sramfuncs = ABSOLUTE(.);
|
||||
*(.ramfunc .ramfunc.*)
|
||||
_eramfuncs = ABSOLUTE(.);
|
||||
. = ALIGN(8);
|
||||
FILL(0xff)
|
||||
. += 8;
|
||||
} > datasram AT > progflash =0xff
|
||||
|
||||
_framfuncs = LOADADDR(.ramfunc);
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > datasram
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
||||
@@ -0,0 +1,221 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_OS_API is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="kinetis"
|
||||
CONFIG_ARCH_CHIP_KINETIS=y
|
||||
CONFIG_ARCH_CHIP_MK66FN2M0VMD18=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=15175
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_BULKIN_REQLEN=96
|
||||
CONFIG_CDCACM_PRODUCTID=0x001c
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMUK66 v3.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=8000
|
||||
CONFIG_CDCACM_VENDORID=0x1FC9
|
||||
CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS"
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_ETH0_PHY_TJA1100=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_AUTOMOUNTER=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_IOB_NBUFFERS=48
|
||||
CONFIG_IOB_NCHAINS=16
|
||||
CONFIG_KINETIS_ADC0=y
|
||||
CONFIG_KINETIS_ADC1=y
|
||||
CONFIG_KINETIS_CRC=y
|
||||
CONFIG_KINETIS_DMA=y
|
||||
CONFIG_KINETIS_EMAC_RMIICLK1588CLKIN=y
|
||||
CONFIG_KINETIS_ENET=y
|
||||
CONFIG_KINETIS_FLEXCAN0=y
|
||||
CONFIG_KINETIS_FLEXCAN1=y
|
||||
CONFIG_KINETIS_GPIOIRQ=y
|
||||
CONFIG_KINETIS_I2C0=y
|
||||
CONFIG_KINETIS_I2C1=y
|
||||
CONFIG_KINETIS_LPTMR0=y
|
||||
CONFIG_KINETIS_LPUART0=y
|
||||
CONFIG_KINETIS_MERGE_TTY=y
|
||||
CONFIG_KINETIS_PDB=y
|
||||
CONFIG_KINETIS_PIT=y
|
||||
CONFIG_KINETIS_PORTAINTS=y
|
||||
CONFIG_KINETIS_PORTBINTS=y
|
||||
CONFIG_KINETIS_PORTCINTS=y
|
||||
CONFIG_KINETIS_PORTDINTS=y
|
||||
CONFIG_KINETIS_PORTEINTS=y
|
||||
CONFIG_KINETIS_RTC=y
|
||||
CONFIG_KINETIS_SDHC=y
|
||||
CONFIG_KINETIS_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_KINETIS_SPI0=y
|
||||
CONFIG_KINETIS_SPI1=y
|
||||
CONFIG_KINETIS_SPI2=y
|
||||
CONFIG_KINETIS_UART0=y
|
||||
CONFIG_KINETIS_UART0_RXDMA=y
|
||||
CONFIG_KINETIS_UART1=y
|
||||
CONFIG_KINETIS_UART1_RXDMA=y
|
||||
CONFIG_KINETIS_UART2=y
|
||||
CONFIG_KINETIS_UART2_RXDMA=y
|
||||
CONFIG_KINETIS_UART4=y
|
||||
CONFIG_KINETIS_UART4_RXDMA=y
|
||||
CONFIG_KINETIS_UARTFIFOS=y
|
||||
CONFIG_KINETIS_UART_BREAKS=y
|
||||
CONFIG_KINETIS_UART_EXTEDED_BREAK=y
|
||||
CONFIG_KINETIS_UART_INVERT=y
|
||||
CONFIG_KINETIS_USBDCD=y
|
||||
CONFIG_KINETS_LPUART_LOWEST=y
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_LPUART0_BAUD=57600
|
||||
CONFIG_LPUART0_SERIAL_CONSOLE=y
|
||||
CONFIG_MAX_WDOGPARMS=2
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_MULTIBLOCK_DISABLE=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NETDEV_IFINDEX=y
|
||||
CONFIG_NETDEV_LATEINIT=y
|
||||
CONFIG_NETUTILS_TELNETD=y
|
||||
CONFIG_NET_BROADCAST=y
|
||||
CONFIG_NET_CAN=y
|
||||
CONFIG_NET_CAN_NOTIFIER=y
|
||||
CONFIG_NET_CAN_RAW_TX_DEADLINE=y
|
||||
CONFIG_NET_CAN_SOCK_OPTS=y
|
||||
CONFIG_NET_ICMP=y
|
||||
CONFIG_NET_ICMP_SOCKET=y
|
||||
CONFIG_NET_TCP=y
|
||||
CONFIG_NET_TIMESTAMP=y
|
||||
CONFIG_NET_UDP=y
|
||||
CONFIG_NFILE_DESCRIPTORS=15
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_DISABLE_BASENAME=y
|
||||
CONFIG_NSH_DISABLE_DD=y
|
||||
CONFIG_NSH_DISABLE_DIRNAME=y
|
||||
CONFIG_NSH_DISABLE_EXPORT=y
|
||||
CONFIG_NSH_DISABLE_HEXDUMP=y
|
||||
CONFIG_NSH_DISABLE_LOSETUP=y
|
||||
CONFIG_NSH_DISABLE_MB=y
|
||||
CONFIG_NSH_DISABLE_MH=y
|
||||
CONFIG_NSH_DISABLE_MKFIFO=y
|
||||
CONFIG_NSH_DISABLE_MKRD=y
|
||||
CONFIG_NSH_DISABLE_PUT=y
|
||||
CONFIG_NSH_DISABLE_REBOOT=y
|
||||
CONFIG_NSH_DISABLE_TELNETD=y
|
||||
CONFIG_NSH_DISABLE_UNAME=y
|
||||
CONFIG_NSH_DISABLE_WGET=y
|
||||
CONFIG_NSH_DISABLE_XD=y
|
||||
CONFIG_NSH_FILEIOSIZE=512
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_READLINE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PREALLOC_WDOGS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAMTRON_WRITEWAIT=y
|
||||
CONFIG_RAM_SIZE=262144
|
||||
CONFIG_RAM_START=0x1fff0000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RTC=y
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_CUTERM=y
|
||||
CONFIG_SYSTEM_CUTERM_DEFAULT_BAUD=57600
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYSTEM_PING=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TIME_EXTENDED=y
|
||||
CONFIG_UART0_IFLOWCONTROL=y
|
||||
CONFIG_UART0_OFLOWCONTROL=y
|
||||
CONFIG_UART1_RXBUFSIZE=600
|
||||
CONFIG_UART1_TXBUFSIZE=1100
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_IFLOWCONTROL=y
|
||||
CONFIG_UART4_OFLOWCONTROL=y
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_TXBUFSIZE=1100
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_DUALSPEED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2944
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
||||
@@ -0,0 +1,118 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR nxp
|
||||
MODEL fmuk66-e
|
||||
LABEL socketcan
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
ROMFSROOT px4fmu_common
|
||||
TESTING
|
||||
UAVCAN_INTERFACES 2
|
||||
SERIAL_PORTS
|
||||
GPS1:/dev/ttyS3
|
||||
TEL1:/dev/ttyS4
|
||||
TEL2:/dev/ttyS1
|
||||
DRIVERS
|
||||
adc
|
||||
barometer # all available barometer drivers
|
||||
barometer/mpl3115a2
|
||||
batt_smbus
|
||||
camera_capture
|
||||
camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
gps
|
||||
#heater
|
||||
#imu # all available imu drivers
|
||||
imu/bosch/bmi088
|
||||
imu/invensense/icm42688p
|
||||
irlock
|
||||
lights/blinkm
|
||||
lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
lights/rgbled_pwm
|
||||
magnetometer # all available magnetometer drivers
|
||||
mkblctrl
|
||||
#optical_flow # all available optical flow drivers
|
||||
optical_flow/px4flow
|
||||
#osd
|
||||
pca9685
|
||||
power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
rc_input
|
||||
roboclaw
|
||||
safety_button
|
||||
tap_esc
|
||||
telemetry # all available telemetry drivers
|
||||
#test_ppm # NOT Portable YET
|
||||
tone_alarm
|
||||
#uavcannode_v1
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
battery_status
|
||||
camera_feedback
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
events
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
#hardfault_log # Needs bbsrm
|
||||
i2cdetect
|
||||
led_control
|
||||
mixer
|
||||
motor_ramp
|
||||
motor_test
|
||||
mtd
|
||||
nshterm
|
||||
param
|
||||
perf
|
||||
pwm
|
||||
reboot
|
||||
reflect
|
||||
sd_bench
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
usb_connected
|
||||
ver
|
||||
work_queue
|
||||
EXAMPLES
|
||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||
hello
|
||||
hwtest # Hardware test
|
||||
#matlab_csv_serial
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
uuv_example_app
|
||||
work_item
|
||||
)
|
||||
@@ -0,0 +1,53 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2016, 2018 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_library(drivers_board
|
||||
autoleds.c
|
||||
automount.c
|
||||
can.c
|
||||
i2c.cpp
|
||||
init.c
|
||||
led.c
|
||||
sdhc.c
|
||||
spi.cpp
|
||||
timer_config.cpp
|
||||
usb.c
|
||||
)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
nuttx_arch # sdio
|
||||
nuttx_drivers # sdio
|
||||
drivers__led # drv_led_start
|
||||
px4_layer
|
||||
)
|
||||
@@ -0,0 +1,164 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
/*
|
||||
* This module shall be used during board bring up of Nuttx.
|
||||
*
|
||||
* The NXP FMUK66-E has a separate Red, Green and Blue LEDs driven by the K66
|
||||
* as follows:
|
||||
*
|
||||
* LED K66
|
||||
* ------ -------------------------------------------------------
|
||||
* RED FB_CS0_b/ UART2_CTS_b / ADC0_SE5b / SPI0_SCK / FTM3_CH1/ PTD1
|
||||
* GREEN FTM2_FLT0/ CMP0_IN3/ FB_AD6 / I2S0_RX_BCLK/ FTM3_CH5/ ADC1_SE5b/ PTC9
|
||||
* BLUE CMP0_IN2/ FB_AD7 / I2S0_MCLK/ FTM3_CH4/ ADC1_SE4b/ PTC8
|
||||
*
|
||||
* If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board
|
||||
* the NXP fmuk66-e. The following definitions describe how NuttX controls
|
||||
* the LEDs:
|
||||
*
|
||||
* SYMBOL Meaning LED state
|
||||
* RED GREEN BLUE
|
||||
* ------------------- ----------------------- -----------------
|
||||
* LED_STARTED NuttX has been started OFF OFF OFF
|
||||
* LED_HEAPALLOCATE Heap has been allocated OFF OFF ON
|
||||
* LED_IRQSENABLED Interrupts enabled OFF OFF ON
|
||||
* LED_STACKCREATED Idle stack created OFF ON OFF
|
||||
* LED_INIRQ In an interrupt (no change)
|
||||
* LED_SIGNAL In a signal handler (no change)
|
||||
* LED_ASSERTION An assertion failed (no change)
|
||||
* LED_PANIC The system has crashed FLASH OFF OFF
|
||||
* LED_IDLE K66 is in sleep mode (Optional, not used)
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "kinetis.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Summary of all possible settings */
|
||||
|
||||
#define LED_NOCHANGE 0 /* LED_IRQSENABLED, LED_INIRQ, LED_SIGNAL, LED_ASSERTION */
|
||||
#define LED_OFF_OFF_OFF 1 /* LED_STARTED */
|
||||
#define LED_OFF_OFF_ON 2 /* LED_HEAPALLOCATE */
|
||||
#define LED_OFF_ON_OFF 3 /* LED_STACKCREATED */
|
||||
#define LED_ON_OFF_OFF 4 /* LED_PANIC */
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_initialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize the on-board LED
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_initialize(void)
|
||||
{
|
||||
kinetis_pinconfig(GPIO_LED_R);
|
||||
kinetis_pinconfig(GPIO_LED_G);
|
||||
kinetis_pinconfig(GPIO_LED_B);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_on
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_on(int led)
|
||||
{
|
||||
if (led != LED_NOCHANGE) {
|
||||
bool redoff = true;
|
||||
bool greenoff = true;
|
||||
bool blueoff = true;
|
||||
|
||||
switch (led) {
|
||||
default:
|
||||
case LED_OFF_OFF_OFF:
|
||||
break;
|
||||
|
||||
case LED_OFF_OFF_ON:
|
||||
blueoff = false;
|
||||
break;
|
||||
|
||||
case LED_OFF_ON_OFF:
|
||||
greenoff = false;
|
||||
break;
|
||||
|
||||
case LED_ON_OFF_OFF:
|
||||
redoff = false;
|
||||
break;
|
||||
}
|
||||
|
||||
kinetis_gpiowrite(GPIO_LED_R, redoff);
|
||||
kinetis_gpiowrite(GPIO_LED_G, greenoff);
|
||||
kinetis_gpiowrite(GPIO_LED_B, blueoff);
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_off
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_off(int led)
|
||||
{
|
||||
if (led == LED_ON_OFF_OFF) {
|
||||
kinetis_gpiowrite(GPIO_LED_R, true);
|
||||
kinetis_gpiowrite(GPIO_LED_G, true);
|
||||
kinetis_gpiowrite(GPIO_LED_B, true);
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* CONFIG_ARCH_LEDS */
|
||||
@@ -0,0 +1,304 @@
|
||||
/************************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#if defined(CONFIG_FS_AUTOMOUNTER_DEBUG) && !defined(CONFIG_DEBUG_FS)
|
||||
# define CONFIG_DEBUG_FS 1
|
||||
#endif
|
||||
|
||||
#include <debug.h>
|
||||
#include <stddef.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/clock.h>
|
||||
#include <nuttx/fs/automount.h>
|
||||
|
||||
#include "board_config.h"
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Types
|
||||
************************************************************************************/
|
||||
/* This structure represents the changeable state of the automounter */
|
||||
|
||||
struct fmuk66_automount_state_s {
|
||||
volatile automount_handler_t handler; /* Upper half handler */
|
||||
FAR void *arg; /* Handler argument */
|
||||
bool enable; /* Fake interrupt enable */
|
||||
bool pending; /* Set if there an event while disabled */
|
||||
};
|
||||
|
||||
/* This structure represents the static configuration of an automounter */
|
||||
|
||||
struct fmuk66_automount_config_s {
|
||||
/* This must be first thing in structure so that we can simply cast from struct
|
||||
* automount_lower_s to struct fmuk66_automount_config_s
|
||||
*/
|
||||
|
||||
struct automount_lower_s lower; /* Publicly visible part */
|
||||
FAR struct fmuk66_automount_state_s *state; /* Changeable state */
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
* Private Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
static int fmuk66_attach(FAR const struct automount_lower_s *lower, automount_handler_t isr, FAR void *arg);
|
||||
static void fmuk66_enable(FAR const struct automount_lower_s *lower, bool enable);
|
||||
static bool fmuk66_inserted(FAR const struct automount_lower_s *lower);
|
||||
|
||||
/************************************************************************************
|
||||
* Private Data
|
||||
************************************************************************************/
|
||||
|
||||
static struct fmuk66_automount_state_s g_sdhc_state;
|
||||
static const struct fmuk66_automount_config_s g_sdhc_config = {
|
||||
.lower =
|
||||
{
|
||||
.fstype = CONFIG_FMUK66_SDHC_AUTOMOUNT_FSTYPE,
|
||||
.blockdev = CONFIG_FMUK66_SDHC_AUTOMOUNT_BLKDEV,
|
||||
.mountpoint = CONFIG_FMUK66_SDHC_AUTOMOUNT_MOUNTPOINT,
|
||||
.ddelay = MSEC2TICK(CONFIG_FMUK66_SDHC_AUTOMOUNT_DDELAY),
|
||||
.udelay = MSEC2TICK(CONFIG_FMUK66_SDHC_AUTOMOUNT_UDELAY),
|
||||
.attach = fmuk66_attach,
|
||||
.enable = fmuk66_enable,
|
||||
.inserted = fmuk66_inserted
|
||||
},
|
||||
.state = &g_sdhc_state
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: fmuk66_attach
|
||||
*
|
||||
* Description:
|
||||
* Attach a new SDHC event handler
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - An instance of the auto-mounter lower half state structure
|
||||
* isr - The new event handler to be attach
|
||||
* arg - Client data to be provided when the event handler is invoked.
|
||||
*
|
||||
* Returned Value:
|
||||
* Always returns OK
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static int fmuk66_attach(FAR const struct automount_lower_s *lower, automount_handler_t isr, FAR void *arg)
|
||||
{
|
||||
FAR const struct fmuk66_automount_config_s *config;
|
||||
FAR struct fmuk66_automount_state_s *state;
|
||||
|
||||
/* Recover references to our structure */
|
||||
|
||||
config = (FAR struct fmuk66_automount_config_s *)lower;
|
||||
DEBUGASSERT(config != NULL && config->state != NULL);
|
||||
|
||||
state = config->state;
|
||||
|
||||
/* Save the new handler info (clearing the handler first to eliminate race
|
||||
* conditions).
|
||||
*/
|
||||
|
||||
state->handler = NULL;
|
||||
state->pending = false;
|
||||
state->arg = arg;
|
||||
state->handler = isr;
|
||||
return OK;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: fmuk66_enable
|
||||
*
|
||||
* Description:
|
||||
* Enable card insertion/removal event detection
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - An instance of the auto-mounter lower half state structure
|
||||
* enable - True: enable event detection; False: disable
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void fmuk66_enable(FAR const struct automount_lower_s *lower, bool enable)
|
||||
{
|
||||
FAR const struct fmuk66_automount_config_s *config;
|
||||
FAR struct fmuk66_automount_state_s *state;
|
||||
irqstate_t flags;
|
||||
|
||||
/* Recover references to our structure */
|
||||
|
||||
config = (FAR struct fmuk66_automount_config_s *)lower;
|
||||
DEBUGASSERT(config != NULL && config->state != NULL);
|
||||
|
||||
state = config->state;
|
||||
|
||||
/* Save the fake enable setting */
|
||||
|
||||
flags = enter_critical_section();
|
||||
state->enable = enable;
|
||||
|
||||
/* Did an interrupt occur while interrupts were disabled? */
|
||||
|
||||
if (enable && state->pending) {
|
||||
/* Yes.. perform the fake interrupt if the interrutp is attached */
|
||||
|
||||
if (state->handler) {
|
||||
bool inserted = fmuk66_cardinserted();
|
||||
(void)state->handler(&config->lower, state->arg, inserted);
|
||||
}
|
||||
|
||||
state->pending = false;
|
||||
}
|
||||
|
||||
leave_critical_section(flags);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: fmuk66_inserted
|
||||
*
|
||||
* Description:
|
||||
* Check if a card is inserted into the slot.
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - An instance of the auto-mounter lower half state structure
|
||||
*
|
||||
* Returned Value:
|
||||
* True if the card is inserted; False otherwise
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static bool fmuk66_inserted(FAR const struct automount_lower_s *lower)
|
||||
{
|
||||
return fmuk66_cardinserted();
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: fmuk66_automount_initialize
|
||||
*
|
||||
* Description:
|
||||
* Configure auto-mounters for each enable and so configured SDHC
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void fmuk66_automount_initialize(void)
|
||||
{
|
||||
FAR void *handle;
|
||||
|
||||
finfo("Initializing automounter(s)\n");
|
||||
|
||||
/* Initialize the SDHC0 auto-mounter */
|
||||
|
||||
handle = automount_initialize(&g_sdhc_config.lower);
|
||||
|
||||
if (!handle) {
|
||||
ferr("ERROR: Failed to initialize auto-mounter for SDHC0\n");
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: fmuk66_automount_event
|
||||
*
|
||||
* Description:
|
||||
* The SDHC card detection logic has detected an insertion or removal event. It
|
||||
* has already scheduled the MMC/SD block driver operations. Now we need to
|
||||
* schedule the auto-mount event which will occur with a substantial delay to make
|
||||
* sure that everything has settle down.
|
||||
*
|
||||
* Input Parameters:
|
||||
* slotno - Identifies the SDHC0 slot: SDHC0_SLOTNO or SDHC1_SLOTNO. There is a
|
||||
* terminology problem here: Each SDHC supports two slots, slot A and slot B.
|
||||
* Only slot A is used. So this is not a really a slot, but an HSCMI peripheral
|
||||
* number.
|
||||
* inserted - True if the card is inserted in the slot. False otherwise.
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
* Assumptions:
|
||||
* Interrupts are disabled.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void fmuk66_automount_event(bool inserted)
|
||||
{
|
||||
FAR const struct fmuk66_automount_config_s *config = &g_sdhc_config;
|
||||
FAR struct fmuk66_automount_state_s *state = &g_sdhc_state;
|
||||
|
||||
/* Is the auto-mounter interrupt attached? */
|
||||
|
||||
if (state->handler) {
|
||||
/* Yes.. Have we been asked to hold off interrupts? */
|
||||
|
||||
if (!state->enable) {
|
||||
/* Yes.. just remember the there is a pending interrupt. We will
|
||||
* deliver the interrupt when interrupts are "re-enabled."
|
||||
*/
|
||||
|
||||
state->pending = true;
|
||||
|
||||
} else {
|
||||
/* No.. forward the event to the handler */
|
||||
|
||||
(void)state->handler(&config->lower, state->arg, inserted);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* HAVE_AUTOMOUNTER */
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,129 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016, 2018 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file can.c
|
||||
*
|
||||
* Board-specific CAN functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/can/can.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <chip.h>
|
||||
#include <kinetis.h>
|
||||
#include "up_arch.h"
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#ifdef CONFIG_CAN
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration ********************************************************************/
|
||||
|
||||
#if defined(KINETIS_FLEXCAN0) && defined(KINETIS_FLEXCAN1)
|
||||
# warning "Both CAN0 and CAN1 are enabled. Assuming only CAN0."
|
||||
# undef KINETIS_FLEXCAN0
|
||||
#endif
|
||||
|
||||
#ifdef KINETIS_FLEXCAN0
|
||||
# define CAN_PORT 1
|
||||
#else
|
||||
# define CAN_PORT 2
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
int can_devinit(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: can_devinit
|
||||
*
|
||||
* Description:
|
||||
* All architectures must provide the following interface to work with
|
||||
* examples/can.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int can_devinit(void)
|
||||
{
|
||||
static bool initialized = false;
|
||||
struct can_dev_s *can;
|
||||
int ret;
|
||||
|
||||
/* Check if we have already initialized */
|
||||
|
||||
if (!initialized) {
|
||||
/* Call kinetis_caninitialize() to get an instance of the CAN interface */
|
||||
|
||||
can = kinetis_caninitialize(CAN_PORT);
|
||||
|
||||
if (can == NULL) {
|
||||
canerr("ERROR: Failed to get CAN interface\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Register the CAN driver at "/dev/can0" */
|
||||
|
||||
ret = can_register("/dev/can0", can);
|
||||
|
||||
if (ret < 0) {
|
||||
canerr("ERROR: can_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif
|
||||
@@ -0,0 +1,39 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/i2c_hw_description.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusInternal(PX4_BUS_NUMBER_TO_PX4(1)),
|
||||
initI2CBusExternal(PX4_BUS_NUMBER_TO_PX4(0)),
|
||||
};
|
||||
@@ -0,0 +1,307 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016, 2018 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file init.c
|
||||
*
|
||||
* NXP fmuk66-e specific early startup code. This file implements the
|
||||
* board_app_initialize() function that is called early by nsh during startup.
|
||||
*
|
||||
* Code here is run before the rcS script is invoked; it should start required
|
||||
* subsystems and perform board-specific initialization.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform/gpio.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.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 <kinetis.h>
|
||||
#include <kinetis_uart.h>
|
||||
#include <hardware/kinetis_uart.h>
|
||||
#include <hardware/kinetis_sim.h>
|
||||
#include "board_config.h"
|
||||
|
||||
#include "up_arch.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_platform_common/init.h>
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
__END_DECLS
|
||||
|
||||
/****************************************************************************
|
||||
* Protected Functions
|
||||
****************************************************************************/
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
/************************************************************************************
|
||||
* Name: board_on_reset
|
||||
*
|
||||
* Description:
|
||||
* Optionally provided function called on entry to board_system_reset
|
||||
* It should perform any house keeping prior to the rest.
|
||||
*
|
||||
* status - 1 if resetting to boot loader
|
||||
* 0 if just resetting
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void board_on_reset(int status)
|
||||
{
|
||||
for (int i = 0; i < 6; ++i) {
|
||||
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i)));
|
||||
}
|
||||
|
||||
px4_arch_configgpio(io_timer_channel_get_gpio_output(6)); // Echo trigger pin
|
||||
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(7)));
|
||||
|
||||
if (status >= 0) {
|
||||
up_mdelay(6);
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_read_VBUS_state
|
||||
*
|
||||
* Description:
|
||||
* All boards must provide a way to read the state of VBUS, this my be simple
|
||||
* digital input on a GPIO. Or something more complicated like a Analong input
|
||||
* or reading a bit from a USB controller register.
|
||||
*
|
||||
* Returns - 0 if connected.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int board_read_VBUS_state(void)
|
||||
{
|
||||
return BOARD_ADC_USB_CONNECTED ? 0 : 1;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_peripheral_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_peripheral_reset(int ms)
|
||||
{
|
||||
/* set the peripheral rails off */
|
||||
|
||||
/* wait for the peripheral rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||
|
||||
/* re-enable power */
|
||||
|
||||
/* switch the peripheral rail back on */
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: kinetis_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All Kinetis architectures must provide the following entry point. This entry point
|
||||
* is called early in the intitialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void
|
||||
kinetis_boardinitialize(void)
|
||||
{
|
||||
board_on_reset(-1); /* Reset PWM first thing */
|
||||
|
||||
/* configure LEDs */
|
||||
board_autoled_initialize();
|
||||
|
||||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
|
||||
px4_gpio_init(gpio, arraySize(gpio));
|
||||
|
||||
fmuk66_timer_initialize();
|
||||
|
||||
/* Power on Spektrum */
|
||||
|
||||
VDD_3V3_SPEKTRUM_POWER_EN(true);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_app_initialize
|
||||
*
|
||||
* Description:
|
||||
* Perform application specific initialization. This function is never
|
||||
* called directly from application code, but only indirectly via the
|
||||
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
|
||||
*
|
||||
* Input Parameters:
|
||||
* arg - The boardctl() argument is passed to the board_app_initialize()
|
||||
* implementation without modification. The argument has no
|
||||
* meaning to NuttX; the meaning of the argument is a contract
|
||||
* between the board-specific initalization logic and the the
|
||||
* matching application logic. The value cold be such things as a
|
||||
* mode enumeration value, a set of DIP switch switch settings, a
|
||||
* pointer to configuration data read from a file or serial FLASH,
|
||||
* or whatever you would like to do with it. Every implementation
|
||||
* should accept zero/NULL as a default configuration.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||
* any failure to indicate the nature of the failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
|
||||
VDD_3V3_SD_CARD_EN(true);
|
||||
VDD_3V3_SENSORS_EN(true);
|
||||
|
||||
/* configure SPI interfaces */
|
||||
|
||||
fmuk66_spidev_initialize();
|
||||
|
||||
VDD_ETH_EN(true);
|
||||
|
||||
px4_platform_init();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
syslog(LOG_ERR, "DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
/* set up the serial DMA polling */
|
||||
#ifdef SERIAL_HAVE_DMA
|
||||
static struct hrt_call serial_dma_call;
|
||||
struct timespec ts;
|
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered
|
||||
* a DMA event.
|
||||
*/
|
||||
ts.tv_sec = 0;
|
||||
ts.tv_nsec = 1000000;
|
||||
|
||||
hrt_call_every(&serial_dma_call,
|
||||
ts_to_abstime(&ts),
|
||||
ts_to_abstime(&ts),
|
||||
(hrt_callout)kinetis_serial_dma_poll,
|
||||
NULL);
|
||||
#endif
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_RED);
|
||||
led_off(LED_GREEN);
|
||||
led_off(LED_BLUE);
|
||||
|
||||
int ret = fmuk66_sdhc_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
board_autoled_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
/* Initialize the auto-mounter */
|
||||
|
||||
fmuk66_automount_initialize();
|
||||
#endif
|
||||
|
||||
/* Configure SPI-based devices */
|
||||
|
||||
#ifdef CONFIG_SPI
|
||||
ret = fmuk66_spi_bus_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
board_autoled_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_NETDEV_LATEINIT
|
||||
|
||||
# ifdef CONFIG_KINETIS_ENET
|
||||
kinetis_netinitialize(0);
|
||||
# endif
|
||||
|
||||
# ifdef CONFIG_KINETIS_FLEXCAN0
|
||||
kinetis_caninitialize(0);
|
||||
# endif
|
||||
|
||||
# ifdef CONFIG_KINETIS_FLEXCAN1
|
||||
kinetis_caninitialize(1);
|
||||
# endif
|
||||
|
||||
#endif
|
||||
|
||||
return OK;
|
||||
}
|
||||
@@ -0,0 +1,115 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016, 2018 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file led.c
|
||||
*
|
||||
* NXP fmuk66-e LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "kinetis.h"
|
||||
#include "chip.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
|
||||
static uint32_t g_ledmap[] = {
|
||||
0, // Indexed by LED_BLUE
|
||||
GPIO_LED_1, // Indexed by LED_RED, LED_AMBER
|
||||
GPIO_LED_SAFETY, // Indexed by LED_SAFETY
|
||||
GPIO_LED_2, // Indexed by LED_GREEN
|
||||
};
|
||||
|
||||
__EXPORT void led_init(void)
|
||||
{
|
||||
/* Configure LED GPIOs for output */
|
||||
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
|
||||
if (g_ledmap[l] != 0) {
|
||||
kinetis_pinconfig(g_ledmap[l]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void phy_set_led(int led, bool state)
|
||||
{
|
||||
/* Drive High to switch on */
|
||||
|
||||
if (g_ledmap[led] != 0) {
|
||||
kinetis_gpiowrite(g_ledmap[led], state);
|
||||
}
|
||||
}
|
||||
|
||||
static bool phy_get_led(int led)
|
||||
{
|
||||
|
||||
if (g_ledmap[led] != 0) {
|
||||
return kinetis_gpioread(g_ledmap[led]);
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
phy_set_led(led, true);
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
phy_set_led(led, false);
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
|
||||
phy_set_led(led, !phy_get_led(led));
|
||||
}
|
||||
@@ -0,0 +1,270 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 (SDHC) signals of the MCU. This slot will accept micro
|
||||
* format SD memory cards. The SD card detect pin (PTE6) is an open switch that
|
||||
* shorts with VDD when card is inserted.
|
||||
*
|
||||
* ------------ ------------- --------
|
||||
* SD Card Slot Board Signal K66 Pin
|
||||
* ------------ ------------- --------
|
||||
* DAT0 SDHC0_D0 PTE1
|
||||
* DAT1 SDHC0_D1 PTE0
|
||||
* DAT2 SDHC0_D2 PTE5
|
||||
* CD/DAT3 SDHC0_D3 PTE4
|
||||
* CMD SDHC0_CMD PTE3
|
||||
* CLK SDHC0_DCLK PTE2
|
||||
* SWITCH D_CARD_DETECT PTE6
|
||||
* ------------ ------------- --------
|
||||
*
|
||||
* There is no Write Protect pin available to the K66.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.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 "kinetis.h"
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#ifdef CONFIG_KINETIS_SDHC
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
/* This structure holds static information unique to one SDHC peripheral */
|
||||
|
||||
struct fmuk66_sdhc_state_s {
|
||||
struct sdio_dev_s *sdhc; /* R/W device handle */
|
||||
bool inserted; /* TRUE: card is inserted */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/* HSCMI device state */
|
||||
|
||||
static struct fmuk66_sdhc_state_s g_sdhc;
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
#if defined(GPIO_SD_CARDDETECT)
|
||||
/****************************************************************************
|
||||
* Name: fmuk66_mediachange
|
||||
****************************************************************************/
|
||||
|
||||
static void fmuk66_mediachange(struct fmuk66_sdhc_state_s *sdhc)
|
||||
{
|
||||
bool inserted;
|
||||
|
||||
/* Get the current value of the card detect pin. This pin is pulled up on
|
||||
* board. So low means that a card is present.
|
||||
*/
|
||||
|
||||
inserted = !kinetis_gpioread(GPIO_SD_CARDDETECT);
|
||||
mcinfo("inserted: %s\n", inserted ? "Yes" : "No");
|
||||
|
||||
/* Has the pin changed state? */
|
||||
|
||||
if (inserted != sdhc->inserted) {
|
||||
mcinfo("Media change: %d->%d\n", sdhc->inserted, inserted);
|
||||
|
||||
/* Yes.. perform the appropriate action (this might need some debounce). */
|
||||
|
||||
sdhc->inserted = inserted;
|
||||
sdhc_mediachange(sdhc->sdhc, inserted);
|
||||
|
||||
#ifdef CONFIG_FMUK66_SDHC_AUTOMOUNT
|
||||
/* Let the automounter know about the insertion event */
|
||||
|
||||
fmuk66_automount_event(fmuk66_cardinserted());
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: fmuk66_cdinterrupt
|
||||
****************************************************************************/
|
||||
|
||||
static int fmuk66_cdinterrupt(int irq, FAR void *context, FAR void *args)
|
||||
{
|
||||
/* All of the work is done by fmuk66_mediachange() */
|
||||
|
||||
fmuk66_mediachange((struct fmuk66_sdhc_state_s *) args);
|
||||
return OK;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: fmuk66_sdhc_initialize
|
||||
*
|
||||
* Description:
|
||||
* Inititialize the SDHC SD card slot
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int fmuk66_sdhc_initialize(void)
|
||||
{
|
||||
int ret;
|
||||
struct fmuk66_sdhc_state_s *sdhc = &g_sdhc;
|
||||
/* Configure GPIO pins */
|
||||
|
||||
VDD_3V3_SD_CARD_EN(true);
|
||||
|
||||
#if defined(GPIO_SD_CARDDETECT)
|
||||
kinetis_pinconfig(GPIO_SD_CARDDETECT);
|
||||
|
||||
/* Attached the card detect interrupt (but don't enable it yet) */
|
||||
|
||||
kinetis_pinirqattach(GPIO_SD_CARDDETECT, fmuk66_cdinterrupt, sdhc);
|
||||
#endif
|
||||
/* Configure the write protect GPIO -- None */
|
||||
|
||||
/* Mount the SDHC-based MMC/SD block driver */
|
||||
/* First, get an instance of the SDHC interface */
|
||||
|
||||
mcinfo("Initializing SDHC slot %d\n", CONFIG_NSH_MMCSDSLOTNO);
|
||||
|
||||
sdhc->sdhc = sdhc_initialize(CONFIG_NSH_MMCSDSLOTNO);
|
||||
|
||||
if (!sdhc->sdhc) {
|
||||
mcerr("ERROR: Failed to initialize SDHC slot %d\n", CONFIG_NSH_MMCSDSLOTNO);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
// Testing done on SanDISK HC all failed sd_bench with Drive/Slew other than default and _PIN_OUTPUT_FAST|_PIN_OUTPUT_HIGHDRIVE
|
||||
// _PIN_OUTPUT_FAST|_PIN_OUTPUT_HIGHDRIVE Square noisy, pass SanDISK HC
|
||||
// _PIN_OUTPUT_FAST|_PIN_OUTPUT_LOWDRIVE Square noisy, pass SanDISK HC
|
||||
// _PIN_OUTPUT_HIGHDRIVE|_PIN_OUTPUT_SLOW sinusoidal fail SanDISK HC pass SanDISK HC1
|
||||
// _PIN_OUTPUT_LOWDRIVE|_PIN_OUTPUT_SLOW sinusoidal fail SanDISK HC pass SanDISK HC1
|
||||
// _PIN_OUTPUT_SLOW sinusoidal fail SanDISK HC pass SanDISK HC1
|
||||
|
||||
// This up dating of the driver setting is for EMI issue with GPS and FCC
|
||||
// With this setting the clock is sinusoidal N.B. sd_bench fails on SanDISK HC, but
|
||||
// Passes SanDISK **HC1** - use HC1 or Kingston cards!
|
||||
|
||||
kinetis_pinconfig(PIN_SDHC0_DCLK | _PIN_OUTPUT_HIGHDRIVE | _PIN_OUTPUT_SLOW);
|
||||
|
||||
/* Now bind the SDHC interface to the MMC/SD driver */
|
||||
|
||||
mcinfo("Bind SDHC to the MMC/SD driver, minor=%d\n", CONFIG_NSH_MMCSDMINOR);
|
||||
|
||||
ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdhc->sdhc);
|
||||
|
||||
if (ret != OK) {
|
||||
syslog(LOG_ERR, "ERROR: Failed to bind SDHC to the MMC/SD driver: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
syslog(LOG_ERR, "Successfully bound SDHC to the MMC/SD driver\n");
|
||||
|
||||
#if defined(GPIO_SD_CARDDETECT)
|
||||
/* Handle the initial card state */
|
||||
|
||||
fmuk66_mediachange(sdhc);
|
||||
|
||||
/* Enable CD interrupts to handle subsequent media changes */
|
||||
|
||||
kinetis_pinirqenable(GPIO_SD_CARDDETECT);
|
||||
#else
|
||||
sdhc_mediachange(sdhc->sdhc, true);
|
||||
#endif
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: fmuk66_cardinserted
|
||||
*
|
||||
* Description:
|
||||
* Check if a card is inserted into the SDHC slot
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
bool fmuk66_cardinserted(void)
|
||||
{
|
||||
bool inserted;
|
||||
|
||||
/* Get the current value of the card detect pin. This pin is pulled up on
|
||||
* board. So low means that a card is present.
|
||||
*/
|
||||
|
||||
inserted = !kinetis_gpioread(GPIO_SD_CARDDETECT);
|
||||
mcinfo("inserted: %s\n", inserted ? "Yes" : "No");
|
||||
return inserted;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: fmuk66_writeprotected
|
||||
*
|
||||
* Description:
|
||||
* Check if a card is inserted into the SDHC slot
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
bool fmuk66_writeprotected(void)
|
||||
{
|
||||
/* There are no write protect pins */
|
||||
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* HAVE_MMCSD */
|
||||
@@ -0,0 +1,313 @@
|
||||
/************************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#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 <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
//#include <unistd.h>
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "chip.h"
|
||||
#include <kinetis.h>
|
||||
#include "board_config.h"
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
#if defined(CONFIG_KINETIS_SPI0) || defined(CONFIG_KINETIS_SPI1) || defined(CONFIG_KINETIS_SPI2)
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI0, {
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortC, GPIO::Pin2})
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortB, GPIO::Pin10}, SPI::DRDY{GPIO::PortE, GPIO::Pin9}),
|
||||
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortB, GPIO::Pin9}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}),
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortE, GPIO::Pin6}),
|
||||
initSPIDevice(DRV_DEVTYPE_UNUSED, SPI::CS{GPIO::PortA, GPIO::Pin19}), // CAL Memory
|
||||
}, {GPIO::PortB, GPIO::Pin8}),
|
||||
initSPIBusExternal(SPI::Bus::SPI2, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortB, GPIO::Pin20}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortD, GPIO::Pin15}),
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
||||
|
||||
|
||||
#define PX4_MK_GPIO(pin_ftmx, io) ((((uint32_t)(pin_ftmx)) & ~(_PIN_MODE_MASK | _PIN_OPTIONS_MASK)) |(io))
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void board_spi_reset(int ms, int bus_mask)
|
||||
{
|
||||
/* Goal not to back feed the chips on the bus via IO lines */
|
||||
|
||||
/* Next Change CS to inputs with pull downs */
|
||||
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||
if (px4_spi_buses[bus].bus == PX4_BUS_NUMBER_TO_PX4(1)) {
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||
kinetis_pinconfig(PX4_MK_GPIO(px4_spi_buses[bus].devices[i].cs_gpio, GPIO_PULLDOWN));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Turn all the int inputs to inputs with pull down */
|
||||
|
||||
kinetis_pinconfig(PX4_MK_GPIO(GPIO_nSPI1_DRDY1_BMI1088_ACCEL_INT1, GPIO_PULLDOWN));
|
||||
kinetis_pinconfig(PX4_MK_GPIO(GPIO_nSPI1_DRDY2_BMI1088_GYRO_INT2, GPIO_PULLDOWN));
|
||||
kinetis_pinconfig(PX4_MK_GPIO(GPIO_nSPI1_DRDY3_ICM42688_INT1, GPIO_PULLDOWN));
|
||||
|
||||
/* Power Down The Sensors */
|
||||
|
||||
VDD_3V3_SENSORS_EN(false);
|
||||
up_mdelay(ms);
|
||||
|
||||
/* Power Up The Sensors */
|
||||
VDD_3V3_SENSORS_EN(true);
|
||||
up_mdelay(2);
|
||||
|
||||
/* Restore all the CS to ouputs inactive */
|
||||
|
||||
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||
if (px4_spi_buses[bus].bus == PX4_BUS_NUMBER_TO_PX4(1)) {
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||
kinetis_pinconfig(px4_spi_buses[bus].devices[i].cs_gpio);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Restore all the int inputs to inputs */
|
||||
|
||||
kinetis_pinconfig(GPIO_nSPI1_DRDY1_BMI1088_ACCEL_INT1);
|
||||
kinetis_pinconfig(GPIO_nSPI1_DRDY2_BMI1088_GYRO_INT2);
|
||||
kinetis_pinconfig(GPIO_nSPI1_DRDY3_ICM42688_INT1);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: fmuk66_spidev_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the NXP FMUK66-E board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void fmuk66_spidev_initialize(void)
|
||||
{
|
||||
board_spi_reset(10, 0xffff);
|
||||
|
||||
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||
kinetis_pinconfig(px4_spi_buses[bus].devices[i].cs_gpio);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: kinetis_spi_bus_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the NXP FMUK66 v3 board.
|
||||
*
|
||||
************************************************************************************/
|
||||
static const px4_spi_bus_t *_spi_bus0;
|
||||
static const px4_spi_bus_t *_spi_bus1;
|
||||
static const px4_spi_bus_t *_spi_bus2;
|
||||
|
||||
__EXPORT int fmuk66_spi_bus_initialize(void)
|
||||
{
|
||||
for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) {
|
||||
switch (px4_spi_buses[i].bus) {
|
||||
case PX4_BUS_NUMBER_TO_PX4(0): _spi_bus0 = &px4_spi_buses[i]; break;
|
||||
|
||||
case PX4_BUS_NUMBER_TO_PX4(1): _spi_bus1 = &px4_spi_buses[i]; break;
|
||||
|
||||
case PX4_BUS_NUMBER_TO_PX4(2): _spi_bus2 = &px4_spi_buses[i]; break;
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure SPI-based devices */
|
||||
|
||||
struct spi_dev_s *spi_sensors = px4_spibus_initialize(PX4_BUS_NUMBER_TO_PX4(1));
|
||||
|
||||
if (!spi_sensors) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 1);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default bus 1 to 1MHz and de-assert the known chip selects.
|
||||
*/
|
||||
|
||||
SPI_SETFREQUENCY(spi_sensors, 1 * 1000 * 1000);
|
||||
SPI_SETBITS(spi_sensors, 8);
|
||||
SPI_SETMODE(spi_sensors, SPIDEV_MODE0);
|
||||
|
||||
/* Get the SPI port for the Memory */
|
||||
|
||||
struct spi_dev_s *spi_memory = px4_spibus_initialize(PX4_BUS_NUMBER_TO_PX4(0));
|
||||
|
||||
if (!spi_memory) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 0);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default bus 0 to 12MHz and de-assert the known chip selects.
|
||||
*/
|
||||
|
||||
SPI_SETFREQUENCY(spi_memory, 12 * 1000 * 1000);
|
||||
SPI_SETBITS(spi_memory, 8);
|
||||
SPI_SETMODE(spi_memory, SPIDEV_MODE3);
|
||||
|
||||
/* Configure EXTERNAL SPI-based devices */
|
||||
|
||||
struct spi_dev_s *spi_ext = px4_spibus_initialize(PX4_BUS_NUMBER_TO_PX4(2));
|
||||
|
||||
if (!spi_ext) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 2);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default external bus to 1MHz and de-assert the known chip selects.
|
||||
*/
|
||||
|
||||
SPI_SETFREQUENCY(spi_ext, 8 * 1000 * 1000);
|
||||
SPI_SETBITS(spi_ext, 8);
|
||||
SPI_SETMODE(spi_ext, SPIDEV_MODE3);
|
||||
|
||||
/* deselect all */
|
||||
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||
SPI_SELECT(spi_ext, px4_spi_buses[bus].devices[i].devid, false);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return OK;
|
||||
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: kinetis_spi[n]select, kinetis_spi[n]status, and kinetis_spi[n]cmddata
|
||||
*
|
||||
* Description:
|
||||
* These external functions must be provided by board-specific logic. They are
|
||||
* implementations of the select, status, and cmddata methods of the SPI interface
|
||||
* defined by struct spi_ops_s (see include/nuttx/spi/spi.h). All other methods
|
||||
* including kinetis_spibus_initialize()) are provided by common Kinetis logic.
|
||||
* To use this common SPI logic on your board:
|
||||
*
|
||||
* 1. Provide logic in kinetis_boardinitialize() to configure SPI chip select
|
||||
* pins.
|
||||
* 2. Provide kinetis_spi[n]select() and kinetis_spi[n]status() functions
|
||||
* in your board-specific logic. These functions will perform chip selection
|
||||
* and status operations using GPIOs in the way your board is configured.
|
||||
* 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
|
||||
* kinetis_spi[n]cmddata() functions in your board-specific logic. These
|
||||
* functions will perform cmd/data selection operations using GPIOs in the way
|
||||
* your board is configured.
|
||||
* 3. Add a call to kinetis_spibus_initialize() in your low level application
|
||||
* initialization logic
|
||||
* 4. The handle returned by kinetis_spibus_initialize() may then be used to bind the
|
||||
* SPI driver to higher level logic (e.g., calling
|
||||
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to
|
||||
* the SPI MMC/SD driver).
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static inline void kinetis_spixselect(const px4_spi_bus_t *bus, struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||
if (bus->devices[i].cs_gpio == 0) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (devid == bus->devices[i].devid) {
|
||||
// SPI select is active low, so write !selected to select the device
|
||||
kinetis_gpiowrite(bus->devices[i].cs_gpio, !selected);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void kinetis_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
|
||||
kinetis_spixselect(_spi_bus0, dev, devid, selected);
|
||||
}
|
||||
|
||||
uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
void kinetis_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
|
||||
kinetis_spixselect(_spi_bus1, dev, devid, selected);
|
||||
}
|
||||
|
||||
uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
void kinetis_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
|
||||
kinetis_spixselect(_spi_bus2, dev, devid, selected);
|
||||
}
|
||||
|
||||
uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
|
||||
#endif /* CONFIG_KINETIS_SPI0 || CONFIG_KINETIS_SPI1 || CONFIG_KINETIS_SPI2 */
|
||||
@@ -0,0 +1,188 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016, 2018 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* @file timer_config.c
|
||||
*
|
||||
* Configuration data for the kinetis pwm_servo, input capture and pwm input driver.
|
||||
*
|
||||
* Note that these arrays must always be fully-sized.
|
||||
*/
|
||||
|
||||
// TODO:Stubbed out for now
|
||||
#include <stdint.h>
|
||||
|
||||
#include <kinetis.h>
|
||||
#include "hardware/kinetis_sim.h"
|
||||
#include "hardware/kinetis_ftm.h"
|
||||
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <px4_arch/io_timer_hw_description.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::FTM0),
|
||||
initIOTimer(Timer::FTM3),
|
||||
initIOTimer(Timer::FTM2),
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel0}, {GPIO::PortC, GPIO::Pin1}),
|
||||
initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel3}, {GPIO::PortA, GPIO::Pin6}),
|
||||
initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel4}, {GPIO::PortD, GPIO::Pin4}),
|
||||
initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel5}, {GPIO::PortD, GPIO::Pin5}),
|
||||
initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel6}, {GPIO::PortD, GPIO::Pin6}),
|
||||
initIOTimerChannel(io_timers, {Timer::FTM0, Timer::Channel7}, {GPIO::PortD, GPIO::Pin7}),
|
||||
initIOTimerChannel(io_timers, {Timer::FTM3, Timer::Channel6}, {GPIO::PortE, GPIO::Pin11}),
|
||||
initIOTimerChannel(io_timers, {Timer::FTM3, Timer::Channel7}, {GPIO::PortE, GPIO::Pin12}),
|
||||
initIOTimerChannel(io_timers, {Timer::FTM3, Timer::Channel0}, {GPIO::PortD, GPIO::Pin0}),
|
||||
initIOTimerChannel(io_timers, {Timer::FTM2, Timer::Channel0}, {GPIO::PortA, GPIO::Pin10}),
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
initIOTimerChannelMapping(io_timers, timer_io_channels);
|
||||
|
||||
const struct io_timers_t led_pwm_timers[MAX_LED_TIMERS] = {
|
||||
{
|
||||
.base = KINETIS_FTM3_BASE,
|
||||
.clock_register = KINETIS_SIM_SCGC3,
|
||||
.clock_bit = SIM_SCGC3_FTM3,
|
||||
.vectorno = 0,
|
||||
},
|
||||
};
|
||||
|
||||
const struct timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = {
|
||||
{
|
||||
.gpio_out = LED_TIM3_CH1OUT, // RGB_R
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 2,
|
||||
},
|
||||
{
|
||||
.gpio_out = LED_TIM3_CH5OUT, // RGB_G
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 6,
|
||||
},
|
||||
{
|
||||
.gpio_out = LED_TIM3_CH4OUT, // RGB_B
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 5,
|
||||
},
|
||||
};
|
||||
|
||||
#define _REG(_addr) (*(volatile uint32_t *)(_addr))
|
||||
|
||||
/* Timer register accessors */
|
||||
|
||||
#define REG(t, _reg) _REG(KINETIS_FTM##t##_BASE + (_reg))
|
||||
|
||||
#define rSC(t) REG(t,KINETIS_FTM_SC_OFFSET)
|
||||
#define rCNT(t) REG(t,KINETIS_FTM_CNT_OFFSET)
|
||||
#define rMOD(t) REG(t,KINETIS_FTM_MOD_OFFSET)
|
||||
#define rC0SC(t) REG(t,KINETIS_FTM_C0SC_OFFSET)
|
||||
#define rC0V(t) REG(t,KINETIS_FTM_C0V_OFFSET)
|
||||
#define rC1SC(t) REG(t,KINETIS_FTM_C1SC_OFFSET)
|
||||
#define rC1V(t) REG(t,KINETIS_FTM_C1V_OFFSET)
|
||||
#define rC2SC(t) REG(t,KINETIS_FTM_C2SC_OFFSET)
|
||||
#define rC2V(t) REG(t,KINETIS_FTM_C2V_OFFSET)
|
||||
#define rC3SC(t) REG(t,KINETIS_FTM_C3SC_OFFSET)
|
||||
#define rC3V(t) REG(t,KINETIS_FTM_C3V_OFFSET)
|
||||
#define rC4SC(t) REG(t,KINETIS_FTM_C4SC_OFFSET)
|
||||
#define rC4V(t) REG(t,KINETIS_FTM_C4V_OFFSET)
|
||||
#define rC5SC(t) REG(t,KINETIS_FTM_C5SC_OFFSET)
|
||||
#define rC5V(t) REG(t,KINETIS_FTM_C5V_OFFSET)
|
||||
#define rC6SC(t) REG(t,KINETIS_FTM_C6SC_OFFSET)
|
||||
#define rC6V(t) REG(t,KINETIS_FTM_C6V_OFFSET)
|
||||
#define rC7SC(t) REG(t,KINETIS_FTM_C7SC_OFFSET)
|
||||
#define rC7V(t) REG(t,KINETIS_FTM_C7V_OFFSET)
|
||||
|
||||
#define rCNTIN(t) REG(t,KINETIS_FTM_CNTIN_OFFSET)
|
||||
#define rSTATUS(t) REG(t,KINETIS_FTM_STATUS_OFFSET)
|
||||
#define rMODE(t) REG(t,KINETIS_FTM_MODE_OFFSET)
|
||||
#define rSYNC(t) REG(t,KINETIS_FTM_SYNC_OFFSET)
|
||||
#define rOUTINIT(t) REG(t,KINETIS_FTM_OUTINIT_OFFSET)
|
||||
#define rOUTMASK(t) REG(t,KINETIS_FTM_OUTMASK_OFFSET)
|
||||
#define rCOMBINE(t) REG(t,KINETIS_FTM_COMBINE_OFFSET)
|
||||
#define rDEADTIME(t) REG(t,KINETIS_FTM_DEADTIME_OFFSET)
|
||||
#define rEXTTRIG(t) REG(t,KINETIS_FTM_EXTTRIG_OFFSET)
|
||||
#define rPOL(t) REG(t,KINETIS_FTM_POL_OFFSET)
|
||||
#define rFMS(t) REG(t,KINETIS_FTM_FMS_OFFSET)
|
||||
#define rFILTER(t) REG(t,KINETIS_FTM_FILTER_OFFSET)
|
||||
#define rFLTCTRL(t) REG(t,KINETIS_FTM_FLTCTRL_OFFSET)
|
||||
#define rQDCTRL(t) REG(t,KINETIS_FTM_QDCTRL_OFFSET)
|
||||
#define rCONF(t) REG(t,KINETIS_FTM_CONF_OFFSET)
|
||||
#define rFLTPOL(t) REG(t,KINETIS_FTM_FLTPOL_OFFSET)
|
||||
#define rSYNCONF(t) REG(t,KINETIS_FTM_SYNCONF_OFFSET)
|
||||
#define rINVCTRL(t) REG(t,KINETIS_FTM_INVCTRL_OFFSET)
|
||||
#define rSWOCTRL(t) REG(t,KINETIS_FTM_SWOCTRL_OFFSET)
|
||||
#define rPWMLOAD(t) REG(t,KINETIS_FTM_PWMLOAD_OFFSET)
|
||||
|
||||
#if !defined(BOARD_PWM_SRC_CLOCK_FREQ)
|
||||
#define BOARD_PWM_SRC_CLOCK_FREQ 16000000
|
||||
#endif
|
||||
|
||||
|
||||
void fmuk66_timer_initialize(void)
|
||||
{
|
||||
|
||||
|
||||
/* Y1 is 16 Mhz used to driver the FTM_CLKIN0 (PCT12) */
|
||||
|
||||
|
||||
/* Enable PCT12 as FTM_CLKIN0 */
|
||||
|
||||
kinetis_pinconfig(PIN_FTM_CLKIN0_3);
|
||||
|
||||
/* Select FTM_CLKIN0 as source for FTM0, FTM2, and FTM3 */
|
||||
|
||||
uint32_t regval = _REG(KINETIS_SIM_SOPT4);
|
||||
regval &= ~(SIM_SOPT4_FTM0CLKSEL | SIM_SOPT4_FTM2CLKSEL | SIM_SOPT4_FTM3CLKSEL);
|
||||
_REG(KINETIS_SIM_SOPT4) = regval;
|
||||
|
||||
|
||||
/* Enabled System Clock Gating Control for FTM 0 and 2*/
|
||||
|
||||
regval = _REG(KINETIS_SIM_SCGC6);
|
||||
regval |= SIM_SCGC6_FTM0 | SIM_SCGC6_FTM2;
|
||||
_REG(KINETIS_SIM_SCGC6) = regval;
|
||||
|
||||
/* Enabled System Clock Gating Control for FTM 2 and 3 */
|
||||
|
||||
regval = _REG(KINETIS_SIM_SCGC3);
|
||||
regval |= SIM_SCGC3_FTM2 | SIM_SCGC3_FTM3;
|
||||
_REG(KINETIS_SIM_SCGC3) = regval;
|
||||
|
||||
}
|
||||
@@ -0,0 +1,113 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016, 2018 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file usb.c
|
||||
*
|
||||
* Board-specific USB functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
|
||||
#include <up_arch.h>
|
||||
#include <kinetis.h>
|
||||
#include <kinetis_usbotg.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: kinetis_usbpullup
|
||||
*
|
||||
* Description:
|
||||
* If USB is supported and the board supports a pullup via GPIO (for USB software
|
||||
* connect and disconnect), then the board software must provide kinetis_usbpullup.
|
||||
* See include/nuttx/usb/usbdev.h for additional description of this method.
|
||||
* Alternatively, if no pull-up GPIO the following EXTERN can be redefined to be
|
||||
* NULL.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT
|
||||
int kinetis_usbpullup(FAR struct usbdev_s *dev, bool enable)
|
||||
{
|
||||
usbtrace(TRACE_DEVPULLUP, (uint16_t)enable);
|
||||
|
||||
if (enable) {
|
||||
putreg8(USB_CONTROL_DPPULLUPNONOTG, KINETIS_USB0_CONTROL);
|
||||
|
||||
} else {
|
||||
putreg8(0, KINETIS_USB0_CONTROL);
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: kinetis_usbsuspend
|
||||
*
|
||||
* Description:
|
||||
* Board logic must provide the kinetis_usbsuspend logic if the USBDEV driver is
|
||||
* used. This function is called whenever the USB enters or leaves suspend mode.
|
||||
* This is an opportunity for the board logic to shutdown clocks, power, etc.
|
||||
* while the USB is suspended.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT
|
||||
void kinetis_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||
{
|
||||
uinfo("resume: %d\n", resume);
|
||||
}
|
||||
Submodule platforms/nuttx/NuttX/nuttx updated: dc10293feb...e48308ad33
Reference in New Issue
Block a user