diff --git a/boards/airmind/mindpx-v2/src/init.c b/boards/airmind/mindpx-v2/src/init.c index e9f840b05f..84fd5225c8 100644 --- a/boards/airmind/mindpx-v2/src/init.c +++ b/boards/airmind/mindpx-v2/src/init.c @@ -72,6 +72,7 @@ #include #include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/boards/auav/x21/src/init.c b/boards/auav/x21/src/init.c index 65e6fa7306..42c672a52e 100644 --- a/boards/auav/x21/src/init.c +++ b/boards/auav/x21/src/init.c @@ -73,6 +73,7 @@ #include #include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/boards/av/x-v1/src/init.c b/boards/av/x-v1/src/init.c index 89b64561ec..f2dc3bd706 100644 --- a/boards/av/x-v1/src/init.c +++ b/boards/av/x-v1/src/init.c @@ -71,6 +71,7 @@ #include #include #include +#include static int configure_switch(void); diff --git a/boards/nxp/fmuk66-v3/src/init.c b/boards/nxp/fmuk66-v3/src/init.c index 9a0a5080ef..87e28b6f52 100644 --- a/boards/nxp/fmuk66-v3/src/init.c +++ b/boards/nxp/fmuk66-v3/src/init.c @@ -74,6 +74,7 @@ #include #include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/boards/omnibus/f4sd/src/init.c b/boards/omnibus/f4sd/src/init.c index 6e68a8e42e..c957044f6d 100644 --- a/boards/omnibus/f4sd/src/init.c +++ b/boards/omnibus/f4sd/src/init.c @@ -73,6 +73,7 @@ #include #include +#include # if defined(FLASH_BASED_PARAMS) # include diff --git a/boards/px4/fmu-v2/src/init.c b/boards/px4/fmu-v2/src/init.c index f96ca3ccb6..1148b3438d 100644 --- a/boards/px4/fmu-v2/src/init.c +++ b/boards/px4/fmu-v2/src/init.c @@ -73,6 +73,7 @@ #include #include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/boards/px4/fmu-v3/src/init.c b/boards/px4/fmu-v3/src/init.c index f96ca3ccb6..1148b3438d 100644 --- a/boards/px4/fmu-v3/src/init.c +++ b/boards/px4/fmu-v3/src/init.c @@ -73,6 +73,7 @@ #include #include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/boards/px4/fmu-v4/src/init.c b/boards/px4/fmu-v4/src/init.c index 928e54def8..984932d663 100644 --- a/boards/px4/fmu-v4/src/init.c +++ b/boards/px4/fmu-v4/src/init.c @@ -74,6 +74,7 @@ #include #include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/boards/px4/fmu-v4pro/src/init.c b/boards/px4/fmu-v4pro/src/init.c index a67e3a6b7f..7dcfd84c03 100644 --- a/boards/px4/fmu-v4pro/src/init.c +++ b/boards/px4/fmu-v4pro/src/init.c @@ -74,6 +74,7 @@ #include #include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/boards/px4/fmu-v5/src/init.c b/boards/px4/fmu-v5/src/init.c index 721982bff4..fa0448dfe8 100644 --- a/boards/px4/fmu-v5/src/init.c +++ b/boards/px4/fmu-v5/src/init.c @@ -70,6 +70,7 @@ #include #include #include +#include /**************************************************************************** * Pre-Processor Definitions diff --git a/src/drivers/boards/common/CMakeLists.txt b/src/drivers/boards/common/CMakeLists.txt index d324293887..05994817e3 100644 --- a/src/drivers/boards/common/CMakeLists.txt +++ b/src/drivers/boards/common/CMakeLists.txt @@ -37,6 +37,7 @@ if ((${PX4_PLATFORM} MATCHES "nuttx") AND NOT ${PX4_BOARD} MATCHES "io") add_library(drivers_boards_common board_crashdump.c board_dma_alloc.c + board_fat_dma_alloc.c board_gpio_init.c board_dcache_control.c ) diff --git a/src/drivers/boards/common/board_common.h b/src/drivers/boards/common/board_common.h index 3f393f7f16..35fe4aa120 100644 --- a/src/drivers/boards/common/board_common.h +++ b/src/drivers/boards/common/board_common.h @@ -502,56 +502,6 @@ __EXPORT bool board_supports_single_wire(uint32_t uxart_base); int board_read_VBUS_state(void); #endif -/************************************************************************************ - * Name: board_dma_alloc_init - * - * Description: - * All boards may optionally provide this API to instantiate a pool of - * memory for uses with FAST FS DMA operations. - * - * Provision is controlled by declaring BOARD_DMA_ALLOC_POOL_SIZE in board_config.h - * - * Input Parameters: - * None - * - * Returned Value: - * Zero (OK) is returned on success; a negated errno value is returned on failure - * EPERM - board does not support function - * ENOMEM - There is not enough memory to satisfy allocation. - * - ************************************************************************************/ -#if defined(BOARD_DMA_ALLOC_POOL_SIZE) -__EXPORT int board_dma_alloc_init(void); -#else -#define board_dma_alloc_init() (-EPERM) -#endif - -/************************************************************************************ - * Name: board_get_dma_usage - * - * Description: - * All boards may optionally provide this API to supply instrumentation for a pool of - * memory used for DMA operations. - * - * Provision is controlled by declaring BOARD_DMA_ALLOC_POOL_SIZE in board_config.h - * - * Input Parameters: - * dma_total - A pointer to receive the total allocation size of the memory - * allocated with board_dma_alloc_init. It should be equal to - * BOARD_DMA_ALLOC_POOL_SIZE. - * dma_used - A pointer to receive the current allocation in use. - * dma_peak_used - A pointer to receive the peak allocation used. - * - * Returned Value: - * Zero (OK) is returned on success; - * - ************************************************************************************/ -#if defined(BOARD_DMA_ALLOC_POOL_SIZE) -__EXPORT int board_get_dma_usage(uint16_t *dma_total, uint16_t *dma_used, uint16_t *dma_peak_used); -#else -#define board_get_dma_usage(dma_total,dma_used, dma_peak_used) (-ENOMEM) -#endif - /************************************************************************************ * Name: board_rc_input * diff --git a/src/drivers/boards/common/board_dma_alloc.c b/src/drivers/boards/common/board_dma_alloc.c index c00068ec13..bb26de9f21 100644 --- a/src/drivers/boards/common/board_dma_alloc.c +++ b/src/drivers/boards/common/board_dma_alloc.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * Copyright (C) 2016-2019 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 @@ -37,10 +37,6 @@ * Provide the board dma allocator interface. */ -/************************************************************************************ - * Included Files - ************************************************************************************/ - #include #include "board_config.h" @@ -50,18 +46,6 @@ #include -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - /************************************************************************************ * Name: board_dma_alloc_init * @@ -72,9 +56,7 @@ ************************************************************************************/ #if defined(BOARD_DMA_ALLOC_POOL_SIZE) -# if !defined(CONFIG_GRAN) || !defined(CONFIG_FAT_DMAMEMORY) -# error microSD DMA support requires CONFIG_GRAN and CONFIG_FAT_DMAMEMORY -# endif +#if defined(CONFIG_GRAN) static GRAN_HANDLE dma_allocator; @@ -92,10 +74,12 @@ static uint8_t g_dma_heap[BOARD_DMA_ALLOC_POOL_SIZE] __attribute__((aligned(64)) static perf_counter_t g_dma_perf; static uint16_t dma_heap_inuse; static uint16_t dma_heap_peak_use; + /**************************************************************************** * Public Functions ****************************************************************************/ -__EXPORT int board_dma_alloc_init(void) +__EXPORT int +board_dma_alloc_init(void) { dma_allocator = gran_initialize(g_dma_heap, sizeof(g_dma_heap), @@ -114,7 +98,8 @@ __EXPORT int board_dma_alloc_init(void) return OK; } -__EXPORT int board_get_dma_usage(uint16_t *dma_total, uint16_t *dma_used, uint16_t *dma_peak_used) +__EXPORT int +board_get_dma_usage(uint16_t *dma_total, uint16_t *dma_used, uint16_t *dma_peak_used) { *dma_total = sizeof(g_dma_heap); *dma_used = dma_heap_inuse; @@ -122,15 +107,9 @@ __EXPORT int board_get_dma_usage(uint16_t *dma_total, uint16_t *dma_used, uint16 return OK; } -/* - * DMA-aware allocator stubs for the FAT filesystem. - */ -__EXPORT void *fat_dma_alloc(size_t size); -__EXPORT void fat_dma_free(FAR void *memory, size_t size); - -void * -fat_dma_alloc(size_t size) +__EXPORT void * +board_dma_alloc(size_t size) { void *rv = NULL; perf_count(g_dma_perf); @@ -147,10 +126,12 @@ fat_dma_alloc(size_t size) return rv; } -void -fat_dma_free(FAR void *memory, size_t size) +__EXPORT void +board_dma_free(FAR void *memory, size_t size) { gran_free(dma_allocator, memory, size); dma_heap_inuse -= size; } -#endif /* defined(BOARD_DMA_ALLOC_POOL_SIZE) */ + +#endif /* CONFIG_GRAN */ +#endif /* BOARD_DMA_ALLOC_POOL_SIZE */ diff --git a/src/drivers/boards/common/board_dma_alloc.h b/src/drivers/boards/common/board_dma_alloc.h new file mode 100644 index 0000000000..d4b85ed357 --- /dev/null +++ b/src/drivers/boards/common/board_dma_alloc.h @@ -0,0 +1,133 @@ +/**************************************************************************** + * + * Copyright (C) 2016-2019 PX4 Development Team. All rights reserved. + * Author: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_dma_alloc.h + * + * Provide DMA capable memory allocation interface + */ + +#pragma once + +#include +#include +#include + +/************************************************************************************ + * Name: board_dma_alloc_init + * + * Description: + * All boards may optionally provide this API to instantiate a pool of + * memory for uses with FAST FS DMA operations. + * + * Provision is controlled by declaring BOARD_DMA_ALLOC_POOL_SIZE in board_config.h + * + * Input Parameters: + * None + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on failure + * EPERM - board does not support function + * ENOMEM - There is not enough memory to satisfy allocation. + * + ************************************************************************************/ +#if defined(BOARD_DMA_ALLOC_POOL_SIZE) +__EXPORT int board_dma_alloc_init(void); +#else +#define board_dma_alloc_init() (-EPERM) +#endif + +/************************************************************************************ + * Name: board_get_dma_usage + * + * Description: + * All boards may optionally provide this API to supply instrumentation for a pool of + * memory used for DMA operations. + * + * Provision is controlled by declaring BOARD_DMA_ALLOC_POOL_SIZE in board_config.h + * + * Input Parameters: + * dma_total - A pointer to receive the total allocation size of the memory + * allocated with board_dma_alloc_init. It should be equal to + * BOARD_DMA_ALLOC_POOL_SIZE. + * dma_used - A pointer to receive the current allocation in use. + * dma_peak_used - A pointer to receive the peak allocation used. + * + * Returned Value: + * Zero (OK) is returned on success; + * + ************************************************************************************/ +#if defined(BOARD_DMA_ALLOC_POOL_SIZE) +__EXPORT int board_get_dma_usage(uint16_t *dma_total, uint16_t *dma_used, uint16_t *dma_peak_used); +#else +#define board_get_dma_usage(dma_total,dma_used, dma_peak_used) (-ENOMEM) +#endif + +/************************************************************************************ + * Name: dma_alloc + * + * Description: + * All boards may optionally provide this API to supply DMA capable memory + * + * Input Parameters: + * size - A pointer to receive the total allocation size of the memory + * allocated with board_dma_alloc_init. It should be equal to + * BOARD_DMA_ALLOC_POOL_SIZE. + * + * Returned Value: + * Zero (OK) is returned on success; + * + ************************************************************************************/ +#if defined(BOARD_DMA_ALLOC_POOL_SIZE) +__EXPORT void *board_dma_alloc(size_t size); +#else +#define board_dma_alloc(size) (NULL) +#endif + +/************************************************************************************ + * Name: dma_free + * + * Description: + * All boards may optionally provide this API to supply DMA capable memory + * + * Input Parameters: + * memory - A pointer to previously allocated DMA memory + * size - Size of the previously allocated DMA memory + * + ************************************************************************************/ +#if defined(BOARD_DMA_ALLOC_POOL_SIZE) +__EXPORT void board_dma_free(FAR void *memory, size_t size); +#else +#define board_dma_free(memory, size) () +#endif diff --git a/src/drivers/boards/common/board_fat_dma_alloc.c b/src/drivers/boards/common/board_fat_dma_alloc.c new file mode 100644 index 0000000000..740f09cbb8 --- /dev/null +++ b/src/drivers/boards/common/board_fat_dma_alloc.c @@ -0,0 +1,71 @@ +/**************************************************************************** + * + * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_dma_alloc.c + * + * Provide the board dma allocator interface. + */ + +#include +#include "board_config.h" + +#include "board_dma_alloc.h" +#include + +#if defined(CONFIG_FAT_DMAMEMORY) + +# if !defined(CONFIG_GRAN) +# error microSD DMA support requires CONFIG_GRAN and CONFIG_FAT_DMAMEMORY +# endif + +/* + * DMA-aware allocator stubs for the FAT filesystem. + */ + +__EXPORT void *fat_dma_alloc(size_t size); +__EXPORT void fat_dma_free(FAR void *memory, size_t size); + +void * +fat_dma_alloc(size_t size) +{ + return board_dma_alloc(size); +} + +void +fat_dma_free(FAR void *memory, size_t size) +{ + return board_dma_free(memory, size); +} + +#endif /* CONFIG_FAT_DMAMEMORY && CONFIG_GRAN */ diff --git a/src/lib/systemlib/print_load_nuttx.c b/src/lib/systemlib/print_load_nuttx.c index 8486219bea..e0a91cbc0d 100644 --- a/src/lib/systemlib/print_load_nuttx.c +++ b/src/lib/systemlib/print_load_nuttx.c @@ -46,6 +46,10 @@ #include #include +#if defined(BOARD_DMA_ALLOC_POOL_SIZE) +#include +#endif /* BOARD_DMA_ALLOC_POOL_SIZE */ + #if defined(CONFIG_SCHED_INSTRUMENTATION) #if !defined(CONFIG_TASK_NAME_SIZE)