forked from Archive/PX4-Autopilot
Adding px4fmu-v4pro
This commit is contained in:
parent
f14a0ba107
commit
925102464b
|
@ -0,0 +1,12 @@
|
|||
{
|
||||
"board_id": 13,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the PX4FMUv4PRO board, based on STM32F469",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "PX4FMUv4PRO",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
|
@ -299,6 +299,29 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp PX4FMU_V4PRO
|
||||
then
|
||||
# Internal SPI bus ICM-20608-G
|
||||
if mpu6000 -R 2 -T 20608 start
|
||||
then
|
||||
fi
|
||||
|
||||
# Internal SPI bus mpu9250
|
||||
if mpu9250 -R 2 start
|
||||
then
|
||||
fi
|
||||
|
||||
# Possible external compasses
|
||||
if hmc5883 -X start
|
||||
then
|
||||
fi
|
||||
|
||||
# Internal SPI bus
|
||||
if lis3mdl -R 2 start
|
||||
then
|
||||
fi
|
||||
fi
|
||||
|
||||
if meas_airspeed start
|
||||
then
|
||||
else
|
||||
|
|
|
@ -0,0 +1,225 @@
|
|||
include(nuttx/px4_impl_nuttx)
|
||||
|
||||
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake)
|
||||
|
||||
set(config_uavcan_num_ifaces 2)
|
||||
|
||||
set(config_module_list
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
drivers/device
|
||||
drivers/stm32
|
||||
drivers/stm32/adc
|
||||
drivers/stm32/tone_alarm
|
||||
drivers/led
|
||||
drivers/px4fmu
|
||||
drivers/px4io
|
||||
drivers/boards/px4fmu-v4pro
|
||||
drivers/rgbled
|
||||
drivers/mpu6000
|
||||
drivers/mpu9250
|
||||
drivers/lsm303d
|
||||
drivers/l3gd20
|
||||
drivers/hmc5883
|
||||
drivers/ms5611
|
||||
drivers/mb12xx
|
||||
drivers/srf02
|
||||
drivers/sf0x
|
||||
drivers/ll40ls
|
||||
drivers/trone
|
||||
drivers/gps
|
||||
drivers/pwm_out_sim
|
||||
drivers/hott
|
||||
drivers/hott/hott_telemetry
|
||||
drivers/hott/hott_sensors
|
||||
drivers/blinkm
|
||||
drivers/airspeed
|
||||
drivers/ets_airspeed
|
||||
drivers/meas_airspeed
|
||||
drivers/frsky_telemetry
|
||||
modules/sensors
|
||||
drivers/mkblctrl
|
||||
drivers/px4flow
|
||||
drivers/oreoled
|
||||
drivers/vmount
|
||||
drivers/pwm_input
|
||||
drivers/camera_trigger
|
||||
drivers/bst
|
||||
drivers/snapdragon_rc_pwm
|
||||
drivers/lis3mdl
|
||||
drivers/sf1xx
|
||||
drivers/bmp280
|
||||
drivers/bma180
|
||||
drivers/bmi160
|
||||
drivers/tap_esc
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
systemcmds/bl_update
|
||||
systemcmds/config
|
||||
systemcmds/dumpfile
|
||||
systemcmds/esc_calib
|
||||
systemcmds/hardfault_log
|
||||
systemcmds/mixer
|
||||
systemcmds/motor_ramp
|
||||
systemcmds/mtd
|
||||
systemcmds/nshterm
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/pwm
|
||||
systemcmds/reboot
|
||||
systemcmds/sd_bench
|
||||
systemcmds/top
|
||||
systemcmds/topic_listener
|
||||
systemcmds/ver
|
||||
|
||||
#
|
||||
# Testing
|
||||
#
|
||||
drivers/sf0x/sf0x_tests
|
||||
drivers/test_ppm
|
||||
modules/commander/commander_tests
|
||||
modules/mc_pos_control/mc_pos_control_tests
|
||||
modules/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/unit_test
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
modules/commander
|
||||
modules/load_mon
|
||||
modules/navigator
|
||||
modules/mavlink
|
||||
modules/gpio_led
|
||||
modules/uavcan
|
||||
modules/land_detector
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
modules/attitude_estimator_q
|
||||
modules/position_estimator_inav
|
||||
modules/local_position_estimator
|
||||
modules/ekf2
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
# modules/segway # XXX Needs GCC 4.7 fix
|
||||
modules/fw_pos_control_l1
|
||||
modules/fw_att_control
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
modules/sdlog2
|
||||
modules/logger
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/uORB
|
||||
modules/dataman
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/conversion
|
||||
lib/launchdetection
|
||||
lib/terrain_estimation
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
platforms/nuttx
|
||||
|
||||
# had to add for cmake, not sure why wasn't in original config
|
||||
platforms/common
|
||||
platforms/nuttx/px4_layer
|
||||
|
||||
#
|
||||
# OBC challenge
|
||||
#
|
||||
modules/bottle_drop
|
||||
|
||||
#
|
||||
# Rover apps
|
||||
#
|
||||
examples/rover_steering_control
|
||||
|
||||
#
|
||||
# Demo apps
|
||||
#
|
||||
#examples/math_demo
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/px4_simple_app
|
||||
examples/px4_simple_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/daemon
|
||||
#examples/px4_daemon_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/debug_values
|
||||
#examples/px4_mavlink_debug
|
||||
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/example_fixedwing_control
|
||||
#examples/fixedwing_control
|
||||
|
||||
# Hardware test
|
||||
#examples/hwtest
|
||||
|
||||
# EKF
|
||||
examples/ekf_att_pos_estimator
|
||||
)
|
||||
|
||||
set(config_extra_builtin_cmds
|
||||
serdis
|
||||
sercon
|
||||
)
|
||||
|
||||
set(config_io_board
|
||||
px4io-v2
|
||||
)
|
||||
|
||||
set(config_extra_libs
|
||||
uavcan
|
||||
uavcan_stm32_driver
|
||||
)
|
||||
|
||||
set(config_io_extra_libs
|
||||
)
|
||||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon"
|
||||
STACK_MAIN "2048"
|
||||
COMPILE_FLAGS "-Os")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis"
|
||||
STACK_MAIN "2048"
|
||||
COMPILE_FLAGS "-Os")
|
|
@ -0,0 +1,22 @@
|
|||
#
|
||||
# For a description of the syntax of this configuration file,
|
||||
# see misc/tools/kconfig-language.txt.
|
||||
#
|
||||
|
||||
if ARCH_BOARD_PX4FMU_V4PRO
|
||||
|
||||
config BOARD_HAS_PROBES
|
||||
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
|
||||
default y
|
||||
---help---
|
||||
This board provides GPIO FMU-CH1-6 as PROBE_1-6 to provide timing signals from selected drivers.
|
||||
|
||||
config BOARD_USE_PROBES
|
||||
bool "Enable the use the board provided GPIO FMU-CH1-6 as PROBE_1-6 to provide timing signals from selected drivers"
|
||||
default n
|
||||
depends on BOARD_HAS_PROBES
|
||||
|
||||
---help---
|
||||
Select to use GPIO FMU-CH1-6 to provide timing signals from selected drivers.
|
||||
|
||||
endif
|
|
@ -0,0 +1,433 @@
|
|||
/************************************************************************************
|
||||
* configs/px4fmu-v4pro/include/board.h
|
||||
* include/arch/board/board.h
|
||||
*
|
||||
* Copyright (C) 2009, 2016 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
* Kevin Lopez Alvarez <kevin@drotek.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __NUTTX_CONFIG_PX4FMUV4_PRO_INCLUDE_BOARD_H
|
||||
#define __NUTTX_CONFIG_PX4FMUV4_PRO_INCLUDE_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
|
||||
#include <stm32.h>
|
||||
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The PX4FMUV4-PRO 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) : 180000000 Determined by PLL configuration
|
||||
* HCLK(Hz) : 180000000 (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 : 12 (STM32_PLLCFG_PLLM)
|
||||
* PLLN : 180 (STM32_PLLCFG_PLLN)
|
||||
* PLLP : 2 (STM32_PLLCFG_PLLP)
|
||||
* PLLQ : 2 (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, : Use PLLSA1M
|
||||
* 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 / 12) * 180
|
||||
* = 369,000,000
|
||||
* SYSCLK = PLL_VCO / PLLP
|
||||
* = 360,000,000 / 2 = 180,000,000
|
||||
* USB OTG FS, SDIO and RNG Clock is from PLL SAIP
|
||||
* = 48,000,000
|
||||
*/
|
||||
|
||||
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(12)
|
||||
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(180)
|
||||
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
|
||||
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(2)
|
||||
#define STM32_PLLCFG_PLLR RCC_PLLCFG_PLLR(2)
|
||||
|
||||
/* Configure factors for PLLSAI clock */
|
||||
|
||||
#define STM32_RCC_PLLSAICFGR_PLLSAIN RCC_PLLSAICFGR_PLLSAIN(96)
|
||||
#define STM32_RCC_PLLSAICFGR_PLLSAIP RCC_PLLSAICFGR_PLLSAIP(4)
|
||||
#define STM32_RCC_PLLSAICFGR_PLLSAIQ RCC_PLLSAICFGR_PLLSAIQ(2)
|
||||
#define STM32_RCC_PLLSAICFGR_PLLSAIR RCC_PLLSAICFGR_PLLSAIR(2)
|
||||
|
||||
/* Configure Dedicated Clock Configuration Register */
|
||||
|
||||
#define STM32_RCC_DCKCFGR_PLLI2SDIVQ RCC_DCKCFGR_PLLI2SDIVQ(1)
|
||||
#define STM32_RCC_DCKCFGR_PLLSAIDIVQ RCC_DCKCFGR_PLLSAIDIVQ(1)
|
||||
#define STM32_RCC_DCKCFGR_PLLSAIDIVR RCC_DCKCFGR_PLLSAIDIVR_DIV2
|
||||
#define STM32_RCC_DCKCFGR_SAI1ASRC RCC_DCKCFGR_SAI1ASRC_PLLSAI
|
||||
#define STM32_RCC_DCKCFGR_SAI1BSRC RCC_DCKCFGR_SAI1BSRC_PLLI2S
|
||||
#define STM32_RCC_DCKCFGR_TIMPRE 0
|
||||
#define STM32_RCC_DCKCFGR_48MSEL RCC_DCKCFGR_48MSEL_PLLSAI
|
||||
#define STM32_RCC_DCKCFGR_SDMMCSEL RCC_DCKCFGR_SDMMCSEL_48MHZ
|
||||
#define STM32_RCC_DCKCFGR_DSISEL RCC_DCKCFGR_DSISEL_DSIPHY
|
||||
|
||||
/* Configure factors for PLLI2S clock */
|
||||
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(96)
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(4)
|
||||
#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2)
|
||||
|
||||
|
||||
#define STM32_SYSCLK_FREQUENCY 180000000ul
|
||||
|
||||
/* AHB clock (HCLK) is SYSCLK (180MHz) */
|
||||
|
||||
#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 (45MHz) */
|
||||
|
||||
#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 (90MHz) */
|
||||
|
||||
#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-11 are on APB2, others on APB1
|
||||
*/
|
||||
|
||||
#define BOARD_TIM1_FREQUENCY STM32_APB2_TIM1_CLKIN
|
||||
#define BOARD_TIM2_FREQUENCY STM32_APB1_TIM2_CLKIN
|
||||
#define BOARD_TIM3_FREQUENCY STM32_APB1_TIM3_CLKIN
|
||||
#define BOARD_TIM4_FREQUENCY STM32_APB1_TIM4_CLKIN
|
||||
#define BOARD_TIM5_FREQUENCY STM32_APB1_TIM5_CLKIN
|
||||
#define BOARD_TIM6_FREQUENCY STM32_APB1_TIM6_CLKIN
|
||||
#define BOARD_TIM7_FREQUENCY STM32_APB1_TIM7_CLKIN
|
||||
#define BOARD_TIM8_FREQUENCY STM32_APB2_TIM8_CLKIN
|
||||
#define BOARD_TIM9_FREQUENCY STM32_APB2_TIM9_CLKIN
|
||||
#define BOARD_TIM10_FREQUENCY STM32_APB2_TIM10_CLKIN
|
||||
#define BOARD_TIM11_FREQUENCY STM32_APB2_TIM11_CLKIN
|
||||
#define BOARD_TIM12_FREQUENCY STM32_APB1_TIM12_CLKIN
|
||||
#define BOARD_TIM13_FREQUENCY STM32_APB1_TIM13_CLKIN
|
||||
#define BOARD_TIM14_FREQUENCY STM32_APB1_TIM14_CLKIN
|
||||
|
||||
/* SDMMC dividers. Note that slower clocking is required when DMA is disabled
|
||||
* in order to avoid RX overrun/TX underrun errors due to delayed responses
|
||||
* to service FIFOs in interrupt driven mode. These values have not been
|
||||
* tuned!!!
|
||||
*
|
||||
* SDIOCLK =48MHz, SDMMC_CK=SDIOCLK/(118+2)=400 KHz
|
||||
*/
|
||||
|
||||
/* Use the Falling edge of the SDIO_CLK clock to change the edge the
|
||||
* data and commands are change on
|
||||
*/
|
||||
|
||||
#define SDIO_CLKCR_EDGE SDIO_CLKCR_NEGEDGE
|
||||
|
||||
#define SDIO_INIT_CLKDIV (118 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
|
||||
/* DMA ON: SDIOCLK=48MHz, SDMMC_CK=SDIOCLK/(1+2)=16 MHz
|
||||
* DMA OFF: SDIOCLK=48MHz, SDMMC_CK=SDIOCLK/(2+2)=12 MHz
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SDIO_DMA
|
||||
# define SDIO_MMCXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
/* DMA ON: SDIOCLK=48MHz, SDMMC_CK=SDIOCLK/(1+2)=16 MHz
|
||||
* DMA OFF: SDIOCLK=48MHz, SDMMC_CK=SDIOCLK/(2+2)=12 MHz
|
||||
*/
|
||||
//TODO #warning "Check Freq for 24mHz"
|
||||
|
||||
#ifdef CONFIG_SDIO_DMA
|
||||
# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define SDIO_SDXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
/* DMA Channel/Stream Selections *****************************************************/
|
||||
/* Stream selections are arbitrary for now but might become important in the future
|
||||
* is we set aside more DMA channels/streams.
|
||||
*
|
||||
* SDIO DMA
|
||||
* DMAMAP_SDIO_1 = Channel 4, Stream 3 <- may later be used by SPI DMA
|
||||
* DMAMAP_SDIO_2 = Channel 4, Stream 6
|
||||
*/
|
||||
|
||||
#define DMAMAP_SDIO DMAMAP_SDIO_1
|
||||
|
||||
|
||||
/* FLASH wait states
|
||||
*
|
||||
* --------- ---------- ----------- ---------
|
||||
* VDD MAX SYSCLK WAIT STATES OVERDRIVE
|
||||
* --------- ---------- ----------- ---------
|
||||
* 1.7-2.1 V 168 MHz 8 OFF
|
||||
* 2.1-2.4 V 180 MHz 8 ON
|
||||
* 2.4-2.7 V 180 MHz 7 ON
|
||||
* 2.7-3.6 V 180 MHz 5 ON
|
||||
* --------- ---------- ----------- --------
|
||||
*-
|
||||
*/
|
||||
|
||||
#define BOARD_FLASH_WAITSTATES 5
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* The px4fmu-v4pro board has numerous LEDs.
|
||||
* FMU_LED_RED, FMU_LED_GREEN & FMU_LED_BLUE are directly connected and
|
||||
* can be controlled by software.
|
||||
*
|
||||
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.
|
||||
* The following definitions are used to access individual LEDs.
|
||||
*/
|
||||
|
||||
/* LED index values for use with board_userled() */
|
||||
|
||||
#define BOARD_LED1 0
|
||||
#define BOARD_LED2 1
|
||||
#define BOARD_LED3 2
|
||||
#define BOARD_NLEDS 3
|
||||
|
||||
#define BOARD_LED_RED BOARD_LED1
|
||||
#define BOARD_LED_GREEN BOARD_LED2
|
||||
#define BOARD_LED_BLUE BOARD_LED3
|
||||
|
||||
/* LED bits for use with board_userled_all() */
|
||||
|
||||
#define BOARD_LED1_BIT (1 << BOARD_LED1)
|
||||
#define BOARD_LED2_BIT (1 << BOARD_LED2)
|
||||
#define BOARD_LED3_BIT (1 << BOARD_LED3)
|
||||
|
||||
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
|
||||
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
|
||||
* events as follows:
|
||||
*
|
||||
*
|
||||
* SYMBOL Meaning LED state
|
||||
* Red Green Blue
|
||||
* ---------------------- -------------------------- ------ ------ ----*/
|
||||
|
||||
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
|
||||
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
|
||||
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
|
||||
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
|
||||
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
|
||||
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
|
||||
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
|
||||
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
|
||||
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */
|
||||
|
||||
/* Thus if the Green LED is statically on, NuttX has successfully booted and
|
||||
* is, apparently, running normally. If the Red LED is flashing at
|
||||
* approximately 2Hz, then a fatal error has been detected and the system
|
||||
* has halted.
|
||||
*/
|
||||
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
||||
/*
|
||||
* UARTs.
|
||||
*/
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* ESP8266 */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_2
|
||||
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_2
|
||||
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3
|
||||
#define GPIO_USART3_RTS GPIO_USART3_RTS_2
|
||||
#define GPIO_USART3_CTS GPIO_USART3_CTS_2
|
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_1
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_1
|
||||
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* RC_INPUT */
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_1
|
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_1
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_1
|
||||
|
||||
/* UART8 has no alternate pin config */
|
||||
|
||||
/* UART RX DMA configurations */
|
||||
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
|
||||
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
|
||||
|
||||
/*
|
||||
* CAN
|
||||
*
|
||||
* CAN1 is routed to the onboard transceiver.
|
||||
*/
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3
|
||||
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_1
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_RX_1
|
||||
|
||||
/*
|
||||
* 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.
|
||||
*/
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
|
||||
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
|
||||
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
|
||||
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2
|
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2
|
||||
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN1)
|
||||
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN0)
|
||||
|
||||
|
||||
/*
|
||||
* SPI
|
||||
*
|
||||
* There are sensors on SPI1, and SPI2 is connected to the FRAM.
|
||||
|
||||
*/
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
|
||||
|
||||
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1
|
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_1
|
||||
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1
|
||||
#define GPIO_SPI5_SCK GPIO_SPI5_SCK_1
|
||||
#define GPIO_SPI5_NSS GPIO_SPI5_NSS_1
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes
|
||||
************************************************************************************/
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the initialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
EXTERN void stm32_boardinitialize(void);
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __NUTTX_CONFIG_PX4FMUV4_PRO_INCLUDE_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,164 @@
|
|||
############################################################################
|
||||
# configs/px4fmu-v4pro/nsh/Make.defs
|
||||
#
|
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name NuttX nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
include ${TOPDIR}/.config
|
||||
include ${TOPDIR}/tools/Config.mk
|
||||
include $(TOPDIR)/PX4_Warnings.mk
|
||||
include $(TOPDIR)/PX4_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${HOST_OS_FIRST_LETTER}
|
||||
|
||||
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
|
||||
|
||||
CC = $(CROSSDEV)gcc
|
||||
CXX = $(CROSSDEV)g++
|
||||
CPP = $(CROSSDEV)gcc -E
|
||||
LD = $(CROSSDEV)ld
|
||||
AR = $(CROSSDEV)ar rcs
|
||||
NM = $(CROSSDEV)nm
|
||||
OBJCOPY = $(CROSSDEV)objcopy
|
||||
OBJDUMP = $(CROSSDEV)objdump
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m4 \
|
||||
-mthumb \
|
||||
-march=armv7e-m \
|
||||
-mfpu=fpv4-sp-d16 \
|
||||
-mfloat-abi=hard
|
||||
|
||||
# Enable precise stack overflow tracking
|
||||
|
||||
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
|
||||
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
|
||||
endif
|
||||
|
||||
# Pull in *just* libm from the toolchain ... this is grody
|
||||
|
||||
LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
|
||||
EXTRA_LIBS += $(LIBM)
|
||||
|
||||
# Use our linker script
|
||||
|
||||
LDSCRIPT = ld.script
|
||||
|
||||
ifeq ($(WINTOOL),y)
|
||||
# Windows-native toolchains
|
||||
DIRLINK = $(TOPDIR)/tools/copydir.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||
else
|
||||
ifeq ($(PX4_WINTOOL),y)
|
||||
# Windows-native toolchains (MSYS)
|
||||
DIRLINK = $(TOPDIR)/tools/copydir.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||
else
|
||||
# Linux/Cygwin-native toolchain
|
||||
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
|
||||
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}
|
||||
|
||||
# Optimization flags
|
||||
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
|
||||
-fno-strict-aliasing \
|
||||
-fno-strength-reduce \
|
||||
-fomit-frame-pointer \
|
||||
-funsafe-math-optimizations \
|
||||
-fno-builtin-printf \
|
||||
-ffunction-sections \
|
||||
-fdata-sections
|
||||
|
||||
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
|
||||
ARCHOPTIMIZATION += -g
|
||||
endif
|
||||
|
||||
ARCHCFLAGS = -std=gnu99
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
|
||||
ARCHWARNINGS = $(PX4_ARCHWARNINGS)
|
||||
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
|
||||
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
|
||||
ARCHDEFINES =
|
||||
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
|
||||
|
||||
# This seems to be the only way to add linker flags
|
||||
|
||||
EXTRA_LIBS += --warn-common \
|
||||
--gc-sections
|
||||
|
||||
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
|
||||
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
|
||||
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
|
||||
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
|
||||
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
|
||||
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
|
||||
|
||||
NXFLATLDFLAGS1 = -r -d -warn-common
|
||||
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
|
||||
LDNXFLATFLAGS = -e main -s 2048
|
||||
|
||||
OBJEXT = .o
|
||||
LIBEXT = .a
|
||||
EXEEXT =
|
||||
|
||||
# Produce partially-linked $1 from files in $2
|
||||
|
||||
define PRELINK
|
||||
@echo "PRELINK: $1"
|
||||
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
|
||||
endef
|
||||
|
||||
HOSTCC = gcc
|
||||
HOSTINCLUDES = -I.
|
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
|
||||
HOSTLDFLAGS =
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,67 @@
|
|||
#!/bin/bash
|
||||
# configs/stm3240g-eval/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,158 @@
|
|||
/****************************************************************************
|
||||
* configs/px4fmu-v4pro/common/ld.script
|
||||
*
|
||||
* Copyright (C) 2011, 2016 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 STM32F469II has 2048Kb of FLASH beginning at address 0x0800:0000 and
|
||||
* 384Kb of SRAM. SRAM is split up into three blocks:
|
||||
*
|
||||
* 1) 160Kb of SRAM beginning at address 0x2000:0000
|
||||
* 2) 32Kb of SRAM beginning at address 0x2002:8000
|
||||
* 3) 128Kb of SRAM beginning at address 0x2003: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 = 320K
|
||||
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)
|
||||
EXTERN(_bootdelay_signature)
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
. = ALIGN(32);
|
||||
/*
|
||||
This signature provides the bootloader with a way to delay booting
|
||||
*/
|
||||
_bootdelay_signature = ABSOLUTE(.);
|
||||
FILL(0xffecc2925d7d05c5)
|
||||
. += 8;
|
||||
*(.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,88 @@
|
|||
############################################################################
|
||||
# configs/px4fmu-v4pro/src/Makefile
|
||||
#
|
||||
# Copyright (C) 2011, 2016 Gregory Nutt. All rights reserved.
|
||||
# Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
# David Sidrane <david_s5@nscdg.com>
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name NuttX nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
-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)
|
||||
|
||||
ifneq ($(BOARD_CONTEXT),y)
|
||||
context:
|
||||
endif
|
||||
|
||||
-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,48 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE drivers__boards__px4fmu-v4pro
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
../common/board_name.c
|
||||
../common/board_dma_alloc.c
|
||||
px4fmu_can.c
|
||||
px4fmu_init.c
|
||||
px4fmu_timer_config.c
|
||||
px4fmu_spi.c
|
||||
px4fmu_usb.c
|
||||
px4fmu_led.c
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
|
@ -0,0 +1,388 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2016 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file board_config.h
|
||||
*
|
||||
* PX4FMUv2 internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
/* these headers are not C++ safe */
|
||||
#include <stm32.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
/* PX4IO connection configuration */
|
||||
#define PX4IO_SERIAL_DEVICE "/dev/ttyS4"
|
||||
#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
|
||||
#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
|
||||
#define PX4IO_SERIAL_BASE STM32_USART6_BASE /* hardwired on the board */
|
||||
#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
|
||||
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX_2
|
||||
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX_2
|
||||
#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
|
||||
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
|
||||
|
||||
/* Configuration ************************************************************************************/
|
||||
//{GPIO_RSSI_IN, 0, 0}, - pio Analog used as PWM
|
||||
//{0, GPIO_LED_SAFETY, 0}, pio replacement
|
||||
//{GPIO_SAFETY_SWITCH_IN, 0, 0}, pio replacement
|
||||
//{0, GPIO_PERIPH_3V3_EN, 0}, Owned by the 8266 driver
|
||||
//{0, GPIO_SBUS_INV, 0}, https://github.com/PX4/Firmware/blob/master/src/modules/px4iofirmware/sbus.c
|
||||
//{GPIO_8266_GPIO0, 0, 0}, Owned by the 8266 driver
|
||||
//{0, GPIO_SPEKTRUM_PWR_EN, 0}, Owned Spektum driver input to auto pilot
|
||||
//{0, GPIO_8266_PD, 0}, Owned by the 8266 driver
|
||||
//{0, GPIO_8266_RST, 0}, Owned by the 8266 driver
|
||||
|
||||
/* PX4FMU GPIOs ***********************************************************************************/
|
||||
/* LEDs */
|
||||
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN11)
|
||||
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN3)
|
||||
|
||||
#define GPIO_LED_RED GPIO_LED1
|
||||
#define GPIO_LED_GREEN GPIO_LED2
|
||||
#define GPIO_LED_BLUE GPIO_LED3
|
||||
|
||||
/* Define the Chip Selects */
|
||||
|
||||
/* SPI Bus 1 Internal Sensors */
|
||||
|
||||
#define GPIO_SPI_CS_MPU9250 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_SPI_CS_LIS3MDL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN15)
|
||||
#define GPIO_SPI_CS_MS5611 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
|
||||
#define GPIO_SPI_CS_ICM_20608_G (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
|
||||
|
||||
/* SPI Bus 2 Memory */
|
||||
|
||||
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
|
||||
|
||||
/* Aux Chip selects (not pined out on RC0 HW) */
|
||||
|
||||
#define GPIO_AUX_CS0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN10)
|
||||
#define GPIO_AUX_CS1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN11)
|
||||
#define GPIO_AUX_CS2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN12)
|
||||
#define GPIO_AUX_CS3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN13)
|
||||
#define GPIO_AUX_CS4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN14)
|
||||
#define GPIO_AUX_CS5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN15)
|
||||
|
||||
|
||||
/* External Chip selects on Connectors ahead PAD3 */
|
||||
|
||||
#define GPIO_SPI5_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN6)
|
||||
#define GPIO_SPI6_CS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN11)
|
||||
|
||||
/* Define the Ready interrupts */
|
||||
|
||||
#define GPIO_DRDY_MPU9250 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15)
|
||||
#define GPIO_DRDY_LIS3MDL (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN12)
|
||||
#define GPIO_DRDY_ICM_20608_G (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14)
|
||||
|
||||
|
||||
/*
|
||||
* Define the ability to shut off off the sensor signals
|
||||
* by changing the signals to inputs
|
||||
*/
|
||||
|
||||
#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz))
|
||||
|
||||
#define GPIO_SPI_CS_OFF_MPU9250 _PIN_OFF(GPIO_SPI_CS_MPU9250)
|
||||
#define GPIO_SPI_CS_OFF_LIS3MDL _PIN_OFF(GPIO_SPI_CS_LIS3MDL)
|
||||
#define GPIO_SPI_CS_OFF_MS5611 _PIN_OFF(GPIO_SPI_CS_MS5611)
|
||||
#define GPIO_SPI_CS_OFF_ICM_20608_G _PIN_OFF(GPIO_SPI_CS_ICM_20608_G)
|
||||
|
||||
#define GPIO_DRDY_OFF_MPU9250 _PIN_OFF(GPIO_DRDY_MPU9250)
|
||||
#define GPIO_DRDY_OFF_LIS3MDL _PIN_OFF(GPIO_DRDY_LIS3MDL)
|
||||
#define GPIO_DRDY_OFF_ICM_20608_G _PIN_OFF(GPIO_DRDY_ICM_20608_G)
|
||||
|
||||
|
||||
/* SPI1 off */
|
||||
|
||||
#define GPIO_SPI1_SCK_OFF _PIN_OFF(GPIO_SPI1_SCK)
|
||||
#define GPIO_SPI1_MISO_OFF _PIN_OFF(GPIO_SPI1_MISO)
|
||||
#define GPIO_SPI1_MOSI_OFF _PIN_OFF(GPIO_SPI1_MOSI)
|
||||
|
||||
#define PX4_SPI_BUS_SENSORS 1
|
||||
#define PX4_SPI_BUS_RAMTRON 2
|
||||
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS
|
||||
#define PX4_SPI_EXT0 5
|
||||
#define PX4_SPI_EXT1 6
|
||||
|
||||
/* 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
|
||||
#define PX4_SPIDEV_BARO 3
|
||||
#define PX4_SPIDEV_MPU 4
|
||||
#define PX4_SPIDEV_HMC 5
|
||||
#define PX4_SPIDEV_ICM 6
|
||||
#define PX4_SPIDEV_LIS 7
|
||||
#define PX4_SPIDEV_BMI 8
|
||||
#define PX4_SPIDEV_BMA 9
|
||||
#define PX4_SPIDEV_EXT0 10
|
||||
#define PX4_SPIDEV_EXT1 11
|
||||
|
||||
|
||||
/* I2C busses */
|
||||
#define PX4_I2C_BUS_ONBOARD 1
|
||||
#define PX4_I2C_BUS_EXPANSION 2
|
||||
#define PX4_I2C_BUS_LED PX4_I2C_BUS_ONBOARD
|
||||
|
||||
/* Devices on the external bus.
|
||||
*
|
||||
* Note that these are unshifted addresses.
|
||||
*/
|
||||
#define PX4_I2C_OBDEV_LED 0x55
|
||||
#define PX4_I2C_OBDEV_HMC5883 0x1e
|
||||
#define PX4_I2C_OBDEV_LIS3MDL 0x1e
|
||||
|
||||
/*
|
||||
* ADC channels
|
||||
*
|
||||
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver
|
||||
*/
|
||||
#define ADC_CHANNELS (1 << 2) | (1 << 3) | (1 << 4) | (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14)
|
||||
|
||||
// ADC defines to be used in sensors.cpp to read from a particular channel
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL 3
|
||||
//#define ADC_BATTERY_VOLTAGE_CHANNEL2 4
|
||||
//#define ADC_BATTERY_CURRENT_CHANNEL2 5
|
||||
#define ADC_5V_RAIL_SENSE 4
|
||||
#define ADC_RC_RSSI_CHANNEL 11
|
||||
|
||||
/* User GPIOs
|
||||
*
|
||||
* GPIO0-5 are the PWM servo outputs.
|
||||
*/
|
||||
#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN14)
|
||||
#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN13)
|
||||
#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11)
|
||||
#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN9)
|
||||
#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
|
||||
|
||||
#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14)
|
||||
#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13)
|
||||
#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11)
|
||||
#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9)
|
||||
#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_VDD_BRICK2_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN5)
|
||||
#define GPIO_VDD_3V3_SENSORS_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_VDD_3V3_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
|
||||
#define GPIO_VDD_5V_PERIPH_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN4)
|
||||
#define GPIO_VDD_5V_RC_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN3)
|
||||
#define GPIO_VBUS_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN0)
|
||||
|
||||
/* Tone alarm output */
|
||||
#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_PIN15)
|
||||
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15)
|
||||
|
||||
/* PWM
|
||||
*
|
||||
* Six PWM outputs are configured.
|
||||
*
|
||||
* Pins:
|
||||
*
|
||||
* CH1 : PE14 : TIM1_CH4
|
||||
* CH2 : PE13 : TIM1_CH3
|
||||
* CH3 : PE11 : TIM1_CH2
|
||||
* CH4 : PE9 : TIM1_CH1
|
||||
* CH5 : PD13 : TIM4_CH2
|
||||
* CH6 : PD14 : TIM4_CH3
|
||||
*/
|
||||
#define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN9)
|
||||
#define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11)
|
||||
#define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13)
|
||||
#define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14)
|
||||
#define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_TIM4_CH3OUT (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN14)
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 6
|
||||
|
||||
#define GPIO_TIM1_CH1IN GPIO_TIM1_CH1IN_2
|
||||
#define GPIO_TIM1_CH2IN GPIO_TIM1_CH2IN_2
|
||||
#define GPIO_TIM1_CH3IN GPIO_TIM1_CH3IN_2
|
||||
#define GPIO_TIM1_CH4IN GPIO_TIM1_CH4IN_2
|
||||
#define GPIO_TIM4_CH2IN GPIO_TIM4_CH2IN_2
|
||||
#define GPIO_TIM4_CH3IN GPIO_TIM4_CH3IN_2
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 6
|
||||
|
||||
/* USB OTG FS
|
||||
*
|
||||
* PA9 OTG_FS_VBUS VBUS sensing
|
||||
*/
|
||||
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 3 /* use timer8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel */
|
||||
|
||||
#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 2 */
|
||||
#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF2|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
|
||||
|
||||
//#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
|
||||
#define PWMIN_TIMER 4
|
||||
#define PWMIN_TIMER_CHANNEL 2
|
||||
#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2
|
||||
|
||||
#define GPIO_RSSI_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_LED_SAFETY (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN3)
|
||||
#define GPIO_BTN_SAFETY (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4)
|
||||
//#define GPIO_PERIPH_3V3_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
|
||||
/* for R12, this signal is active high */
|
||||
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
|
||||
#define INVERT_RC_INPUT(_s) px4_arch_gpiowrite(GPIO_SBUS_INV, _s)
|
||||
|
||||
#define GPIO_8266_GPIO0 (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN2)
|
||||
//TODO:VET#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
|
||||
#define GPIO_8266_PD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5)
|
||||
#define GPIO_8266_RST (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN6)
|
||||
|
||||
/* Power switch controls ******************************************************/
|
||||
|
||||
#define POWER_SPEKTRUM(_s) px4_arch_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (1-_s))
|
||||
#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(GPIO_USART1_RX)
|
||||
|
||||
// FMUv4-pro has a separate GPIO for serial RC output
|
||||
#define GPIO_RC_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
|
||||
#define SPEKTRUM_RX_AS_GPIO() px4_arch_configgpio(GPIO_RC_OUT)
|
||||
#define SPEKTRUM_RX_HIGH(_s) px4_arch_gpiowrite(GPIO_RC_OUT, (_s))
|
||||
|
||||
|
||||
#define BOARD_NAME "PX4FMU_V4PRO"
|
||||
|
||||
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
|
||||
* this board support the ADC system_power interface, and therefore
|
||||
* provides the true logic GPIO BOARD_ADC_xxxx macros.
|
||||
*/
|
||||
#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS))
|
||||
#define BOARD_ADC_BRICK_VALID (px4_arch_gpioread(GPIO_VDD_BRICK_VALID))
|
||||
#define BOARD_ADC_BRICK2_VALID (px4_arch_gpioread(GPIO_VDD_BRICK2_VALID))
|
||||
#define BOARD_ADC_SERVO_VALID (1)
|
||||
#define BOARD_ADC_PERIPH_5V_OC (px4_arch_gpioread(GPIO_VDD_5V_PERIPH_OC))
|
||||
#define BOARD_ADC_HIPOWER_5V_OC (0)
|
||||
|
||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||
|
||||
#define BOARD_FMU_GPIO_TAB { \
|
||||
{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, \
|
||||
{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, \
|
||||
{GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, 0}, \
|
||||
{GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0}, \
|
||||
{GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0}, \
|
||||
{GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0}, \
|
||||
{0, GPIO_VDD_3V3_SENSORS_EN, 0}, \
|
||||
{GPIO_VDD_BRICK_VALID, 0, 0}, }
|
||||
|
||||
/* This board provides a DMA pool and APIs */
|
||||
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||
|
||||
/****************************************************************************************************
|
||||
* 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);
|
||||
void board_spi_reset(int ms);
|
||||
|
||||
extern void stm32_usbinitialize(void);
|
||||
|
||||
extern void board_peripheral_reset(int ms);
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_archinitialize
|
||||
*
|
||||
* Description:
|
||||
* Perform architecture specific initialization for NSH.
|
||||
*
|
||||
* CONFIG_NSH_ARCHINIT=y :
|
||||
* Called from the NSH library
|
||||
*
|
||||
* CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
|
||||
* CONFIG_NSH_ARCHINIT=n :
|
||||
* Called from board_initialize().
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_NSH_LIBRARY
|
||||
int nsh_archinitialize(void);
|
||||
#endif
|
||||
|
||||
#include "../common/board_common.h"
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
|
@ -0,0 +1,130 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4fmu_can.c
|
||||
*
|
||||
* Board-specific CAN functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/drivers/can.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
#include "stm32.h"
|
||||
#include "stm32_can.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#ifdef CONFIG_CAN
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration ********************************************************************/
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
|
||||
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
|
||||
# undef CONFIG_STM32_CAN2
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_CAN1
|
||||
# define CAN_PORT 1
|
||||
#else
|
||||
# define CAN_PORT 2
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
int can_devinit(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: can_devinit
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following interface to work with
|
||||
* examples/can.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int can_devinit(void)
|
||||
{
|
||||
static bool initialized = false;
|
||||
struct can_dev_s *can;
|
||||
int ret;
|
||||
|
||||
/* Check if we have already initialized */
|
||||
|
||||
if (!initialized) {
|
||||
/* Call stm32_caninitialize() to get an instance of the CAN interface */
|
||||
|
||||
can = stm32_caninitialize(CAN_PORT);
|
||||
|
||||
if (can == NULL) {
|
||||
canerr("ERROR: Failed to get CAN interface\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Register the CAN driver at "/dev/can0" */
|
||||
|
||||
ret = can_register("/dev/can0", can);
|
||||
|
||||
if (ret < 0) {
|
||||
canerr("ERROR: can_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,674 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2016 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4fmu_init.c
|
||||
*
|
||||
* PX4FMU-specific early startup code. This file implements the
|
||||
* nsh_archinitialize() function that is called early by nsh during startup.
|
||||
*
|
||||
* Code here is run before the rcS script is invoked; it should start required
|
||||
* subsystems and perform board-specific initialisation.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
#include <nuttx/sdio.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <nuttx/mm/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/px4_macros.h>
|
||||
#include <systemlib/cpuload.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include <systemlib/hardfault_log.h>
|
||||
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/* Debug ********************************************************************/
|
||||
|
||||
#ifdef CONFIG_CPP_HAVE_VARARGS
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message(...) syslog(__VA_ARGS__)
|
||||
# else
|
||||
# define message(...) printf(__VA_ARGS__)
|
||||
# endif
|
||||
#else
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message syslog
|
||||
# else
|
||||
# define message printf
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
__END_DECLS
|
||||
|
||||
/****************************************************************************
|
||||
* Protected Functions
|
||||
****************************************************************************/
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
/************************************************************************************
|
||||
* Name: board_peripheral_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_peripheral_reset(int ms)
|
||||
{
|
||||
/* set the peripheral rails off */
|
||||
stm32_configgpio(GPIO_VDD_3V3_PERIPH_EN);
|
||||
|
||||
stm32_gpiowrite(GPIO_VDD_3V3_PERIPH_EN, 0);
|
||||
|
||||
// bool last = stm32_gpioread(GPIO_SPEKTRUM_PWR_EN);
|
||||
/* Keep Spektum on to discharge rail*/
|
||||
// stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, 1);
|
||||
|
||||
/* wait for the peripheral rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
warnx("reset done, %d ms", ms);
|
||||
|
||||
/* re-enable power */
|
||||
|
||||
/* switch the peripheral rail back on */
|
||||
// stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, last);
|
||||
stm32_gpiowrite(GPIO_VDD_3V3_PERIPH_EN, 1);
|
||||
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the initialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void
|
||||
stm32_boardinitialize(void)
|
||||
{
|
||||
/* configure LEDs */
|
||||
board_autoled_initialize();
|
||||
|
||||
/* configure ADC pins */
|
||||
//todo:Revisit! ADC3 etc
|
||||
stm32_configgpio(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */
|
||||
stm32_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */
|
||||
stm32_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */
|
||||
stm32_configgpio(GPIO_ADC1_IN11); /* RSSI analog in */
|
||||
|
||||
/* configure power supply control/sense pins */
|
||||
stm32_configgpio(GPIO_VDD_3V3_PERIPH_EN);
|
||||
stm32_configgpio(GPIO_VDD_BRICK_VALID);
|
||||
|
||||
stm32_configgpio(GPIO_SBUS_INV);
|
||||
stm32_configgpio(GPIO_8266_GPIO0);
|
||||
// stm32_configgpio(GPIO_SPEKTRUM_PWR_EN);
|
||||
stm32_configgpio(GPIO_8266_PD);
|
||||
stm32_configgpio(GPIO_8266_RST);
|
||||
stm32_configgpio(GPIO_BTN_SAFETY);
|
||||
|
||||
#ifdef GPIO_RC_OUT
|
||||
stm32_configgpio(GPIO_RC_OUT); /* Serial RC output pin */
|
||||
stm32_gpiowrite(GPIO_RC_OUT, 1); /* set it high to pull RC input up */
|
||||
#endif
|
||||
|
||||
/* configure the GPIO pins to outputs and keep them low */
|
||||
stm32_configgpio(GPIO_GPIO0_OUTPUT);
|
||||
stm32_configgpio(GPIO_GPIO1_OUTPUT);
|
||||
stm32_configgpio(GPIO_GPIO2_OUTPUT);
|
||||
stm32_configgpio(GPIO_GPIO3_OUTPUT);
|
||||
stm32_configgpio(GPIO_GPIO4_OUTPUT);
|
||||
stm32_configgpio(GPIO_GPIO5_OUTPUT);
|
||||
|
||||
/* configure SPI interfaces */
|
||||
stm32_spiinitialize();
|
||||
|
||||
stm32_usbinitialize();
|
||||
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_app_initialize
|
||||
*
|
||||
* Description:
|
||||
* Perform application specific initialization. This function is never
|
||||
* called directly from application code, but only indirectly via the
|
||||
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
|
||||
*
|
||||
* Input Parameters:
|
||||
* arg - The boardctl() argument is passed to the board_app_initialize()
|
||||
* implementation without modification. The argument has no
|
||||
* meaning to NuttX; the meaning of the argument is a contract
|
||||
* between the board-specific initalization logic and the the
|
||||
* matching application logic. The value cold be such things as a
|
||||
* mode enumeration value, a set of DIP switch switch settings, a
|
||||
* pointer to configuration data read from a file or serial FLASH,
|
||||
* or whatever you would like to do with it. Every implementation
|
||||
* should accept zero/NULL as a default configuration.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||
* any failure to indicate the nature of the failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static struct spi_dev_s *spi1;
|
||||
static struct spi_dev_s *spi2;
|
||||
static struct spi_dev_s *spi5;
|
||||
static struct spi_dev_s *spi6;
|
||||
static struct sdio_dev_s *sdio;
|
||||
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
|
||||
#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
|
||||
|
||||
/* run C++ ctors before we go any further */
|
||||
|
||||
up_cxxinitialize();
|
||||
|
||||
# if defined(CONFIG_EXAMPLES_NSH_CXXINITIALIZE)
|
||||
# error CONFIG_EXAMPLES_NSH_CXXINITIALIZE Must not be defined! Use CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE.
|
||||
# endif
|
||||
|
||||
#else
|
||||
# error platform is dependent on c++ both CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE must be defined.
|
||||
#endif
|
||||
|
||||
/* configure the high-resolution time/callout interface */
|
||||
hrt_init();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
message("DMA alloc FAILED");
|
||||
}
|
||||
|
||||
/* 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);
|
||||
|
||||
#if defined(CONFIG_STM32_BBSRAM)
|
||||
|
||||
/* NB. the use of the console requires the hrt running
|
||||
* to poll the DMA
|
||||
*/
|
||||
|
||||
/* Using Battery Backed Up SRAM */
|
||||
|
||||
int filesizes[CONFIG_STM32_BBSRAM_FILES + 1] = BSRAM_FILE_SIZES;
|
||||
|
||||
stm32_bbsraminitialize(BBSRAM_PATH, filesizes);
|
||||
|
||||
#if defined(CONFIG_STM32_SAVE_CRASHDUMP)
|
||||
|
||||
/* Panic Logging in Battery Backed Up Files */
|
||||
|
||||
/*
|
||||
* In an ideal world, if a fault happens in flight the
|
||||
* system save it to BBSRAM will then reboot. Upon
|
||||
* rebooting, the system will log the fault to disk, recover
|
||||
* the flight state and continue to fly. But if there is
|
||||
* a fault on the bench or in the air that prohibit the recovery
|
||||
* or committing the log to disk, the things are too broken to
|
||||
* fly. So the question is:
|
||||
*
|
||||
* Did we have a hard fault and not make it far enough
|
||||
* through the boot sequence to commit the fault data to
|
||||
* the SD card?
|
||||
*/
|
||||
|
||||
/* Do we have an uncommitted hard fault in BBSRAM?
|
||||
* - this will be reset after a successful commit to SD
|
||||
*/
|
||||
int hadCrash = hardfault_check_status("boot");
|
||||
|
||||
if (hadCrash == OK) {
|
||||
|
||||
message("[boot] There is a hard fault logged. Hold down the SPACE BAR," \
|
||||
" while booting to halt the system!\n");
|
||||
|
||||
/* Yes. So add one to the boot count - this will be reset after a successful
|
||||
* commit to SD
|
||||
*/
|
||||
|
||||
int reboots = hardfault_increment_reboot("boot", false);
|
||||
|
||||
/* Also end the misery for a user that holds for a key down on the console */
|
||||
|
||||
int bytesWaiting;
|
||||
ioctl(fileno(stdin), FIONREAD, (unsigned long)((uintptr_t) &bytesWaiting));
|
||||
|
||||
if (reboots > 2 || bytesWaiting != 0) {
|
||||
|
||||
/* Since we can not commit the fault dump to disk. Display it
|
||||
* to the console.
|
||||
*/
|
||||
|
||||
hardfault_write("boot", fileno(stdout), HARDFAULT_DISPLAY_FORMAT, false);
|
||||
|
||||
message("[boot] There were %d reboots with Hard fault that were not committed to disk - System halted %s\n",
|
||||
reboots,
|
||||
(bytesWaiting == 0 ? "" : " Due to Key Press\n"));
|
||||
|
||||
|
||||
/* For those of you with a debugger set a break point on up_assert and
|
||||
* then set dbgContinue = 1 and go.
|
||||
*/
|
||||
|
||||
/* Clear any key press that got us here */
|
||||
|
||||
static volatile bool dbgContinue = false;
|
||||
int c = '>';
|
||||
|
||||
while (!dbgContinue) {
|
||||
|
||||
switch (c) {
|
||||
|
||||
case EOF:
|
||||
|
||||
|
||||
case '\n':
|
||||
case '\r':
|
||||
case ' ':
|
||||
continue;
|
||||
|
||||
default:
|
||||
|
||||
putchar(c);
|
||||
putchar('\n');
|
||||
|
||||
switch (c) {
|
||||
|
||||
case 'D':
|
||||
case 'd':
|
||||
hardfault_write("boot", fileno(stdout), HARDFAULT_DISPLAY_FORMAT, false);
|
||||
break;
|
||||
|
||||
case 'C':
|
||||
case 'c':
|
||||
hardfault_rearm("boot");
|
||||
hardfault_increment_reboot("boot", true);
|
||||
break;
|
||||
|
||||
case 'B':
|
||||
case 'b':
|
||||
dbgContinue = true;
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
} // Inner Switch
|
||||
|
||||
message("\nEnter B - Continue booting\n" \
|
||||
"Enter C - Clear the fault log\n" \
|
||||
"Enter D - Dump fault log\n\n?>");
|
||||
fflush(stdout);
|
||||
|
||||
if (!dbgContinue) {
|
||||
c = getchar();
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
} // outer switch
|
||||
} // for
|
||||
|
||||
} // inner if
|
||||
} // outer if
|
||||
|
||||
#endif // CONFIG_STM32_SAVE_CRASHDUMP
|
||||
#endif // CONFIG_STM32_BBSRAM
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_RED);
|
||||
led_off(LED_GREEN);
|
||||
led_off(LED_BLUE);
|
||||
|
||||
/* Configure SPI-based devices */
|
||||
|
||||
spi1 = stm32_spibus_initialize(PX4_SPI_BUS_SENSORS);
|
||||
|
||||
if (!spi1) {
|
||||
message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
|
||||
board_autoled_on(LED_RED);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default SPI1 to 1MHz and de-assert the known chip selects. */
|
||||
SPI_SETFREQUENCY(spi1, 10000000);
|
||||
SPI_SETBITS(spi1, 8);
|
||||
SPI_SETMODE(spi1, SPIDEV_MODE3);
|
||||
SPI_SELECT(spi1, PX4_SPIDEV_ICM, false);
|
||||
SPI_SELECT(spi1, PX4_SPIDEV_BARO, false);
|
||||
SPI_SELECT(spi1, PX4_SPIDEV_LIS, false);
|
||||
SPI_SELECT(spi1, PX4_SPIDEV_MPU, false);
|
||||
up_udelay(20);
|
||||
|
||||
/* Get the SPI port for the FRAM */
|
||||
|
||||
spi2 = stm32_spibus_initialize(PX4_SPI_BUS_RAMTRON);
|
||||
|
||||
if (!spi2) {
|
||||
message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_RAMTRON);
|
||||
board_autoled_on(LED_RED);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default SPI2 to 12MHz and de-assert the known chip selects.
|
||||
*/
|
||||
|
||||
// XXX start with 10.4 MHz and go up to 20 once validated
|
||||
SPI_SETFREQUENCY(spi2, 20 * 1000 * 1000);
|
||||
SPI_SETBITS(spi2, 8);
|
||||
SPI_SETMODE(spi2, SPIDEV_MODE3);
|
||||
SPI_SELECT(spi2, SPIDEV_FLASH, false);
|
||||
|
||||
/* Configure SPI 5-based devices */
|
||||
|
||||
spi5 = stm32_spibus_initialize(PX4_SPI_EXT0);
|
||||
|
||||
if (!spi5) {
|
||||
message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_EXT0);
|
||||
board_autoled_on(LED_RED);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default SPI5 to 1MHz and de-assert the known chip selects. */
|
||||
SPI_SETFREQUENCY(spi5, 10000000);
|
||||
SPI_SETBITS(spi5, 8);
|
||||
SPI_SETMODE(spi5, SPIDEV_MODE3);
|
||||
SPI_SELECT(spi5, PX4_SPIDEV_EXT0, false);
|
||||
|
||||
/* Configure SPI 6-based devices */
|
||||
|
||||
spi6 = stm32_spibus_initialize(PX4_SPI_EXT1);
|
||||
|
||||
if (!spi6) {
|
||||
message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_EXT1);
|
||||
board_autoled_on(LED_RED);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default SPI6 to 1MHz and de-assert the known chip selects. */
|
||||
SPI_SETFREQUENCY(spi6, 10000000);
|
||||
SPI_SETBITS(spi6, 8);
|
||||
SPI_SETMODE(spi6, SPIDEV_MODE3);
|
||||
SPI_SELECT(spi6, PX4_SPIDEV_EXT1, false);
|
||||
|
||||
#ifdef CONFIG_MMCSD
|
||||
/* First, get an instance of the SDIO interface */
|
||||
|
||||
sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
|
||||
|
||||
if (!sdio) {
|
||||
message("[boot] Failed to initialize SDIO slot %d\n",
|
||||
CONFIG_NSH_MMCSDSLOTNO);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Now bind the SDIO interface to the MMC/SD driver */
|
||||
int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
|
||||
|
||||
if (ret != OK) {
|
||||
message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Then let's guess and say that there is a card in the slot. There is no card detect GPIO. */
|
||||
sdio_mediachange(sdio, true);
|
||||
|
||||
#endif
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
static void copy_reverse(stack_word_t *dest, stack_word_t *src, int size)
|
||||
{
|
||||
while (size--) {
|
||||
*dest++ = *src--;
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void board_crashdump(uintptr_t currentsp, FAR void *tcb, FAR const uint8_t *filename, int lineno)
|
||||
{
|
||||
/* We need a chunk of ram to save the complete context in.
|
||||
* Since we are going to reboot we will use &_sdata
|
||||
* which is the lowest memory and the amount we will save
|
||||
* _should be_ below any resources we need herein.
|
||||
* Unfortunately this is hard to test. See dead below
|
||||
*/
|
||||
|
||||
fullcontext_s *pdump = (fullcontext_s *)&_sdata;
|
||||
|
||||
(void)enter_critical_section();
|
||||
|
||||
struct tcb_s *rtcb = (struct tcb_s *)tcb;
|
||||
|
||||
/* Zero out everything */
|
||||
|
||||
memset(pdump, 0, sizeof(fullcontext_s));
|
||||
|
||||
/* Save Info */
|
||||
|
||||
pdump->info.lineno = lineno;
|
||||
|
||||
if (filename) {
|
||||
|
||||
int offset = 0;
|
||||
unsigned int len = strlen((char *)filename) + 1;
|
||||
|
||||
if (len > sizeof(pdump->info.filename)) {
|
||||
offset = len - sizeof(pdump->info.filename) ;
|
||||
}
|
||||
|
||||
strncpy(pdump->info.filename, (char *)&filename[offset], sizeof(pdump->info.filename));
|
||||
}
|
||||
|
||||
/* Save the value of the pointer for current_regs as debugging info.
|
||||
* It should be NULL in case of an ASSERT and will aid in cross
|
||||
* checking the validity of system memory at the time of the
|
||||
* fault.
|
||||
*/
|
||||
|
||||
pdump->info.current_regs = (uintptr_t) CURRENT_REGS;
|
||||
|
||||
/* Save Context */
|
||||
|
||||
|
||||
#if CONFIG_TASK_NAME_SIZE > 0
|
||||
strncpy(pdump->info.name, rtcb->name, CONFIG_TASK_NAME_SIZE);
|
||||
#endif
|
||||
|
||||
pdump->info.pid = rtcb->pid;
|
||||
|
||||
|
||||
/* If current_regs is not NULL then we are in an interrupt context
|
||||
* and the user context is in current_regs else we are running in
|
||||
* the users context
|
||||
*/
|
||||
|
||||
if (CURRENT_REGS) {
|
||||
pdump->info.stacks.interrupt.sp = currentsp;
|
||||
|
||||
pdump->info.flags |= (eRegsPresent | eUserStackPresent | eIntStackPresent);
|
||||
memcpy(pdump->info.regs, (void *)CURRENT_REGS, sizeof(pdump->info.regs));
|
||||
pdump->info.stacks.user.sp = pdump->info.regs[REG_R13];
|
||||
|
||||
} else {
|
||||
|
||||
/* users context */
|
||||
pdump->info.flags |= eUserStackPresent;
|
||||
|
||||
pdump->info.stacks.user.sp = currentsp;
|
||||
}
|
||||
|
||||
if (pdump->info.pid == 0) {
|
||||
|
||||
pdump->info.stacks.user.top = g_idle_topstack - 4;
|
||||
pdump->info.stacks.user.size = CONFIG_IDLETHREAD_STACKSIZE;
|
||||
|
||||
} else {
|
||||
pdump->info.stacks.user.top = (uint32_t) rtcb->adj_stack_ptr;
|
||||
pdump->info.stacks.user.size = (uint32_t) rtcb->adj_stack_size;;
|
||||
}
|
||||
|
||||
#if CONFIG_ARCH_INTERRUPTSTACK > 3
|
||||
|
||||
/* Get the limits on the interrupt stack memory */
|
||||
|
||||
pdump->info.stacks.interrupt.top = (uint32_t)&g_intstackbase;
|
||||
pdump->info.stacks.interrupt.size = (CONFIG_ARCH_INTERRUPTSTACK & ~3);
|
||||
|
||||
/* If In interrupt Context save the interrupt stack data centered
|
||||
* about the interrupt stack pointer
|
||||
*/
|
||||
|
||||
if ((pdump->info.flags & eIntStackPresent) != 0) {
|
||||
stack_word_t *ps = (stack_word_t *) pdump->info.stacks.interrupt.sp;
|
||||
copy_reverse(pdump->istack, &ps[arraySize(pdump->istack) / 2], arraySize(pdump->istack));
|
||||
}
|
||||
|
||||
/* Is it Invalid? */
|
||||
|
||||
if (!(pdump->info.stacks.interrupt.sp <= pdump->info.stacks.interrupt.top &&
|
||||
pdump->info.stacks.interrupt.sp > pdump->info.stacks.interrupt.top - pdump->info.stacks.interrupt.size)) {
|
||||
pdump->info.flags |= eInvalidIntStackPrt;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/* If In interrupt context or User save the user stack data centered
|
||||
* about the user stack pointer
|
||||
*/
|
||||
if ((pdump->info.flags & eUserStackPresent) != 0) {
|
||||
stack_word_t *ps = (stack_word_t *) pdump->info.stacks.user.sp;
|
||||
copy_reverse(pdump->ustack, &ps[arraySize(pdump->ustack) / 2], arraySize(pdump->ustack));
|
||||
}
|
||||
|
||||
/* Is it Invalid? */
|
||||
|
||||
if (!(pdump->info.stacks.user.sp <= pdump->info.stacks.user.top &&
|
||||
pdump->info.stacks.user.sp > pdump->info.stacks.user.top - pdump->info.stacks.user.size)) {
|
||||
pdump->info.flags |= eInvalidUserStackPtr;
|
||||
}
|
||||
|
||||
int rv = stm32_bbsram_savepanic(HARDFAULT_FILENO, (uint8_t *)pdump, sizeof(fullcontext_s));
|
||||
|
||||
/* Test if memory got wiped because of using _sdata */
|
||||
|
||||
if (rv == -ENXIO) {
|
||||
char *dead = "Memory wiped - dump not saved!";
|
||||
|
||||
while (*dead) {
|
||||
up_lowputc(*dead++);
|
||||
}
|
||||
|
||||
} else if (rv == -ENOSPC) {
|
||||
|
||||
/* hard fault again */
|
||||
|
||||
up_lowputc('!');
|
||||
}
|
||||
|
||||
|
||||
#if defined(CONFIG_BOARD_RESET_ON_CRASH)
|
||||
px4_systemreset(false);
|
||||
#endif
|
||||
}
|
|
@ -0,0 +1,106 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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 px4fmu2_led.c
|
||||
*
|
||||
* PX4FMU LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "stm32.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
|
||||
|
||||
static uint32_t g_ledmap[] = {
|
||||
GPIO_LED_BLUE, // Indexed by LED_BLUE
|
||||
GPIO_LED_RED, // Indexed by LED_RED, LED_AMBER
|
||||
GPIO_LED_SAFETY, // Indexed by LED_SAFETY
|
||||
GPIO_LED_GREEN, // Indexed by LED_GREEN
|
||||
};
|
||||
|
||||
__EXPORT void led_init(void)
|
||||
{
|
||||
/* Configure LED GPIOs for output */
|
||||
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
|
||||
stm32_configgpio(g_ledmap[l]);
|
||||
}
|
||||
}
|
||||
|
||||
static void phy_set_led(int led, bool state)
|
||||
{
|
||||
/* Pull Down to switch on */
|
||||
stm32_gpiowrite(g_ledmap[led], !state);
|
||||
}
|
||||
|
||||
static bool phy_get_led(int led)
|
||||
{
|
||||
|
||||
return !stm32_gpioread(g_ledmap[led]);
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
phy_set_led(led, true);
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
phy_set_led(led, false);
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
|
||||
phy_set_led(led, !phy_get_led(led));
|
||||
}
|
|
@ -0,0 +1,263 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4fmu_spi.c
|
||||
*
|
||||
* Board-specific SPI functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <up_arch.h>
|
||||
#include <chip.h>
|
||||
#include <stm32.h>
|
||||
#include "board_config.h"
|
||||
#include <systemlib/err.h>
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_spiinitialize(void)
|
||||
{
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
stm32_configgpio(GPIO_SPI_CS_MPU9250);
|
||||
stm32_configgpio(GPIO_SPI_CS_LIS3MDL);
|
||||
stm32_configgpio(GPIO_SPI_CS_MS5611);
|
||||
stm32_configgpio(GPIO_SPI_CS_ICM_20608_G);
|
||||
|
||||
stm32_configgpio(GPIO_DRDY_MPU9250);
|
||||
stm32_configgpio(GPIO_DRDY_LIS3MDL);
|
||||
stm32_configgpio(GPIO_DRDY_ICM_20608_G);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI2
|
||||
stm32_configgpio(GPIO_SPI_CS_FRAM);
|
||||
#endif
|
||||
#ifdef CONFIG_STM32_SPI5
|
||||
stm32_configgpio(GPIO_SPI5_CS);
|
||||
#endif
|
||||
#ifdef CONFIG_STM32_SPI6
|
||||
stm32_configgpio(GPIO_SPI6_CS);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
__EXPORT void stm32_spi1select(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_ICM:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU9250, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_LIS3MDL, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MS5611, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ICM_20608_G, !selected);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_BARO:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU9250, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_LIS3MDL, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MS5611, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ICM_20608_G, 1);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_LIS:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU9250, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_LIS3MDL, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MS5611, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ICM_20608_G, 1);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_MPU:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU9250, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_LIS3MDL, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MS5611, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ICM_20608_G, 1);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32_SPI2
|
||||
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
stm32_gpiowrite(GPIO_SPI_CS_FRAM, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
/* FRAM is always present */
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi5select and stm32_spi5status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 5.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_STM32_SPI5
|
||||
__EXPORT void stm32_spi5select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
stm32_gpiowrite(GPIO_SPI5_CS, !selected);
|
||||
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spi6select and stm32_spi6status
|
||||
*
|
||||
* Description:
|
||||
* Called by stm32 spi driver on bus 6.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_STM32_SPI6
|
||||
__EXPORT void stm32_spi6select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
|
||||
{
|
||||
stm32_gpiowrite(GPIO_SPI6_CS, !selected);
|
||||
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi6status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
__EXPORT void board_spi_reset(int ms)
|
||||
{
|
||||
/* disable SPI bus */
|
||||
stm32_configgpio(GPIO_SPI_CS_OFF_MPU9250);
|
||||
stm32_configgpio(GPIO_SPI_CS_OFF_LIS3MDL);
|
||||
stm32_configgpio(GPIO_SPI_CS_OFF_MS5611);
|
||||
stm32_configgpio(GPIO_SPI_CS_OFF_ICM_20608_G);
|
||||
|
||||
stm32_gpiowrite(GPIO_SPI_CS_OFF_MPU9250, 0);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_OFF_LIS3MDL, 0);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_OFF_MS5611, 0);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_OFF_ICM_20608_G, 0);
|
||||
|
||||
stm32_configgpio(GPIO_SPI1_SCK_OFF);
|
||||
stm32_configgpio(GPIO_SPI1_MISO_OFF);
|
||||
stm32_configgpio(GPIO_SPI1_MOSI_OFF);
|
||||
|
||||
stm32_gpiowrite(GPIO_SPI1_SCK_OFF, 0);
|
||||
stm32_gpiowrite(GPIO_SPI1_MISO_OFF, 0);
|
||||
stm32_gpiowrite(GPIO_SPI1_MOSI_OFF, 0);
|
||||
|
||||
stm32_configgpio(GPIO_DRDY_OFF_MPU9250);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_LIS3MDL);
|
||||
stm32_configgpio(GPIO_DRDY_OFF_ICM_20608_G);
|
||||
|
||||
stm32_gpiowrite(GPIO_DRDY_OFF_MPU9250, 0);
|
||||
stm32_gpiowrite(GPIO_DRDY_OFF_LIS3MDL, 0);
|
||||
stm32_gpiowrite(GPIO_DRDY_OFF_ICM_20608_G, 0);
|
||||
|
||||
/* set the sensor rail off */
|
||||
stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN);
|
||||
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0);
|
||||
|
||||
/* wait for the sensor rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
warnx("reset done, %d ms", ms);
|
||||
|
||||
/* re-enable power */
|
||||
|
||||
/* switch the sensor rail back on */
|
||||
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1);
|
||||
|
||||
/* wait a bit before starting SPI, different times didn't influence results */
|
||||
usleep(100);
|
||||
|
||||
/* reconfigure the SPI pins */
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
stm32_configgpio(GPIO_SPI_CS_MPU9250);
|
||||
stm32_configgpio(GPIO_SPI_CS_LIS3MDL);
|
||||
stm32_configgpio(GPIO_SPI_CS_MS5611);
|
||||
stm32_configgpio(GPIO_SPI_CS_ICM_20608_G);
|
||||
|
||||
stm32_configgpio(GPIO_SPI1_SCK);
|
||||
stm32_configgpio(GPIO_SPI1_MISO);
|
||||
stm32_configgpio(GPIO_SPI1_MOSI);
|
||||
|
||||
/* bring up the EXTI pins again */
|
||||
stm32_configgpio(GPIO_DRDY_MPU9250);
|
||||
stm32_configgpio(GPIO_DRDY_LIS3MDL);
|
||||
stm32_configgpio(GPIO_DRDY_ICM_20608_G);
|
||||
|
||||
#endif
|
||||
|
||||
}
|
|
@ -0,0 +1,126 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* @file px4fmu_timer_config.c
|
||||
*
|
||||
* Configuration data for the stm32 pwm_servo, input capture and pwm input driver.
|
||||
*
|
||||
* Note that these arrays must always be fully-sized.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <stm32.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include <stm32_tim.h>
|
||||
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <drivers/stm32/drv_io_timer.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
__EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
{
|
||||
.base = STM32_TIM1_BASE,
|
||||
.clock_register = STM32_RCC_APB2ENR,
|
||||
.clock_bit = RCC_APB2ENR_TIM1EN,
|
||||
.clock_freq = STM32_APB2_TIM1_CLKIN,
|
||||
.first_channel_index = 0,
|
||||
.last_channel_index = 3,
|
||||
.handler = io_timer_handler0,
|
||||
.vectorno = STM32_IRQ_TIM1CC,
|
||||
|
||||
},
|
||||
{
|
||||
.base = STM32_TIM4_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_bit = RCC_APB1ENR_TIM4EN,
|
||||
.clock_freq = STM32_APB1_TIM4_CLKIN,
|
||||
.first_channel_index = 4,
|
||||
.last_channel_index = 5,
|
||||
.handler = io_timer_handler1,
|
||||
.vectorno = STM32_IRQ_TIM4,
|
||||
}
|
||||
};
|
||||
|
||||
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
{
|
||||
.gpio_out = GPIO_TIM1_CH4OUT,
|
||||
.gpio_in = GPIO_TIM1_CH4IN,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 4,
|
||||
.ccr_offset = STM32_GTIM_CCR4_OFFSET,
|
||||
.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM1_CH3OUT,
|
||||
.gpio_in = GPIO_TIM1_CH3IN,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 3,
|
||||
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
|
||||
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM1_CH2OUT,
|
||||
.gpio_in = GPIO_TIM1_CH2IN,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 2,
|
||||
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
|
||||
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM1_CH1OUT,
|
||||
.gpio_in = GPIO_TIM1_CH1IN,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 1,
|
||||
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM4_CH2OUT,
|
||||
.gpio_in = GPIO_TIM4_CH2IN,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 2,
|
||||
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
|
||||
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM4_CH3OUT,
|
||||
.gpio_in = GPIO_TIM4_CH3IN,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 3,
|
||||
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
|
||||
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
|
||||
}
|
||||
};
|
|
@ -0,0 +1,107 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4fmu_usb.c
|
||||
*
|
||||
* Board-specific USB functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
|
||||
#include <up_arch.h>
|
||||
#include <stm32.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to setup USB-related GPIO pins for the PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbinitialize(void)
|
||||
{
|
||||
/* The OTG FS has an internal soft pull-up */
|
||||
|
||||
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
|
||||
|
||||
#ifdef CONFIG_STM32_OTGFS
|
||||
stm32_configgpio(GPIO_OTGFS_VBUS);
|
||||
/* XXX We only support device mode
|
||||
stm32_configgpio(GPIO_OTGFS_PWRON);
|
||||
stm32_configgpio(GPIO_OTGFS_OVER);
|
||||
*/
|
||||
#endif
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbsuspend
|
||||
*
|
||||
* Description:
|
||||
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
|
||||
* used. This function is called whenever the USB enters or leaves suspend mode.
|
||||
* This is an opportunity for the board logic to shutdown clocks, power, etc.
|
||||
* while the USB is suspended.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||
{
|
||||
uinfo("resume: %d\n", resume);
|
||||
}
|
Loading…
Reference in New Issue