forked from Archive/PX4-Autopilot
Initial config for ASC module
This commit is contained in:
parent
c0e3ab632e
commit
40ba3f5131
|
@ -0,0 +1,12 @@
|
|||
{
|
||||
"board_id": 78,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the ASCv1 board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "ASCv1",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
6
Makefile
6
Makefile
|
@ -42,7 +42,7 @@ endif
|
|||
CMAKE_VER := $(shell Tools/check_cmake.sh; echo $$?)
|
||||
ifneq ($(CMAKE_VER),0)
|
||||
$(warning Not a valid CMake version or CMake not installed.)
|
||||
$(warning On Ubuntu, install or upgrade via:)
|
||||
$(warning On Ubuntu 16.04, install or upgrade via:)
|
||||
$(warning )
|
||||
$(warning 3rd party PPA:)
|
||||
$(warning sudo add-apt-repository ppa:george-edison55/cmake-3.x -y)
|
||||
|
@ -147,6 +147,9 @@ endef
|
|||
tap-v1_default:
|
||||
$(call cmake-build,nuttx_tap-v1_default)
|
||||
|
||||
asc-v1_default:
|
||||
$(call cmake-build,nuttx_asc-v1_default)
|
||||
|
||||
px4fmu-v1_default:
|
||||
$(call cmake-build,nuttx_px4fmu-v1_default)
|
||||
|
||||
|
@ -254,6 +257,7 @@ checks_defaults: \
|
|||
check_mindpx-v2_default \
|
||||
check_px4-stm32f4discovery_default \
|
||||
check_tap-v1_default \
|
||||
check_asc-v1_default
|
||||
|
||||
checks_bootloaders: \
|
||||
|
||||
|
|
|
@ -0,0 +1,129 @@
|
|||
include(nuttx/px4_impl_nuttx)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake)
|
||||
|
||||
set(config_module_list
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
drivers/device
|
||||
drivers/stm32
|
||||
drivers/stm32/adc
|
||||
drivers/stm32/tone_alarm
|
||||
drivers/led
|
||||
#drivers/px4fmu
|
||||
drivers/boards/asc-v1
|
||||
drivers/rgbled_pwm
|
||||
drivers/tap_esc
|
||||
#drivers/mpu6500
|
||||
drivers/ms5611
|
||||
drivers/hmc5883
|
||||
drivers/gps
|
||||
drivers/airspeed
|
||||
drivers/meas_airspeed
|
||||
modules/sensors
|
||||
drivers/camera_trigger
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
systemcmds/bl_update
|
||||
systemcmds/mixer
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/pwm
|
||||
systemcmds/motor_test
|
||||
systemcmds/reboot
|
||||
systemcmds/top
|
||||
systemcmds/config
|
||||
systemcmds/nshterm
|
||||
systemcmds/mtd
|
||||
systemcmds/dumpfile
|
||||
systemcmds/ver
|
||||
systemcmds/topic_listener
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
modules/commander
|
||||
modules/load_mon
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
modules/land_detector
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
modules/ekf2
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
modules/fw_pos_control_l1
|
||||
modules/fw_att_control
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
modules/logger
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/uORB
|
||||
modules/dataman
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/conversion
|
||||
lib/launchdetection
|
||||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
platforms/nuttx/px4_layer
|
||||
)
|
||||
|
||||
set(config_extra_builtin_cmds
|
||||
serdis
|
||||
sercon
|
||||
)
|
||||
|
||||
set(config_io_board
|
||||
)
|
||||
|
||||
set(config_extra_libs
|
||||
)
|
||||
|
||||
set(config_io_extra_libs
|
||||
)
|
||||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon"
|
||||
STACK_MAIN "2048")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis"
|
||||
STACK_MAIN "2048")
|
|
@ -0,0 +1,432 @@
|
|||
/************************************************************************************
|
||||
* configs/tap-v1/include/board.h
|
||||
* include/arch/board/board.h
|
||||
*
|
||||
* Copyright (C) 2012-2016 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* 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 NuttX 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __CONFIG_TAP_V1_INCLUDE_BOARD_H
|
||||
#define __CONFIG_TAP_V1_INCLUDE_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_sdio.h"
|
||||
#include "stm32.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The TAP V1 uses a 16MHz crystal connected to the HSE.
|
||||
*
|
||||
* This is the canonical configuration:
|
||||
* System Clock source : PLL (HSE)
|
||||
* SYSCLK(Hz) : 168000000 Determined by PLL configuration
|
||||
* HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE)
|
||||
* AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE)
|
||||
* APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1)
|
||||
* APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2)
|
||||
* HSE Frequency(Hz) : 16000000 (STM32_BOARD_XTAL)
|
||||
* PLLM : 8 (STM32_PLLCFG_PLLM)
|
||||
* PLLN : 168 (STM32_PLLCFG_PLLN)
|
||||
* PLLP : 2 (STM32_PLLCFG_PLLP)
|
||||
* PLLQ : 7 (STM32_PLLCFG_PLLQ)
|
||||
* Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK
|
||||
* Flash Latency(WS) : 5
|
||||
* Prefetch Buffer : OFF
|
||||
* Instruction cache : ON
|
||||
* Data cache : ON
|
||||
* Require 48MHz for USB OTG FS, : Enabled
|
||||
* SDIO and RNG clock
|
||||
*/
|
||||
|
||||
/* HSI - 16 MHz RC factory-trimmed
|
||||
* LSI - 32 KHz RC
|
||||
* HSE - On-board crystal frequency is 16MHz
|
||||
* LSE - not installed
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_XTAL 16000000ul
|
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
* PLL source is HSE
|
||||
* PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
|
||||
* = (16,000,000 / 8) * 168
|
||||
* = 336,000,000
|
||||
* SYSCLK = PLL_VCO / PLLP
|
||||
* = 336,000,000 / 2 = 168,000,000
|
||||
* USB OTG FS, SDIO and RNG Clock
|
||||
* = PLL_VCO / PLLQ
|
||||
* = 336,000,000 / 7
|
||||
* = 48,000,000
|
||||
*/
|
||||
|
||||
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8)
|
||||
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(168)
|
||||
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
|
||||
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7)
|
||||
|
||||
#define STM32_SYSCLK_FREQUENCY 168000000ul
|
||||
|
||||
/* AHB clock (HCLK) is SYSCLK (168MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
|
||||
#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
|
||||
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
|
||||
|
||||
/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
|
||||
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
|
||||
|
||||
/* Timers driven from APB1 will be twice PCLK1 */
|
||||
|
||||
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
|
||||
|
||||
/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */
|
||||
|
||||
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
|
||||
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* Timers driven from APB2 will be twice PCLK2 */
|
||||
|
||||
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
|
||||
* otherwise frequency is 2xAPBx.
|
||||
* Note: TIM1,8 are on APB2, others on APB1
|
||||
*/
|
||||
|
||||
#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY)
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
|
||||
* way. The following definitions are used to access individual LEDs.
|
||||
*/
|
||||
|
||||
/* LED index values for use with stm32_setled()
|
||||
*
|
||||
* PC4 BLUE_LED D4 Blue LED cathode
|
||||
* PC5 RED_LED D5 Red LED cathode
|
||||
*/
|
||||
#define BOARD_LED1 0
|
||||
#define BOARD_LED2 1
|
||||
#define BOARD_NLEDS 2
|
||||
|
||||
#define BOARD_LED_BLUE BOARD_LED1
|
||||
#define BOARD_LED_RED BOARD_LED2
|
||||
|
||||
/* LED bits for use with stm32_setleds() */
|
||||
|
||||
#define BOARD_LED1_BIT (1 << BOARD_LED1)
|
||||
#define BOARD_LED2_BIT (1 << BOARD_LED2)
|
||||
|
||||
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board
|
||||
* the tap-v1. The following definitions describe how NuttX controls
|
||||
* the LEDs:
|
||||
*/
|
||||
|
||||
#define LED_STARTED 0 /* BLUE */
|
||||
#define LED_HEAPALLOCATE 1 /* LED2 */
|
||||
#define LED_IRQSENABLED 2 /* BLUE */
|
||||
#define LED_STACKCREATED 3 /* BLUE + RED */
|
||||
#define LED_INIRQ 4 /* BLUE */
|
||||
#define LED_SIGNAL 5 /* RED */
|
||||
#define LED_ASSERTION 6 /* BLUE + RED */
|
||||
#define LED_PANIC 7 /* BLUE + RED */
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
||||
/*
|
||||
* USARTs.
|
||||
*
|
||||
*
|
||||
* Peripheral Port Signal Name CONN
|
||||
* USART1_TX PB6 GPS_USART1_TX JP1-15,16
|
||||
* USART1_RX PB7 GPS_USART1_RX JP1-13,14
|
||||
* USART2_TX PA2 GB_USART2_TX JP2-19,20
|
||||
* USART2_RX PA3 GB_USART2_RX JP2-21,22
|
||||
* USART3_TX PC10 RF2_USART3_TX J3-2
|
||||
* USART3_RX PC11 RF2_USART3_RX J3-1
|
||||
* USART6_TX PC6 RF_USART6_TX JP2-15,16
|
||||
* USART6_RX PC7 RF_USART6_RX JP2-17,18
|
||||
*/
|
||||
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_2
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_2
|
||||
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_1
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_1
|
||||
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_2
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_2
|
||||
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_1
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1
|
||||
|
||||
/* USART DMA configuration for USART 1 and 6 */
|
||||
|
||||
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
|
||||
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
|
||||
|
||||
/*
|
||||
* UARTs.
|
||||
*
|
||||
* N.B. The 's' is here to match the wrong labeling on Schematic
|
||||
*
|
||||
* Peripheral Port Signal Name CONN
|
||||
* UART4_TX PA0 OFS_UsART4_TX JP1-19,20
|
||||
* UART4_RX PA1 OFS_UsART4_RX JP1-17,18
|
||||
* UART5_TX PC12 ESC_UsART5_TX U7-HCT244 etal ESC
|
||||
* UART5_RX PD2 ESC_UsART5_RX U8-5 74HCT151
|
||||
*
|
||||
* Note that UART5 has no optional pinout, so it is not listed here.
|
||||
*
|
||||
*/
|
||||
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_1
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_1
|
||||
|
||||
/*
|
||||
* I2C
|
||||
*
|
||||
* Peripheral Port Signal Name CONN
|
||||
* I2C1_SDA PB9 I2C1_SDA J2-4,9,16,21 mpu6050, U4 MS6507
|
||||
* I2C1_SDL PB8 I2C1_SCL J2-3,10,15,22 mpu6050, U4 MS6507
|
||||
* I2C2_SDA PB11 Sonar Echo/I2C_SDA JP2-31,32
|
||||
* I2C2_SDL PB10 Sonar Trig/I2C_SCL JP2-29,30
|
||||
* I2C3_SDA PC9 COMPASS_I2C3_SDA JP1-27,28
|
||||
* I2C3_SDL PA8 COMPASS_I2C3_SCL JP1-25,26
|
||||
*
|
||||
* The optional _GPIO configurations allow the I2C driver to manually
|
||||
* reset the bus to clear stuck slaves. They match the pin configuration,
|
||||
* but are normally-high GPIOs.
|
||||
*/
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2
|
||||
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
|
||||
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
|
||||
|
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
|
||||
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
|
||||
|
||||
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_1
|
||||
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1
|
||||
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN9)
|
||||
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8)
|
||||
|
||||
/*
|
||||
* SPI
|
||||
*
|
||||
* Peripheral Port Signal Name CONN
|
||||
* SPI2_NSS PB12 SD_SPI2_NSS SD-2 CS
|
||||
* SPI2_SCK PB13 SD_SPI2_SCK SD-5 CLK
|
||||
* SPI2_MISO PB14 SD_SPI2_MISO SD-7 D0
|
||||
* SPI2_MOSI PB15 SD_SPI2_MOSI SD-3 DI
|
||||
*
|
||||
*/
|
||||
|
||||
#define GPIO_SPI2_NSS (GPIO_SPI2_NSS_1 | GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_2 | GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI2_MISO (GPIO_SPI2_MISO_1 | GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI2_MOSI (GPIO_SPI2_MOSI_1 | GPIO_SPEED_50MHz)
|
||||
|
||||
/* SPI DMA configuration for SPI2 (microSD) */
|
||||
#define DMACHAN_SPI2_RX DMAMAP_SPI2_RX
|
||||
#define DMACHAN_SPI2_TX DMAMAP_SPI2_TX
|
||||
|
||||
/* The following Pin Mapping is just for completeness */
|
||||
/*
|
||||
* JTAG
|
||||
*
|
||||
* We will only enable SW-DP, JTAG-DP will be disabled
|
||||
*
|
||||
* Function Port Signal Name CONN
|
||||
* SWDIO PA13 DAT J10-3,J7
|
||||
* SWCLK PA14 CLK J10-4,J8
|
||||
*
|
||||
*/
|
||||
|
||||
/*
|
||||
* BOOT
|
||||
*
|
||||
* Function Port Signal Name CONN
|
||||
* BOOT0 NA BOOT0 GND via 10 K
|
||||
* BOOT1 PB2 BOOT1 V3.3 - 10 K
|
||||
*
|
||||
* As jumpered the device can only boot from FLASH.
|
||||
*
|
||||
* It can be booted to:
|
||||
*
|
||||
* SRAM if BOOT0 is pulled High with 1K.
|
||||
* System memory if:
|
||||
* BOOT0 is pulled High with 1K and
|
||||
* BOOT1 is pulled Low with 1K
|
||||
*/
|
||||
|
||||
/*
|
||||
* Timer PWM
|
||||
*
|
||||
* Peripheral Port Signal Name CONN
|
||||
* TIM3_CH1 PA6 LED_R JP2-23,24
|
||||
* TIM3_CH2 PA7 LED_G JP2-25,26
|
||||
* TIM3_CH3 PB0 LED_B JP2-27,28
|
||||
* TIM3_CH4 PB1 nPWM_1 AUX1(Landing Gear) JP1-21,22
|
||||
*/
|
||||
|
||||
/*
|
||||
* GPIO
|
||||
*
|
||||
* Port Signal Name CONN
|
||||
* PA4 POWER JP1-23, - Must be held High to run w/o USB
|
||||
* PB4 TEMP_CONT J2-2,11,14,23 - Gyro Heater
|
||||
* PC0 VOLTAGE JP2-13,14 - 1.84 @16.66 1.67 @15.12 Scale 0.1105
|
||||
* PC1 KEY_AD JP1-31,32 - Low when Power button is depressed
|
||||
* PC2 SD_SW SD-9 SW - Card Present
|
||||
* PC3 PCON_RADIO JP1-29,30
|
||||
* PC13 S2 U8-9 74HCT151
|
||||
* PC14 S1 U8-10 74HCT151
|
||||
* PC15 S0 U8-11 74HCT151
|
||||
*/
|
||||
|
||||
/*
|
||||
* USB
|
||||
*
|
||||
* Port Signal Name CONN
|
||||
* PA9 OTG_FS_VBUS J1-1
|
||||
* PA10 OTG_FS_ID J1-4
|
||||
* PA11 OTG_FS_DM J1-2
|
||||
* PA12 OTG_FS_DP J1-3
|
||||
*/
|
||||
|
||||
/*
|
||||
* UNUSED PINS - In an idle world - these would have been tied to pads to
|
||||
* facilitate debugging probs.
|
||||
* Port
|
||||
* PA15
|
||||
* PB3
|
||||
* PB5
|
||||
* PC8
|
||||
*/
|
||||
|
||||
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
|
||||
|
||||
#if defined(CONFIG_BOARD_USE_PROBES)
|
||||
# define PROBE_N(n) (1<<((n)-1))
|
||||
# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
|
||||
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN3)
|
||||
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5)
|
||||
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
|
||||
|
||||
# define PROBE_INIT(mask) \
|
||||
do { \
|
||||
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
|
||||
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
|
||||
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
|
||||
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
|
||||
} while(0)
|
||||
|
||||
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
|
||||
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
|
||||
#else
|
||||
# define PROBE_INIT(mask)
|
||||
# define PROBE(n,s)
|
||||
# define PROBE_MARK(n)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes
|
||||
************************************************************************************/
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the initialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
EXTERN void stm32_boardinitialize(void);
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __CONFIG_TAP_V1_INCLUDE_BOARD_H */
|
|
@ -0,0 +1,42 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* nsh_romfsetc.h
|
||||
*
|
||||
* This file is a stub for 'make export' purposes; the actual ROMFS
|
||||
* must be supplied by the library client.
|
||||
*/
|
||||
|
||||
extern unsigned char romfs_img[];
|
||||
extern unsigned int romfs_img_len;
|
|
@ -0,0 +1,160 @@
|
|||
############################################################################
|
||||
# configs/tap-v1/nsh/Make.defs
|
||||
#
|
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# 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 NuttX 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
include ${TOPDIR}/.config
|
||||
include ${TOPDIR}/tools/Config.mk
|
||||
|
||||
include $(TOPDIR)/PX4_Warnings.mk
|
||||
|
||||
#
|
||||
# We only support building with the ARM bare-metal toolchain from
|
||||
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
|
||||
#
|
||||
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
|
||||
|
||||
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
|
||||
|
||||
CC = $(CROSSDEV)gcc
|
||||
CXX = $(CROSSDEV)g++
|
||||
CPP = $(CROSSDEV)gcc -E
|
||||
LD = $(CROSSDEV)ld
|
||||
AR = $(CROSSDEV)ar rcs
|
||||
NM = $(CROSSDEV)nm
|
||||
OBJCOPY = $(CROSSDEV)objcopy
|
||||
OBJDUMP = $(CROSSDEV)objdump
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m4 \
|
||||
-mthumb \
|
||||
-march=armv7e-m \
|
||||
-mfpu=fpv4-sp-d16 \
|
||||
-mfloat-abi=hard
|
||||
|
||||
|
||||
# enable precise stack overflow tracking
|
||||
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
|
||||
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
|
||||
endif
|
||||
|
||||
# pull in *just* libm from the toolchain ... this is grody
|
||||
LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
|
||||
EXTRA_LIBS += $(LIBM)
|
||||
|
||||
# use our linker script
|
||||
LDSCRIPT = ld.script
|
||||
|
||||
ifeq ($(WINTOOL),y)
|
||||
# Windows-native toolchains
|
||||
DIRLINK = $(TOPDIR)/tools/copydir.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||
else
|
||||
ifeq ($(PX4_WINTOOL),y)
|
||||
# Windows-native toolchains (MSYS)
|
||||
DIRLINK = $(TOPDIR)/tools/copydir.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||
else
|
||||
# Linux/Cygwin-native toolchain
|
||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||
endif
|
||||
endif
|
||||
|
||||
# tool versions
|
||||
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
|
||||
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
|
||||
|
||||
# optimisation flags
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
|
||||
-fno-strict-aliasing \
|
||||
-fno-strength-reduce \
|
||||
-fomit-frame-pointer \
|
||||
-funsafe-math-optimizations \
|
||||
-fno-builtin-printf \
|
||||
-ffunction-sections \
|
||||
-fdata-sections
|
||||
|
||||
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
|
||||
ARCHOPTIMIZATION += -g
|
||||
endif
|
||||
|
||||
ARCHCFLAGS = -std=gnu99
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
|
||||
ARCHWARNINGS = $(PX4_ARCHWARNINGS)
|
||||
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
|
||||
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
|
||||
ARCHDEFINES =
|
||||
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
|
||||
|
||||
# this seems to be the only way to add linker flags
|
||||
EXTRA_LIBS += --warn-common \
|
||||
--gc-sections
|
||||
|
||||
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
|
||||
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
|
||||
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
|
||||
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
|
||||
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
|
||||
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
|
||||
|
||||
NXFLATLDFLAGS1 = -r -d -warn-common
|
||||
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
|
||||
LDNXFLATFLAGS = -e main -s 2048
|
||||
|
||||
OBJEXT = .o
|
||||
LIBEXT = .a
|
||||
EXEEXT =
|
||||
|
||||
|
||||
# produce partially-linked $1 from files in $2
|
||||
define PRELINK
|
||||
@echo "PRELINK: $1"
|
||||
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
|
||||
endef
|
||||
|
||||
HOSTCC = gcc
|
||||
HOSTINCLUDES = -I.
|
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
|
||||
HOSTLDFLAGS =
|
||||
|
|
@ -0,0 +1,982 @@
|
|||
#
|
||||
# Automatically generated file; DO NOT EDIT.
|
||||
# Nuttx/ Configuration
|
||||
#
|
||||
CONFIG_NUTTX_NEWCONFIG=y
|
||||
|
||||
#
|
||||
# Build Setup
|
||||
#
|
||||
# CONFIG_EXPERIMENTAL is not set
|
||||
CONFIG_HOST_LINUX=y
|
||||
# CONFIG_HOST_OSX is not set
|
||||
# CONFIG_HOST_WINDOWS is not set
|
||||
# CONFIG_HOST_OTHER is not set
|
||||
|
||||
#
|
||||
# Build Configuration
|
||||
#
|
||||
CONFIG_APPS_DIR="../apps"
|
||||
# CONFIG_BUILD_2PASS is not set
|
||||
|
||||
#
|
||||
# Binary Output Formats
|
||||
#
|
||||
# CONFIG_RRLOAD_BINARY is not set
|
||||
# CONFIG_INTELHEX_BINARY is not set
|
||||
# CONFIG_MOTOROLA_SREC is not set
|
||||
CONFIG_RAW_BINARY=y
|
||||
|
||||
#
|
||||
# Customize Header Files
|
||||
#
|
||||
# CONFIG_ARCH_STDBOOL_H is not set
|
||||
CONFIG_ARCH_MATH_H=y
|
||||
# CONFIG_ARCH_FLOAT_H is not set
|
||||
# CONFIG_ARCH_STDARG_H is not set
|
||||
|
||||
#
|
||||
# Debug Options
|
||||
#
|
||||
# CONFIG_DEBUG is not set
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
|
||||
#
|
||||
# System Type
|
||||
#
|
||||
# CONFIG_ARCH_8051 is not set
|
||||
CONFIG_ARCH_ARM=y
|
||||
# CONFIG_ARCH_AVR is not set
|
||||
# CONFIG_ARCH_HC is not set
|
||||
# CONFIG_ARCH_MIPS is not set
|
||||
# CONFIG_ARCH_RGMP is not set
|
||||
# CONFIG_ARCH_SH is not set
|
||||
# CONFIG_ARCH_SIM is not set
|
||||
# CONFIG_ARCH_X86 is not set
|
||||
# CONFIG_ARCH_Z16 is not set
|
||||
# CONFIG_ARCH_Z80 is not set
|
||||
CONFIG_ARCH="arm"
|
||||
|
||||
#
|
||||
# ARM Options
|
||||
#
|
||||
# CONFIG_ARCH_CHIP_C5471 is not set
|
||||
# CONFIG_ARCH_CHIP_CALYPSO is not set
|
||||
# CONFIG_ARCH_CHIP_DM320 is not set
|
||||
# CONFIG_ARCH_CHIP_IMX is not set
|
||||
# CONFIG_ARCH_CHIP_KINETIS is not set
|
||||
# CONFIG_ARCH_CHIP_KL is not set
|
||||
# CONFIG_ARCH_CHIP_LM is not set
|
||||
# CONFIG_ARCH_CHIP_LPC17XX is not set
|
||||
# CONFIG_ARCH_CHIP_LPC214X is not set
|
||||
# CONFIG_ARCH_CHIP_LPC2378 is not set
|
||||
# CONFIG_ARCH_CHIP_LPC31XX is not set
|
||||
# CONFIG_ARCH_CHIP_LPC43XX is not set
|
||||
# CONFIG_ARCH_CHIP_NUC1XX is not set
|
||||
# CONFIG_ARCH_CHIP_SAM34 is not set
|
||||
CONFIG_ARCH_CHIP_STM32=y
|
||||
# CONFIG_ARCH_CHIP_STR71X is not set
|
||||
CONFIG_ARCH_CORTEXM4=y
|
||||
CONFIG_ARCH_FAMILY="armv7-m"
|
||||
CONFIG_ARCH_CHIP="stm32"
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARCH_HAVE_CMNVECTOR=y
|
||||
CONFIG_ARMV7M_CMNVECTOR=y
|
||||
CONFIG_ARCH_HAVE_FPU=y
|
||||
CONFIG_ARCH_FPU=y
|
||||
CONFIG_ARCH_HAVE_MPU=y
|
||||
# CONFIG_ARMV7M_MPU is not set
|
||||
|
||||
#
|
||||
# ARMV7M Configuration Options
|
||||
#
|
||||
# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
|
||||
# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
|
||||
# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set
|
||||
CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y
|
||||
# CONFIG_ARMV7M_STACKCHECK is not set
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
|
||||
#
|
||||
# STM32 Configuration Options
|
||||
#
|
||||
# CONFIG_ARCH_CHIP_STM32L151C6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151C8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151CB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151R6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151R8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151RB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151V6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151V8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L151VB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152C6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152C8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152CB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152R6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152R8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152RB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152V6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152V8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32L152VB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100C8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100CB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100R8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100RB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100RC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100RD is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100RE is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100V8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100VB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100VC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100VD is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F100VE is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F102CB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103C4 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103C8 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103RET6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103VET6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F107VC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F207IG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302CB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302CC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302RB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302RC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302VB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F302VC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303CB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303CC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303RB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303RC is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303VB is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F303VC is not set
|
||||
CONFIG_ARCH_CHIP_STM32F405RG=y
|
||||
# CONFIG_ARCH_CHIP_STM32F405VG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F405ZG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F407VE is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F407VG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F407ZE is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F407ZG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F407IE is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F407IG is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F427V is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F427Z is not set
|
||||
# CONFIG_ARCH_CHIP_STM32F427I is not set
|
||||
# CONFIG_STM32_STM32L15XX is not set
|
||||
# CONFIG_STM32_ENERGYLITE is not set
|
||||
# CONFIG_STM32_STM32F10XX is not set
|
||||
# CONFIG_STM32_VALUELINE is not set
|
||||
# CONFIG_STM32_CONNECTIVITYLINE is not set
|
||||
# CONFIG_STM32_PERFORMANCELINE is not set
|
||||
# CONFIG_STM32_HIGHDENSITY is not set
|
||||
# CONFIG_STM32_MEDIUMDENSITY is not set
|
||||
# CONFIG_STM32_LOWDENSITY is not set
|
||||
# CONFIG_STM32_STM32F20XX is not set
|
||||
# CONFIG_STM32_STM32F30XX is not set
|
||||
CONFIG_STM32_STM32F40XX=y
|
||||
# CONFIG_STM32_DFU is not set
|
||||
|
||||
#
|
||||
# STM32 Peripheral Support
|
||||
#
|
||||
CONFIG_STM32_ADC1=y
|
||||
# CONFIG_STM32_ADC2 is not set
|
||||
# CONFIG_STM32_ADC3 is not set
|
||||
CONFIG_STM32_BKPSRAM=y
|
||||
# CONFIG_STM32_CAN1 is not set
|
||||
# CONFIG_STM32_CAN2 is not set
|
||||
CONFIG_STM32_CCMDATARAM=y
|
||||
# CONFIG_STM32_CRC is not set
|
||||
# CONFIG_STM32_CRYP is not set
|
||||
CONFIG_STM32_DMA1=y
|
||||
CONFIG_STM32_DMA2=y
|
||||
# CONFIG_STM32_DAC1 is not set
|
||||
# CONFIG_STM32_DAC2 is not set
|
||||
# CONFIG_STM32_DCMI is not set
|
||||
# CONFIG_STM32_ETHMAC is not set
|
||||
# CONFIG_STM32_FSMC is not set
|
||||
# CONFIG_STM32_HASH is not set
|
||||
CONFIG_STM32_I2C1=y
|
||||
CONFIG_STM32_I2C2=y
|
||||
CONFIG_STM32_I2C3=y
|
||||
CONFIG_STM32_OTGFS=y
|
||||
# CONFIG_STM32_OTGHS is not set
|
||||
CONFIG_STM32_PWR=y
|
||||
# CONFIG_STM32_RNG is not set
|
||||
# CONFIG_STM32_SDIO is not set
|
||||
# CONFIG_STM32_SPI1 is not set
|
||||
CONFIG_STM32_SPI2=y
|
||||
# CONFIG_STM32_SPI3 is not set
|
||||
CONFIG_STM32_SYSCFG=y
|
||||
# CONFIG_STM32_TIM1 is not set
|
||||
# CONFIG_STM32_TIM2 is not set
|
||||
# CONFIG_STM32_TIM3 is not set
|
||||
CONFIG_STM32_TIM4=y
|
||||
CONFIG_STM32_TIM5=y
|
||||
CONFIG_STM32_TIM6=y
|
||||
CONFIG_STM32_TIM7=y
|
||||
# CONFIG_STM32_TIM8 is not set
|
||||
CONFIG_STM32_TIM9=y
|
||||
CONFIG_STM32_TIM10=y
|
||||
CONFIG_STM32_TIM11=y
|
||||
CONFIG_STM32_TIM12=y
|
||||
CONFIG_STM32_TIM13=y
|
||||
CONFIG_STM32_TIM14=y
|
||||
CONFIG_STM32_USART1=y
|
||||
CONFIG_STM32_USART2=y
|
||||
CONFIG_STM32_USART3=y
|
||||
CONFIG_STM32_UART4=y
|
||||
CONFIG_STM32_UART5=y
|
||||
CONFIG_STM32_USART6=y
|
||||
# CONFIG_STM32_IWDG is not set
|
||||
CONFIG_STM32_WWDG=y
|
||||
CONFIG_STM32_ADC=y
|
||||
CONFIG_STM32_SPI=y
|
||||
CONFIG_STM32_I2C=y
|
||||
|
||||
#
|
||||
# Alternate Pin Mapping
|
||||
#
|
||||
CONFIG_STM32_FLASH_PREFETCH=y
|
||||
# CONFIG_STM32_JTAG_DISABLE is not set
|
||||
# CONFIG_STM32_JTAG_FULL_ENABLE is not set
|
||||
# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
|
||||
CONFIG_STM32_JTAG_SW_ENABLE=y
|
||||
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
|
||||
# CONFIG_STM32_FORCEPOWER is not set
|
||||
# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
|
||||
# CONFIG_STM32_CCMEXCLUDE is not set
|
||||
CONFIG_STM32_DMACAPABLE=y
|
||||
# CONFIG_STM32_TIM4_PWM is not set
|
||||
# CONFIG_STM32_TIM5_PWM is not set
|
||||
# CONFIG_STM32_TIM9_PWM is not set
|
||||
# CONFIG_STM32_TIM10_PWM is not set
|
||||
# CONFIG_STM32_TIM11_PWM is not set
|
||||
# CONFIG_STM32_TIM12_PWM is not set
|
||||
# CONFIG_STM32_TIM13_PWM is not set
|
||||
# CONFIG_STM32_TIM14_PWM is not set
|
||||
# CONFIG_STM32_TIM4_ADC is not set
|
||||
# CONFIG_STM32_TIM5_ADC is not set
|
||||
CONFIG_STM32_USART=y
|
||||
|
||||
#
|
||||
# U[S]ART Configuration
|
||||
#
|
||||
# CONFIG_USART1_RS485 is not set
|
||||
CONFIG_USART1_RXDMA=y
|
||||
# CONFIG_USART2_RS485 is not set
|
||||
CONFIG_USART2_RXDMA=y
|
||||
# CONFIG_USART3_RS485 is not set
|
||||
CONFIG_USART3_RXDMA=y
|
||||
# CONFIG_UART4_RS485 is not set
|
||||
CONFIG_UART4_RXDMA=y
|
||||
# CONFIG_UART5_RS485 is not set
|
||||
CONFIG_UART5_RXDMA=y
|
||||
# CONFIG_USART6_RS485 is not set
|
||||
CONFIG_USART6_RXDMA=y
|
||||
CONFIG_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32_USART_SINGLEWIRE=y
|
||||
|
||||
#
|
||||
# SPI Configuration
|
||||
#
|
||||
# CONFIG_STM32_SPI_INTERRUPTS is not set
|
||||
# CONFIG_STM32_SPI_DMA is not set
|
||||
|
||||
#
|
||||
# I2C Configuration
|
||||
#
|
||||
# CONFIG_STM32_I2C_DYNTIMEO is not set
|
||||
CONFIG_STM32_I2CTIMEOSEC=0
|
||||
CONFIG_STM32_I2CTIMEOMS=10
|
||||
# CONFIG_STM32_I2CTIMEOTICKS is not set (PX4 Codbase has this)
|
||||
# CONFIG_STM32_I2C_DUTY16_9 is not set
|
||||
|
||||
#
|
||||
# USB Host Configuration
|
||||
#
|
||||
|
||||
#
|
||||
# USB Device Configuration
|
||||
#
|
||||
|
||||
#
|
||||
# External Memory Configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Architecture Options
|
||||
#
|
||||
# CONFIG_ARCH_NOINTC is not set
|
||||
# CONFIG_ARCH_VECNOTIRQ is not set
|
||||
CONFIG_ARCH_DMA=y
|
||||
CONFIG_ARCH_IRQPRIO=y
|
||||
# CONFIG_CUSTOM_STACK is not set
|
||||
# CONFIG_ADDRENV is not set
|
||||
CONFIG_ARCH_HAVE_VFORK=y
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
# CONFIG_ENDIAN_BIG is not set
|
||||
# CONFIG_ARCH_HAVE_RAMFUNCS is not set
|
||||
CONFIG_ARCH_HAVE_RAMVECTORS=y
|
||||
# CONFIG_ARCH_RAMVECTORS is not set
|
||||
|
||||
#
|
||||
# Board Settings
|
||||
#
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
# CONFIG_ARCH_CALIBRATION is not set
|
||||
CONFIG_DRAM_START=0x20000000
|
||||
CONFIG_DRAM_SIZE=196608
|
||||
CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=750
|
||||
|
||||
#
|
||||
# Boot options
|
||||
#
|
||||
# CONFIG_BOOT_RUNFROMEXTSRAM is not set
|
||||
CONFIG_BOOT_RUNFROMFLASH=y
|
||||
# CONFIG_BOOT_RUNFROMISRAM is not set
|
||||
# CONFIG_BOOT_RUNFROMSDRAM is not set
|
||||
# CONFIG_BOOT_COPYTORAM is not set
|
||||
|
||||
#
|
||||
# Board Selection
|
||||
#
|
||||
CONFIG_ARCH_BOARD_ASC_V1=y
|
||||
CONFIG_ARCH_BOARD="asc-v1"
|
||||
|
||||
#
|
||||
# Common Board Options
|
||||
#
|
||||
# CONFIG_NSH_MMCSDMINOR=0
|
||||
# CONFIG_NSH_MMCSDSLOTNO=0
|
||||
# CONFIG_NSH_MMCSDSPIPORTNO=2
|
||||
|
||||
#
|
||||
# Board-Specific Options
|
||||
#
|
||||
|
||||
#
|
||||
# RTOS Features
|
||||
#
|
||||
# CONFIG_BOARD_INITIALIZE is not set
|
||||
CONFIG_MSEC_PER_TICK=1
|
||||
CONFIG_RR_INTERVAL=0
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
# CONFIG_SCHED_HAVE_PARENT is not set
|
||||
# CONFIG_JULIAN_TIME is not set
|
||||
CONFIG_START_YEAR=1970
|
||||
CONFIG_START_MONTH=1
|
||||
CONFIG_START_DAY=1
|
||||
CONFIG_DEV_CONSOLE=y
|
||||
# CONFIG_MUTEX_TYPES is not set
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||
CONFIG_SEM_NNESTPRIO=8
|
||||
# CONFIG_FDCLONE_DISABLE is not set
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_SDCLONE_DISABLE=y
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
# CONFIG_SCHED_STARTHOOK is not set
|
||||
CONFIG_SCHED_ATEXIT=y
|
||||
CONFIG_SCHED_ATEXIT_MAX=1
|
||||
# CONFIG_SCHED_ONEXIT is not set
|
||||
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||
# CONFIG_DISABLE_OS_API is not set
|
||||
|
||||
#
|
||||
# Signal Numbers
|
||||
#
|
||||
CONFIG_SIG_SIGUSR1=1
|
||||
CONFIG_SIG_SIGUSR2=2
|
||||
CONFIG_SIG_SIGALARM=3
|
||||
CONFIG_SIG_SIGCONDTIMEDOUT=16
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
|
||||
#
|
||||
# Sizes of configurable things (0 disables)
|
||||
#
|
||||
CONFIG_MAX_TASKS=32
|
||||
CONFIG_MAX_TASK_ARGS=10
|
||||
CONFIG_NPTHREAD_KEYS=4
|
||||
CONFIG_NFILE_DESCRIPTORS=46
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NAME_MAX=32
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
CONFIG_MQ_MAXMSGSIZE=32
|
||||
CONFIG_MAX_WDOGPARMS=2
|
||||
CONFIG_PREALLOC_WDOGS=50
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
|
||||
#
|
||||
# Stack and heap information
|
||||
#
|
||||
CONFIG_IDLETHREAD_STACKSIZE=1000
|
||||
CONFIG_USERMAIN_STACKSIZE=2500
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_PTHREAD_STACK_DEFAULT=2048
|
||||
|
||||
#
|
||||
# Device Drivers
|
||||
#
|
||||
# CONFIG_DISABLE_POLL is not set
|
||||
CONFIG_DEV_NULL=y
|
||||
# CONFIG_DEV_ZERO is not set
|
||||
# CONFIG_LOOP is not set
|
||||
# CONFIG_RAMDISK is not set
|
||||
# CONFIG_CAN is not set
|
||||
# CONFIG_PWM is not set
|
||||
CONFIG_I2C=y
|
||||
# CONFIG_I2C_SLAVE is not set
|
||||
CONFIG_I2C_TRANSFER=y
|
||||
# CONFIG_I2C_WRITEREAD is not set
|
||||
# CONFIG_I2C_POLLED is not set
|
||||
# CONFIG_I2C_TRACE is not set
|
||||
CONFIG_ARCH_HAVE_I2CRESET=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_SPI=y
|
||||
# CONFIG_SPI_OWNBUS is not set
|
||||
CONFIG_SPI_EXCHANGE=y
|
||||
# CONFIG_SPI_CMDDATA is not set
|
||||
# CONFIG_RTC is not set
|
||||
CONFIG_WATCHDOG=y
|
||||
# CONFIG_ANALOG is not set
|
||||
# CONFIG_AUDIO_DEVICES is not set
|
||||
# CONFIG_BCH is not set
|
||||
# CONFIG_INPUT is not set
|
||||
# CONFIG_LCD is not set
|
||||
# CONFIG_MMCSD is not set
|
||||
# CONFIG_MMCSD_NSLOTS=1
|
||||
# CONFIG_MMCSD_READONLY is not set
|
||||
# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_HAVECARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_SDIOWAIT_WRCOMPLETE is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_MMCSD_SPICLOCK=24000000
|
||||
# CONFIG_MMCSD_SDIO is not set
|
||||
# CONFIG_MTD is not set
|
||||
CONFIG_PIPES=y
|
||||
# CONFIG_PM is not set
|
||||
# CONFIG_POWER is not set
|
||||
# CONFIG_SENSORS is not set
|
||||
CONFIG_SERIAL=y
|
||||
# CONFIG_DEV_LOWCONSOLE is not set
|
||||
CONFIG_SERIAL_REMOVABLE=y
|
||||
# CONFIG_16550_UART is not set
|
||||
CONFIG_ARCH_HAVE_UART4=y
|
||||
CONFIG_ARCH_HAVE_UART5=y
|
||||
CONFIG_ARCH_HAVE_USART1=y
|
||||
CONFIG_ARCH_HAVE_USART2=y
|
||||
CONFIG_ARCH_HAVE_USART3=y
|
||||
CONFIG_ARCH_HAVE_USART6=y
|
||||
CONFIG_MCU_SERIAL=y
|
||||
CONFIG_STANDARD_SERIAL=y
|
||||
CONFIG_SERIAL_NPOLLWAITERS=2
|
||||
# CONFIG_USART1_SERIAL_CONSOLE is not set
|
||||
# CONFIG_USART2_SERIAL_CONSOLE is not set
|
||||
CONFIG_USART3_SERIAL_CONSOLE=y
|
||||
# CONFIG_UART4_SERIAL_CONSOLE is not set
|
||||
# CONFIG_UART5_SERIAL_CONSOLE is not set
|
||||
# CONFIG_USART6_SERIAL_CONSOLE is not set
|
||||
# CONFIG_NO_SERIAL_CONSOLE is not set
|
||||
|
||||
#
|
||||
# USART1 Configuration
|
||||
#
|
||||
CONFIG_USART1_RXBUFSIZE=128
|
||||
CONFIG_USART1_TXBUFSIZE=128
|
||||
CONFIG_USART1_BAUD=57600
|
||||
CONFIG_USART1_BITS=8
|
||||
CONFIG_USART1_PARITY=0
|
||||
CONFIG_USART1_2STOP=0
|
||||
# CONFIG_USART1_IFLOWCONTROL is not set
|
||||
# CONFIG_USART1_OFLOWCONTROL is not set
|
||||
|
||||
#
|
||||
# USART2 Configuration
|
||||
#
|
||||
CONFIG_USART2_RXBUFSIZE=300
|
||||
CONFIG_USART2_TXBUFSIZE=300
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_BITS=8
|
||||
CONFIG_USART2_PARITY=0
|
||||
CONFIG_USART2_2STOP=0
|
||||
# CONFIG_USART2_IFLOWCONTROL is not set
|
||||
# CONFIG_USART2_OFLOWCONTROL is not set
|
||||
|
||||
#
|
||||
# USART3 Configuration
|
||||
#
|
||||
CONFIG_USART3_RXBUFSIZE=256
|
||||
CONFIG_USART3_TXBUFSIZE=256
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_BITS=8
|
||||
CONFIG_USART3_PARITY=0
|
||||
CONFIG_USART3_2STOP=0
|
||||
# CONFIG_USART3_IFLOWCONTROL is not set
|
||||
# CONFIG_USART3_OFLOWCONTROL is not set
|
||||
|
||||
#
|
||||
# UART4 Configuration
|
||||
#
|
||||
CONFIG_UART4_RXBUFSIZE=256
|
||||
CONFIG_UART4_TXBUFSIZE=256
|
||||
CONFIG_UART4_BAUD=115200
|
||||
CONFIG_UART4_BITS=8
|
||||
CONFIG_UART4_PARITY=0
|
||||
CONFIG_UART4_2STOP=0
|
||||
# CONFIG_UART4_IFLOWCONTROL is not set
|
||||
# CONFIG_UART4_OFLOWCONTROL is not set
|
||||
|
||||
#
|
||||
# UART5 Configuration
|
||||
#
|
||||
CONFIG_UART5_RXBUFSIZE=300
|
||||
CONFIG_UART5_TXBUFSIZE=300
|
||||
CONFIG_UART5_BAUD=57600
|
||||
CONFIG_UART5_BITS=8
|
||||
CONFIG_UART5_PARITY=0
|
||||
CONFIG_UART5_2STOP=0
|
||||
# CONFIG_UART5_IFLOWCONTROL is not set
|
||||
# CONFIG_UART5_OFLOWCONTROL is not set
|
||||
|
||||
#
|
||||
# USART6 Configuration
|
||||
#
|
||||
CONFIG_USART6_RXBUFSIZE=128
|
||||
CONFIG_USART6_TXBUFSIZE=64
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_BITS=8
|
||||
CONFIG_USART6_PARITY=0
|
||||
CONFIG_USART6_2STOP=0
|
||||
# CONFIG_USART6_IFLOWCONTROL is not set
|
||||
# CONFIG_USART6_OFLOWCONTROL is not set
|
||||
# CONFIG_SERIAL_IFLOWCONTROL is not set
|
||||
# CONFIG_SERIAL_OFLOWCONTROL is not set
|
||||
CONFIG_USBDEV=y
|
||||
|
||||
#
|
||||
# USB Device Controller Driver Options
|
||||
#
|
||||
# CONFIG_USBDEV_ISOCHRONOUS is not set
|
||||
# CONFIG_USBDEV_DUALSPEED is not set
|
||||
# CONFIG_USBDEV_SELFPOWERED is not set
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
# CONFIG_USBDEV_DMA is not set
|
||||
# CONFIG_USBDEV_TRACE is not set
|
||||
|
||||
#
|
||||
# USB Device Class Driver Options
|
||||
#
|
||||
# CONFIG_USBDEV_COMPOSITE is not set
|
||||
# CONFIG_PL2303 is not set
|
||||
CONFIG_CDCACM=y
|
||||
# CONFIG_CDCACM_CONSOLE is not set
|
||||
CONFIG_CDCACM_EP0MAXPACKET=64
|
||||
CONFIG_CDCACM_EPINTIN=1
|
||||
CONFIG_CDCACM_EPINTIN_FSSIZE=64
|
||||
CONFIG_CDCACM_EPINTIN_HSSIZE=64
|
||||
CONFIG_CDCACM_EPBULKOUT=3
|
||||
CONFIG_CDCACM_EPBULKOUT_FSSIZE=64
|
||||
CONFIG_CDCACM_EPBULKOUT_HSSIZE=512
|
||||
CONFIG_CDCACM_EPBULKIN=2
|
||||
CONFIG_CDCACM_EPBULKIN_FSSIZE=64
|
||||
CONFIG_CDCACM_EPBULKIN_HSSIZE=512
|
||||
CONFIG_CDCACM_NWRREQS=4
|
||||
CONFIG_CDCACM_NRDREQS=4
|
||||
CONFIG_CDCACM_BULKIN_REQLEN=96
|
||||
CONFIG_CDCACM_RXBUFSIZE=300
|
||||
CONFIG_CDCACM_TXBUFSIZE=1000
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
CONFIG_CDCACM_PRODUCTID=0x0040
|
||||
CONFIG_CDCACM_VENDORSTR="The Autopilot"
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 ASC v1.x"
|
||||
# CONFIG_USBMSC is not set
|
||||
# CONFIG_USBHOST is not set
|
||||
# CONFIG_WIRELESS is not set
|
||||
|
||||
#
|
||||
# System Logging Device Options
|
||||
#
|
||||
|
||||
#
|
||||
# System Logging
|
||||
#
|
||||
# CONFIG_RAMLOG is not set
|
||||
|
||||
#
|
||||
# Networking Support
|
||||
#
|
||||
# CONFIG_NET is not set
|
||||
|
||||
#
|
||||
# File Systems
|
||||
#
|
||||
|
||||
#
|
||||
# File system configuration
|
||||
#
|
||||
# CONFIG_DISABLE_MOUNTPOINT is not set
|
||||
# CONFIG_FS_RAMMAP is not set
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_MAXFNAME=32
|
||||
CONFIG_FS_FATTIME=y
|
||||
# CONFIG_FAT_DMAMEMORY is not set
|
||||
# CONFIG_FS_NXFFS is not set
|
||||
CONFIG_FS_ROMFS=y
|
||||
# CONFIG_FS_SMARTFS is not set
|
||||
CONFIG_FS_BINFS=y
|
||||
|
||||
#
|
||||
# System Logging
|
||||
#
|
||||
# CONFIG_SYSLOG_ENABLE is not set
|
||||
# CONFIG_SYSLOG is not set
|
||||
|
||||
#
|
||||
# Graphics Support
|
||||
#
|
||||
# CONFIG_NX is not set
|
||||
|
||||
#
|
||||
# Memory Management
|
||||
#
|
||||
# CONFIG_MM_MULTIHEAP is not set
|
||||
# CONFIG_MM_SMALL is not set
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_GRAN=y
|
||||
# CONFIG_GRAN_SINGLE is not set
|
||||
# CONFIG_GRAN_INTR is not set
|
||||
|
||||
#
|
||||
# Audio Support
|
||||
#
|
||||
# CONFIG_AUDIO is not set
|
||||
|
||||
#
|
||||
# Binary Formats
|
||||
#
|
||||
# CONFIG_BINFMT_DISABLE is not set
|
||||
# CONFIG_BINFMT_EXEPATH is not set
|
||||
# CONFIG_NXFLAT is not set
|
||||
# CONFIG_ELF is not set
|
||||
CONFIG_BUILTIN=y
|
||||
# CONFIG_PIC is not set
|
||||
# CONFIG_SYMTAB_ORDEREDBYNAME is not set
|
||||
|
||||
#
|
||||
# Library Routines
|
||||
#
|
||||
|
||||
#
|
||||
# Standard C Library Options
|
||||
#
|
||||
CONFIG_STDIO_BUFFER_SIZE=180
|
||||
CONFIG_STDIO_LINEBUFFER=y
|
||||
CONFIG_NUNGET_CHARS=2
|
||||
CONFIG_LIB_HOMEDIR="/"
|
||||
# CONFIG_NOPRINTF_FIELDWIDTH is not set
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIB_RAND_ORDER=1
|
||||
# CONFIG_EOL_IS_CR is not set
|
||||
# CONFIG_EOL_IS_LF is not set
|
||||
# CONFIG_EOL_IS_BOTH_CRLF is not set
|
||||
CONFIG_EOL_IS_EITHER_CRLF=y
|
||||
# CONFIG_LIBC_EXECFUNCS is not set
|
||||
CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
|
||||
CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
# CONFIG_LIBC_STRERROR_SHORT is not set
|
||||
# CONFIG_LIBC_PERROR_STDOUT is not set
|
||||
CONFIG_ARCH_LOWPUTC=y
|
||||
CONFIG_LIB_SENDFILE_BUFSIZE=512
|
||||
# CONFIG_ARCH_ROMGETC is not set
|
||||
CONFIG_ARCH_OPTIMIZED_FUNCTIONS=y
|
||||
CONFIG_ARCH_MEMCPY=y
|
||||
# CONFIG_ARCH_MEMCMP is not set
|
||||
# CONFIG_ARCH_MEMMOVE is not set
|
||||
# CONFIG_ARCH_MEMSET is not set
|
||||
# CONFIG_MEMSET_OPTSPEED is not set
|
||||
# CONFIG_ARCH_STRCHR is not set
|
||||
# CONFIG_ARCH_STRCMP is not set
|
||||
# CONFIG_ARCH_STRCPY is not set
|
||||
# CONFIG_ARCH_STRNCPY is not set
|
||||
# CONFIG_ARCH_STRLEN is not set
|
||||
# CONFIG_ARCH_STRNLEN is not set
|
||||
# CONFIG_ARCH_BZERO is not set
|
||||
|
||||
#
|
||||
# Non-standard Library Support
|
||||
#
|
||||
CONFIG_SCHED_WORKQUEUE=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_WORKPRIORITY=192
|
||||
CONFIG_SCHED_WORKPERIOD=5000
|
||||
CONFIG_SCHED_WORKSTACKSIZE=1600
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKPERIOD=50000
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1600
|
||||
# CONFIG_LIB_KBDCODEC is not set
|
||||
# CONFIG_LIB_SLCDCODEC is not set
|
||||
|
||||
#
|
||||
# Basic CXX Support
|
||||
#
|
||||
CONFIG_C99_BOOL8=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
# CONFIG_CXX_NEWLONG is not set
|
||||
|
||||
#
|
||||
# uClibc++ Standard C++ Library
|
||||
#
|
||||
# CONFIG_UCLIBCXX is not set
|
||||
|
||||
#
|
||||
# Application Configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Built-In Applications
|
||||
#
|
||||
CONFIG_BUILTIN_PROXY_STACKSIZE=1024
|
||||
|
||||
#
|
||||
# Examples
|
||||
#
|
||||
# CONFIG_EXAMPLES_BUTTONS is not set
|
||||
# CONFIG_EXAMPLES_CAN is not set
|
||||
CONFIG_EXAMPLES_CDCACM=y
|
||||
# CONFIG_EXAMPLES_COMPOSITE is not set
|
||||
# CONFIG_EXAMPLES_CXXTEST is not set
|
||||
# CONFIG_EXAMPLES_DHCPD is not set
|
||||
# CONFIG_EXAMPLES_ELF is not set
|
||||
# CONFIG_EXAMPLES_FTPC is not set
|
||||
# CONFIG_EXAMPLES_FTPD is not set
|
||||
# CONFIG_EXAMPLES_HELLO is not set
|
||||
# CONFIG_EXAMPLES_HELLOXX is not set
|
||||
# CONFIG_EXAMPLES_JSON is not set
|
||||
# CONFIG_EXAMPLES_HIDKBD is not set
|
||||
# CONFIG_EXAMPLES_KEYPADTEST is not set
|
||||
# CONFIG_EXAMPLES_IGMP is not set
|
||||
# CONFIG_EXAMPLES_LCDRW is not set
|
||||
# CONFIG_EXAMPLES_MM is not set
|
||||
# CONFIG_EXAMPLES_MODBUS is not set
|
||||
CONFIG_EXAMPLES_MOUNT=y
|
||||
# CONFIG_EXAMPLES_NRF24L01TERM is not set
|
||||
CONFIG_EXAMPLES_NSH=y
|
||||
# CONFIG_EXAMPLES_NULL is not set
|
||||
# CONFIG_EXAMPLES_NX is not set
|
||||
# CONFIG_EXAMPLES_NXCONSOLE is not set
|
||||
# CONFIG_EXAMPLES_NXFFS is not set
|
||||
# CONFIG_EXAMPLES_NXFLAT is not set
|
||||
# CONFIG_EXAMPLES_NXHELLO is not set
|
||||
# CONFIG_EXAMPLES_NXIMAGE is not set
|
||||
# CONFIG_EXAMPLES_NXLINES is not set
|
||||
# CONFIG_EXAMPLES_NXTEXT is not set
|
||||
# CONFIG_EXAMPLES_OSTEST is not set
|
||||
# CONFIG_EXAMPLES_PASHELLO is not set
|
||||
# CONFIG_EXAMPLES_PIPE is not set
|
||||
# CONFIG_EXAMPLES_POSIXSPAWN is not set
|
||||
# CONFIG_EXAMPLES_QENCODER is not set
|
||||
# CONFIG_EXAMPLES_RGMP is not set
|
||||
# CONFIG_EXAMPLES_ROMFS is not set
|
||||
# CONFIG_EXAMPLES_SENDMAIL is not set
|
||||
# CONFIG_EXAMPLES_SERLOOP is not set
|
||||
# CONFIG_EXAMPLES_SLCD is not set
|
||||
# CONFIG_EXAMPLES_SMART_TEST is not set
|
||||
# CONFIG_EXAMPLES_SMART is not set
|
||||
# CONFIG_EXAMPLES_TCPECHO is not set
|
||||
# CONFIG_EXAMPLES_TELNETD is not set
|
||||
# CONFIG_EXAMPLES_THTTPD is not set
|
||||
# CONFIG_EXAMPLES_TIFF is not set
|
||||
# CONFIG_EXAMPLES_TOUCHSCREEN is not set
|
||||
# CONFIG_EXAMPLES_UDP is not set
|
||||
# CONFIG_EXAMPLES_UIP is not set
|
||||
# CONFIG_EXAMPLES_USBSERIAL is not set
|
||||
# CONFIG_EXAMPLES_USBMSC is not set
|
||||
# CONFIG_EXAMPLES_USBTERM is not set
|
||||
# CONFIG_EXAMPLES_WATCHDOG is not set
|
||||
|
||||
#
|
||||
# Graphics Support
|
||||
#
|
||||
# CONFIG_TIFF is not set
|
||||
|
||||
#
|
||||
# Interpreters
|
||||
#
|
||||
# CONFIG_INTERPRETERS_FICL is not set
|
||||
# CONFIG_INTERPRETERS_PCODE is not set
|
||||
|
||||
#
|
||||
# Network Utilities
|
||||
#
|
||||
|
||||
#
|
||||
# Networking Utilities
|
||||
#
|
||||
# CONFIG_NETUTILS_CODECS is not set
|
||||
# CONFIG_NETUTILS_DHCPC is not set
|
||||
# CONFIG_NETUTILS_DHCPD is not set
|
||||
# CONFIG_NETUTILS_FTPC is not set
|
||||
# CONFIG_NETUTILS_FTPD is not set
|
||||
# CONFIG_NETUTILS_JSON is not set
|
||||
# CONFIG_NETUTILS_RESOLV is not set
|
||||
# CONFIG_NETUTILS_SMTP is not set
|
||||
# CONFIG_NETUTILS_TELNETD is not set
|
||||
# CONFIG_NETUTILS_TFTPC is not set
|
||||
# CONFIG_NETUTILS_THTTPD is not set
|
||||
# CONFIG_NETUTILS_UIPLIB is not set
|
||||
# CONFIG_NETUTILS_WEBCLIENT is not set
|
||||
|
||||
#
|
||||
# FreeModBus
|
||||
#
|
||||
# CONFIG_MODBUS is not set
|
||||
|
||||
#
|
||||
# NSH Library
|
||||
#
|
||||
CONFIG_NSH_LIBRARY=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
|
||||
#
|
||||
# Disable Individual commands
|
||||
#
|
||||
# CONFIG_NSH_DISABLE_CAT is not set
|
||||
# CONFIG_NSH_DISABLE_CD is not set
|
||||
# CONFIG_NSH_DISABLE_CP is not set
|
||||
# CONFIG_NSH_DISABLE_DD is not set
|
||||
# CONFIG_NSH_DISABLE_ECHO is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXIT is not set
|
||||
# CONFIG_NSH_DISABLE_FREE is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_HELP is not set
|
||||
# CONFIG_NSH_DISABLE_HEXDUMP is not set
|
||||
CONFIG_NSH_DISABLE_IFCONFIG=y
|
||||
# CONFIG_NSH_DISABLE_KILL is not set
|
||||
CONFIG_NSH_DISABLE_LOSETUP=y
|
||||
# CONFIG_NSH_DISABLE_LS is not set
|
||||
# CONFIG_NSH_DISABLE_MB is not set
|
||||
# CONFIG_NSH_DISABLE_MKDIR is not set
|
||||
# CONFIG_NSH_DISABLE_MKFATFS is not set
|
||||
# CONFIG_NSH_DISABLE_MKFIFO is not set
|
||||
# CONFIG_NSH_DISABLE_MKRD is not set
|
||||
# CONFIG_NSH_DISABLE_MH is not set
|
||||
# CONFIG_NSH_DISABLE_MOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_MW is not set
|
||||
CONFIG_NSH_DISABLE_NSFMOUNT=y
|
||||
# CONFIG_NSH_DISABLE_PS is not set
|
||||
CONFIG_NSH_DISABLE_PING=y
|
||||
CONFIG_NSH_DISABLE_PUT=y
|
||||
# CONFIG_NSH_DISABLE_PWD is not set
|
||||
# CONFIG_NSH_DISABLE_RM is not set
|
||||
# CONFIG_NSH_DISABLE_RMDIR is not set
|
||||
# CONFIG_NSH_DISABLE_SET is not set
|
||||
# CONFIG_NSH_DISABLE_SH is not set
|
||||
# CONFIG_NSH_DISABLE_SLEEP is not set
|
||||
# CONFIG_NSH_DISABLE_TEST is not set
|
||||
# CONFIG_NSH_DISABLE_UMOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_UNSET is not set
|
||||
# CONFIG_NSH_DISABLE_USLEEP is not set
|
||||
CONFIG_NSH_DISABLE_WGET=y
|
||||
# CONFIG_NSH_DISABLE_XD is not set
|
||||
|
||||
#
|
||||
# Configure Command Options
|
||||
#
|
||||
# CONFIG_NSH_CMDOPT_DF_H is not set
|
||||
CONFIG_NSH_CODECS_BUFSIZE=128
|
||||
CONFIG_NSH_FILEIOSIZE=512
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=12
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
# CONFIG_NSH_ROMFSRC is not set
|
||||
CONFIG_NSH_ROMFSMOUNTPT="/etc"
|
||||
CONFIG_NSH_INITSCRIPT="init.d/rcS"
|
||||
CONFIG_NSH_ROMFSDEVNO=0
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_ARCHROMFS=y
|
||||
CONFIG_NSH_FATDEVNO=1
|
||||
CONFIG_NSH_FATSECTSIZE=512
|
||||
CONFIG_NSH_FATNSECTORS=1024
|
||||
CONFIG_NSH_FATMOUNTPT="/tmp"
|
||||
CONFIG_NSH_CONSOLE=y
|
||||
# CONFIG_NSH_USBCONSOLE is not set
|
||||
|
||||
#
|
||||
# USB Trace Support
|
||||
#
|
||||
# CONFIG_NSH_CONDEV is not set
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
|
||||
#
|
||||
# NxWidgets/NxWM
|
||||
#
|
||||
|
||||
#
|
||||
# System NSH Add-Ons
|
||||
#
|
||||
|
||||
#
|
||||
# Custom Free Memory Command
|
||||
#
|
||||
# CONFIG_SYSTEM_FREE is not set
|
||||
|
||||
#
|
||||
# I2C tool
|
||||
#
|
||||
# CONFIG_SYSTEM_I2CTOOL is not set
|
||||
|
||||
#
|
||||
# FLASH Program Installation
|
||||
#
|
||||
# CONFIG_SYSTEM_INSTALL is not set
|
||||
|
||||
#
|
||||
# FLASH Erase-all Command
|
||||
#
|
||||
|
||||
#
|
||||
# readline()
|
||||
#
|
||||
CONFIG_SYSTEM_READLINE=y
|
||||
CONFIG_READLINE_ECHO=y
|
||||
|
||||
#
|
||||
# Power Off
|
||||
#
|
||||
# CONFIG_SYSTEM_POWEROFF is not set
|
||||
|
||||
#
|
||||
# RAMTRON
|
||||
#
|
||||
# CONFIG_SYSTEM_RAMTRON is not set
|
||||
|
||||
#
|
||||
# SD Card
|
||||
#
|
||||
# CONFIG_SYSTEM_SDCARD is not set
|
||||
|
||||
#
|
||||
# Sysinfo
|
||||
#
|
||||
CONFIG_SYSTEM_SYSINFO=y
|
||||
|
||||
#
|
||||
# USB Monitor
|
||||
#
|
|
@ -0,0 +1,75 @@
|
|||
#!/bin/bash
|
||||
# configs/px4fmu-v1/usbnsh/setenv.sh
|
||||
#
|
||||
# Copyright (C) 2013 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# 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 NuttX 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.
|
||||
#
|
||||
|
||||
if [ "$_" = "$0" ] ; then
|
||||
echo "You must source this script, not run it!" 1>&2
|
||||
exit 1
|
||||
fi
|
||||
|
||||
WD=`pwd`
|
||||
if [ ! -x "setenv.sh" ]; then
|
||||
echo "This script must be executed from the top-level NuttX build directory"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
if [ -z "${PATH_ORIG}" ]; then
|
||||
export PATH_ORIG="${PATH}"
|
||||
fi
|
||||
|
||||
# This is the Cygwin path to the location where I installed the RIDE
|
||||
# toolchain under windows. You will also have to edit this if you install
|
||||
# the RIDE toolchain in any other location
|
||||
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
|
||||
|
||||
# This is the Cygwin path to the location where I installed the CodeSourcery
|
||||
# toolchain under windows. You will also have to edit this if you install
|
||||
# the CodeSourcery toolchain in any other location
|
||||
export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
|
||||
|
||||
# These are the Cygwin paths to the locations where I installed the Atollic
|
||||
# toolchain under windows. You will also have to edit this if you install
|
||||
# the Atollic toolchain in any other location. /usr/bin is added before
|
||||
# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
|
||||
# at those locations as well.
|
||||
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
|
||||
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
|
||||
|
||||
# This is the Cygwin path to the location where I build the buildroot
|
||||
# toolchain.
|
||||
#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
|
||||
|
||||
# Add the path to the toolchain to the PATH varialble
|
||||
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
|
||||
|
||||
echo "PATH : ${PATH}"
|
|
@ -0,0 +1,150 @@
|
|||
/****************************************************************************
|
||||
* configs/tap-v1/scripts/ld.script
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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 NuttX 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The STM32F405RG has 1024Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 192Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000
|
||||
* 3) 64Kb of CCM SRAM beginning at address 0x1000:0000
|
||||
*
|
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
|
||||
* where the code expects to begin execution by jumping to the entry point in
|
||||
* the 0x0800:0000 address range.
|
||||
*
|
||||
* The first 16 KiB of flash is reserved for the bootloader.
|
||||
* Paramater storage will use the next 2 16KiB Sectors.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x0800C000, LENGTH = 976K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
|
||||
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
|
||||
EXTERN(_vectors) /* force the vectors to be included in the output */
|
||||
|
||||
/*
|
||||
* Ensure that abort() is present in the final object. The exception handling
|
||||
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
|
||||
*/
|
||||
EXTERN(abort)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
|
||||
/*
|
||||
* This is a hack to make the newlib libm __errno() call
|
||||
* use the NuttX get_errno_ptr() function.
|
||||
*/
|
||||
__errno = get_errno_ptr;
|
||||
} > flash
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
/*
|
||||
* Construction data for parameters.
|
||||
*/
|
||||
__param ALIGN(4): {
|
||||
__param_start = ABSOLUTE(.);
|
||||
KEEP(*(__param*))
|
||||
__param_end = ABSOLUTE(.);
|
||||
} > flash
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > flash
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > flash
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
} > sram AT > flash
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > sram
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
|
@ -0,0 +1,84 @@
|
|||
############################################################################
|
||||
# configs/tap-v1/src/Makefile
|
||||
#
|
||||
# Copyright (C) 2013 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# 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 NuttX 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
-include $(TOPDIR)/Make.defs
|
||||
|
||||
CFLAGS += -I$(TOPDIR)/sched
|
||||
|
||||
ASRCS =
|
||||
AOBJS = $(ASRCS:.S=$(OBJEXT))
|
||||
|
||||
CSRCS = empty.c
|
||||
COBJS = $(CSRCS:.c=$(OBJEXT))
|
||||
|
||||
SRCS = $(ASRCS) $(CSRCS)
|
||||
OBJS = $(AOBJS) $(COBJS)
|
||||
|
||||
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
|
||||
ifeq ($(WINTOOL),y)
|
||||
CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
|
||||
-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
|
||||
-I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
|
||||
else
|
||||
CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
|
||||
endif
|
||||
|
||||
all: libboard$(LIBEXT)
|
||||
|
||||
$(AOBJS): %$(OBJEXT): %.S
|
||||
$(call ASSEMBLE, $<, $@)
|
||||
|
||||
$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
|
||||
$(call COMPILE, $<, $@)
|
||||
|
||||
libboard$(LIBEXT): $(OBJS)
|
||||
$(call ARCHIVE, $@, $(OBJS))
|
||||
|
||||
.depend: Makefile $(SRCS)
|
||||
$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
|
||||
$(Q) touch $@
|
||||
|
||||
depend: .depend
|
||||
|
||||
clean:
|
||||
$(call DELFILE, libboard$(LIBEXT))
|
||||
$(call CLEAN)
|
||||
|
||||
distclean: clean
|
||||
$(call DELFILE, Make.dep)
|
||||
$(call DELFILE, .depend)
|
||||
|
||||
-include Make.dep
|
||||
|
|
@ -0,0 +1,4 @@
|
|||
/*
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* we have this empty source file to keep it company.
|
||||
*/
|
|
@ -0,0 +1,49 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
# Author: David Sidrane <david_s5@nscdg.com>
|
||||
#
|
||||
# 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_module(
|
||||
MODULE drivers__boards__asc-v1
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
../common/board_name.c
|
||||
asc_init.c
|
||||
asc_pwr.c
|
||||
asc_timer_config.c
|
||||
asc_spi.c
|
||||
asc_usb.c
|
||||
asc_led.c
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
|
@ -0,0 +1,230 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2016 PX4 Development Team. All rights reserved.
|
||||
* Author: David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* 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 tap-v1_init.c
|
||||
*
|
||||
* tap-v1-specific early startup code. This file implements the
|
||||
* nsh_archinitialize() function that is called early by nsh during startup.
|
||||
*
|
||||
* Code here is run before the rcS script is invoked; it should start required
|
||||
* subsystems and perform board-specific initialisation.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
|
||||
|
||||
|
||||
#include "stm32.h"
|
||||
#include "board_config.h"
|
||||
#include "stm32_uart.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_led.h>
|
||||
|
||||
#include <systemlib/cpuload.h>
|
||||
|
||||
# if defined(FLASH_BASED_PARAMS)
|
||||
# include <systemlib/flashparams/flashfs.h>
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/* Debug ********************************************************************/
|
||||
|
||||
#ifdef CONFIG_CPP_HAVE_VARARGS
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message(...) lowsyslog(__VA_ARGS__)
|
||||
# else
|
||||
# define message(...) printf(__VA_ARGS__)
|
||||
# endif
|
||||
#else
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message lowsyslog
|
||||
# else
|
||||
# define message printf
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
__END_DECLS
|
||||
|
||||
/****************************************************************************
|
||||
* Protected Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the intitialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_boardinitialize(void)
|
||||
{
|
||||
/* Hold power state */
|
||||
|
||||
board_pwr_init(0);
|
||||
|
||||
/* TEMP ctrl Off (active high, init is clear) */
|
||||
|
||||
stm32_configgpio(GPIO_TEMP_CONT);
|
||||
|
||||
|
||||
/* Select 0 */
|
||||
|
||||
stm32_configgpio(GPIO_S0);
|
||||
stm32_configgpio(GPIO_S1);
|
||||
stm32_configgpio(GPIO_S2);
|
||||
|
||||
/* Radio Off (active low, init is set) */
|
||||
|
||||
stm32_configgpio(GPIO_PCON_RADIO);
|
||||
|
||||
|
||||
/* configure always-on ADC pins */
|
||||
|
||||
stm32_configgpio(GPIO_ADC1_IN10);
|
||||
|
||||
|
||||
/* configure SPI interfaces */
|
||||
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* configure LEDs (empty call to NuttX' ledinit) */
|
||||
|
||||
up_ledinit();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_archinitialize
|
||||
*
|
||||
* Description:
|
||||
* Perform architecture specific initialization
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
__EXPORT int nsh_archinitialize(void)
|
||||
{
|
||||
int result;
|
||||
|
||||
/* configure the high-resolution time/callout interface */
|
||||
hrt_init();
|
||||
|
||||
/* configure CPU load estimation */
|
||||
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
||||
cpuload_initialize_once();
|
||||
#endif
|
||||
|
||||
/* set up the serial DMA polling */
|
||||
static struct hrt_call serial_dma_call;
|
||||
struct timespec ts;
|
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered
|
||||
* a DMA event.
|
||||
*/
|
||||
ts.tv_sec = 0;
|
||||
ts.tv_nsec = 1000000;
|
||||
|
||||
hrt_call_every(&serial_dma_call,
|
||||
ts_to_abstime(&ts),
|
||||
ts_to_abstime(&ts),
|
||||
(hrt_callout)stm32_serial_dma_poll,
|
||||
NULL);
|
||||
|
||||
board_pwr_init(1);
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_AMBER);
|
||||
led_off(LED_BLUE);
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
static sector_descriptor_t sector_map[] = {
|
||||
{1, 16 * 1024, 0x08004000},
|
||||
{2, 16 * 1024, 0x08008000},
|
||||
{0, 0, 0},
|
||||
};
|
||||
|
||||
/* Initalizee the flashfs layer to use heap allocated memory */
|
||||
|
||||
result = parameter_flashfs_init(sector_map, NULL, 0);
|
||||
|
||||
if (result != OK) {
|
||||
message("[boot] FAILED to init params in FLASH %d\n", result);
|
||||
up_ledon(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
return OK;
|
||||
}
|
|
@ -0,0 +1,107 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2016 PX4 Development Team. All rights reserved.
|
||||
* Author: David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* 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 tap-v1_led.c
|
||||
*
|
||||
* TAP_V1 LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "stm32.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
__EXPORT void led_init(void)
|
||||
{
|
||||
/* Configure LED1-2 GPIOs for output */
|
||||
|
||||
stm32_configgpio(GPIO_BLUE_LED);
|
||||
stm32_configgpio(GPIO_RED_LED);
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
if (led == 0) {
|
||||
/* Pull down to switch on */
|
||||
stm32_gpiowrite(GPIO_BLUE_LED, false);
|
||||
}
|
||||
|
||||
if (led == 1) {
|
||||
/* Pull down to switch on */
|
||||
stm32_gpiowrite(GPIO_RED_LED, false);
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
if (led == 0) {
|
||||
/* Pull up to switch off */
|
||||
stm32_gpiowrite(GPIO_BLUE_LED, true);
|
||||
}
|
||||
|
||||
if (led == 1) {
|
||||
/* Pull up to switch off */
|
||||
stm32_gpiowrite(GPIO_RED_LED, true);
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
if (led == 0) {
|
||||
stm32_gpiowrite(GPIO_BLUE_LED, !stm32_gpioread(GPIO_BLUE_LED));
|
||||
}
|
||||
|
||||
if (led == 1) {
|
||||
stm32_gpiowrite(GPIO_RED_LED, !stm32_gpioread(GPIO_RED_LED));
|
||||
}
|
||||
}
|
|
@ -0,0 +1,167 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
* Author: David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* 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 tap-v1_pwr.c
|
||||
*
|
||||
* Board-specific SPI functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <time.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "board_config.h"
|
||||
#include <stm32_pwr.h>
|
||||
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
|
||||
/************************************************************************************
|
||||
* Private Data
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
static int board_button_irq(int irq, FAR void *context)
|
||||
{
|
||||
static struct timespec time_down;
|
||||
|
||||
if (board_pwr_button_down()) {
|
||||
|
||||
led_on(BOARD_LED_RED);
|
||||
|
||||
clock_gettime(CLOCK_REALTIME, &time_down);
|
||||
|
||||
} else {
|
||||
|
||||
led_off(BOARD_LED_RED);
|
||||
|
||||
struct timespec now;
|
||||
|
||||
clock_gettime(CLOCK_REALTIME, &now);
|
||||
|
||||
uint64_t tdown_ms = time_down.tv_sec * 1000 + time_down.tv_nsec / 1000000;
|
||||
|
||||
uint64_t tnow_ms = now.tv_sec * 1000 + now.tv_nsec / 1000000;
|
||||
|
||||
if (tdown_ms != 0 && (tnow_ms - tdown_ms) >= MS_PWR_BUTTON_DOWN) {
|
||||
|
||||
led_on(BOARD_LED_BLUE);
|
||||
|
||||
up_mdelay(750);
|
||||
stm32_pwr_enablebkp();
|
||||
/* XXX wow, this is evil - write a magic number into backup register zero */
|
||||
*(uint32_t *)0x40002850 = 0xdeaddead;
|
||||
up_mdelay(750);
|
||||
up_systemreset();
|
||||
|
||||
while (1);
|
||||
}
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_pwr_init()
|
||||
*
|
||||
* Description:
|
||||
* Called to configure power control for the tap-v1 board.
|
||||
*
|
||||
* Input Parameters:
|
||||
* stage- 0 for boot, 1 for board init
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void board_pwr_init(int stage)
|
||||
{
|
||||
if (stage == 0) {
|
||||
stm32_configgpio(POWER_ON_GPIO);
|
||||
stm32_configgpio(KEY_AD_GPIO);
|
||||
}
|
||||
|
||||
if (stage == 1) {
|
||||
stm32_gpiosetevent(KEY_AD_GPIO, true, true, true, board_button_irq);
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_pwr_button_down
|
||||
*
|
||||
* Description:
|
||||
* Called to Read the logical state of the active low power button.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
bool board_pwr_button_down(void)
|
||||
{
|
||||
return 0 == stm32_gpioread(KEY_AD_GPIO);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_pwr
|
||||
*
|
||||
* Description:
|
||||
* Called to turn on or off the TAP
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void board_pwr(bool on_not_off)
|
||||
{
|
||||
if (on_not_off) {
|
||||
stm32_configgpio(POWER_ON_GPIO);
|
||||
|
||||
} else {
|
||||
|
||||
stm32_configgpio(POWER_OFF_GPIO);
|
||||
}
|
||||
}
|
|
@ -0,0 +1,88 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2016 PX4 Development Team. All rights reserved.
|
||||
* Author: David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* 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 tap-v1_spi.c
|
||||
*
|
||||
* Board-specific SPI functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/spi.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "chip.h"
|
||||
#include "stm32.h"
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the tap-v1 board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_spiinitialize(void)
|
||||
{
|
||||
stm32_configgpio(GPIO_SPI_CS_SDCARD);
|
||||
stm32_configgpio(GPIO_SPI_SD_SW);
|
||||
}
|
||||
|
||||
|
||||
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
/* there can only be one device on this bus, so always select it */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_SDCARD, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return !stm32_gpioread(GPIO_SPI_SD_SW);
|
||||
}
|
||||
|
|
@ -0,0 +1,133 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2016 PX4 Development Team. All rights reserved.
|
||||
* Author: David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* 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 tap-v1_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_TIM3_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_bit = RCC_APB1ENR_TIM3EN,
|
||||
.clock_freq = STM32_APB1_TIM3_CLKIN,
|
||||
.first_channel_index = 0,
|
||||
.last_channel_index = 3,
|
||||
.handler = io_timer_handler0,
|
||||
.vectorno = STM32_IRQ_TIM3,
|
||||
}
|
||||
};
|
||||
|
||||
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH1OUT,
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 1,
|
||||
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH2OUT,
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 2,
|
||||
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
|
||||
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH3OUT,
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 3,
|
||||
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
|
||||
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH4OUT,
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 4,
|
||||
.ccr_offset = STM32_GTIM_CCR4_OFFSET,
|
||||
.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF
|
||||
}
|
||||
};
|
||||
|
||||
__EXPORT const struct io_timers_t led_pwm_timers[1] = {
|
||||
{
|
||||
.base = STM32_TIM3_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_bit = RCC_APB1ENR_TIM3EN,
|
||||
.clock_freq = STM32_APB1_TIM3_CLKIN,
|
||||
.vectorno = STM32_IRQ_TIM3,
|
||||
.first_channel_index = 0,
|
||||
.last_channel_index = 2,
|
||||
}
|
||||
};
|
||||
|
||||
__EXPORT const struct timer_io_channels_t led_pwm_channels[3] = {
|
||||
{
|
||||
.gpio_out = LED_TIM3_CH1OUT,
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 1,
|
||||
},
|
||||
{
|
||||
.gpio_out = LED_TIM3_CH2OUT,
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 2,
|
||||
},
|
||||
{
|
||||
.gpio_out = LED_TIM3_CH3OUT,
|
||||
.gpio_in = 0,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 3,
|
||||
}
|
||||
};
|
|
@ -0,0 +1,105 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2016 PX4 Development Team. All rights reserved.
|
||||
* Author: David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* 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 tap-v1_usb.c
|
||||
*
|
||||
* Board-specific USB functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "stm32.h"
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to setup USB-related GPIO pins for the tap-v1 board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbinitialize(void)
|
||||
{
|
||||
/* The OTG FS has an internal soft pull-up */
|
||||
|
||||
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
|
||||
|
||||
#ifdef CONFIG_STM32_OTGFS
|
||||
stm32_configgpio(GPIO_OTGFS_VBUS);
|
||||
#endif
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbsuspend
|
||||
*
|
||||
* Description:
|
||||
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
|
||||
* used. This function is called whenever the USB enters or leaves suspend mode.
|
||||
* This is an opportunity for the board logic to shutdown clocks, power, etc.
|
||||
* while the USB is suspended.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||
{
|
||||
//ulldbg("resume: %d\n", resume);
|
||||
}
|
||||
|
|
@ -0,0 +1,347 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-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_config.h
|
||||
*
|
||||
* @author David Sidrane <david_s5@nscdg.com>
|
||||
* @author Lorenz Meier <lorenz@px4.io>
|
||||
*
|
||||
* TAP_V1 internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
/* these headers are not C++ safe */
|
||||
#include <stm32.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
/* Configuration ************************************************************************************/
|
||||
|
||||
#define UDID_START 0x1FFF7A10
|
||||
|
||||
/* PX4FMU GPIOs ***********************************************************************************/
|
||||
/* LEDs
|
||||
*
|
||||
* PC4 BLUE_LED D4 Blue LED cathode
|
||||
* PC5 RED_LED D5 Red LED cathode
|
||||
*/
|
||||
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN5)
|
||||
#define GPIO_BLUE_LED GPIO_LED1
|
||||
#define GPIO_RED_LED GPIO_LED2
|
||||
/*
|
||||
* SPI
|
||||
*
|
||||
* Peripheral Port Signal Name CONN
|
||||
* SPI2_NSS PB12 SD_SPI2_NSS SD-2 CS
|
||||
* SPI2_SCK PB13 SD_SPI2_SCK SD-5 CLK
|
||||
* SPI2_MISO PB14 SD_SPI2_MISO SD-7 D0
|
||||
* SPI2_MOSI PB15 SD_SPI2_MOSI SD-3 DI
|
||||
*
|
||||
* PC2 SD_SW SD-9 SW
|
||||
*
|
||||
*/
|
||||
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_SPI_SD_SW (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN2)
|
||||
|
||||
|
||||
/*
|
||||
* I2C busses
|
||||
*
|
||||
* Peripheral Port Signal Name CONN
|
||||
* I2C1_SDA PB9 I2C1_SDA J2-4,9,16,21 mpu6050, U4 MS6507
|
||||
* I2C1_SDL PB8 I2C1_SCL J2-3,10,15,22 mpu6050, U4 MS6507
|
||||
*
|
||||
* I2C2_SDA PB11 Sonar Echo/I2C_SDA JP2-31,32
|
||||
* I2C2_SDL PB10 Sonar Trig/I2C_SCL JP2-29,30
|
||||
*
|
||||
* I2C3_SDA PC9 COMPASS_I2C3_SDA JP1-27,28
|
||||
* I2C3_SDL PA8 COMPASS_I2C3_SCL JP1-25,26
|
||||
*
|
||||
*/
|
||||
#define PX4_I2C_BUS_ONBOARD 1
|
||||
#define PX4_I2C_BUS_SONAR 2
|
||||
#define PX4_I2C_BUS_EXPANSION 3
|
||||
|
||||
#define PX4_I2C_OBDEV_HMC5883 0x1e
|
||||
|
||||
/*
|
||||
* Devices on the onboard bus.
|
||||
*
|
||||
* Note that these are unshifted addresses (not includinf R/W).
|
||||
*/
|
||||
|
||||
/* todo:
|
||||
* Cannot tell from the schematic if there is one or 2 MPU6050
|
||||
* The slave address of the MPU-60X0 is b110100X which is 7 bits long.
|
||||
* The LSB bit of the 7 bit address is determined by the logic level
|
||||
* on pin AD0. This allows two MPU-60X0s to be connected to the same I2C bus.
|
||||
* When used in this configuration, the address of the one of the devices
|
||||
* should be b1101000 (pin AD0 is logic low) and the address of the other
|
||||
* should be b1101001 (pin AD0 is logic high).
|
||||
*/
|
||||
#define PX4_I2C_ON_BOARD_MPU6050_ADDRS {0x68,0x69}
|
||||
|
||||
|
||||
/*
|
||||
* ADC channels
|
||||
*
|
||||
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver
|
||||
* PC0 VOLTAGE JP2-13,14 - 1.84 @16.66 1.67 @15.12 Scale 0.1105
|
||||
*
|
||||
*/
|
||||
#define ADC_CHANNELS (1 << 10)
|
||||
/* todo:Revisit - cannnot tell from schematic - some could be ADC */
|
||||
|
||||
// ADC defines to be used in sensors.cpp to read from a particular channel
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
|
||||
|
||||
|
||||
/* User GPIOs
|
||||
*
|
||||
* TIM3_CH1 PA6 LED_R JP2-23,24
|
||||
* TIM3_CH2 PA7 LED_G JP2-25,26
|
||||
* TIM3_CH3 PB0 LED_B JP2-27,28
|
||||
* TIM3_CH4 PB1 nPWM_1 AUX1(Landing Gear) JP1-21,22
|
||||
*
|
||||
* I2C2_SDA PB11 Sonar Echo/I2C_SDA JP2-31,32
|
||||
* I2C2_SDL PB10 Sonar Trig/I2C_SCL JP2-29,30
|
||||
*
|
||||
*/
|
||||
#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN11)
|
||||
|
||||
#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN6)
|
||||
#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN7)
|
||||
#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN11)
|
||||
|
||||
/*
|
||||
* Tone alarm output
|
||||
*/
|
||||
/* todo:Revisit - cannnot tell from schematic - one could be tone alarm*/
|
||||
#define TONE_ALARM_TIMER 8 /* timer 8 */
|
||||
#define TONE_ALARM_CHANNEL 3 /* channel 3 */
|
||||
#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
|
||||
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
|
||||
|
||||
/*
|
||||
* PWM
|
||||
*
|
||||
* Four PWM outputs can be configured on pins
|
||||
*
|
||||
*
|
||||
* Peripheral Port Signal Name CONN
|
||||
* TIM3_CH1 PA6 LED_R JP2-23,24
|
||||
* TIM3_CH2 PA7 LED_G JP2-25,26
|
||||
* TIM3_CH3 PB0 LED_B JP2-27,28
|
||||
* TIM3_CH4 PB1 nPWM_1 AUX1(Landing Gear) JP1-21,22
|
||||
*
|
||||
*/
|
||||
#define GPIO_TIM3_CH1OUT GPIO_TIM3_CH1OUT_1
|
||||
#define GPIO_TIM3_CH2OUT GPIO_TIM3_CH2OUT_1
|
||||
#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_1
|
||||
#define GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_1
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 4
|
||||
|
||||
#define BOARD_HAS_LED_PWM
|
||||
#define LED_TIM3_CH1OUT GPIO_TIM3_CH1OUT
|
||||
#define LED_TIM3_CH2OUT GPIO_TIM3_CH2OUT
|
||||
#define LED_TIM3_CH3OUT GPIO_TIM3_CH3OUT
|
||||
|
||||
|
||||
/* USB OTG FS
|
||||
*
|
||||
* PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED)
|
||||
*/
|
||||
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
|
||||
|
||||
/* High-resolution timer
|
||||
*/
|
||||
#define HRT_TIMER 1 /* use timer1 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
|
||||
|
||||
#define BOARD_NAME "TAP_V1"
|
||||
|
||||
/* By Providing BOARD_ADC_USB_CONNECTED this board support the ADC
|
||||
* system_power interface, and herefore provides the true logic
|
||||
* GPIO BOARD_ADC_xxxx macros.
|
||||
*/
|
||||
#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS))
|
||||
#define BOARD_ADC_BRICK_VALID (1)
|
||||
#define BOARD_ADC_SERVO_VALID (1)
|
||||
#define BOARD_ADC_PERIPH_5V_OC (0)
|
||||
#define BOARD_ADC_HIPOWER_5V_OC (0)
|
||||
|
||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||
|
||||
#define BOARD_FMU_GPIO_TAB { \
|
||||
{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, \
|
||||
{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, \
|
||||
{GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, 0}, \
|
||||
{GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0}, \
|
||||
{GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0}, \
|
||||
{GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0}, }
|
||||
|
||||
|
||||
#define MS_PWR_BUTTON_DOWN 750
|
||||
#define KEY_AD_GPIO (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTC|GPIO_PIN1)
|
||||
#define POWER_ON_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
|
||||
#define POWER_OFF_GPIO (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN4)
|
||||
|
||||
#define GPIO_S0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN15)
|
||||
#define GPIO_S1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN14)
|
||||
#define GPIO_S2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
|
||||
|
||||
#define GPIO_PCON_RADIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN3)
|
||||
#define RF_RADIO_CONTOL(_on_true) px4_arch_gpiowrite(GPIO_PCON_RADIO, !(_on_true))
|
||||
|
||||
#define GPIO_TEMP_CONT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN4)
|
||||
#define TEMP_CONTROL(_on_true) px4_arch_gpiowrite(GPIO_TEMP_CONT, (_on_true))
|
||||
|
||||
#define FLASH_BASED_PARAMS
|
||||
/****************************************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public data
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
|
||||
#define board_spi_reset(ms)
|
||||
#define board_peripheral_reset(ms)
|
||||
|
||||
extern void stm32_usbinitialize(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_sdio_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SDIO.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
extern int board_sdio_initialize(void);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_archinitialize
|
||||
*
|
||||
* Description:
|
||||
* Perform architecture specific initialization for NSH.
|
||||
*
|
||||
* CONFIG_NSH_ARCHINIT=y :
|
||||
* Called from the NSH library
|
||||
*
|
||||
* CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
|
||||
* CONFIG_NSH_ARCHINIT=n :
|
||||
* Called from board_initialize().
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_NSH_LIBRARY
|
||||
int nsh_archinitialize(void);
|
||||
#endif
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_pwr_init()
|
||||
*
|
||||
* Description:
|
||||
* Called to configure power control for the tap-v1 board.
|
||||
*
|
||||
* Input Parameters:
|
||||
* stage- 0 for boot, 1 for board init
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void board_pwr_init(int stage);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_pwr_button_down
|
||||
*
|
||||
* Description:
|
||||
* Called to Read the logical state of the power button
|
||||
****************************************************************************/
|
||||
|
||||
bool board_pwr_button_down(void);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_pwr
|
||||
*
|
||||
* Description:
|
||||
* Called to turn on or off the TAP
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void board_pwr(bool on_not_off);
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
__END_DECLS
|
|
@ -155,6 +155,10 @@
|
|||
/* no GPIO driver on the PX4_STM32F4DISCOVERY board */
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_ASC_V1
|
||||
/* no GPIO driver on the ASC board */
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_SITL
|
||||
/* no GPIO driver on the SITL configuration */
|
||||
#endif
|
||||
|
@ -164,7 +168,7 @@
|
|||
!defined(CONFIG_ARCH_BOARD_AEROCORE) && !defined(CONFIG_ARCH_BOARD_PX4_STM32F4DISCOVERY) && \
|
||||
!defined(CONFIG_ARCH_BOARD_MINDPX_V2) && \
|
||||
!defined(CONFIG_ARCH_BOARD_PX4FMU_V4) && !defined(CONFIG_ARCH_BOARD_SITL) && \
|
||||
!defined(CONFIG_ARCH_BOARD_TAP_V1)
|
||||
!defined(CONFIG_ARCH_BOARD_TAP_V1) && !defined(CONFIG_ARCH_BOARD_ASC_V1)
|
||||
# error No CONFIG_ARCH_BOARD_xxxx set
|
||||
#endif
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue