board_common.h: move under platforms/common

Also move board_determine_hw_info and board_gpio_init under platforms/nuttx
This commit is contained in:
Beat Küng 2019-10-25 13:42:51 +02:00
parent dc601f15f1
commit b30171ba8d
51 changed files with 168 additions and 84 deletions

View File

@ -57,4 +57,4 @@
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
#include <system_config.h>
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>

View File

@ -346,7 +346,7 @@ extern void stm32_usbinitialize(void);
#define board_peripheral_reset(ms)
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -57,4 +57,4 @@
#define PX4_NUMBER_I2C_BUSES 3
#include <system_config.h>
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>

View File

@ -266,7 +266,7 @@ int usbmsc_archinitialize(void);
extern int composite_archinitialize(void);
#endif
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -270,7 +270,7 @@ extern void stm32_usbinitialize(void);
extern void stm32_spiinitialize(void);
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS

View File

@ -388,7 +388,7 @@ void board_spi_reset(int ms);
int nsh_archinitialize(void);
#endif
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -71,6 +71,7 @@
#include <systemlib/px4_macros.h>
#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>
static int configure_switch(void);
@ -91,7 +92,7 @@ __EXPORT void board_on_reset(int status)
/* configure the GPIO pins to outputs and keep them low */
const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
if (status >= 0) {
up_mdelay(6);
@ -118,7 +119,7 @@ stm32_boardinitialize(void)
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */
stm32_spiinitialize();

View File

@ -64,7 +64,7 @@
#define PX4_NUMBER_I2C_BUSES 1
#include <system_config.h>
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#ifdef __cplusplus
extern "C" {

View File

@ -283,7 +283,7 @@ extern int stm32_spi_bus_initialize(void);
void board_spi_reset(int ms);
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -3,6 +3,7 @@
************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <px4_platform/gpio.h>
#include <stdint.h>
#include <stdbool.h>
@ -46,7 +47,7 @@ static const uint32_t spi1selects_gpio[] = PX4_FLOW_BUS_CS_GPIO;
__EXPORT void stm32_spiinitialize(void)
{
#ifdef CONFIG_STM32_SPI1
board_gpio_init(spi1selects_gpio, arraySize(spi1selects_gpio));
px4_gpio_init(spi1selects_gpio, arraySize(spi1selects_gpio));
#endif
}

View File

@ -60,4 +60,4 @@
#define PX4_NUMBER_I2C_BUSES 1
#include <system_config.h>
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>

View File

@ -270,7 +270,7 @@ extern void board_peripheral_reset(int ms);
int nsh_archinitialize(void);
#endif
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -68,6 +68,8 @@
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <px4_platform/gpio.h>
#include <drivers/boards/common/board_dma_alloc.h>
# if defined(FLASH_BASED_PARAMS)
@ -120,7 +122,7 @@ __EXPORT void board_on_reset(int status)
/* configure the GPIO pins to outputs and keep them low */
const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
if (status >= 0) {
up_mdelay(6);
@ -149,7 +151,7 @@ stm32_boardinitialize(void)
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */

View File

@ -180,7 +180,7 @@ extern void stm32_spiinitialize(void);
extern int board_sdio_initialize(void);
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -41,9 +41,11 @@ add_library(drivers_board
timer_config.c
usb.c
)
add_dependencies(drivers_board arch_board_hw_info)
target_link_libraries(drivers_board
PRIVATE
arch_board_hw_info
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio

View File

@ -544,7 +544,7 @@ extern void board_peripheral_reset(int ms);
int nsh_archinitialize(void);
#endif
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -70,6 +70,8 @@
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#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>
/****************************************************************************
@ -182,7 +184,7 @@ __EXPORT void board_on_reset(int status)
/* configure the GPIO pins to outputs and keep them low */
const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
if (status >= 0) {
up_mdelay(6);
@ -236,7 +238,7 @@ stm32_boardinitialize(void)
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */

View File

@ -392,7 +392,7 @@ extern void board_peripheral_reset(int ms);
int nsh_archinitialize(void);
#endif
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -69,6 +69,7 @@
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#include <px4_platform_common/init.h>
#include <px4_platform/gpio.h>
#include <drivers/boards/common/board_dma_alloc.h>
/****************************************************************************
@ -132,7 +133,7 @@ __EXPORT void board_on_reset(int status)
/* configure the GPIO pins to outputs and keep them low */
const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
if (status >= 0) {
up_mdelay(6);
@ -159,7 +160,7 @@ stm32_boardinitialize(void)
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */
stm32_spiinitialize();

View File

@ -664,7 +664,7 @@ void fmuk66_automount_event(bool inserted);
void fmuk66_timer_initialize(void);
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -46,6 +46,7 @@
****************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <px4_platform/gpio.h>
#include <stdbool.h>
#include <stdio.h>
@ -116,7 +117,7 @@ void board_on_reset(int status)
/* configure the GPIO pins to outputs and keep them low */
const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
if (status >= 0) {
up_mdelay(6);
@ -178,7 +179,7 @@ kinetis_boardinitialize(void)
board_autoled_initialize();
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
fmuk66_timer_initialize();

View File

@ -313,7 +313,7 @@ extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -54,4 +54,4 @@
#define PX4_NUMBER_I2C_BUSES 1
#include <system_config.h>
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>

View File

@ -274,7 +274,7 @@ int usbmsc_archinitialize(void);
extern int composite_archinitialize(void);
#endif
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -343,7 +343,7 @@ int usbmsc_archinitialize(void);
extern int composite_archinitialize(void);
#endif
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -517,7 +517,7 @@ extern void board_peripheral_reset(int ms);
extern void stm32_usbinitialize(void);
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -518,7 +518,7 @@ extern void board_peripheral_reset(int ms);
extern void stm32_usbinitialize(void);
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -393,7 +393,7 @@ extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -390,7 +390,7 @@ extern void board_peripheral_reset(int ms);
int nsh_archinitialize(void);
#endif
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -41,9 +41,11 @@ add_library(drivers_board
timer_config.c
usb.c
)
add_dependencies(drivers_board arch_board_hw_info)
target_link_libraries(drivers_board
PRIVATE
arch_board_hw_info
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio

View File

@ -737,7 +737,7 @@ extern void board_peripheral_reset(int ms);
int nsh_archinitialize(void);
#endif
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -69,6 +69,8 @@
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#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>
/****************************************************************************
@ -137,7 +139,7 @@ __EXPORT void board_on_reset(int status)
/* configure the GPIO pins to outputs and keep them low */
const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
if (status >= 0) {
up_mdelay(6);
@ -166,7 +168,7 @@ stm32_boardinitialize(void)
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */

View File

@ -41,9 +41,11 @@ add_library(drivers_board
timer_config.c
usb.c
)
add_dependencies(drivers_board arch_board_hw_info)
target_link_libraries(drivers_board
PRIVATE
arch_board_hw_info
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio

View File

@ -736,7 +736,7 @@ extern void board_peripheral_reset(int ms);
int nsh_archinitialize(void);
#endif
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -69,6 +69,8 @@
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#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>
/****************************************************************************
@ -143,7 +145,7 @@ __EXPORT void board_on_reset(int status)
/* configure the GPIO pins to outputs and keep them low */
const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
if (status >= 0) {
up_mdelay(6);
@ -172,7 +174,7 @@ stm32_boardinitialize(void)
/* configure pins */
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
board_gpio_init(gpio, arraySize(gpio));
px4_gpio_init(gpio, arraySize(gpio));
/* configure SPI interfaces */

View File

@ -47,7 +47,7 @@
#include <nuttx/compiler.h>
#include <stdint.h>
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
/******************************************************************************
* Definitions

View File

@ -55,4 +55,4 @@
#define ADC_BATTERY_CURRENT_CHANNEL 1
#include <system_config.h>
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>

View File

@ -58,4 +58,4 @@
#define BOARD_ARMED_STATE_LED LED_GREEN
#include <system_config.h>
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>

View File

@ -123,7 +123,7 @@ int board_can_initialize(void);
extern int composite_archinitialize(void);
#endif
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -382,7 +382,7 @@ extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */

View File

@ -1079,4 +1079,3 @@ __EXPORT bool board_has_bus(enum board_bus_types type, uint32_t bus);
*/
int board_hardfault_init(int display_to_console, bool allow_prompt);
#include "board_internal_common.h"

View File

@ -36,6 +36,7 @@ if (NOT ${PX4_BOARD} MATCHES "px4_io")
add_library(px4_layer
console_buffer.cpp
gpio.c
px4_nuttx_tasks.c
px4_nuttx_impl.cpp
px4_init.cpp

View File

@ -33,7 +33,7 @@
****************************************************************************/
/**
* @file board_gpio_init.c.c
* @file gpio.c
* Implementation of Generic PIO init Note we use he HAL version of configgpio
* So this will work with any ARCH
*/
@ -41,10 +41,10 @@
#include <px4_platform_common/px4_config.h>
/************************************************************************************
* Name: board_gpio_init
* Name: px4_gpio_init
*
* Description:
* Board may provide a list of GPI pins to get initialized
* A board may provide a list of GPI pins to get initialized
*
* list - A list of GPIO pins to be initialized
* count - Size of the list
@ -53,7 +53,7 @@
************************************************************************************/
void board_gpio_init(const uint32_t list[], int count)
void px4_gpio_init(const uint32_t list[], int count)
{
for (int gpio = 0; gpio < count; gpio++) {
if (list[gpio] != 0) {

View File

@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
* Author: David Sidrane <david_s5@nscdg.com>
* Copyright (c) 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
@ -31,36 +30,10 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file board_internal_common.h
*
* Provide the internal common board interfaces that should only be used
* in the board source.
*/
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
/************************************************************************************
* Name: board_gpio_init
*
* Description:
* Board may provide a list of GPI pins to get initialized
*
* Input Parameters:
* list - A list of GPIO pins to be initialized
* count - Size of the list
*
* Returned Value:
* Nothing
*
************************************************************************************/
__EXPORT void board_gpio_init(const uint32_t list[], int count);
__BEGIN_DECLS
/************************************************************************************
* Name: board_determine_hw_info
@ -84,3 +57,6 @@ __EXPORT void board_gpio_init(const uint32_t list[], int count);
************************************************************************************/
__EXPORT int board_determine_hw_info(void);
__END_DECLS

View File

@ -0,0 +1,56 @@
/****************************************************************************
*
* Copyright (c) 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
* 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.
*
****************************************************************************/
#pragma once
__BEGIN_DECLS
/************************************************************************************
* Name: px4_gpio_init
*
* Description:
* A board may provide a list of GPI pins to get initialized
*
* Input Parameters:
* list - A list of GPIO pins to be initialized
* count - Size of the list
*
* Returned Value:
* Nothing
*
************************************************************************************/
__EXPORT void px4_gpio_init(const uint32_t list[], int count);
__END_DECLS

View File

@ -0,0 +1,36 @@
############################################################################
#
# Copyright (c) 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
# 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.
#
############################################################################
px4_add_library(arch_board_hw_info
board_hw_rev_ver.c
)

View File

@ -40,10 +40,9 @@
#include <drivers/drv_adc.h>
#include <px4_arch/adc.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform/board_determine_hw_info.h>
#include <stdio.h>
#include "board_config.h"
#include "../board_internal_common.h"
#include <board_config.h>
#include <systemlib/px4_macros.h>

View File

@ -33,6 +33,7 @@
add_subdirectory(../stm32_common/adc adc)
add_subdirectory(../stm32_common/board_hw_info board_hw_info)
add_subdirectory(../stm32_common/dshot dshot)
add_subdirectory(../stm32_common/hrt hrt)
add_subdirectory(../stm32_common/led_pwm led_pwm)

View File

@ -13,4 +13,4 @@
#define BOARD_HAS_NO_RESET
#define BOARD_HAS_NO_BOOTLOADER
#include <drivers/boards/common/board_common.h>
#include <px4_platform_common/board_common.h>

View File

@ -38,7 +38,6 @@ if ((${PX4_PLATFORM} MATCHES "nuttx") AND NOT ${PX4_BOARD} MATCHES "px4_io")
board_crashdump.c
board_dma_alloc.c
board_fat_dma_alloc.c
board_gpio_init.c
)
if (${CONFIG_ARCH_CHIP} MATCHES "kinetis")

View File

@ -35,7 +35,6 @@ add_library(drivers_boards_common_arch
board_identity.c
board_mcu_version.c
board_reset.c
board_hw_rev_ver.c
board_critmon.c
)
add_dependencies(drivers_boards_common_arch prebuild_targets)