rename nuttx board support packages for consistecy (#8777)

This commit is contained in:
Daniel Agar 2018-02-19 19:12:32 -05:00 committed by GitHub
parent 7b5b1c4f23
commit a35abf2453
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
127 changed files with 168 additions and 379 deletions

View File

@ -30,15 +30,12 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__aerocore2
SRCS
aerocore2_can.c
aerocore2_init.c
aerocore2_timer_config.c
aerocore2_spi.c
aerocore2_usb.c
aerocore2_led.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
can.c
init.c
led.c
spi.c
timer_config.c
usb.c
)

View File

@ -31,13 +31,10 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__aerofc-v1
SRCS
aerofc_init.c
aerofc_spi.c
aerofc_led.c
aerofc_timer_config.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
init.c
led.c
spi.c
timer_config.c
)

View File

@ -30,15 +30,12 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__auav-x21
SRCS
auav_can.c
auav_init.c
auav_timer_config.c
auav_spi.c
auav_usb.c
auav_led.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
can.c
init.c
led.c
spi.c
timer_config.c
usb.c
)

View File

@ -30,13 +30,10 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__crazyflie
SRCS
crazyflie_init.c
crazyflie_usb.c
crazyflie_led.c
crazyflie_timer_config.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
init.c
led.c
timer_config.c
usb.c
)

View File

@ -31,23 +31,12 @@
#
############################################################################
message(WARNING-"Configuraton is incomplete")
message(WARNING-"Configuraton is incomplete")
message(WARNING-"Configuraton is incomplete")
message(WARNING-"Configuraton is incomplete")
message(WARNING-"Configuraton is incomplete")
message(WARNING-"DO NOT RUN THIS ON HW")
message(WARNING-"IT IS NOT PINED OUT TO HW")
message(WARNING-"Configuraton is incomplete")
message(WARNING-"Configuraton is incomplete")
message(WARNING-"Configuraton is incomplete")
message(WARNING "Configuraton is incomplete")
message(WARNING "DO NOT RUN THIS ON HW")
message(WARNING "IT IS NOT PINED OUT TO HW")
px4_add_module(
MODULE drivers__boards__esc35-v1
SRCS
esc35_init.c
esc35_led.c
esc35_usb.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
init.c
led.c
usb.c
)

View File

@ -30,15 +30,12 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__mindpx-v2
SRCS
mindpx_can.c
mindpx2_init.c
mindpx_timer_config.c
mindpx_spi.c
mindpx_usb.c
mindpx2_led.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
can.c
init.c
led.c
spi.c
timer_config.c
usb.c
)

View File

@ -30,18 +30,15 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__nxphlite-v3
SRCS
nxphlite_autoleds.c
nxphlite_automount.c
nxphlite_can.c
nxphlite_init.c
nxphlite_led.c
nxphlite_sdhc.c
nxphlite_spi.c
nxphlite_timer_config.c
nxphlite_usb.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
autoleds.c
automount.c
can.c
init.c
led.c
sdhc.c
spi.c
timer_config.c
usb.c
)

View File

@ -30,16 +30,13 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4-same70xplained-v1
SRCS
px4same70xplained_can.c
px4same70xplained_init.c
px4same70xplained_timer_config.c
px4same70xplained_spi.c
px4same70xplained_usb.c
px4same70xplained_led.c
px4same70xplained_sdram.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
can.c
init.c
led.c
sdram.c
spi.c
timer_config.c
usb.c
)

View File

@ -30,12 +30,9 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4-stm32f4discovery
SRCS
px4discovery_init.c
px4discovery_usb.c
px4discovery_led.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
init.c
led.c
usb.c
)

View File

@ -31,14 +31,10 @@
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4cannode-v1
SRCS
px4cannode_can.c
px4cannode_buttons.c
px4cannode_init.c
px4cannode_led.c
px4cannode_spi.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
buttons.c
can.c
init.c
led.c
spi.c
)

View File

@ -31,12 +31,8 @@
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4esc-v1
SRCS
px4esc_init.c
px4esc_led.c
px4esc_usb.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
init.c
led.c
usb.c
)

