src/drivers/boards: move to platforms/nuttx/src/px4/common

This commit is contained in:
Beat Küng 2019-10-25 16:41:46 +02:00
parent be7ed5e388
commit 3b7c1b4ff1
25 changed files with 23 additions and 108 deletions

View File

@ -394,7 +394,6 @@ add_subdirectory(src/lib EXCLUDE_FROM_ALL)
add_subdirectory(platforms/${PX4_PLATFORM}/src/px4)
add_subdirectory(platforms EXCLUDE_FROM_ALL)
add_subdirectory(src/modules/uORB EXCLUDE_FROM_ALL) # TODO: platform layer
add_subdirectory(src/drivers/boards EXCLUDE_FROM_ALL)
if(EXISTS "${PX4_BOARD_DIR}/CMakeLists.txt")
add_subdirectory(${PX4_BOARD_DIR})

View File

@ -72,7 +72,7 @@
#include <drivers/drv_board_led.h>
#include <px4_platform_common/init.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -73,7 +73,7 @@
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -72,7 +72,7 @@
#include <px4_platform_common/init.h>
#include <px4_platform_common/i2c.h>
#include <px4_platform/gpio.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
static int configure_switch(void);

View File

@ -70,7 +70,7 @@
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <px4_platform/gpio.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
# if defined(FLASH_BASED_PARAMS)
# include <parameters/flashparams/flashfs.h>

View File

@ -72,7 +72,7 @@
#include <px4_platform_common/init.h>
#include <px4_platform/board_determine_hw_info.h>
#include <px4_platform/gpio.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -70,7 +70,7 @@
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -75,7 +75,7 @@
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -73,7 +73,7 @@
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
# if defined(FLASH_BASED_PARAMS)
# include <parameters/flashparams/flashfs.h>

View File

@ -73,7 +73,7 @@
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -73,7 +73,7 @@
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -74,7 +74,7 @@
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -74,7 +74,7 @@
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -71,7 +71,7 @@
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <px4_platform/board_determine_hw_info.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -71,7 +71,7 @@
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <px4_platform/board_determine_hw_info.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -74,7 +74,7 @@
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
/****************************************************************************
* Pre-Processor Definitions

View File

@ -78,7 +78,6 @@ endif()
target_link_libraries(nuttx_arch
INTERFACE
drivers_board
drivers_boards_common
arch_hrt
)

View File

@ -35,6 +35,9 @@
if (NOT ${PX4_BOARD} MATCHES "px4_io")
add_library(px4_layer
board_crashdump.c
board_dma_alloc.c
board_fat_dma_alloc.c
console_buffer.cpp
gpio.c
px4_nuttx_tasks.c

View File

@ -38,10 +38,8 @@
*/
#include <px4_platform_common/px4_config.h>
#include "board_config.h"
#include "board_dma_alloc.h"
#include <perf/perf_counter.h>
#include <px4_platform/board_dma_alloc.h>
#include <board_config.h>
#if defined(CONFIG_FAT_DMAMEMORY)

View File

@ -44,6 +44,8 @@
#include <stdint.h>
#include <stdbool.h>
#include <board_config.h>
/************************************************************************************
* Name: board_dma_alloc_init
*

View File

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

View File

@ -1,52 +0,0 @@
############################################################################
#
# Copyright (c) 2017 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.
#
############################################################################
# common board drivers (currently only for nuttx fmu boards)
if ((${PX4_PLATFORM} MATCHES "nuttx") AND NOT ${PX4_BOARD} MATCHES "px4_io")
add_library(drivers_boards_common
board_crashdump.c
board_dma_alloc.c
board_fat_dma_alloc.c
)
target_link_libraries(drivers_boards_common
PRIVATE
nuttx_arch # bbsram
nuttx_mm # dma gran alloc
systemlib
)
else()
add_library(drivers_boards_common INTERFACE)
endif()

View File

@ -47,7 +47,7 @@
#include <drivers/drv_hrt.h>
#if defined(BOARD_DMA_ALLOC_POOL_SIZE)
#include <drivers/boards/common/board_dma_alloc.h>
#include <px4_platform/board_dma_alloc.h>
#endif /* BOARD_DMA_ALLOC_POOL_SIZE */
#if defined(CONFIG_SCHED_INSTRUMENTATION)