mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-20 11:23:06 +08:00
boards: add nxp fmuk66-v3 and rddrone-uavcan146 socketcan builds
This commit is contained in:
@@ -41,6 +41,7 @@ pipeline {
|
||||
"mro_x21-777_default",
|
||||
"mro_x21_default",
|
||||
"nxp_fmuk66-v3_default",
|
||||
"nxp_fmuk66-v3_socketcan",
|
||||
"nxp_fmurt1062-v1_default",
|
||||
"nxp_rddrone-uavcan146_default",
|
||||
"omnibus_f4sd_default",
|
||||
|
||||
@@ -27,6 +27,7 @@ jobs:
|
||||
mro_x21-777_default,
|
||||
mro_x21_default,
|
||||
nxp_fmuk66-v3_default,
|
||||
nxp_fmuk66-v3_socketcan,
|
||||
nxp_fmurt1062-v1_default,
|
||||
nxp_rddrone-uavcan146_default,
|
||||
omnibus_f4sd_default,
|
||||
|
||||
@@ -0,0 +1,226 @@
|
||||
#
|
||||
# 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_NXFONTS_DISABLE_16BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_1BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_24BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_2BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_32BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_4BPP=y
|
||||
CONFIG_NXFONTS_DISABLE_8BPP=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PREALLOC_WDOGS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_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_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=2688
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
||||
@@ -0,0 +1,119 @@
|
||||
|
||||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR nxp
|
||||
MODEL fmuk66-v3
|
||||
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/fxas21002c
|
||||
imu/fxos8701cq
|
||||
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
|
||||
shutdown
|
||||
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
|
||||
)
|
||||
@@ -64,6 +64,7 @@
|
||||
#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"
|
||||
@@ -164,7 +165,7 @@ __EXPORT void board_peripheral_reset(int ms)
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
* Name: kinetis_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All Kinetis architectures must provide the following entry point. This entry point
|
||||
@@ -284,6 +285,22 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
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;
|
||||
|
||||
@@ -34,7 +34,7 @@ px4_add_board(
|
||||
#differential_pressure # all available differential pressure drivers
|
||||
#distance_sensor # all available distance sensor drivers
|
||||
#dshot
|
||||
#gps
|
||||
gps
|
||||
#imu # all available imu drivers
|
||||
#lights
|
||||
#magnetometer # all available magnetometer drivers
|
||||
|
||||
@@ -5,6 +5,8 @@
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_NET_ETHERNET is not set
|
||||
# CONFIG_NET_IPv4 is not set
|
||||
# CONFIG_NSH_ARGCAT is not set
|
||||
# CONFIG_NSH_CMDOPT_HEXDUMP is not set
|
||||
# CONFIG_NSH_CMDPARMS is not set
|
||||
@@ -23,9 +25,11 @@ CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=3997
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_CLOCK_MONOTONIC=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_EXAMPLES_HELLO=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
@@ -35,6 +39,7 @@ CONFIG_I2CTOOL_MAXBUS=0
|
||||
CONFIG_I2CTOOL_MINADDR=0x00
|
||||
CONFIG_INTELHEX_BINARY=y
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_LPUART0_RXBUFSIZE=64
|
||||
CONFIG_LPUART0_TXBUFSIZE=64
|
||||
CONFIG_LPUART1_RXBUFSIZE=64
|
||||
@@ -43,12 +48,21 @@ CONFIG_LPUART1_TXBUFSIZE=64
|
||||
CONFIG_MAX_TASKS=16
|
||||
CONFIG_MAX_WDOGPARMS=2
|
||||
CONFIG_MOTOROLA_SREC=y
|
||||
CONFIG_NET=y
|
||||
CONFIG_NETDEV_IFINDEX=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_TIMESTAMP=y
|
||||
CONFIG_NFILE_DESCRIPTORS=15
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_FILEIOSIZE=512
|
||||
CONFIG_NSH_READLINE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
CONFIG_PREALLOC_TIMERS=4
|
||||
CONFIG_PREALLOC_WDOGS=16
|
||||
@@ -57,14 +71,21 @@ CONFIG_RAM_START=0x1fff0000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_RR_INTERVAL=200
|
||||
CONFIG_RTC=y
|
||||
CONFIG_RTC_FREQUENCY=32768
|
||||
CONFIG_RTC_HIRES=y
|
||||
CONFIG_S32K1XX_FLEXCAN0=y
|
||||
CONFIG_S32K1XX_FLEXCAN1=y
|
||||
CONFIG_S32K1XX_LPI2C0=y
|
||||
CONFIG_S32K1XX_LPSPI0=y
|
||||
CONFIG_S32K1XX_LPUART0=y
|
||||
CONFIG_S32K1XX_LPUART1=y
|
||||
CONFIG_S32K1XX_RTC=y
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SPITOOL_DEFFREQ=400000
|
||||
CONFIG_SPITOOL_MAXBUS=0
|
||||
CONFIG_SPITOOL_PROGNAME="spi"
|
||||
@@ -77,5 +98,6 @@ CONFIG_SYMTAB_ORDEREDBYNAME=y
|
||||
CONFIG_SYSTEM_I2CTOOL=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYSTEM_SPITOOL=y
|
||||
CONFIG_TIME_EXTENDED=y
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
CONFIG_WATCHDOG=y
|
||||
|
||||
@@ -83,6 +83,12 @@ SECTIONS
|
||||
*(.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;
|
||||
} > dflash
|
||||
|
||||
.init_section :
|
||||
@@ -92,6 +98,15 @@ SECTIONS
|
||||
_einit = ABSOLUTE(.);
|
||||
} > dflash
|
||||
|
||||
/*
|
||||
* Construction data for parameters.
|
||||
*/
|
||||
__param ALIGN(4): {
|
||||
__param_start = ABSOLUTE(.);
|
||||
KEEP(*(__param*))
|
||||
__param_end = ABSOLUTE(.);
|
||||
} > dflash
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab*)
|
||||
|
||||
Reference in New Issue
Block a user