View File

@ -31,14 +31,8 @@
#
############################################################################
message(FATAL_ERROR Configuraton is incomplete")
px4_add_module(
MODULE drivers__boards__px4flow-v2
SRCS
px4flow_init.c
px4flow_led.c
px4flow_can.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
can.c
init.c
led.c
)

View File

@ -30,16 +30,13 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4fmu-v2
SRCS
px4fmu_can.c
px4fmu_i2c.c
px4fmu_init.c
px4fmu_led.c
px4fmu_spi.c
px4fmu_timer_config.c
px4fmu_usb.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
can.c
i2c.c
init.c
led.c
spi.c
timer_config.c
usb.c
)

View File

@ -1,126 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2012 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 px4fmu_timer_config.c
*
* Configuration data for the stm32 pwm_servo, input capture and pwm input driver.
*
* Note that these arrays must always be fully-sized.
*/
#include <stdint.h>
#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/stm32/drv_io_timer.h>
#include "board_config.h"
__EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
{
.base = STM32_TIM1_BASE,
.clock_register = STM32_RCC_APB2ENR,
.clock_bit = RCC_APB2ENR_TIM1EN,
.clock_freq = STM32_APB2_TIM1_CLKIN,
.first_channel_index = 0,
.last_channel_index = 3,
.handler = io_timer_handler0,
.vectorno = STM32_IRQ_TIM1CC,
},
{
.base = STM32_TIM4_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM4EN,
.clock_freq = STM32_APB1_TIM4_CLKIN,
.first_channel_index = 4,
.last_channel_index = 5,
.handler = io_timer_handler1,
.vectorno = STM32_IRQ_TIM4
}
};
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
{
.gpio_out = GPIO_TIM1_CH4OUT,
.gpio_in = GPIO_TIM1_CH4IN,
.timer_index = 0,
.timer_channel = 4,
.ccr_offset = STM32_GTIM_CCR4_OFFSET,
.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF
},
{
.gpio_out = GPIO_TIM1_CH3OUT,
.gpio_in = GPIO_TIM1_CH3IN,
.timer_index = 0,
.timer_channel = 3,
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
},
{
.gpio_out = GPIO_TIM1_CH2OUT,
.gpio_in = GPIO_TIM1_CH2IN,
.timer_index = 0,
.timer_channel = 2,
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
},
{
.gpio_out = GPIO_TIM1_CH1OUT,
.gpio_in = GPIO_TIM1_CH1IN,
.timer_index = 0,
.timer_channel = 1,
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
},
{
.gpio_out = GPIO_TIM4_CH2OUT,
.gpio_in = GPIO_TIM4_CH2IN,
.timer_index = 1,
.timer_channel = 2,
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
},
{
.gpio_out = GPIO_TIM4_CH3OUT,
.gpio_in = GPIO_TIM4_CH3IN,
.timer_index = 1,
.timer_channel = 3,
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
}
};

View File

@ -30,15 +30,12 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4fmu-v4
SRCS
px4fmu_can.c
px4fmu_init.c
px4fmu_timer_config.c
px4fmu_spi.c
px4fmu_usb.c
px4fmu_led.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
can.c
init.c
led.c
spi.c
timer_config.c
usb.c
)

View File

@ -30,15 +30,12 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4fmu-v4pro
SRCS
px4fmu_can.c
px4fmu_init.c
px4fmu_timer_config.c
px4fmu_spi.c
px4fmu_usb.c
px4fmu_led.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
can.c
init.c
led.c
spi.c
timer_config.c
usb.c
)

View File

@ -30,16 +30,13 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4fmu-v5
SRCS
# WIP px4fmu_can.c
px4fmu_init.c
px4fmu_sdio.c
px4fmu_timer_config.c
px4fmu_spi.c
px4fmu_usb.c
px4fmu_led.c
DEPENDS
platforms__common
)
px4_add_library(drivers_board
#stm32_can.c # WIP
init.c
led.c
sdio.c
spi.c
timer_config.c
usb.c
)

Some files were not shown because too many files have changed in this diff Show More