remove BOARD_NAME from board_config.h and set automatically

This commit is contained in:
Daniel Agar 2018-11-22 12:35:42 -05:00 committed by David Sidrane
parent 2d052c02fa
commit ec4c9da253
34 changed files with 32 additions and 63 deletions

View File

@ -42,7 +42,6 @@
#define BOARD_OVERRIDE_UUID "OCPOC00000000000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_OCPOC
#define BOARD_NAME "AEROTENNA_OCPOC"
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_HAS_NO_RESET
#define BOARD_HAS_NO_BOOTLOADER

View File

@ -293,8 +293,6 @@
#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(GPIO_USART1_RX)
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define BOARD_NAME "AIRMIND_MINDPX_V2"
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
* provides the true logic GPIO BOARD_ADC_xxxx macros.

View File

@ -42,8 +42,6 @@
#define BOARD_OVERRIDE_UUID "EAGLEID000000000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_EAGLE
#define BOARD_NAME "ATLFLIGHT_EAGLE"
#define BOARD_HAS_NO_RESET
#define BOARD_HAS_NO_BOOTLOADER

View File

@ -38,8 +38,10 @@
*/
#pragma once
#define BOARD_NAME "ATLFLIGHT_EXCELSIOR"
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
#define BOARD_HAS_NO_RESET
#define BOARD_HAS_NO_BOOTLOADER

View File

@ -300,8 +300,6 @@ __BEGIN_DECLS
#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2
#endif
#define BOARD_NAME "ATMEL_SAME70XPLAINED"
/*
* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore

View File

@ -134,8 +134,6 @@
GPIO_PORTA | GPIO_PIN1 | GPIO_OUTPUT_CLEAR)
#define GPIO_LED_BLUE GPIO_LED3
#define BOARD_NAME "AUAV_ESC35_V1"
__BEGIN_DECLS
/************************************************************************************

View File

@ -203,8 +203,6 @@
#define PWMIN_TIMER_CHANNEL 2
#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2
#define BOARD_NAME "AUAV_X21"
/* By Providing BOARD_ADC_USB_CONNECTED this board support the ADC
* system_power interface, and therefore provides the true logic
* GPIO BOARD_ADC_xxxx macros.

View File

@ -337,8 +337,6 @@
# warning SDIO initialization cannot be perfomed on the IDLE thread
#endif
#define BOARD_NAME "AV_X_V1"
/* AV-X_V1 never powers off the Servo rail */
#define BOARD_ADC_SERVO_VALID (1)

View File

@ -45,8 +45,6 @@
#define BOARD_OVERRIDE_UUID "BBBLUEID00000000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_BBBLUE
#define BOARD_NAME "BEAGLEBONE_BLUE"
#define BOARD_BATTERY1_V_DIV (11.0f)
//#define BOARD_BATTERY1_A_PER_V (15.391030303f)

View File

@ -215,8 +215,6 @@
#define HRT_TIMER 8 /* use timer8 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
#define BOARD_NAME "BITCRAZE_CRAZYFLIE"
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
__BEGIN_DECLS

View File

@ -42,8 +42,6 @@
#define BOARD_OVERRIDE_UUID "RPIID00000000000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_RPI
#define BOARD_NAME "EMLID_NAVIO2"
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
#define ADC_BATTERY_CURRENT_CHANNEL 3

View File

@ -200,8 +200,6 @@
#define HRT_TIMER 8 /* use timer8 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
#define BOARD_NAME "GUMSTIX_AEROCORE2"
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
#define BOARD_FMU_GPIO_TAB { \

View File

@ -129,8 +129,6 @@
#define HRT_TIMER 3 /* use timer3 for the HRT */
#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel */
#define BOARD_NAME "INTEL_AEROFC_V1"
#define FLASH_BASED_PARAMS
#define FLASH_BASED_DATAMAN

View File

@ -391,9 +391,6 @@ __BEGIN_DECLS
#define PWMIN_TIMER_CHANNEL 2
#define GPIO_PWM_IN GPIO_FTM0_CH2IN
#define BOARD_NAME "NXP_HLITE_V3"
/* Define True logic Power Control in arch agnostic form */
#define VDD_ETH_EN(on_true) px4_arch_gpiowrite(nGPIO_ETHERNET_P_EN, !(on_true))

View File

@ -252,8 +252,6 @@
//#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(GPIO_USART1_RX)
//#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define BOARD_NAME "OMNIBUS_F4SD"
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
#define BOARD_FMU_GPIO_TAB { \

View File

@ -42,8 +42,6 @@
#define BOARD_OVERRIDE_UUID "BEBOPID000000000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_BEBOP
#define BOARD_NAME "PARROT_BEBOP"
#define BOARD_HAS_NO_RESET
#define BOARD_HAS_NO_BOOTLOADER

View File

