diff --git a/boards/nxp/fmuk66-v3/nuttx-config/nsh/defconfig b/boards/nxp/fmuk66-v3/nuttx-config/nsh/defconfig index 0a4b929168..cf4a4d6d41 100644 --- a/boards/nxp/fmuk66-v3/nuttx-config/nsh/defconfig +++ b/boards/nxp/fmuk66-v3/nuttx-config/nsh/defconfig @@ -107,7 +107,6 @@ 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 @@ -167,7 +166,6 @@ CONFIG_NSH_STRERROR=y CONFIG_NSH_VARS=y CONFIG_PIPES=y CONFIG_PREALLOC_TIMERS=50 -CONFIG_PREALLOC_WDOGS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_STACK_MIN=512 CONFIG_RAMTRON_SETSPEED=y @@ -203,7 +201,6 @@ 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 diff --git a/boards/nxp/fmuk66-v3/nuttx-config/scripts/script.ld b/boards/nxp/fmuk66-v3/nuttx-config/scripts/script.ld index a5db9d15b0..84953b8ac8 100644 --- a/boards/nxp/fmuk66-v3/nuttx-config/scripts/script.ld +++ b/boards/nxp/fmuk66-v3/nuttx-config/scripts/script.ld @@ -82,11 +82,6 @@ SECTIONS *(.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; diff --git a/boards/nxp/fmuk66-v3/nuttx-config/socketcan/defconfig b/boards/nxp/fmuk66-v3/nuttx-config/socketcan/defconfig index af38d02152..f464337d6a 100644 --- a/boards/nxp/fmuk66-v3/nuttx-config/socketcan/defconfig +++ b/boards/nxp/fmuk66-v3/nuttx-config/socketcan/defconfig @@ -108,11 +108,9 @@ 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 @@ -164,7 +162,6 @@ CONFIG_NSH_STRERROR=y CONFIG_NSH_VARS=y CONFIG_PIPES=y CONFIG_PREALLOC_TIMERS=50 -CONFIG_PREALLOC_WDOGS=50 CONFIG_PRIORITY_INHERITANCE=y CONFIG_PTHREAD_STACK_MIN=512 CONFIG_RAMTRON_SETSPEED=y @@ -200,7 +197,6 @@ 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 diff --git a/boards/nxp/fmuk66-v3/src/CMakeLists.txt b/boards/nxp/fmuk66-v3/src/CMakeLists.txt index 2c563c1f83..c5c34e8613 100644 --- a/boards/nxp/fmuk66-v3/src/CMakeLists.txt +++ b/boards/nxp/fmuk66-v3/src/CMakeLists.txt @@ -34,7 +34,6 @@ add_library(drivers_board autoleds.c automount.c - can.c i2c.cpp init.c led.c diff --git a/boards/nxp/fmuk66-v3/src/can.c b/boards/nxp/fmuk66-v3/src/can.c deleted file mode 100644 index b0e9ff91c9..0000000000 --- a/boards/nxp/fmuk66-v3/src/can.c +++ /dev/null @@ -1,129 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2016, 2018 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file can.c - * - * Board-specific CAN functions. - */ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include -#include - -#include -#include - -#include -#include -#include "up_arch.h" - -#include "board_config.h" - -#ifdef CONFIG_CAN - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ -/* Configuration ********************************************************************/ - -#if defined(KINETIS_FLEXCAN0) && defined(KINETIS_FLEXCAN1) -# warning "Both CAN0 and CAN1 are enabled. Assuming only CAN0." -# undef KINETIS_FLEXCAN0 -#endif - -#ifdef KINETIS_FLEXCAN0 -# define CAN_PORT 1 -#else -# define CAN_PORT 2 -#endif - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ -int can_devinit(void); - -/************************************************************************************ - * Name: can_devinit - * - * Description: - * All architectures must provide the following interface to work with - * examples/can. - * - ************************************************************************************/ - -int can_devinit(void) -{ - static bool initialized = false; - struct can_dev_s *can; - int ret; - - /* Check if we have already initialized */ - - if (!initialized) { - /* Call kinetis_caninitialize() to get an instance of the CAN interface */ - - can = kinetis_caninitialize(CAN_PORT); - - if (can == NULL) { - canerr("ERROR: Failed to get CAN interface\n"); - return -ENODEV; - } - - /* Register the CAN driver at "/dev/can0" */ - - ret = can_register("/dev/can0", can); - - if (ret < 0) { - canerr("ERROR: can_register failed: %d\n", ret); - return ret; - } - - /* Now we are initialized */ - - initialized = true; - } - - return OK; -} - -#endif diff --git a/boards/nxp/fmuk66-v3/src/init.c b/boards/nxp/fmuk66-v3/src/init.c index 4734421a69..8f05dfe745 100644 --- a/boards/nxp/fmuk66-v3/src/init.c +++ b/boards/nxp/fmuk66-v3/src/init.c @@ -67,7 +67,7 @@ #include #include "board_config.h" -#include "up_arch.h" +#include "arm_arch.h" #include #include @@ -84,7 +84,7 @@ ****************************************************************************/ /* - * Ideally we'd be able to get these from up_internal.h, + * Ideally we'd be able to get these from arm_internal.h, * but since we want to be able to disable the NuttX use * of leds for system indication at will and there is no * separate switch, we need to build independent of the @@ -293,14 +293,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) kinetis_netinitialize(0); # endif -# ifdef CONFIG_KINETIS_FLEXCAN0 - kinetis_caninitialize(0); -# endif - -# ifdef CONFIG_KINETIS_FLEXCAN1 - kinetis_caninitialize(1); -# endif - #endif return OK; diff --git a/boards/nxp/fmuk66-v3/src/led.c b/boards/nxp/fmuk66-v3/src/led.c index 339456dd7c..dca4e56069 100644 --- a/boards/nxp/fmuk66-v3/src/led.c +++ b/boards/nxp/fmuk66-v3/src/led.c @@ -48,7 +48,7 @@ #include /* - * Ideally we'd be able to get these from up_internal.h, + * Ideally we'd be able to get these from arm_internal.h, * but since we want to be able to disable the NuttX use * of leds for system indication at will and there is no * separate switch, we need to build independent of the diff --git a/boards/nxp/fmuk66-v3/src/spi.cpp b/boards/nxp/fmuk66-v3/src/spi.cpp index 5a53664ce8..65a562f32b 100644 --- a/boards/nxp/fmuk66-v3/src/spi.cpp +++ b/boards/nxp/fmuk66-v3/src/spi.cpp @@ -47,7 +47,7 @@ #include #include -#include "up_arch.h" +#include "arm_arch.h" #include "chip.h" #include #include "board_config.h" diff --git a/boards/nxp/fmuk66-v3/src/usb.c b/boards/nxp/fmuk66-v3/src/usb.c index c4943f9f37..3c7098437e 100644 --- a/boards/nxp/fmuk66-v3/src/usb.c +++ b/boards/nxp/fmuk66-v3/src/usb.c @@ -51,7 +51,7 @@ #include #include -#include +#include #include #include #include "board_config.h"