forked from Archive/PX4-Autopilot
Add Gumstix AeroCore device
Based on the work of Andrew Smith [1], add board configuration and device drivers to support the Gumstix AeroCore (previously Aerodroid) board [2]. The AeroCore is an autopilot board based on a STM32F427 similar to the FMUv2. [1] https://github.com/smithandrewc/Firmware [2] https://store.gumstix.com/index.php/products/585/ Signed-off-by: Ash Charles <ashcharles@gmail.com>
This commit is contained in:
parent
178a3e8567
commit
e5508a1aa0
|
@ -0,0 +1,12 @@
|
|||
{
|
||||
"board_id": 19,
|
||||
"magic": "AeroCore",
|
||||
"description": "Firmware for the Gumstix AeroCore board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "AEROCORE",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
|
@ -0,0 +1,11 @@
|
|||
#
|
||||
# Board-specific definitions for the Gumstix AeroCore
|
||||
#
|
||||
|
||||
#
|
||||
# Configure the toolchain
|
||||
#
|
||||
CONFIG_ARCH = CORTEXM4F
|
||||
CONFIG_BOARD = AEROCORE
|
||||
|
||||
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
|
|
@ -0,0 +1,125 @@
|
|||
#
|
||||
# Makefile for the AeroCore *default* configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Use the configuration's ROMFS.
|
||||
#
|
||||
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/stm32
|
||||
MODULES += drivers/stm32/adc
|
||||
MODULES += drivers/stm32/tone_alarm
|
||||
MODULES += drivers/led
|
||||
MODULES += drivers/px4fmu
|
||||
MODULES += drivers/boards/aerocore
|
||||
MODULES += drivers/lsm303d
|
||||
MODULES += drivers/l3gd20
|
||||
MODULES += drivers/ms5611
|
||||
MODULES += drivers/gps
|
||||
MODULES += drivers/hil
|
||||
MODULES += modules/sensors
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/boardinfo
|
||||
MODULES += systemcmds/mixer
|
||||
MODULES += systemcmds/param
|
||||
MODULES += systemcmds/perf
|
||||
MODULES += systemcmds/preflight_check
|
||||
MODULES += systemcmds/pwm
|
||||
MODULES += systemcmds/esc_calib
|
||||
MODULES += systemcmds/reboot
|
||||
MODULES += systemcmds/top
|
||||
MODULES += systemcmds/config
|
||||
MODULES += systemcmds/nshterm
|
||||
MODULES += systemcmds/mtd
|
||||
MODULES += systemcmds/dumpfile
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
MODULES += modules/commander
|
||||
MODULES += modules/navigator
|
||||
MODULES += modules/mavlink
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
MODULES += modules/attitude_estimator_ekf
|
||||
MODULES += modules/attitude_estimator_so3
|
||||
MODULES += modules/fw_att_pos_estimator
|
||||
MODULES += modules/position_estimator_inav
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
MODULES += modules/fw_pos_control_l1
|
||||
MODULES += modules/fw_att_control
|
||||
MODULES += modules/mc_att_control
|
||||
MODULES += modules/mc_pos_control
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
MODULES += modules/systemlib
|
||||
MODULES += modules/systemlib/mixer
|
||||
MODULES += modules/controllib
|
||||
MODULES += modules/uORB
|
||||
MODULES += modules/dataman
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
LIBRARIES += lib/mathlib/CMSIS
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
MODULES += lib/ecl
|
||||
MODULES += lib/external_lgpl
|
||||
MODULES += lib/geo
|
||||
MODULES += lib/conversion
|
||||
MODULES += lib/launchdetection
|
||||
|
||||
#
|
||||
# Demo apps
|
||||
#
|
||||
#MODULES += examples/math_demo
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/hello_sky
|
||||
MODULES += examples/px4_simple_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/daemon
|
||||
#MODULES += examples/px4_daemon_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/debug_values
|
||||
#MODULES += examples/px4_mavlink_debug
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
|
||||
#MODULES += examples/fixedwing_control
|
||||
|
||||
# Hardware test
|
||||
#MODULES += examples/hwtest
|
||||
|
||||
#
|
||||
# Transitional support - add commands from the NuttX export archive.
|
||||
#
|
||||
# In general, these should move to modules over time.
|
||||
#
|
||||
# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
|
||||
# to make the table a bit more readable.
|
||||
#
|
||||
define _B
|
||||
$(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
|
||||
endef
|
||||
|
||||
BUILTIN_COMMANDS := \
|
||||
$(call _B, hello, , 2048, hello_main) \
|
||||
$(call _B, i2c, , 2048, i2c_main)
|
|
@ -0,0 +1,263 @@
|
|||
/************************************************************************************
|
||||
* configs/aerocore/include/board.h
|
||||
* include/arch/board/board.h
|
||||
*
|
||||
* Copyright (C) 2009 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_BOARD_BOARD_H
|
||||
#define __ARCH_BOARD_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include <stm32.h>
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The AeroCore uses a 24MHz crystal connected to the HSE.
|
||||
*
|
||||
* This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c:
|
||||
* 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) : 24000000 (STM32_BOARD_XTAL)
|
||||
* PLLM : 24 (STM32_PLLCFG_PLLM)
|
||||
* PLLN : 336 (STM32_PLLCFG_PLLN)
|
||||
* PLLP : 2 (STM32_PLLCFG_PLLP)
|
||||
* PLLQ : 7 (STM32_PLLCFG_PPQ)
|
||||
* 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 24MHz
|
||||
* LSE - not installed
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_XTAL 24000000ul
|
||||
|
||||
#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
|
||||
* = (24,000,000 / 24) * 336
|
||||
* = 336,000,000
|
||||
* SYSCLK = PLL_VCO / PLLP
|
||||
* = 336,000,000 / 2 = 168,000,000
|
||||
* USB OTG FS, SDIO and RNG Clock
|
||||
* = PLL_VCO / PLLQ
|
||||
* = 48,000,000
|
||||
*/
|
||||
|
||||
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24)
|
||||
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
|
||||
#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)
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
||||
/*
|
||||
* UARTs.
|
||||
*/
|
||||
/* USART1 on PB[6,7]: GPS */
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_2
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_2
|
||||
|
||||
/* USART2 on PD[5,6]: J5 Breakout */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2
|
||||
#define GPIO_USART2_CTS 0 // unused
|
||||
#define GPIO_USART2_RTS 0 // unused
|
||||
|
||||
/* USART3 on PD[8,9]: to DuoVero UART2 */
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3
|
||||
#define GPIO_USART3_CTS 0 // unused
|
||||
#define GPIO_USART3_RTS 0 // unused
|
||||
|
||||
/* UART7 on PE[78]: J7 Breakout */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_1
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_1
|
||||
|
||||
/*
|
||||
* UART8 on PE[0-1]: System Console on Port C of USB (J7)
|
||||
* No alternate pin config
|
||||
*/
|
||||
|
||||
/* USART[1,6] require a RX DMA configuration */
|
||||
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
|
||||
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
|
||||
|
||||
/*
|
||||
* I2C
|
||||
*
|
||||
* 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.
|
||||
*/
|
||||
|
||||
/* PB[10-11]: I2C2 is broken out on J9 header */
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
|
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1
|
||||
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
|
||||
|
||||
/*
|
||||
* SPI
|
||||
*/
|
||||
/* PA[4-7] SPI1 broken out on J12 */
|
||||
#define GPIO_SPI1_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) /* should be GPIO_SPI1_NSS_2 but use as a GPIO */
|
||||
#define GPIO_SPI1_SCK (GPIO_SPI1_SCK_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI1_MISO (GPIO_SPI1_MISO_1|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI1_MOSI (GPIO_SPI1_MOSI_1|GPIO_SPEED_50MHz)
|
||||
|
||||
/* PB[12-15]: SPI2 connected to DuoVero SPI1 */
|
||||
#define GPIO_SPI2_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) /* should be GPIO_SPI2_NSS_2 but use as a GPIO */
|
||||
#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)
|
||||
|
||||
/* PC[10-12]: SPI3 connected to onboard sensors */
|
||||
#define GPIO_SPI3_SCK (GPIO_SPI3_SCK_2|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI3_MISO (GPIO_SPI3_MISO_2|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI3_MOSI (GPIO_SPI3_MOSI_2|GPIO_SPEED_50MHz)
|
||||
|
||||
/* PE[11-14]: SPI4 connected to FRAM */
|
||||
#define GPIO_SPI4_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN11) /* should be GPIO_SPI4_NSS_2 but use as a GPIO */
|
||||
#define GPIO_SPI4_SCK (GPIO_SPI4_SCK_2|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI4_MISO (GPIO_SPI4_MISO_2|GPIO_SPEED_50MHz)
|
||||
#define GPIO_SPI4_MOSI (GPIO_SPI4_MOSI_2|GPIO_SPEED_50MHz)
|
||||
|
||||
/************************************************************************************
|
||||
* 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 intitialization -- 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 /* __ARCH_BOARD_BOARD_H */
|
|
@ -0,0 +1,42 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013 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,179 @@
|
|||
############################################################################
|
||||
# configs/aerocore/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
|
||||
|
||||
#
|
||||
# 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 = -O3
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m4 \
|
||||
-mthumb \
|
||||
-march=armv7e-m \
|
||||
-mfpu=fpv4-sp-d16 \
|
||||
-mfloat-abi=hard
|
||||
|
||||
|
||||
# enable precise stack overflow tracking
|
||||
INSTRUMENTATIONDEFINES = -finstrument-functions \
|
||||
-ffixed-r10
|
||||
|
||||
# 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 = -Wall \
|
||||
-Wextra \
|
||||
-Wdouble-promotion \
|
||||
-Wshadow \
|
||||
-Wfloat-equal \
|
||||
-Wframe-larger-than=1024 \
|
||||
-Wpointer-arith \
|
||||
-Wlogical-op \
|
||||
-Wmissing-declarations \
|
||||
-Wpacked \
|
||||
-Wno-unused-parameter
|
||||
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
|
||||
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
|
||||
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
|
||||
|
||||
ARCHCWARNINGS = $(ARCHWARNINGS) \
|
||||
-Wbad-function-cast \
|
||||
-Wstrict-prototypes \
|
||||
-Wold-style-declaration \
|
||||
-Wmissing-parameter-type \
|
||||
-Wmissing-prototypes \
|
||||
-Wnested-externs \
|
||||
-Wunsuffixed-float-constants
|
||||
ARCHWARNINGSXX = $(ARCHWARNINGS) \
|
||||
-Wno-psabi
|
||||
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,42 @@
|
|||
############################################################################
|
||||
# configs/aerocore/nsh/appconfig
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
# Path to example in apps/examples containing the user_start entry point
|
||||
|
||||
CONFIGURED_APPS += examples/nsh
|
||||
|
||||
# The NSH application library
|
||||
CONFIGURED_APPS += nshlib
|
||||
CONFIGURED_APPS += system/readline
|
|
@ -0,0 +1,950 @@
|
|||
#
|
||||
# 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 is not set
|
||||
|
||||
#
|
||||
# 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=y
|
||||
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_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 is not set
|
||||
# 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=y
|
||||
# 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_STM32F427=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 is not set
|
||||
CONFIG_STM32_I2C2=y
|
||||
# CONFIG_STM32_I2C3 is not set
|
||||
# CONFIG_STM32_OTGFS is not set
|
||||
# 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=y
|
||||
CONFIG_STM32_SPI2=y
|
||||
CONFIG_STM32_SPI3=y
|
||||
CONFIG_STM32_SPI4=y
|
||||
# CONFIG_STM32_SPI5 is not set
|
||||
# CONFIG_STM32_SPI6 is not set
|
||||
CONFIG_STM32_SYSCFG=y
|
||||
CONFIG_STM32_TIM1=y
|
||||
# CONFIG_STM32_TIM2 is not set
|
||||
CONFIG_STM32_TIM3=y
|
||||
CONFIG_STM32_TIM4=y
|
||||
CONFIG_STM32_TIM5=y
|
||||
# CONFIG_STM32_TIM6 is not set
|
||||
# CONFIG_STM32_TIM7 is not set
|
||||
# CONFIG_STM32_TIM8 is not set
|
||||
CONFIG_STM32_TIM9=y
|
||||
# CONFIG_STM32_TIM10 is not set
|
||||
# CONFIG_STM32_TIM11 is not set
|
||||
# CONFIG_STM32_TIM12 is not set
|
||||
# CONFIG_STM32_TIM13 is not set
|
||||
# CONFIG_STM32_TIM14 is not set
|
||||
CONFIG_STM32_USART1=y
|
||||
CONFIG_STM32_USART2=y
|
||||
CONFIG_STM32_USART3=y
|
||||
# CONFIG_STM32_UART4 is not set
|
||||
# CONFIG_STM32_UART5 is not set
|
||||
# CONFIG_STM32_USART6 is not set
|
||||
CONFIG_STM32_UART7=y
|
||||
CONFIG_STM32_UART8=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_TIM1_PWM is not set
|
||||
# CONFIG_STM32_TIM3_PWM is not set
|
||||
# CONFIG_STM32_TIM4_PWM is not set
|
||||
# CONFIG_STM32_TIM5_PWM is not set
|
||||
# CONFIG_STM32_TIM9_PWM is not set
|
||||
# CONFIG_STM32_TIM1_ADC is not set
|
||||
# CONFIG_STM32_TIM3_ADC 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_UART7_RS485 is not set
|
||||
CONFIG_UART7_RXDMA=y
|
||||
# CONFIG_UART8_RS485 is not set
|
||||
CONFIG_UART8_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=500
|
||||
# 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=262144
|
||||
CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=4096
|
||||
|
||||
#
|
||||
# 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_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD=""
|
||||
|
||||
#
|
||||
# Common Board Options
|
||||
#
|
||||
CONFIG_NSH_MMCSDMINOR=0
|
||||
|
||||
#
|
||||
# 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=36
|
||||
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=6000
|
||||
CONFIG_USERMAIN_STACKSIZE=4096
|
||||
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_MTD=y
|
||||
|
||||
#
|
||||
# MTD Configuration
|
||||
#
|
||||
CONFIG_MTD_PARTITION=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
|
||||
#
|
||||
# MTD Device Drivers
|
||||
#
|
||||
# CONFIG_RAMMTD is not set
|
||||
# CONFIG_MTD_AT24XX is not set
|
||||
# CONFIG_MTD_AT45DB is not set
|
||||
# CONFIG_MTD_M25P is not set
|
||||
# CONFIG_MTD_SMART is not set
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_RAMTRON_FUJITSU=y
|
||||
# CONFIG_MTD_SST25 is not set
|
||||
# CONFIG_MTD_SST39FV is not set
|
||||
# CONFIG_MTD_W25 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_16550_UART is not set
|
||||
CONFIG_ARCH_HAVE_UART7=y
|
||||
CONFIG_ARCH_HAVE_UART8=y
|
||||
CONFIG_ARCH_HAVE_USART1=y
|
||||
CONFIG_ARCH_HAVE_USART2=y
|
||||
CONFIG_ARCH_HAVE_USART3=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 is not set
|
||||
# CONFIG_UART7_SERIAL_CONSOLE is not set
|
||||
CONFIG_UART8_SERIAL_CONSOLE=y
|
||||
# CONFIG_NO_SERIAL_CONSOLE is not set
|
||||
|
||||
#
|
||||
# USART1 Configuration
|
||||
#
|
||||
CONFIG_USART1_RXBUFSIZE=512
|
||||
CONFIG_USART1_TXBUFSIZE=512
|
||||
CONFIG_USART1_BAUD=115200
|
||||
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=512
|
||||
CONFIG_USART2_TXBUFSIZE=512
|
||||
CONFIG_USART2_BAUD=115200
|
||||
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=512
|
||||
CONFIG_USART3_TXBUFSIZE=512
|
||||
CONFIG_USART3_BAUD=115200
|
||||
CONFIG_USART3_BITS=8
|
||||
CONFIG_USART3_PARITY=0
|
||||
CONFIG_USART3_2STOP=0
|
||||
# CONFIG_USART3_IFLOWCONTROL is not set
|
||||
# CONFIG_USART3_OFLOWCONTROL is not set
|
||||
|
||||
#
|
||||
# UART7 Configuration
|
||||
#
|
||||
CONFIG_UART7_RXBUFSIZE=512
|
||||
CONFIG_UART7_TXBUFSIZE=512
|
||||
CONFIG_UART7_BAUD=115200
|
||||
CONFIG_UART7_BITS=8
|
||||
CONFIG_UART7_PARITY=0
|
||||
CONFIG_UART7_2STOP=0
|
||||
# CONFIG_UART7_IFLOWCONTROL is not set
|
||||
# CONFIG_UART7_OFLOWCONTROL is not set
|
||||
|
||||
#
|
||||
# UART8 Configuration
|
||||
#
|
||||
CONFIG_UART8_RXBUFSIZE=512
|
||||
CONFIG_UART8_TXBUFSIZE=512
|
||||
CONFIG_UART8_BAUD=115200
|
||||
CONFIG_UART8_BITS=8
|
||||
CONFIG_UART8_PARITY=0
|
||||
CONFIG_UART8_2STOP=0
|
||||
# CONFIG_UART8_IFLOWCONTROL is not set
|
||||
# CONFIG_UART8_OFLOWCONTROL is not set
|
||||
# CONFIG_SERIAL_IFLOWCONTROL is not set
|
||||
# CONFIG_SERIAL_OFLOWCONTROL is not set
|
||||
# CONFIG_USBDEV 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=y
|
||||
CONFIG_FS_NXFFS=y
|
||||
CONFIG_NXFFS_PREALLOCATED=y
|
||||
CONFIG_NXFFS_ERASEDSTATE=0xff
|
||||
CONFIG_NXFFS_PACKTHRESHOLD=32
|
||||
CONFIG_NXFFS_MAXNAMLEN=32
|
||||
CONFIG_NXFFS_TAILTHRESHOLD=2048
|
||||
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=32
|
||||
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=2000
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKPERIOD=50000
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=2000
|
||||
# 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_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=y
|
||||
# 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_MTDPART is not set
|
||||
# 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 is not set
|
||||
# CONFIG_NSH_DISABLE_KILL is not set
|
||||
# CONFIG_NSH_DISABLE_LOSETUP is not set
|
||||
# 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 is not set
|
||||
# CONFIG_NSH_DISABLE_PS is not set
|
||||
# CONFIG_NSH_DISABLE_PING is not set
|
||||
# CONFIG_NSH_DISABLE_PUT is not set
|
||||
# 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 is not set
|
||||
# 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
|
||||
|
||||
#
|
||||
# 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=y
|
||||
CONFIG_I2CTOOL_MINBUS=0
|
||||
CONFIG_I2CTOOL_MAXBUS=3
|
||||
CONFIG_I2CTOOL_MINADDR=0x03
|
||||
CONFIG_I2CTOOL_MAXADDR=0x77
|
||||
CONFIG_I2CTOOL_MAXREGADDR=0xff
|
||||
CONFIG_I2CTOOL_DEFFREQ=4000000
|
||||
|
||||
#
|
||||
# FLASH Program Installation
|
||||
#
|
||||
# CONFIG_SYSTEM_INSTALL is not set
|
||||
|
||||
#
|
||||
# FLASH Erase-all Command
|
||||
#
|
||||
# CONFIG_SYSTEM_FLASH_ERASEALL is not set
|
||||
|
||||
#
|
||||
# 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,67 @@
|
|||
#!/bin/bash
|
||||
# configs/aerocore/nsh/setenv.sh
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
|
||||
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 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 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"
|
||||
|
||||
# This 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/aerocore/common/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 STM32F427 has 2048Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 256Kb 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 SRAM beginning at address 0x2002:0000
|
||||
* 4) 64Kb of TCM 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 0x4000 of flash is reserved for the bootloader.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x08004000, LENGTH = 2032K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
|
||||
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/aerocore/src/Makefile
|
||||
#
|
||||
# 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)/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,282 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file aerocore_init.c
|
||||
*
|
||||
* AeroCore-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 <nuttx/config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/spi.h>
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <nuttx/gran.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>
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
/****************************************************************************
|
||||
* 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
|
||||
|
||||
/****************************************************************************
|
||||
* Protected Functions
|
||||
****************************************************************************/
|
||||
|
||||
#if defined(CONFIG_FAT_DMAMEMORY)
|
||||
# if !defined(CONFIG_GRAN) || !defined(CONFIG_FAT_DMAMEMORY)
|
||||
# error microSD DMA support requires CONFIG_GRAN
|
||||
# endif
|
||||
|
||||
static GRAN_HANDLE dma_allocator;
|
||||
|
||||
/*
|
||||
* The DMA heap size constrains the total number of things that can be
|
||||
* ready to do DMA at a time.
|
||||
*
|
||||
* For example, FAT DMA depends on one sector-sized buffer per filesystem plus
|
||||
* one sector-sized buffer per file.
|
||||
*
|
||||
* We use a fundamental alignment / granule size of 64B; this is sufficient
|
||||
* to guarantee alignment for the largest STM32 DMA burst (16 beats x 32bits).
|
||||
*/
|
||||
static uint8_t g_dma_heap[8192] __attribute__((aligned(64)));
|
||||
static perf_counter_t g_dma_perf;
|
||||
|
||||
static void
|
||||
dma_alloc_init(void)
|
||||
{
|
||||
dma_allocator = gran_initialize(g_dma_heap,
|
||||
sizeof(g_dma_heap),
|
||||
7, /* 128B granule - must be > alignment (XXX bug?) */
|
||||
6); /* 64B alignment */
|
||||
if (dma_allocator == NULL) {
|
||||
message("[boot] DMA allocator setup FAILED");
|
||||
} else {
|
||||
g_dma_perf = perf_alloc(PC_COUNT, "DMA allocations");
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* DMA-aware allocator stubs for the FAT filesystem.
|
||||
*/
|
||||
|
||||
__EXPORT void *fat_dma_alloc(size_t size);
|
||||
__EXPORT void fat_dma_free(FAR void *memory, size_t size);
|
||||
|
||||
void *
|
||||
fat_dma_alloc(size_t size)
|
||||
{
|
||||
perf_count(g_dma_perf);
|
||||
return gran_alloc(dma_allocator, size);
|
||||
}
|
||||
|
||||
void
|
||||
fat_dma_free(FAR void *memory, size_t size)
|
||||
{
|
||||
gran_free(dma_allocator, memory, size);
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
# define dma_alloc_init()
|
||||
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* 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)
|
||||
{
|
||||
/* configure SPI interfaces */
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* configure LEDs */
|
||||
up_ledinit();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_archinitialize
|
||||
*
|
||||
* Description:
|
||||
* Perform architecture specific initialization
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static struct spi_dev_s *spi3;
|
||||
static struct spi_dev_s *spi4;
|
||||
|
||||
#include <math.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
__EXPORT int matherr(struct __exception *e)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
#else
|
||||
__EXPORT int matherr(struct exception *e)
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
#endif
|
||||
|
||||
__EXPORT int nsh_archinitialize(void)
|
||||
{
|
||||
|
||||
/* configure ADC pins */
|
||||
stm32_configgpio(GPIO_ADC1_IN10); /* used by VBUS valid */
|
||||
stm32_configgpio(GPIO_ADC1_IN11); /* J1 breakout */
|
||||
stm32_configgpio(GPIO_ADC1_IN12); /* J1 breakout */
|
||||
stm32_configgpio(GPIO_ADC1_IN13); /* J1 breakout */
|
||||
|
||||
/* configure the high-resolution time/callout interface */
|
||||
hrt_init();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
dma_alloc_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);
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_AMBER);
|
||||
|
||||
/* Configure Sensors on SPI bus #3 */
|
||||
spi3 = up_spiinitialize(3);
|
||||
if (!spi3) {
|
||||
message("[boot] FAILED to initialize SPI port 3\n");
|
||||
up_ledon(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
/* Default: 1MHz, 8 bits, Mode 3 */
|
||||
SPI_SETFREQUENCY(spi3, 10000000);
|
||||
SPI_SETBITS(spi3, 8);
|
||||
SPI_SETMODE(spi3, SPIDEV_MODE3);
|
||||
SPI_SELECT(spi3, PX4_SPIDEV_GYRO, false);
|
||||
SPI_SELECT(spi3, PX4_SPIDEV_ACCEL_MAG, false);
|
||||
SPI_SELECT(spi3, PX4_SPIDEV_BARO, false);
|
||||
up_udelay(20);
|
||||
message("[boot] Initialized SPI port 3 (SENSORS)\n");
|
||||
|
||||
/* Configure FRAM on SPI bus #4 */
|
||||
spi4 = up_spiinitialize(4);
|
||||
if (!spi4) {
|
||||
message("[boot] FAILED to initialize SPI port 4\n");
|
||||
up_ledon(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
/* Default: ~10MHz, 8 bits, Mode 3 */
|
||||
SPI_SETFREQUENCY(spi4, 10 * 1000 * 1000);
|
||||
SPI_SETBITS(spi4, 8);
|
||||
SPI_SETMODE(spi4, SPIDEV_MODE0);
|
||||
SPI_SELECT(spi4, SPIDEV_FLASH, false);
|
||||
message("[boot] Initialized SPI port 4 (FRAM)\n");
|
||||
|
||||
return OK;
|
||||
}
|
|
@ -0,0 +1,121 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 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 aerocore_led.c
|
||||
*
|
||||
* AeroCore LED backend.
|
||||
*/
|
||||
|
||||
#include <nuttx/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();
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
__EXPORT void led_init()
|
||||
{
|
||||
stm32_configgpio(GPIO_LED0);
|
||||
stm32_configgpio(GPIO_LED1);
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
switch (led) {
|
||||
case 0:
|
||||
stm32_gpiowrite(GPIO_LED0, true);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
stm32_gpiowrite(GPIO_LED1, true);
|
||||
break;
|
||||
|
||||
default:
|
||||
warnx("LED ID not recognized\n");
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
switch (led) {
|
||||
case 0:
|
||||
stm32_gpiowrite(GPIO_LED0, false);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
stm32_gpiowrite(GPIO_LED1, false);
|
||||
break;
|
||||
|
||||
default:
|
||||
warnx("LED ID not recognized\n");
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
switch (led) {
|
||||
case 0:
|
||||
if (stm32_gpioread(GPIO_LED0))
|
||||
stm32_gpiowrite(GPIO_LED0, false);
|
||||
else
|
||||
stm32_gpiowrite(GPIO_LED0, true);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
if (stm32_gpioread(GPIO_LED1))
|
||||
stm32_gpiowrite(GPIO_LED1, false);
|
||||
else
|
||||
stm32_gpiowrite(GPIO_LED1, true);
|
||||
break;
|
||||
|
||||
default:
|
||||
warnx("LED ID not recognized\n");
|
||||
}
|
||||
}
|
|
@ -0,0 +1,117 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* @file aerocore_pwm_servo.c
|
||||
*
|
||||
* Configuration data for the stm32 pwm_servo 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/stm32/drv_pwm_servo.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
|
||||
{
|
||||
.base = STM32_TIM1_BASE,
|
||||
.clock_register = STM32_RCC_APB2ENR,
|
||||
.clock_bit = RCC_APB2ENR_TIM1EN,
|
||||
.clock_freq = STM32_APB2_TIM1_CLKIN
|
||||
},
|
||||
{
|
||||
.base = STM32_TIM3_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_bit = RCC_APB1ENR_TIM3EN,
|
||||
.clock_freq = STM32_APB1_TIM3_CLKIN
|
||||
}
|
||||
};
|
||||
|
||||
__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
|
||||
{
|
||||
.gpio = GPIO_TIM1_CH1OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 1,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM1_CH2OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 2,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM1_CH3OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 3,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM1_CH4OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 4,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM3_CH1OUT,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 1,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM3_CH2OUT,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 2,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM3_CH3OUT,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 3,
|
||||
.default_value = 1500,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM3_CH4OUT,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 4,
|
||||
.default_value = 1500,
|
||||
}
|
||||
};
|
|
@ -0,0 +1,183 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file aerocore_spi.c
|
||||
*
|
||||
* Board-specific SPI functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/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 PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void weak_function stm32_spiinitialize(void)
|
||||
{
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
stm32_configgpio(GPIO_SPI1_NSS);
|
||||
stm32_gpiowrite(GPIO_SPI1_NSS, 1);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI2
|
||||
stm32_configgpio(GPIO_SPI2_NSS);
|
||||
stm32_gpiowrite(GPIO_SPI2_NSS, 1);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI3
|
||||
stm32_configgpio(GPIO_SPI_CS_GYRO);
|
||||
stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
|
||||
stm32_configgpio(GPIO_SPI_CS_BARO);
|
||||
|
||||
/* De-activate all peripherals,
|
||||
* required for some peripheral
|
||||
* state machines
|
||||
*/
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
|
||||
stm32_configgpio(GPIO_EXTI_GYRO_DRDY);
|
||||
stm32_configgpio(GPIO_EXTI_MAG_DRDY);
|
||||
stm32_configgpio(GPIO_EXTI_ACCEL_DRDY);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI4
|
||||
stm32_configgpio(GPIO_SPI4_NSS);
|
||||
stm32_gpiowrite(GPIO_SPI4_NSS, 1);
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
/* there is only one device broken-out so select it */
|
||||
stm32_gpiowrite(GPIO_SPI1_NSS, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI2
|
||||
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
/* there is only one device broken-out so select it */
|
||||
stm32_gpiowrite(GPIO_SPI2_NSS, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI3
|
||||
__EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
/* SPI select is active low, so write !selected to select the device */
|
||||
|
||||
switch (devid) {
|
||||
case PX4_SPIDEV_GYRO:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_ACCEL_MAG:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_BARO:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32_SPI4
|
||||
__EXPORT void stm32_spi4select(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_SPI4_NSS, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
/* FRAM is always present */
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
|
@ -0,0 +1,176 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013, 2014 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
|
||||
*
|
||||
* AeroCore internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <nuttx/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>
|
||||
|
||||
#define UDID_START 0x1FFF7A10
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
/* LEDs */
|
||||
#define GPIO_LED0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN9)
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN10)
|
||||
|
||||
/* Gyro */
|
||||
#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN0)
|
||||
|
||||
/* Accel & Mag */
|
||||
#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN1)
|
||||
#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN2)
|
||||
|
||||
/* GPS */
|
||||
#define GPIO_GPS_NRESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
|
||||
#define GPIO_GPS_TIMEPULSE (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN4)
|
||||
|
||||
/* SPI3--Sensors */
|
||||
#define PX4_SPI_BUS_SENSORS 3
|
||||
#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2)
|
||||
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
|
||||
|
||||
/* Nominal chip selects for devices on SPI bus #3 */
|
||||
#define PX4_SPIDEV_ACCEL_MAG 0
|
||||
#define PX4_SPIDEV_GYRO 1
|
||||
#define PX4_SPIDEV_BARO 2
|
||||
|
||||
/* User GPIOs broken out on J11 */
|
||||
#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN1)
|
||||
//#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_GPIO6_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN12)
|
||||
#define GPIO_GPIO7_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_GPIO8_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
|
||||
#define GPIO_GPIO9_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN15)
|
||||
#define GPIO_GPIO10_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_GPIO11_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN8)
|
||||
|
||||
#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
|
||||
//#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_GPIO6_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN12)
|
||||
#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_GPIO8_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
|
||||
#define GPIO_GPIO9_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15)
|
||||
#define GPIO_GPIO10_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_GPIO11_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
|
||||
|
||||
/* PWM
|
||||
*
|
||||
* Eight PWM outputs are configured.
|
||||
*
|
||||
* Pins:
|
||||
*
|
||||
* CH1 : PA8 : TIM1_CH1
|
||||
* CH2 : PA9 : TIM1_CH2
|
||||
* CH3 : PA10 : TIM1_CH3
|
||||
* CH4 : PA11 : TIM1_CH4
|
||||
* CH5 : PC6 : TIM3_CH1
|
||||
* CH6 : PC7 : TIM3_CH2
|
||||
* CH7 : PC8 : TIM3_CH3
|
||||
* CH8 : PC9 : TIM3_CH4
|
||||
*/
|
||||
#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_1
|
||||
#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_1
|
||||
#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_1
|
||||
#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_1
|
||||
#define GPIO_TIM3_CH1OUT GPIO_TIM3_CH1OUT_3
|
||||
#define GPIO_TIM3_CH2OUT GPIO_TIM3_CH2OUT_3
|
||||
#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_2
|
||||
#define GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_2
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 8 /* use timer 8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
|
||||
|
||||
/* Tone Alarm (no onboard speaker )*/
|
||||
#define TONE_ALARM_TIMER 2 /* timer 2 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* channel 1 */
|
||||
#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
|
||||
|
||||
|
||||
/****************************************************************************************************
|
||||
* 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);
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
|
@ -0,0 +1,8 @@
|
|||
#
|
||||
# Board-specific startup code for the AeroCore
|
||||
#
|
||||
|
||||
SRCS = aerocore_init.c \
|
||||
aerocore_pwm_servo.c \
|
||||
aerocore_spi.c \
|
||||
aerocore_led.c
|
|
@ -85,6 +85,8 @@ __BEGIN_DECLS
|
|||
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
|
||||
|
||||
#define PX4_SPI_BUS_SENSORS 1
|
||||
|
||||
/*
|
||||
* Use these in place of the spi_dev_e enumeration to
|
||||
* select a specific SPI device on SPI1
|
||||
|
|
|
@ -107,6 +107,8 @@ __BEGIN_DECLS
|
|||
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
|
||||
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
|
||||
|
||||
#define PX4_SPI_BUS_SENSORS 1
|
||||
|
||||
/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
|
||||
#define PX4_SPIDEV_GYRO 1
|
||||
#define PX4_SPIDEV_ACCEL_MAG 2
|
||||
|
|
|
@ -94,6 +94,14 @@
|
|||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
/*
|
||||
* AeroCore GPIO numbers and configuration.
|
||||
*
|
||||
*/
|
||||
# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
|
||||
/* no GPIO driver on the PX4IOv1 board */
|
||||
#endif
|
||||
|
|
|
@ -46,7 +46,11 @@
|
|||
#include "drv_sensor.h"
|
||||
#include "drv_orb_dev.h"
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
#define GPS_DEFAULT_UART_PORT "/dev/ttyS0"
|
||||
#else
|
||||
#define GPS_DEFAULT_UART_PORT "/dev/ttyS3"
|
||||
#endif
|
||||
|
||||
#define GPS_DEVICE_PATH "/dev/gps"
|
||||
|
||||
|
|
|
@ -63,6 +63,8 @@
|
|||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#include "ubx.h"
|
||||
#include "mtk.h"
|
||||
|
||||
|
@ -421,7 +423,14 @@ GPS::task_main()
|
|||
void
|
||||
GPS::cmd_reset()
|
||||
{
|
||||
//XXX add reset?
|
||||
#ifdef GPIO_GPS_NRESET
|
||||
warnx("Toggling GPS reset pin");
|
||||
stm32_configgpio(GPIO_GPS_NRESET);
|
||||
stm32_gpiowrite(GPIO_GPS_NRESET, 0);
|
||||
usleep(100);
|
||||
stm32_gpiowrite(GPIO_GPS_NRESET, 1);
|
||||
warnx("Toggled GPS reset pin");
|
||||
#endif
|
||||
}
|
||||
|
||||
void
|
||||
|
|
|
@ -1793,7 +1793,7 @@ start()
|
|||
errx(0, "already started");
|
||||
|
||||
/* create the driver */
|
||||
g_dev = new LSM303D(1 /* SPI dev 1 */, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
|
||||
g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
|
||||
|
||||
if (g_dev == nullptr) {
|
||||
warnx("failed instantiating LSM303D obj");
|
||||
|
|
|
@ -117,7 +117,7 @@ private:
|
|||
device::Device *
|
||||
MS5611_spi_interface(ms5611::prom_u &prom_buf)
|
||||
{
|
||||
return new MS5611_SPI(1 /* XXX MAGIC NUMBER */, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
|
||||
return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
|
||||
}
|
||||
|
||||
MS5611_SPI::MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf) :
|
||||
|
|
|
@ -92,6 +92,7 @@ public:
|
|||
MODE_2PWM,
|
||||
MODE_4PWM,
|
||||
MODE_6PWM,
|
||||
MODE_8PWM,
|
||||
};
|
||||
PX4FMU();
|
||||
virtual ~PX4FMU();
|
||||
|
@ -113,6 +114,9 @@ private:
|
|||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
static const unsigned _max_actuators = 6;
|
||||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_AEROCORE)
|
||||
static const unsigned _max_actuators = 8;
|
||||
#endif
|
||||
|
||||
Mode _mode;
|
||||
unsigned _pwm_default_rate;
|
||||
|
@ -203,6 +207,21 @@ const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
|
|||
{GPIO_VDD_5V_HIPOWER_OC, 0, 0},
|
||||
{GPIO_VDD_5V_PERIPH_OC, 0, 0},
|
||||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_AEROCORE)
|
||||
/* AeroCore breaks out User GPIOs on J11 */
|
||||
{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},
|
||||
{GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, 0},
|
||||
{GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, 0},
|
||||
{GPIO_GPIO8_INPUT, GPIO_GPIO8_OUTPUT, 0},
|
||||
{GPIO_GPIO9_INPUT, GPIO_GPIO9_OUTPUT, 0},
|
||||
{GPIO_GPIO10_INPUT, GPIO_GPIO10_OUTPUT, 0},
|
||||
{GPIO_GPIO11_INPUT, GPIO_GPIO11_OUTPUT, 0},
|
||||
#endif
|
||||
};
|
||||
|
||||
const unsigned PX4FMU::_ngpio = sizeof(PX4FMU::_gpio_tab) / sizeof(PX4FMU::_gpio_tab[0]);
|
||||
|
@ -382,6 +401,20 @@ PX4FMU::set_mode(Mode mode)
|
|||
|
||||
break;
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case MODE_8PWM: // AeroCore PWMs as 8 PWM outs
|
||||
debug("MODE_8PWM");
|
||||
/* default output rates */
|
||||
_pwm_default_rate = 50;
|
||||
_pwm_alt_rate = 50;
|
||||
_pwm_alt_rate_channels = 0;
|
||||
|
||||
/* XXX magic numbers */
|
||||
up_pwm_servo_init(0xff);
|
||||
set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MODE_NONE:
|
||||
debug("MODE_NONE");
|
||||
|
||||
|
@ -602,6 +635,9 @@ PX4FMU::task_main()
|
|||
num_outputs = 6;
|
||||
break;
|
||||
|
||||
case MODE_8PWM:
|
||||
num_outputs = 8;
|
||||
break;
|
||||
default:
|
||||
num_outputs = 0;
|
||||
break;
|
||||
|
@ -757,6 +793,9 @@ PX4FMU::ioctl(file *filp, int cmd, unsigned long arg)
|
|||
case MODE_2PWM:
|
||||
case MODE_4PWM:
|
||||
case MODE_6PWM:
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case MODE_8PWM:
|
||||
#endif
|
||||
ret = pwm_ioctl(filp, cmd, arg);
|
||||
break;
|
||||
|
||||
|
@ -986,6 +1025,15 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
|||
break;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case PWM_SERVO_SET(7):
|
||||
case PWM_SERVO_SET(6):
|
||||
if (_mode < MODE_8PWM) {
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
case PWM_SERVO_SET(5):
|
||||
case PWM_SERVO_SET(4):
|
||||
if (_mode < MODE_6PWM) {
|
||||
|
@ -1013,6 +1061,15 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
|||
|
||||
break;
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case PWM_SERVO_GET(7):
|
||||
case PWM_SERVO_GET(6):
|
||||
if (_mode < MODE_8PWM) {
|
||||
ret = -EINVAL;
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
case PWM_SERVO_GET(5):
|
||||
case PWM_SERVO_GET(4):
|
||||
if (_mode < MODE_6PWM) {
|
||||
|
@ -1040,12 +1097,22 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
|||
case PWM_SERVO_GET_RATEGROUP(3):
|
||||
case PWM_SERVO_GET_RATEGROUP(4):
|
||||
case PWM_SERVO_GET_RATEGROUP(5):
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case PWM_SERVO_GET_RATEGROUP(6):
|
||||
case PWM_SERVO_GET_RATEGROUP(7):
|
||||
#endif
|
||||
*(uint32_t *)arg = up_pwm_servo_get_rate_group(cmd - PWM_SERVO_GET_RATEGROUP(0));
|
||||
break;
|
||||
|
||||
case PWM_SERVO_GET_COUNT:
|
||||
case MIXERIOCGETOUTPUTCOUNT:
|
||||
switch (_mode) {
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
case MODE_8PWM:
|
||||
*(unsigned *)arg = 8;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MODE_6PWM:
|
||||
*(unsigned *)arg = 6;
|
||||
break;
|
||||
|
@ -1091,6 +1158,11 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
|
|||
set_mode(MODE_6PWM);
|
||||
break;
|
||||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_AEROCORE)
|
||||
case 8:
|
||||
set_mode(MODE_8PWM);
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
ret = -EINVAL;
|
||||
|
@ -1181,10 +1253,17 @@ PX4FMU::write(file *filp, const char *buffer, size_t len)
|
|||
unsigned count = len / 2;
|
||||
uint16_t values[6];
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
if (count > 8) {
|
||||
// we have at most 8 outputs
|
||||
count = 8;
|
||||
}
|
||||
#else
|
||||
if (count > 6) {
|
||||
// we have at most 6 outputs
|
||||
count = 6;
|
||||
}
|
||||
#endif
|
||||
|
||||
// allow for misaligned values
|
||||
memcpy(values, buffer, count * 2);
|
||||
|
@ -1458,6 +1537,9 @@ fmu_new_mode(PortMode new_mode)
|
|||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
servo_mode = PX4FMU::MODE_6PWM;
|
||||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_AEROCORE)
|
||||
servo_mode = PX4FMU::MODE_8PWM;
|
||||
#endif
|
||||
break;
|
||||
|
||||
|
@ -1776,7 +1858,7 @@ fmu_main(int argc, char *argv[])
|
|||
fprintf(stderr, "FMU: unrecognised command %s, try:\n", verb);
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, test\n");
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_AEROCORE)
|
||||
fprintf(stderr, " mode_gpio, mode_pwm, test, sensor_reset [milliseconds]\n");
|
||||
#endif
|
||||
exit(1);
|
||||
|
|
|
@ -419,6 +419,10 @@ adc_main(int argc, char *argv[])
|
|||
g_adc = new ADC((1 << 2) | (1 << 3) | (1 << 4) |
|
||||
(1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15));
|
||||
#endif
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
/* XXX this hardcodes the default channel set for AeroCore - should be configurable */
|
||||
g_adc = new ADC((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
|
||||
#endif
|
||||
|
||||
if (g_adc == nullptr)
|
||||
errx(1, "couldn't allocate the ADC driver");
|
||||
|
|
|
@ -141,7 +141,7 @@
|
|||
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
|
||||
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM10EN
|
||||
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1UP
|
||||
# define HRT_TIMER_CLOCK STM32_APB1_TIM10_CLKIN
|
||||
# define HRT_TIMER_CLOCK STM32_APB2_TIM10_CLKIN
|
||||
# if CONFIG_STM32_TIM10
|
||||
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=10
|
||||
# endif
|
||||
|
@ -150,7 +150,7 @@
|
|||
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
|
||||
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM11EN
|
||||
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1TRGCOM
|
||||
# define HRT_TIMER_CLOCK STM32_APB1_TIM11_CLKIN
|
||||
# define HRT_TIMER_CLOCK STM32_APB2_TIM11_CLKIN
|
||||
# if CONFIG_STM32_TIM11
|
||||
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11
|
||||
# endif
|
||||
|
|
|
@ -59,4 +59,8 @@
|
|||
#define HW_ARCH "PX4FMU_V2"
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
#define HW_ARCH "AEROCORE"
|
||||
#endif
|
||||
|
||||
#endif /* VERSION_H_ */
|
||||
|
|
|
@ -206,7 +206,7 @@ int led_init()
|
|||
return ERROR;
|
||||
}
|
||||
|
||||
/* the blue LED is only available on FMUv1 but not FMUv2 */
|
||||
/* the blue LED is only available on FMUv1 & AeroCore but not FMUv2 */
|
||||
(void)ioctl(leds, LED_ON, LED_BLUE);
|
||||
|
||||
/* we consider the amber led mandatory */
|
||||
|
|
|
@ -488,6 +488,15 @@ PARAM_DEFINE_INT32(BAT_V_SCALE_IO, 10000);
|
|||
* @group Battery Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0082f);
|
||||
#elif CONFIG_ARCH_BOARD_AEROCORE
|
||||
/**
|
||||
* Scaling factor for battery voltage sensor on AeroCore.
|
||||
*
|
||||
* For R70 = 133K, R71 = 10K --> scale = 1.8 * 143 / (4096*10) = 0.0063
|
||||
*
|
||||
* @group Battery Calibration
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0063f);
|
||||
#else
|
||||
/**
|
||||
* Scaling factor for battery voltage sensor on FMU v1.
|
||||
|
|
|
@ -126,6 +126,12 @@
|
|||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL -1
|
||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL -1
|
||||
#endif
|
||||
|
||||
#define BATT_V_LOWPASS 0.001f
|
||||
#define BATT_V_IGNORE_THRESHOLD 3.5f
|
||||
|
||||
|
@ -797,7 +803,7 @@ Sensors::accel_init()
|
|||
/* set the driver to poll at 1000Hz */
|
||||
ioctl(fd, SENSORIOCSPOLLRATE, 1000);
|
||||
|
||||
#elif CONFIG_ARCH_BOARD_PX4FMU_V2
|
||||
#elif CONFIG_ARCH_BOARD_PX4FMU_V2 || CONFIG_ARCH_BOARD_AEROCORE
|
||||
|
||||
/* set the accel internal sampling rate up to at leat 800Hz */
|
||||
ioctl(fd, ACCELIOCSSAMPLERATE, 800);
|
||||
|
@ -806,7 +812,7 @@ Sensors::accel_init()
|
|||
ioctl(fd, SENSORIOCSPOLLRATE, 800);
|
||||
|
||||
#else
|
||||
#error Need a board configuration, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
|
||||
#error Need a board configuration, either CONFIG_ARCH_BOARD_PX4FMU_V1, CONFIG_ARCH_BOARD_PX4FMU_V2 or CONFIG_ARCH_BOARD_AEROCORE
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -160,7 +160,11 @@ static void
|
|||
ramtron_attach(void)
|
||||
{
|
||||
/* find the right spi */
|
||||
#ifdef CONFIG_ARCH_BOARD_AEROCORE
|
||||
struct spi_dev_s *spi = up_spiinitialize(4);
|
||||
#else
|
||||
struct spi_dev_s *spi = up_spiinitialize(2);
|
||||
#endif
|
||||
/* this resets the spi bus, set correct bus speed again */
|
||||
SPI_SETFREQUENCY(spi, 10 * 1000 * 1000);
|
||||
SPI_SETBITS(spi, 8);
|
||||
|
|
Loading…
Reference in New Issue