@ -143,8 +143,6 @@
#define GPIO_CAN_CTRL (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
GPIO_PORTC | GPIO_PIN13 | GPIO_OUTPUT_CLEAR)
#define BOARD_NAME "PX4_CANNODE_V1"
__BEGIN_DECLS
/************************************************************************************

View File

@ -216,8 +216,6 @@
#define GPIO_TEST1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_50MHz | \
GPIO_PORTD | GPIO_PIN2 | GPIO_OUTPUT_CLEAR)
#define BOARD_NAME "PX4_ESC_V1"
__BEGIN_DECLS
/************************************************************************************

View File

@ -450,8 +450,6 @@
#define PWMIN_TIMER_CHANNEL 2
#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2
#define BOARD_NAME "PX4_FMU_V2"
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
* provides the true logic GPIO BOARD_ADC_xxxx macros.

View File

@ -450,8 +450,6 @@
#define PWMIN_TIMER_CHANNEL 2
#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2
#define BOARD_NAME "PX4_FMU_V2"
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
* provides the true logic GPIO BOARD_ADC_xxxx macros.

View File

@ -306,8 +306,6 @@
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define BOARD_NAME "PX4_FMU_V4"
/**
* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore

View File

@ -602,8 +602,6 @@
# warning SDIO initialization cannot be perfomed on the IDLE thread
#endif
#define BOARD_NAME "PX4_FMU_V5"
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
* provides the true logic GPIO BOARD_ADC_xxxx macros.

View File

@ -42,8 +42,6 @@
#define BOARD_OVERRIDE_UUID "RPIID00000000000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_RPI
#define BOARD_NAME "RASPBERRYPI"
#define BOARD_HAS_NO_RESET
#define BOARD_HAS_NO_BOOTLOADER

View File

@ -42,7 +42,6 @@
#define BOARD_OVERRIDE_UUID "SIMULATIONID0000" // must be of length 16
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_SITL
#define BOARD_NAME "PX4_SITL"
#define BOARD_BATTERY1_V_DIV (10.177939394f)
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
#define BOARD_HAS_NO_RESET

View File

@ -81,8 +81,6 @@
#define HRT_TIMER 8 /* use timer8 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
#define BOARD_NAME "STM_32F4DISCOVERY"
__BEGIN_DECLS
/****************************************************************************************************

View File

@ -312,8 +312,6 @@ __BEGIN_DECLS
# warning SDIO initialization cannot be perfomed on the IDLE thread
#endif
#define BOARD_NAME "STM_NUCLEOF767ZI"
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
* this board support the ADC system_power interface, and therefore
* provides the true logic GPIO BOARD_ADC_xxxx macros.

View File

@ -80,8 +80,6 @@
GPIO_PORTB | GPIO_PIN6 | GPIO_OUTPUT_CLEAR)
#define BOARD_NAME "THIEMAR_S2740VC_V1"
__BEGIN_DECLS
/************************************************************************************

View File

@ -233,6 +233,20 @@ function(px4_add_module)
add_library(${MODULE} STATIC EXCLUDE_FROM_ALL ${CMAKE_CURRENT_BINARY_DIR}/${MODULE}_unity.cpp)
target_include_directories(${MODULE} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR})
if(DEPENDS)
# using target_link_libraries for dependencies provides linking
# as well as interface include and libraries
foreach(dep ${DEPENDS})
get_target_property(dep_type ${dep} TYPE)
if (${dep_type} STREQUAL "STATIC_LIBRARY")
target_link_libraries(${MODULE}_original PRIVATE ${dep})
else()
add_dependencies(${MODULE}_original ${dep})
endif()
endforeach()
endif()
elseif(DYNAMIC AND MAIN AND (${OS} STREQUAL "posix"))
add_library(${MODULE} SHARED ${SRCS})
target_compile_definitions(${MODULE} PRIVATE ${MAIN}_main=px4_module_main)

View File

@ -75,7 +75,16 @@ if (DEFINED ENV{BUILD_URI})
endif()
add_library(version version.c)
target_compile_definitions(version PRIVATE BUILD_URI=${BUILD_URI})
string(TOUPPER "${PX4_BOARD}" PX4_BOARD_NAME)
target_compile_definitions(version
PUBLIC
PX4_BOARD_NAME="${PX4_BOARD_NAME}"
PRIVATE
BUILD_URI=${BUILD_URI}
)
target_link_libraries(version PRIVATE git_ver)
target_link_libraries(version PRIVATE drivers_board)
add_dependencies(version prebuild_targets)

View File

@ -47,15 +47,6 @@
#include <systemlib/px4_macros.h>
#include <stdint.h>
/* The preferred method for publishing a board name is to
* define it in board_config.h as BOARD_NAME
*/
#ifndef BOARD_NAME
# error "board_config.h must define BOARD_NAME"
#endif
__BEGIN_DECLS
/**
@ -63,7 +54,7 @@ __BEGIN_DECLS
*/
static inline const char *px4_board_name(void)
{
return BOARD_NAME;
return PX4_BOARD_NAME;
}
/**

View File

@ -95,6 +95,7 @@ px4_add_module(
DEPENDS
mixer
version
git_uavcan

View File

@ -79,6 +79,7 @@ px4_add_module(
DEPENDS
drivers_bootloaders
git_uavcan
version
# within libuavcan
libuavcan_dsdlc

View File

@ -78,6 +78,7 @@ px4_add_module(
DEPENDS
drivers_bootloaders
git_uavcan
version
# within libuavcan
libuavcan_dsdlc

View File

@ -101,4 +101,5 @@ px4_add_module(
git_ecl
ecl_geo_lookup # TODO: move this
pwm_limit
version
)