forked from Archive/PX4-Autopilot
AV-X board support
This commit is contained in:
parent
dec03873bc
commit
00c34d8a2b
|
@ -59,7 +59,7 @@ pipeline {
|
||||||
}
|
}
|
||||||
|
|
||||||
// other nuttx default targets
|
// other nuttx default targets
|
||||||
for (def option in ["px4-same70xplained-v1", "px4-stm32f4discovery", "px4cannode-v1", "px4esc-v1", "px4nucleoF767ZI-v1", "s2740vc-v1"]) {
|
for (def option in ["av-x-v1", "px4-same70xplained-v1", "px4-stm32f4discovery", "px4cannode-v1", "px4esc-v1", "px4nucleoF767ZI-v1", "s2740vc-v1"]) {
|
||||||
def node_name = "${option}"
|
def node_name = "${option}"
|
||||||
builds[node_name] = createBuildNode(docker_nuttx, "${node_name}_default")
|
builds[node_name] = createBuildNode(docker_nuttx, "${node_name}_default")
|
||||||
}
|
}
|
||||||
|
|
|
@ -120,7 +120,7 @@ then
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if ver hwcmp MINDPX_V2 CRAZYFLIE AEROFC_V1 PX4FMU_V4 NXPHLITE_V3 OMNIBUS_F4SD
|
if ver hwcmp MINDPX_V2 CRAZYFLIE AEROFC_V1 PX4FMU_V4 NXPHLITE_V3 OMNIBUS_F4SD AV_X_V1
|
||||||
then
|
then
|
||||||
set MIXER_AUX none
|
set MIXER_AUX none
|
||||||
fi
|
fi
|
||||||
|
|
|
@ -329,6 +329,19 @@ then
|
||||||
ist8310 -C -b 5 start
|
ist8310 -C -b 5 start
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
if ver hwcmp AV_X_V1
|
||||||
|
then
|
||||||
|
adis16477 -R 8 start
|
||||||
|
|
||||||
|
#adis16497 start
|
||||||
|
|
||||||
|
lps22hb start
|
||||||
|
|
||||||
|
lsm303agr -R 4 start
|
||||||
|
|
||||||
|
#ms4525_airspeed start
|
||||||
|
fi
|
||||||
|
|
||||||
if ver hwcmp AEROCORE2
|
if ver hwcmp AEROCORE2
|
||||||
then
|
then
|
||||||
l3gd20 -R 12 start
|
l3gd20 -R 12 start
|
||||||
|
|
|
@ -0,0 +1,146 @@
|
||||||
|
|
||||||
|
px4_nuttx_configure(HWCLASS m7 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)
|
||||||
|
|
||||||
|
set(config_uavcan_num_ifaces 2)
|
||||||
|
|
||||||
|
set(config_module_list
|
||||||
|
#
|
||||||
|
# Board support modules
|
||||||
|
#
|
||||||
|
drivers/barometer
|
||||||
|
drivers/differential_pressure
|
||||||
|
drivers/distance_sensor
|
||||||
|
drivers/magnetometer
|
||||||
|
drivers/telemetry
|
||||||
|
|
||||||
|
drivers/batt_smbus
|
||||||
|
drivers/camera_trigger
|
||||||
|
drivers/gps
|
||||||
|
drivers/imu/adis16477
|
||||||
|
#drivers/imu/adis16497
|
||||||
|
drivers/irlock
|
||||||
|
drivers/mkblctrl
|
||||||
|
drivers/pwm_out_sim
|
||||||
|
drivers/px4flow
|
||||||
|
drivers/px4fmu
|
||||||
|
drivers/stm32
|
||||||
|
drivers/stm32/adc
|
||||||
|
drivers/tap_esc
|
||||||
|
drivers/vmount
|
||||||
|
modules/sensors
|
||||||
|
|
||||||
|
#
|
||||||
|
# System commands
|
||||||
|
#
|
||||||
|
systemcmds/bl_update
|
||||||
|
systemcmds/config
|
||||||
|
systemcmds/dumpfile
|
||||||
|
systemcmds/esc_calib
|
||||||
|
systemcmds/hardfault_log
|
||||||
|
systemcmds/led_control
|
||||||
|
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/tune_control
|
||||||
|
systemcmds/ver
|
||||||
|
|
||||||
|
#
|
||||||
|
# Testing
|
||||||
|
#
|
||||||
|
drivers/distance_sensor/sf0x/sf0x_tests
|
||||||
|
drivers/test_ppm
|
||||||
|
#lib/rc/rc_tests
|
||||||
|
modules/commander/commander_tests
|
||||||
|
lib/controllib/controllib_test
|
||||||
|
modules/mavlink/mavlink_tests
|
||||||
|
modules/mc_pos_control/mc_pos_control_tests
|
||||||
|
modules/uORB/uORB_tests
|
||||||
|
systemcmds/tests
|
||||||
|
|
||||||
|
#
|
||||||
|
# General system control
|
||||||
|
#
|
||||||
|
modules/camera_feedback
|
||||||
|
modules/commander
|
||||||
|
modules/events
|
||||||
|
modules/gpio_led
|
||||||
|
modules/land_detector
|
||||||
|
modules/load_mon
|
||||||
|
modules/mavlink
|
||||||
|
modules/navigator
|
||||||
|
modules/uavcan
|
||||||
|
|
||||||
|
#
|
||||||
|
# Estimation modules
|
||||||
|
#
|
||||||
|
modules/attitude_estimator_q
|
||||||
|
modules/ekf2
|
||||||
|
modules/landing_target_estimator
|
||||||
|
modules/local_position_estimator
|
||||||
|
modules/position_estimator_inav
|
||||||
|
modules/wind_estimator
|
||||||
|
|
||||||
|
#
|
||||||
|
# Vehicle Control
|
||||||
|
#
|
||||||
|
modules/fw_att_control
|
||||||
|
modules/fw_pos_control_l1
|
||||||
|
modules/gnd_att_control
|
||||||
|
modules/gnd_pos_control
|
||||||
|
modules/mc_att_control
|
||||||
|
modules/mc_pos_control
|
||||||
|
modules/vtol_att_control
|
||||||
|
|
||||||
|
#
|
||||||
|
# Logging
|
||||||
|
#
|
||||||
|
modules/logger
|
||||||
|
modules/sdlog2
|
||||||
|
|
||||||
|
#
|
||||||
|
# Library modules
|
||||||
|
#
|
||||||
|
modules/dataman
|
||||||
|
|
||||||
|
#
|
||||||
|
# OBC challenge
|
||||||
|
#
|
||||||
|
#examples/bottle_drop
|
||||||
|
|
||||||
|
#
|
||||||
|
# Rover apps
|
||||||
|
#
|
||||||
|
#examples/rover_steering_control
|
||||||
|
|
||||||
|
#
|
||||||
|
# Segway
|
||||||
|
#
|
||||||
|
#examples/segway
|
||||||
|
|
||||||
|
#
|
||||||
|
# Demo apps
|
||||||
|
#
|
||||||
|
|
||||||
|
# Tutorial code from
|
||||||
|
# https://px4.io/dev/px4_simple_app
|
||||||
|
#examples/px4_simple_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
|
||||||
|
)
|
|
@ -0,0 +1,13 @@
|
||||||
|
{
|
||||||
|
"board_id": 50,
|
||||||
|
"magic": "AV-Xv1",
|
||||||
|
"description": "Firmware for the AV-Xv1 board",
|
||||||
|
"image": "",
|
||||||
|
"build_time": 0,
|
||||||
|
"summary": "AV-Xv1",
|
||||||
|
"version": "0.1",
|
||||||
|
"image_size": 0,
|
||||||
|
"image_maxsize": 2064384,
|
||||||
|
"git_identity": "",
|
||||||
|
"board_revision": 0
|
||||||
|
}
|
|
@ -68,6 +68,7 @@ CFLAGS = -Os -g2 ${CMAKE_C_FLAGS} $(ARCHINCLUDES) \
|
||||||
-Wno-bad-function-cast \
|
-Wno-bad-function-cast \
|
||||||
-Wno-cpp \
|
-Wno-cpp \
|
||||||
-Wno-float-equal \
|
-Wno-float-equal \
|
||||||
|
-Wno-format-truncation \
|
||||||
-Wno-implicit-fallthrough \
|
-Wno-implicit-fallthrough \
|
||||||
-Wno-implicit-function-declaration \
|
-Wno-implicit-function-declaration \
|
||||||
-Wno-logical-op \
|
-Wno-logical-op \
|
||||||
|
|
|
@ -0,0 +1,464 @@
|
||||||
|
/************************************************************************************
|
||||||
|
* nuttx-configs/av-x-v1/include/board.h
|
||||||
|
*
|
||||||
|
* Copyright (C) 2016 Gregory Nutt. 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 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.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Included Files
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
#ifndef __ASSEMBLY__
|
||||||
|
# include <stdint.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "stm32_rcc.h"
|
||||||
|
#include "stm32_sdmmc.h"
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Pre-processor Definitions
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
/* Clocking *************************************************************************/
|
||||||
|
/* The av-x-v1 board provides the following clock sources:
|
||||||
|
*
|
||||||
|
* X2: 16 MHz oscillator for STM32F777NI microcontroller and Ethernet PHY.
|
||||||
|
* X1: 32.768 KHz crystal for STM32F777NI embedded RTC
|
||||||
|
*
|
||||||
|
* So we have these clock source available within the STM32
|
||||||
|
*
|
||||||
|
* HSI: 16 MHz RC factory-trimmed
|
||||||
|
* LSI: 32 KHz RC
|
||||||
|
* HSE: 16 MHz crystal for HSE
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define STM32_BOARD_XTAL 16000000ul
|
||||||
|
|
||||||
|
#define STM32_HSI_FREQUENCY 16000000ul
|
||||||
|
#define STM32_LSI_FREQUENCY 32000
|
||||||
|
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||||
|
#define STM32_LSE_FREQUENCY 0
|
||||||
|
|
||||||
|
/* Main PLL Configuration.
|
||||||
|
*
|
||||||
|
* PLL source is HSE = 25,000,000
|
||||||
|
*
|
||||||
|
* PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
|
||||||
|
* Subject to:
|
||||||
|
*
|
||||||
|
* 2 <= PLLM <= 63
|
||||||
|
* 192 <= PLLN <= 432
|
||||||
|
* 192 MHz <= PLL_VCO <= 432MHz
|
||||||
|
*
|
||||||
|
* SYSCLK = PLL_VCO / PLLP
|
||||||
|
* Subject to
|
||||||
|
*
|
||||||
|
* PLLP = {2, 4, 6, 8}
|
||||||
|
* SYSCLK <= 216 MHz
|
||||||
|
*
|
||||||
|
* SDMMC and RNG Clock = PLL_VCO / PLLQ
|
||||||
|
* Subject to
|
||||||
|
* The SDMMC and the random number generator need a frequency lower than or equal
|
||||||
|
* to 48 MHz to work correctly.
|
||||||
|
*
|
||||||
|
* 2 <= PLLQ <= 15
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* SDMMCCLK (= USB OTG FS clock = RNGCLK) should be <= 48MHz
|
||||||
|
*
|
||||||
|
* PLL_VCO = (16,000,000 / 8) * 216 = 432 MHz
|
||||||
|
* SYSCLK = 432 MHz / 2 = 216 MHz
|
||||||
|
* SDMMC and RNG Clock = 432 MHz / 9 = 48 MHz
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8)
|
||||||
|
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(216)
|
||||||
|
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
|
||||||
|
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(9)
|
||||||
|
|
||||||
|
#define STM32_VCO_FREQUENCY ((STM32_HSE_FREQUENCY / 8) * 216)
|
||||||
|
#define STM32_SYSCLK_FREQUENCY (STM32_VCO_FREQUENCY / 2)
|
||||||
|
#define STM32_OTGFS_FREQUENCY (STM32_VCO_FREQUENCY / 9)
|
||||||
|
|
||||||
|
/* Configure factors for PLLSAI clock */
|
||||||
|
|
||||||
|
#define CONFIG_STM32F7_PLLSAI 1
|
||||||
|
#define STM32_RCC_PLLSAICFGR_PLLSAIN RCC_PLLSAICFGR_PLLSAIN(192)
|
||||||
|
#define STM32_RCC_PLLSAICFGR_PLLSAIP RCC_PLLSAICFGR_PLLSAIP(8)
|
||||||
|
#define STM32_RCC_PLLSAICFGR_PLLSAIQ RCC_PLLSAICFGR_PLLSAIQ(4)
|
||||||
|
#define STM32_RCC_PLLSAICFGR_PLLSAIR RCC_PLLSAICFGR_PLLSAIR(2)
|
||||||
|
|
||||||
|
/* Configure Dedicated Clock Configuration Register */
|
||||||
|
|
||||||
|
#define STM32_RCC_DCKCFGR1_PLLI2SDIVQ RCC_DCKCFGR1_PLLI2SDIVQ(1)
|
||||||
|
#define STM32_RCC_DCKCFGR1_PLLSAIDIVQ RCC_DCKCFGR1_PLLSAIDIVQ(1)
|
||||||
|
#define STM32_RCC_DCKCFGR1_PLLSAIDIVR RCC_DCKCFGR1_PLLSAIDIVR(0)
|
||||||
|
#define STM32_RCC_DCKCFGR1_SAI1SRC RCC_DCKCFGR1_SAI1SEL(0)
|
||||||
|
#define STM32_RCC_DCKCFGR1_SAI2SRC RCC_DCKCFGR1_SAI2SEL(0)
|
||||||
|
#define STM32_RCC_DCKCFGR1_TIMPRESRC 0
|
||||||
|
#define STM32_RCC_DCKCFGR1_DFSDM1SRC 0
|
||||||
|
#define STM32_RCC_DCKCFGR1_ADFSDM1SRC 0
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* Configure factors for PLLI2S clock */
|
||||||
|
|
||||||
|
#define CONFIG_STM32F7_PLLI2S 1
|
||||||
|
#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192)
|
||||||
|
#define STM32_RCC_PLLI2SCFGR_PLLI2SP RCC_PLLI2SCFGR_PLLI2SP(2)
|
||||||
|
#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2)
|
||||||
|
#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2)
|
||||||
|
|
||||||
|
/* Configure Dedicated Clock Configuration Register 2 */
|
||||||
|
|
||||||
|
#define STM32_RCC_DCKCFGR2_USART1SRC RCC_DCKCFGR2_USART1SEL_APB
|
||||||
|
#define STM32_RCC_DCKCFGR2_USART2SRC RCC_DCKCFGR2_USART2SEL_APB
|
||||||
|
#define STM32_RCC_DCKCFGR2_UART4SRC RCC_DCKCFGR2_UART4SEL_APB
|
||||||
|
#define STM32_RCC_DCKCFGR2_UART5SRC RCC_DCKCFGR2_UART5SEL_APB
|
||||||
|
#define STM32_RCC_DCKCFGR2_USART6SRC RCC_DCKCFGR2_USART6SEL_APB
|
||||||
|
#define STM32_RCC_DCKCFGR2_UART7SRC RCC_DCKCFGR2_UART7SEL_APB
|
||||||
|
#define STM32_RCC_DCKCFGR2_UART8SRC RCC_DCKCFGR2_UART8SEL_APB
|
||||||
|
#define STM32_RCC_DCKCFGR2_I2C1SRC RCC_DCKCFGR2_I2C1SEL_HSI
|
||||||
|
#define STM32_RCC_DCKCFGR2_I2C2SRC RCC_DCKCFGR2_I2C2SEL_HSI
|
||||||
|
#define STM32_RCC_DCKCFGR2_I2C3SRC RCC_DCKCFGR2_I2C3SEL_HSI
|
||||||
|
#define STM32_RCC_DCKCFGR2_I2C4SRC RCC_DCKCFGR2_I2C4SEL_HSI
|
||||||
|
#define STM32_RCC_DCKCFGR2_LPTIM1SRC RCC_DCKCFGR2_LPTIM1SEL_APB
|
||||||
|
#define STM32_RCC_DCKCFGR2_CECSRC RCC_DCKCFGR2_CECSEL_HSI
|
||||||
|
#define STM32_RCC_DCKCFGR2_CK48MSRC RCC_DCKCFGR2_CK48MSEL_PLL
|
||||||
|
#define STM32_RCC_DCKCFGR2_SDMMCSRC RCC_DCKCFGR2_SDMMCSEL_48MHZ
|
||||||
|
#define STM32_RCC_DCKCFGR2_SDMMC2SRC RCC_DCKCFGR2_SDMMC2SEL_48MHZ
|
||||||
|
#define STM32_RCC_DCKCFGR2_DSISRC RCC_DCKCFGR2_DSISEL_PHY
|
||||||
|
|
||||||
|
|
||||||
|
/* Several prescalers allow the configuration of the two AHB buses, the
|
||||||
|
* high-speed APB (APB2) and the low-speed APB (APB1) domains. The maximum
|
||||||
|
* frequency of the two AHB buses is 216 MHz while the maximum frequency of
|
||||||
|
* the high-speed APB domains is 108 MHz. The maximum allowed frequency of
|
||||||
|
* the low-speed APB domain is 54 MHz.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* AHB clock (HCLK) is SYSCLK (216 MHz) */
|
||||||
|
|
||||||
|
#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 (54 MHz) */
|
||||||
|
|
||||||
|
#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 (108MHz) */
|
||||||
|
|
||||||
|
#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)
|
||||||
|
|
||||||
|
/* 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!!!
|
||||||
|
*
|
||||||
|
* SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(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 STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
|
||||||
|
|
||||||
|
#define STM32_SDMMC_INIT_CLKDIV (118 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||||
|
|
||||||
|
/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz
|
||||||
|
* DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef CONFIG_STM32F7_SDMMC_DMA
|
||||||
|
# define STM32_SDMMC_MMCXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||||
|
#else
|
||||||
|
# define STM32_SDMMC_MMCXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz
|
||||||
|
* DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz
|
||||||
|
*/
|
||||||
|
//TODO #warning "Check Freq for 24mHz"
|
||||||
|
|
||||||
|
#ifdef CONFIG_STM32F7_SDMMC_DMA
|
||||||
|
# define STM32_SDMMC_SDXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||||
|
#else
|
||||||
|
# define STM32_SDMMC_SDXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* DMA Channl/Stream Selections *****************************************************/
|
||||||
|
/* Stream selections are arbitrary for now but might become important in the future
|
||||||
|
* if we set aside more DMA channels/streams.
|
||||||
|
*
|
||||||
|
* SDMMC DMA is on DMA2
|
||||||
|
*
|
||||||
|
* SDMMC1 DMA
|
||||||
|
* DMAMAP_SDMMC1_1 = Channel 4, Stream 3 <- may later be used by SPI DMA
|
||||||
|
* DMAMAP_SDMMC1_2 = Channel 4, Stream 6
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define DMAMAP_SDMMC1 DMAMAP_SDMMC1_1
|
||||||
|
|
||||||
|
|
||||||
|
/* FLASH wait states
|
||||||
|
*
|
||||||
|
* --------- ---------- -----------
|
||||||
|
* VDD MAX SYSCLK WAIT STATES
|
||||||
|
* --------- ---------- -----------
|
||||||
|
* 1.7-2.1 V 180 MHz 8
|
||||||
|
* 2.1-2.4 V 216 MHz 9
|
||||||
|
* 2.4-2.7 V 216 MHz 8
|
||||||
|
* 2.7-3.6 V 216 MHz 7
|
||||||
|
* --------- ---------- -----------
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define BOARD_FLASH_WAITSTATES 7
|
||||||
|
|
||||||
|
/* Alternate function pin selections ************************************************/
|
||||||
|
|
||||||
|
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PB7 */
|
||||||
|
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PB6 */
|
||||||
|
|
||||||
|
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||||
|
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||||
|
|
||||||
|
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||||
|
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
|
||||||
|
|
||||||
|
#define GPIO_UART4_RX GPIO_UART4_RX_4 /* PD0 */
|
||||||
|
#define GPIO_UART4_TX GPIO_UART4_TX_3 /* PA12 */
|
||||||
|
|
||||||
|
#define GPIO_UART5_RX GPIO_UART5_RX_4 /* PB8 */
|
||||||
|
#define GPIO_UART5_TX GPIO_UART5_TX_4 /* PB9 */
|
||||||
|
|
||||||
|
#define GPIO_USART6_RX GPIO_USART6_RX_2 /* PG9 */
|
||||||
|
#define GPIO_USART6_TX GPIO_USART6_TX_2 /* PG14 */
|
||||||
|
|
||||||
|
// SWAPPED in REV C
|
||||||
|
#define GPIO_UART7_RX GPIO_UART7_TX_1 /* PE8 */
|
||||||
|
#define GPIO_UART7_TX GPIO_UART7_RX_1 /* PE7 */
|
||||||
|
|
||||||
|
/* USART8: has no remap
|
||||||
|
*
|
||||||
|
* GPIO_UART8_RX PE0
|
||||||
|
* GPIO_UART8_TX PE1
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* 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 transceiver.
|
||||||
|
*/
|
||||||
|
#define GPIO_CAN1_RX GPIO_CAN1_RX_5 /* PI9 */
|
||||||
|
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
|
||||||
|
|
||||||
|
/* SPI
|
||||||
|
* SPI1-SPI4 sensors
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
|
||||||
|
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */
|
||||||
|
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 /* PA5 */
|
||||||
|
|
||||||
|
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
|
||||||
|
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PI3 */
|
||||||
|
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_4 /* PD3 */
|
||||||
|
|
||||||
|
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1 /* PE5 */
|
||||||
|
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE6 */
|
||||||
|
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 /* PE2 */
|
||||||
|
|
||||||
|
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_1 /* PF8 */
|
||||||
|
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_2 /* PF11 */
|
||||||
|
#define GPIO_SPI5_SCK GPIO_SPI5_SCK_2 /* PH6 */
|
||||||
|
|
||||||
|
/* The STM32 F7 connects to a SMSC LAN8720A PHY using these pins:
|
||||||
|
*
|
||||||
|
* STM32 F7 BOARD LAN8720A
|
||||||
|
* GPIO SIGNAL PIN NAME
|
||||||
|
* -------- ------------ -------------
|
||||||
|
* PB11 RMII_TX_EN TXEN
|
||||||
|
* PB12 RMII_TXD0 TXD0
|
||||||
|
* PB13 RMII_TXD1 TXD1
|
||||||
|
* PC4 RMII_RXD0 RXD0/MODE0
|
||||||
|
* PC5 RMII_RXD1 RXD1/MODE1
|
||||||
|
* PD5 RMII_RXER RXER/PHYAD0
|
||||||
|
* PA7 RMII_CRS_DV CRS_DV/MODE2
|
||||||
|
* PC1 RMII_MDC MDC
|
||||||
|
* PA2 RMII_MDIO MDIO
|
||||||
|
* N/A NRST nRST
|
||||||
|
* PA1 RMII_REF_CLK nINT/REFCLK0
|
||||||
|
* N/A OSC_25M XTAL1/CLKIN
|
||||||
|
*
|
||||||
|
* The PHY address is 0, since RMII_RXER/PHYAD0 features a pull down.
|
||||||
|
* After reset, RMII_RXER/PHYAD0 switches to the RXER function,
|
||||||
|
* receive errors can be detected using GPIO pin PD5
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1
|
||||||
|
#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_1
|
||||||
|
#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_1
|
||||||
|
|
||||||
|
/* I2C Mapping
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */
|
||||||
|
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */
|
||||||
|
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_2 /* PH7 */
|
||||||
|
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
|
||||||
|
|
||||||
|
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | \
|
||||||
|
GPIO_OPENDRAIN | \
|
||||||
|
GPIO_SPEED_50MHz| \
|
||||||
|
GPIO_OUTPUT_SET | \
|
||||||
|
GPIO_PORTH | \
|
||||||
|
GPIO_PIN7)
|
||||||
|
|
||||||
|
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | \
|
||||||
|
GPIO_OPENDRAIN | \
|
||||||
|
GPIO_SPEED_50MHz| \
|
||||||
|
GPIO_OUTPUT_SET | \
|
||||||
|
GPIO_PORTH | \
|
||||||
|
GPIO_PIN8)
|
||||||
|
|
||||||
|
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
|
||||||
|
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
|
||||||
|
|
||||||
|
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | \
|
||||||
|
GPIO_OPENDRAIN | \
|
||||||
|
GPIO_SPEED_50MHz| \
|
||||||
|
GPIO_OUTPUT_SET | \
|
||||||
|
GPIO_PORTF | \
|
||||||
|
GPIO_PIN14)
|
||||||
|
|
||||||
|
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | \
|
||||||
|
GPIO_OPENDRAIN | \
|
||||||
|
GPIO_SPEED_50MHz| \
|
||||||
|
GPIO_OUTPUT_SET | \
|
||||||
|
GPIO_PORTF | \
|
||||||
|
GPIO_PIN15)
|
||||||
|
|
||||||
|
/* SDMMC1
|
||||||
|
*
|
||||||
|
* VDD 3.3
|
||||||
|
* GND
|
||||||
|
* SDMMC1_CK PC12
|
||||||
|
* SDMMC1_CMD PD2
|
||||||
|
* SDMMC1_D0 PC8
|
||||||
|
* SDMMC1_D1 PC9
|
||||||
|
* SDMMC1_D2 PC10
|
||||||
|
* SDMMC1_D3 PC11
|
||||||
|
*/
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
void stm32_boardinitialize(void);
|
||||||
|
|
||||||
|
#undef EXTERN
|
||||||
|
#if defined(__cplusplus)
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* __ASSEMBLY__ */
|
|
@ -0,0 +1,42 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* nsh_romfsetc.h
|
||||||
|
*
|
||||||
|
* This file is a stub for 'make export' purposes; the actual ROMFS
|
||||||
|
* must be supplied by the library client.
|
||||||
|
*/
|
||||||
|
|
||||||
|
extern unsigned char romfs_img[];
|
||||||
|
extern unsigned int romfs_img_len;
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,183 @@
|
||||||
|
/****************************************************************************
|
||||||
|
* nuttx-configs/av-x/scripts/script.ld
|
||||||
|
*
|
||||||
|
* Copyright (C) 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 STM32F765IIT6 has 2048 KiB of main FLASH memory. This FLASH memory
|
||||||
|
* can be accessed from either the AXIM interface at address 0x0800:0000 or
|
||||||
|
* from the ITCM interface at address 0x0020:0000.
|
||||||
|
*
|
||||||
|
* Additional information, including the option bytes, is available at at
|
||||||
|
* FLASH at address 0x1ff0:0000 (AXIM) or 0x0010:0000 (ITCM).
|
||||||
|
*
|
||||||
|
* In the STM32F765IIT6, two different boot spaces can be selected through
|
||||||
|
* the BOOT pin and the boot base address programmed in the BOOT_ADD0 and
|
||||||
|
* BOOT_ADD1 option bytes:
|
||||||
|
*
|
||||||
|
* 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0].
|
||||||
|
* ST programmed value: Flash on ITCM at 0x0020:0000
|
||||||
|
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
|
||||||
|
* ST programmed value: System bootloader at 0x0010:0000
|
||||||
|
*
|
||||||
|
* NuttX does not modify these option byes. On the unmodified NUCLEO-144
|
||||||
|
* board, the BOOT0 pin is at ground so by default, the STM32F765IIT6 will
|
||||||
|
* boot from address 0x0020:0000 in ITCM FLASH.
|
||||||
|
*
|
||||||
|
* The STM32F765IIT6 also has 512 KiB of data SRAM (in addition to ITCM SRAM).
|
||||||
|
* SRAM is split up into three blocks:
|
||||||
|
*
|
||||||
|
* 1) 128 KiB of DTCM SRM beginning at address 0x2000:0000
|
||||||
|
* 2) 368 KiB of SRAM1 beginning at address 0x2002:0000
|
||||||
|
* 3) 16 KiB of SRAM2 beginning at address 0x2007:c000
|
||||||
|
*
|
||||||
|
* 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.
|
||||||
|
*
|
||||||
|
* Bootloader reserves the first 32K bank (2 Mbytes Flash memory single bank)
|
||||||
|
* organization (256 bits read width)
|
||||||
|
*/
|
||||||
|
|
||||||
|
MEMORY
|
||||||
|
{
|
||||||
|
itcm (rwx) : ORIGIN = 0x00208000, LENGTH = 2016K
|
||||||
|
flash (rx) : ORIGIN = 0x08008000, LENGTH = 2016K
|
||||||
|
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||||
|
sram1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K
|
||||||
|
sram2 (rwx) : ORIGIN = 0x2007c000, LENGTH = 16K
|
||||||
|
}
|
||||||
|
|
||||||
|
OUTPUT_ARCH(arm)
|
||||||
|
EXTERN(_vectors)
|
||||||
|
ENTRY(_stext)
|
||||||
|
|
||||||
|
/*
|
||||||
|
* 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.*)
|
||||||
|
*(.glue_7)
|
||||||
|
*(.glue_7t)
|
||||||
|
*(.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(.);
|
||||||
|
} > sram1 AT > flash
|
||||||
|
|
||||||
|
.bss : {
|
||||||
|
_sbss = ABSOLUTE(.);
|
||||||
|
*(.bss .bss.*)
|
||||||
|
*(.gnu.linkonce.b.*)
|
||||||
|
*(COMMON)
|
||||||
|
. = ALIGN(4);
|
||||||
|
_ebss = ABSOLUTE(.);
|
||||||
|
} > sram1
|
||||||
|
|
||||||
|
/* 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,47 @@
|
||||||
|
############################################################################
|
||||||
|
#
|
||||||
|
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||||
|
#
|
||||||
|
# Redistribution and use in source and binary forms, with or without
|
||||||
|
# modification, are permitted provided that the following conditions
|
||||||
|
# are met:
|
||||||
|
#
|
||||||
|
# 1. Redistributions of source code must retain the above copyright
|
||||||
|
# notice, this list of conditions and the following disclaimer.
|
||||||
|
# 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
# notice, this list of conditions and the following disclaimer in
|
||||||
|
# the documentation and/or other materials provided with the
|
||||||
|
# distribution.
|
||||||
|
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
# used to endorse or promote products derived from this software
|
||||||
|
# without specific prior written permission.
|
||||||
|
#
|
||||||
|
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
# POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
#
|
||||||
|
############################################################################
|
||||||
|
|
||||||
|
px4_add_library(drivers_board
|
||||||
|
init.c
|
||||||
|
sdio.c
|
||||||
|
spi.c
|
||||||
|
timer_config.c
|
||||||
|
)
|
||||||
|
target_link_libraries(drivers_board
|
||||||
|
PRIVATE
|
||||||
|
drivers__led # drv_led_start
|
||||||
|
nuttx_apps # up_cxxinitialize
|
||||||
|
nuttx_arch # sdio
|
||||||
|
nuttx_drivers # sdio
|
||||||
|
parameters # param_init
|
||||||
|
)
|
|
@ -0,0 +1,474 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2018 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
|
||||||
|
*
|
||||||
|
* av_x-v1 internal definitions
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
/****************************************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************************************/
|
||||||
|
|
||||||
|
#include <px4_config.h>
|
||||||
|
#include <nuttx/compiler.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include <stm32_gpio.h>
|
||||||
|
|
||||||
|
/* Configuration ************************************************************************************/
|
||||||
|
|
||||||
|
#define BOARD_HAS_NBAT_V 1 // Only one Vbat to ADC
|
||||||
|
#define BOARD_HAS_NBAT_I 0 // No Ibat ADC
|
||||||
|
|
||||||
|
/* SENSORS are on SPI1, 5, 6
|
||||||
|
* MEMORY is on bus SPI2
|
||||||
|
* MS5611 is on bus SPI4
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define PX4_SPI_BUS_SENSOR1 1
|
||||||
|
#define PX4_SPI_BUS_SENSOR2 2
|
||||||
|
#define PX4_SPI_BUS_SENSOR4 4
|
||||||
|
#define PX4_SPI_BUS_SENSOR5 5
|
||||||
|
|
||||||
|
/* Define the Chip Selects, Data Ready and Control signals per SPI bus */
|
||||||
|
|
||||||
|
/* SPI 1 CS */
|
||||||
|
#define GPIO_SPI1_CS1_ADIS16477 /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10)
|
||||||
|
#define GPIO_SPI1_RESET_ADIS16477 /* PB15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
|
||||||
|
|
||||||
|
/* SPI 2 CS */
|
||||||
|
#define GPIO_SPI2_CS1_ADIS16497 /* PI0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN10)
|
||||||
|
|
||||||
|
/* SPI 4 CS */
|
||||||
|
#define GPIO_SPI4_CS1_LPS22HB /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
|
||||||
|
|
||||||
|
/* SPI 5 CS */
|
||||||
|
#define GPIO_SPI5_CS1_LSM303A_M /* PH5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTH|GPIO_PIN5)
|
||||||
|
#define GPIO_SPI5_CS1_LSM303A_X /* PB0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
|
||||||
|
|
||||||
|
/* Define the SPI1 Data Ready interrupts */
|
||||||
|
#define GPIO_SPI1_DRDY1_ADIS16477 /* PJ0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTJ|GPIO_PIN0)
|
||||||
|
|
||||||
|
/* Define the SPI2 Data Ready interrupts */
|
||||||
|
#define GPIO_SPI2_DRDY1_ADIS16497 /* PJ5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTJ|GPIO_PIN5)
|
||||||
|
|
||||||
|
/* Define the SPI4 Data Ready interrupts */
|
||||||
|
#define GPIO_SPI4_DRDY1_LPS22HB /* PK1 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTK|GPIO_PIN1)
|
||||||
|
|
||||||
|
/* Define the SPI5 Data Ready interrupts */
|
||||||
|
#define GPIO_SPI5_DRDY1_LSM303A_M /* PK7 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTK|GPIO_PIN7)
|
||||||
|
#define GPIO_SPI5_DRDY2_LSM303A_X /* PD12 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN12)
|
||||||
|
|
||||||
|
/* 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)
|
||||||
|
|
||||||
|
/* SPI2 off */
|
||||||
|
#define GPIO_SPI2_SCK_OFF _PIN_OFF(GPIO_SPI2_SCK)
|
||||||
|
#define GPIO_SPI2_MISO_OFF _PIN_OFF(GPIO_SPI2_MISO)
|
||||||
|
#define GPIO_SPI2_MOSI_OFF _PIN_OFF(GPIO_SPI2_MOSI)
|
||||||
|
|
||||||
|
/* SPI4 off */
|
||||||
|
#define GPIO_SPI4_SCK_OFF _PIN_OFF(GPIO_SPI4_SCK)
|
||||||
|
#define GPIO_SPI4_MISO_OFF _PIN_OFF(GPIO_SPI4_MISO)
|
||||||
|
#define GPIO_SPI4_MOSI_OFF _PIN_OFF(GPIO_SPI4_MOSI)
|
||||||
|
|
||||||
|
/* SPI5 off */
|
||||||
|
#define GPIO_SPI5_SCK_OFF _PIN_OFF(GPIO_SPI5_SCK)
|
||||||
|
#define GPIO_SPI5_MISO_OFF _PIN_OFF(GPIO_SPI5_MISO)
|
||||||
|
#define GPIO_SPI5_MOSI_OFF _PIN_OFF(GPIO_SPI5_MOSI)
|
||||||
|
|
||||||
|
|
||||||
|
#define GPIO_DRDY_OFF_SPI1_DRDY1_ADIS16477 _PIN_OFF(GPIO_SPI1_DRDY1_ADIS16477)
|
||||||
|
#define GPIO_DRDY_OFF_SPI2_DRDY1_ADIS16497 _PIN_OFF(GPIO_SPI2_DRDY1_ADIS16497)
|
||||||
|
#define GPIO_DRDY_OFF_SPI4_DRDY1_LPS22HB _PIN_OFF(GPIO_SPI4_DRDY1_LPS22HB)
|
||||||
|
#define GPIO_DRDY_OFF_SPI5_DRDY1_LSM303A_M _PIN_OFF(GPIO_SPI5_DRDY1_LSM303A_M)
|
||||||
|
#define GPIO_DRDY_OFF_SPI5_DRDY2_LSM303A_X _PIN_OFF(GPIO_SPI5_DRDY1_LSM303A_X)
|
||||||
|
|
||||||
|
/*
|
||||||
|
* 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))
|
||||||
|
|
||||||
|
|
||||||
|
/* SPI1 */
|
||||||
|
#define PX4_SPIDEV_ADIS16477 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSOR1,0)
|
||||||
|
#define PX4_SENSOR1_BUS_CS_GPIO {GPIO_SPI1_CS1_ADIS16477}
|
||||||
|
#define PX4_SENSOR1_BUS_FIRST_CS PX4_SPIDEV_ADIS16477
|
||||||
|
#define PX4_SENSOR1_BUS_LAST_CS PX4_SPIDEV_ADIS16477
|
||||||
|
|
||||||
|
/* SPI2 */
|
||||||
|
#define PX4_SPIDEV_ADIS16497 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSOR2,0)
|
||||||
|
#define PX4_SENSOR2_BUS_CS_GPIO {GPIO_SPI2_CS1_ADIS16497}
|
||||||
|
#define PX4_SENSOR2_BUS_FIRST_CS PX4_SPIDEV_ADIS16497
|
||||||
|
#define PX4_SENSOR2_BUS_LAST_CS PX4_SPIDEV_ADIS16497
|
||||||
|
|
||||||
|
/* SPI4 */
|
||||||
|
#define PX4_SPIDEV_LPS22HB PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSOR4,0)
|
||||||
|
#define PX4_SENSOR4_BUS_CS_GPIO {GPIO_SPI4_CS1_LPS22HB}
|
||||||
|
#define PX4_SENSOR4_BUS_FIRST_CS PX4_SPIDEV_LPS22HB
|
||||||
|
#define PX4_SENSOR4_BUS_LAST_CS PX4_SPIDEV_LPS22HB
|
||||||
|
|
||||||
|
/* SPI5 */
|
||||||
|
#define PX4_SPIDEV_LSM303A_M PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSOR5,0)
|
||||||
|
#define PX4_SPIDEV_LSM303A_X PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSOR5,1)
|
||||||
|
#define PX4_SENSOR5_BUS_CS_GPIO {GPIO_SPI5_CS1_LSM303A_M, GPIO_SPI5_CS1_LSM303A_X}
|
||||||
|
#define PX4_SENSOR5_BUS_FIRST_CS PX4_SPIDEV_LSM303A_M
|
||||||
|
#define PX4_SENSOR5_BUS_LAST_CS PX4_SPIDEV_LSM303A_X
|
||||||
|
|
||||||
|
/* I2C busses */
|
||||||
|
#define PX4_I2C_BUS_EXPANSION 2
|
||||||
|
#define PX4_I2C_BUS_EXPANSION1 4
|
||||||
|
#define PX4_I2C_BUS_ONBOARD 3
|
||||||
|
|
||||||
|
#define BOARD_NUMBER_I2C_BUSES 4
|
||||||
|
#define BOARD_I2C_BUS_CLOCK_INIT {100000, 100000, 100000, 100000}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* 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
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* ADC defines to be used in sensors.cpp to read from a particular channel */
|
||||||
|
|
||||||
|
#define ADC1_CH(n) (n)
|
||||||
|
#define ADC1_GPIO(n) GPIO_ADC1_IN##n
|
||||||
|
|
||||||
|
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
|
||||||
|
|
||||||
|
#define PX4_ADC_GPIO \
|
||||||
|
/* PA0 */ ADC1_GPIO(0), \
|
||||||
|
/* PA1 */ ADC1_GPIO(1), \
|
||||||
|
/* PA2 */ ADC1_GPIO(2), \
|
||||||
|
/* PA3 */ ADC1_GPIO(3), \
|
||||||
|
/* PA4 */ ADC1_GPIO(4), \
|
||||||
|
/* PB8 */ ADC1_GPIO(8), \
|
||||||
|
/* PC0 */ ADC1_GPIO(10), \
|
||||||
|
/* PC1 */ ADC1_GPIO(11), \
|
||||||
|
/* PC2 */ ADC1_GPIO(12), \
|
||||||
|
/* PC3 */ ADC1_GPIO(13), \
|
||||||
|
/* PC4 */ ADC1_GPIO(14)
|
||||||
|
|
||||||
|
/* Define Channel numbers must match above GPIO pin IN(n)*/
|
||||||
|
|
||||||
|
#define ADC_BATTERY1_VOLTAGE_CHANNEL /* PA0 */ ADC1_CH(0)
|
||||||
|
#define ADC_BATTERY1_CURRENT_CHANNEL /* PA1 */ ADC1_CH(1)
|
||||||
|
#define ADC1_SPARE_2_CHANNEL /* PA4 */ ADC1_CH(4)
|
||||||
|
#define ADC_RSSI_IN_CHANNEL /* PB0 */ ADC1_CH(8)
|
||||||
|
#define ADC_SCALED_V5_CHANNEL /* PC0 */ ADC1_CH(10)
|
||||||
|
#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL /* PC1 */ ADC1_CH(11)
|
||||||
|
#define ADC_HW_VER_SENSE_CHANNEL /* PC2 */ ADC1_CH(12)
|
||||||
|
#define ADC_HW_REV_SENSE_CHANNEL /* PC3 */ ADC1_CH(13)
|
||||||
|
#define ADC1_SPARE_1_CHANNEL /* PC4 */ ADC1_CH(14)
|
||||||
|
|
||||||
|
#if BOARD_HAS_NBAT_V == 2 && BOARD_HAS_NBAT_I == 2
|
||||||
|
#define ADC_CHANNELS \
|
||||||
|
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
|
||||||
|
(1 << ADC_BATTERY1_CURRENT_CHANNEL) | \
|
||||||
|
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
|
||||||
|
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
|
||||||
|
(1 << ADC1_SPARE_2_CHANNEL) | \
|
||||||
|
(1 << ADC_RSSI_IN_CHANNEL) | \
|
||||||
|
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||||
|
(1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
|
||||||
|
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
|
||||||
|
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
|
||||||
|
(1 << ADC1_SPARE_1_CHANNEL))
|
||||||
|
#elif BOARD_HAS_NBAT_V == 1 && BOARD_HAS_NBAT_I == 1
|
||||||
|
#define ADC_CHANNELS \
|
||||||
|
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
|
||||||
|
(1 << ADC_BATTERY1_CURRENT_CHANNEL) | \
|
||||||
|
(1 << ADC1_SPARE_2_CHANNEL) | \
|
||||||
|
(1 << ADC_RSSI_IN_CHANNEL) | \
|
||||||
|
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||||
|
(1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
|
||||||
|
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
|
||||||
|
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
|
||||||
|
(1 << ADC1_SPARE_1_CHANNEL))
|
||||||
|
#elif BOARD_HAS_NBAT_V == 1 && BOARD_HAS_NBAT_I == 0
|
||||||
|
#define ADC_CHANNELS \
|
||||||
|
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
|
||||||
|
(1 << ADC1_SPARE_2_CHANNEL) | \
|
||||||
|
(1 << ADC_RSSI_IN_CHANNEL) | \
|
||||||
|
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||||
|
(1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
|
||||||
|
(1 << ADC_HW_VER_SENSE_CHANNEL) | \
|
||||||
|
(1 << ADC_HW_REV_SENSE_CHANNEL) | \
|
||||||
|
(1 << ADC1_SPARE_1_CHANNEL))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Define Battery 1 Voltage Divider and A per V
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define BOARD_BATTERY1_V_DIV (10.133333333f)
|
||||||
|
#define BOARD_BATTERY1_A_PER_V (36.367515152f)
|
||||||
|
|
||||||
|
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
|
||||||
|
|
||||||
|
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
|
||||||
|
|
||||||
|
/* PWM
|
||||||
|
*
|
||||||
|
* 8 PWM outputs are configured.
|
||||||
|
*
|
||||||
|
* Pins:
|
||||||
|
*
|
||||||
|
* FMU_CH1 : PA8 : TIM1_CH1
|
||||||
|
* FMU_CH2 : PA9 : TIM1_CH2
|
||||||
|
* FMU_CH3 : PA10 : TIM1_CH3
|
||||||
|
* FMU_CH4 : PA11 : TIM1_CH4
|
||||||
|
* FMU_CH5 : PA3 : TIM2_CH4
|
||||||
|
* FMU_CH6 : PI6 : TIM8_CH2
|
||||||
|
* FMU_CH7 : PF7 : TIM11_CH1
|
||||||
|
* FMU_CH8 : PF6 : TIM10_CH1
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
#define GPIO_TIM1_CH1OUT /* PA8 T1C1 FMU1 */ GPIO_TIM1_CH1OUT_1
|
||||||
|
#define GPIO_TIM1_CH2OUT /* PA9 T1C2 FMU2 */ GPIO_TIM1_CH2OUT_1
|
||||||
|
#define GPIO_TIM1_CH3OUT /* PA10 T1C3 FMU3 */ GPIO_TIM1_CH3OUT_1
|
||||||
|
#define GPIO_TIM1_CH4OUT /* PA11 T1C4 FMU4 */ GPIO_TIM1_CH4OUT_1
|
||||||
|
#define GPIO_TIM2_CH4OUT /* PA3 T2C4 FMU5 */ GPIO_TIM2_CH4OUT_1
|
||||||
|
#define GPIO_TIM8_CH2OUT /* PI6 T8C2 FMU6 */ GPIO_TIM8_CH2IN_2
|
||||||
|
#define GPIO_TIM11_CH1OUT /* PF7 T11C1 FMU7 */ GPIO_TIM11_CH1OUT_2
|
||||||
|
#define GPIO_TIM10_CH1OUT /* PF6 T10C1 FMU8 */ GPIO_TIM10_CH1OUT_2
|
||||||
|
|
||||||
|
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||||
|
|
||||||
|
#define GPIO_TIM1_CH1IN /* PA8 T1C1 FMU1 */ GPIO_TIM1_CH1IN_1
|
||||||
|
#define GPIO_TIM1_CH2IN /* PA9 T1C2 FMU2 */ GPIO_TIM1_CH2IN_1
|
||||||
|
#define GPIO_TIM1_CH3IN /* PA10 T1C3 FMU3 */ GPIO_TIM1_CH3IN_1
|
||||||
|
#define GPIO_TIM1_CH4IN /* PA11 T1C4 FMU4 */ GPIO_TIM1_CH4IN_1
|
||||||
|
#define GPIO_TIM2_CH4IN /* PA3 T2C4 FMU5 */ GPIO_TIM2_CH4IN_1
|
||||||
|
#define GPIO_TIM8_CH2IN /* PI6 T8C2 FMU6 */ GPIO_TIM8_CH2IN_2
|
||||||
|
//#define GPIO_TIM11_CH1IN /* PF7 T11C1 FMU7 */ GPIO_TIM11_CH1IN_2
|
||||||
|
//#define GPIO_TIM10_CH1IN /* PF6 T10C1 FMU8 */ GPIO_TIM10_CH1IN_2
|
||||||
|
|
||||||
|
#define DIRECT_INPUT_TIMER_CHANNELS 8
|
||||||
|
|
||||||
|
/* User GPIOs
|
||||||
|
*
|
||||||
|
* GPIO0-5 are the PWM servo outputs.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define _MK_GPIO_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLUP))
|
||||||
|
|
||||||
|
#define GPIO_GPIO0_INPUT /* PA8 T1C1 FMU1 */ _MK_GPIO_INPUT(GPIO_TIM1_CH1IN)
|
||||||
|
#define GPIO_GPIO1_INPUT /* PA9 T1C2 FMU2 */ _MK_GPIO_INPUT(GPIO_TIM1_CH2IN)
|
||||||
|
#define GPIO_GPIO2_INPUT /* PA10 T1C3 FMU3 */ _MK_GPIO_INPUT(GPIO_TIM1_CH3IN)
|
||||||
|
#define GPIO_GPIO3_INPUT /* PA11 T1C4 FMU4 */ _MK_GPIO_INPUT(GPIO_TIM1_CH4IN)
|
||||||
|
#define GPIO_GPIO4_INPUT /* PA3 T2C4 FMU5 */ _MK_GPIO_INPUT(GPIO_TIM2_CH4IN_1)
|
||||||
|
#define GPIO_GPIO5_INPUT /* PI6 T8C2 FMU6 */ _MK_GPIO_INPUT(GPIO_TIM8_CH2IN_2)
|
||||||
|
#define GPIO_GPIO6_INPUT /* PF7 T11C1 FMU7 */ _MK_GPIO_INPUT(GPIO_TIM11_CH1IN_2)
|
||||||
|
#define GPIO_GPIO7_INPUT /* PF6 T10C1 FMU8 */ _MK_GPIO_INPUT(GPIO_TIM10_CH1IN_2)
|
||||||
|
|
||||||
|
#define _MK_GPIO_OUTPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR))
|
||||||
|
|
||||||
|
#define GPIO_GPIO0_OUTPUT /* PA8 T1C1 FMU1 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH1OUT)
|
||||||
|
#define GPIO_GPIO1_OUTPUT /* PA9 T1C2 FMU2 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH2OUT)
|
||||||
|
#define GPIO_GPIO2_OUTPUT /* PA10 T1C3 FMU3 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH3OUT)
|
||||||
|
#define GPIO_GPIO3_OUTPUT /* PA11 T1C4 FMU4 */ _MK_GPIO_OUTPUT(GPIO_TIM1_CH4OUT)
|
||||||
|
#define GPIO_GPIO4_OUTPUT /* PA3 T2C4 FMU5 */ _MK_GPIO_OUTPUT(GPIO_TIM2_CH4OUT_1)
|
||||||
|
#define GPIO_GPIO5_OUTPUT /* PI6 T8C2 FMU6 */ _MK_GPIO_OUTPUT(GPIO_TIM8_CH2OUT_2)
|
||||||
|
#define GPIO_GPIO6_OUTPUT /* PF7 T11C1 FMU7 */ _MK_GPIO_OUTPUT(GPIO_TIM11_CH1OUT_2)
|
||||||
|
#define GPIO_GPIO7_OUTPUT /* PF6 T10C1 FMU8 */ _MK_GPIO_OUTPUT(GPIO_TIM10_CH1OUT_2)
|
||||||
|
|
||||||
|
/* High-resolution timer */
|
||||||
|
#define HRT_TIMER 5 /* use timer5 for the HRT */
|
||||||
|
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 3 */
|
||||||
|
|
||||||
|
//#define RC_UXART_BASE STM32_USART6_BASE /* NOT FMUv5 test HW ONLY*/
|
||||||
|
//#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||||
|
|
||||||
|
#define GPS_DEFAULT_UART_PORT "/dev/ttyS5" /* UART1 on FMUv5 */
|
||||||
|
|
||||||
|
/* Power switch controls ******************************************************/
|
||||||
|
|
||||||
|
#define SDIO_SLOTNO 0 /* Only one slot */
|
||||||
|
#define SDIO_MINOR 0
|
||||||
|
|
||||||
|
/* SD card bringup does not work if performed on the IDLE thread because it
|
||||||
|
* will cause waiting. Use either:
|
||||||
|
*
|
||||||
|
* CONFIG_LIB_BOARDCTL=y, OR
|
||||||
|
* CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_LIB_BOARDCTL) && !defined(CONFIG_BOARD_INITTHREAD)
|
||||||
|
# warning SDIO initialization cannot be perfomed on the IDLE thread
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define BOARD_NAME "AV_X_V1"
|
||||||
|
|
||||||
|
/* AV-X_V1 never powers off the Servo rail */
|
||||||
|
|
||||||
|
#define BOARD_ADC_SERVO_VALID (1)
|
||||||
|
|
||||||
|
#define ADC_BATTERY_VOLTAGE_CHANNEL 0
|
||||||
|
#define ADC_BATTERY_CURRENT_CHANNEL 1 // TODO: review
|
||||||
|
|
||||||
|
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_PERIPH_OC))
|
||||||
|
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_HIPOWER_OC))
|
||||||
|
|
||||||
|
#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}, \
|
||||||
|
{GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, 0}, \
|
||||||
|
{GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, 0}, \
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* GPIO numbers.
|
||||||
|
*
|
||||||
|
* There are no alternate functions on this board.
|
||||||
|
*/
|
||||||
|
#define GPIO_SERVO_1 (1<<0) /**< servo 1 output */
|
||||||
|
#define GPIO_SERVO_2 (1<<1) /**< servo 2 output */
|
||||||
|
#define GPIO_SERVO_3 (1<<2) /**< servo 3 output */
|
||||||
|
#define GPIO_SERVO_4 (1<<3) /**< servo 4 output */
|
||||||
|
#define GPIO_SERVO_5 (1<<4) /**< servo 5 output */
|
||||||
|
#define GPIO_SERVO_6 (1<<5) /**< servo 6 output */
|
||||||
|
#define GPIO_SERVO_7 (1<<6) /**< servo 7 output */
|
||||||
|
#define GPIO_SERVO_8 (1<<7) /**< servo 8 output */
|
||||||
|
|
||||||
|
/* This board provides a DMA pool and APIs */
|
||||||
|
|
||||||
|
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||||
|
|
||||||
|
/* This board provides the board_on_reset interface */
|
||||||
|
|
||||||
|
#define BOARD_HAS_ON_RESET 1
|
||||||
|
|
||||||
|
/* The list of GPIO that will be initialized */
|
||||||
|
|
||||||
|
#define PX4_GPIO_PWM_INIT_LIST { \
|
||||||
|
GPIO_GPIO7_INPUT, \
|
||||||
|
GPIO_GPIO6_INPUT, \
|
||||||
|
GPIO_GPIO5_INPUT, \
|
||||||
|
GPIO_GPIO4_INPUT, \
|
||||||
|
GPIO_GPIO3_INPUT, \
|
||||||
|
GPIO_GPIO2_INPUT, \
|
||||||
|
GPIO_GPIO1_INPUT, \
|
||||||
|
GPIO_GPIO0_INPUT, \
|
||||||
|
}
|
||||||
|
|
||||||
|
#define PX4_GPIO_INIT_LIST { \
|
||||||
|
PX4_ADC_GPIO, \
|
||||||
|
}
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
|
/****************************************************************************************************
|
||||||
|
* Public Types
|
||||||
|
****************************************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************************************
|
||||||
|
* Public data
|
||||||
|
****************************************************************************************************/
|
||||||
|
|
||||||
|
#ifndef __ASSEMBLY__
|
||||||
|
|
||||||
|
/****************************************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: stm32_sdio_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Initialize SDIO-based MMC/SD card support
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
int stm32_sdio_initialize(void);
|
||||||
|
|
||||||
|
/****************************************************************************************************
|
||||||
|
* Name: stm32_spiinitialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||||
|
*
|
||||||
|
****************************************************************************************************/
|
||||||
|
|
||||||
|
extern void stm32_spiinitialize(void);
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_spi_bus_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called to configure SPI Buses.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
extern int stm32_spi_bus_initialize(void);
|
||||||
|
|
||||||
|
void board_spi_reset(int ms);
|
||||||
|
#define board_peripheral_reset(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,364 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2018 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 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 <px4_tasks.h>
|
||||||
|
#include <px4_log.h>
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <debug.h>
|
||||||
|
#include <errno.h>
|
||||||
|
|
||||||
|
#include "platform/cxxinitialize.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 <chip.h>
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#include <stm32_uart.h>
|
||||||
|
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
|
#include <drivers/drv_hrt.h>
|
||||||
|
#include <drivers/drv_board_led.h>
|
||||||
|
|
||||||
|
#include <systemlib/px4_macros.h>
|
||||||
|
#include <systemlib/cpuload.h>
|
||||||
|
#include <perf/perf_counter.h>
|
||||||
|
#include <systemlib/err.h>
|
||||||
|
|
||||||
|
#include <systemlib/hardfault_log.h>
|
||||||
|
|
||||||
|
#include <parameters/param.h>
|
||||||
|
|
||||||
|
#include "up_internal.h"
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: board_on_reset
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Optionally provided function called on entry to board_system_reset
|
||||||
|
* It should perform any house keeping prior to the rest.
|
||||||
|
*
|
||||||
|
* status - 1 if resetting to boot loader
|
||||||
|
* 0 if just resetting
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
__EXPORT void board_on_reset(int status)
|
||||||
|
{
|
||||||
|
/* configure the GPIO pins to outputs and keep them low */
|
||||||
|
|
||||||
|
const uint32_t gpio[] = PX4_GPIO_PWM_INIT_LIST;
|
||||||
|
board_gpio_init(gpio, arraySize(gpio));
|
||||||
|
|
||||||
|
if (status >= 0) {
|
||||||
|
up_mdelay(6);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* 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)
|
||||||
|
{
|
||||||
|
board_on_reset(-1); /* Reset PWM first thing */
|
||||||
|
|
||||||
|
/* configure LEDs */
|
||||||
|
board_autoled_initialize();
|
||||||
|
|
||||||
|
/* configure pins */
|
||||||
|
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
|
||||||
|
board_gpio_init(gpio, arraySize(gpio));
|
||||||
|
|
||||||
|
/* configure SPI interfaces */
|
||||||
|
stm32_spiinitialize();
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* 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 initialization 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.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
|
||||||
|
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||||
|
{
|
||||||
|
/* run C++ ctors before we go any further */
|
||||||
|
up_cxxinitialize();
|
||||||
|
|
||||||
|
/* configure the high-resolution time/callout interface */
|
||||||
|
hrt_init();
|
||||||
|
|
||||||
|
param_init();
|
||||||
|
|
||||||
|
/* configure the DMA allocator */
|
||||||
|
|
||||||
|
if (board_dma_alloc_init() < 0) {
|
||||||
|
PX4_ERR("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_STM32F7_BBSRAM)
|
||||||
|
|
||||||
|
/* NB. the use of the console requires the hrt running
|
||||||
|
* to poll the DMA
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Using Battery Backed Up SRAM */
|
||||||
|
|
||||||
|
int filesizes[CONFIG_STM32F7_BBSRAM_FILES + 1] = BSRAM_FILE_SIZES;
|
||||||
|
|
||||||
|
stm32_bbsraminitialize(BBSRAM_PATH, filesizes);
|
||||||
|
|
||||||
|
#if defined(CONFIG_STM32F7_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) {
|
||||||
|
|
||||||
|
PX4_ERR("[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);
|
||||||
|
|
||||||
|
PX4_ERR("[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
|
||||||
|
|
||||||
|
PX4_ERR("\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_STM32F7_SAVE_CRASHDUMP
|
||||||
|
#endif // CONFIG_STM32F7_BBSRAM
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef CONFIG_SPI
|
||||||
|
int ret = stm32_spi_bus_initialize();
|
||||||
|
|
||||||
|
if (ret != OK) {
|
||||||
|
PX4_ERR("SPI init failed");
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_MMCSD
|
||||||
|
|
||||||
|
ret = stm32_sdio_initialize();
|
||||||
|
|
||||||
|
if (ret != OK) {
|
||||||
|
board_autoled_on(LED_RED);
|
||||||
|
PX4_ERR("SDIO init failed");
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//board_spi_reset(10);
|
||||||
|
|
||||||
|
// ethernet switch
|
||||||
|
//uint8_t txdata[] = {0x51, 0x00, 0x21, 0x00}; //0x5100, 0x2100 MSB to LSB here.
|
||||||
|
//HAL_I2C_Master_Transmit(&hi2c3, (uint16_t)(0x5F<<1), txdata, 4, 0xFFFF);
|
||||||
|
|
||||||
|
return OK;
|
||||||
|
}
|
|
@ -0,0 +1,173 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2014, 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.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <px4_config.h>
|
||||||
|
#include <px4_log.h>
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <debug.h>
|
||||||
|
#include <errno.h>
|
||||||
|
|
||||||
|
#include <nuttx/sdio.h>
|
||||||
|
#include <nuttx/mmcsd.h>
|
||||||
|
|
||||||
|
#include "chip.h"
|
||||||
|
#include "board_config.h"
|
||||||
|
#include "stm32_gpio.h"
|
||||||
|
#include "stm32_sdmmc.h"
|
||||||
|
|
||||||
|
#ifdef CONFIG_MMCSD
|
||||||
|
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Pre-processor Definitions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Card detections requires card support and a card detection GPIO */
|
||||||
|
|
||||||
|
#define HAVE_NCD 1
|
||||||
|
#if !defined(GPIO_SDMMC1_NCD)
|
||||||
|
# undef HAVE_NCD
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Private Data
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
static FAR struct sdio_dev_s *sdio_dev;
|
||||||
|
#ifdef HAVE_NCD
|
||||||
|
static bool g_sd_inserted = 0xff; /* Impossible value */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Private Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: stm32_ncd_interrupt
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Card detect interrupt handler.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#ifdef HAVE_NCD
|
||||||
|
static int stm32_ncd_interrupt(int irq, FAR void *context)
|
||||||
|
{
|
||||||
|
bool present;
|
||||||
|
|
||||||
|
present = !stm32_gpioread(GPIO_SDMMC1_NCD);
|
||||||
|
|
||||||
|
if (sdio_dev && present != g_sd_inserted) {
|
||||||
|
sdio_mediachange(sdio_dev, present);
|
||||||
|
g_sd_inserted = present;
|
||||||
|
}
|
||||||
|
|
||||||
|
return OK;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: stm32_sdio_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Initialize SDIO-based MMC/SD card support
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
int stm32_sdio_initialize(void)
|
||||||
|
{
|
||||||
|
int ret;
|
||||||
|
|
||||||
|
#ifdef HAVE_NCD
|
||||||
|
/* Card detect */
|
||||||
|
bool cd_status;
|
||||||
|
|
||||||
|
/* Configure the card detect GPIO */
|
||||||
|
stm32_configgpio(GPIO_SDMMC1_NCD);
|
||||||
|
|
||||||
|
/* Register an interrupt handler for the card detect pin */
|
||||||
|
stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Mount the SDIO-based MMC/SD block driver */
|
||||||
|
/* First, get an instance of the SDIO interface */
|
||||||
|
finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO);
|
||||||
|
|
||||||
|
sdio_dev = sdio_initialize(SDIO_SLOTNO);
|
||||||
|
|
||||||
|
if (!sdio_dev) {
|
||||||
|
PX4_ERR("[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Now bind the SDIO interface to the MMC/SD driver */
|
||||||
|
|
||||||
|
finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR);
|
||||||
|
|
||||||
|
ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev);
|
||||||
|
|
||||||
|
if (ret != OK) {
|
||||||
|
PX4_ERR("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
finfo("Successfully bound SDIO to the MMC/SD driver\n");
|
||||||
|
|
||||||
|
#ifdef HAVE_NCD
|
||||||
|
/* Use SD card detect pin to check if a card is g_sd_inserted */
|
||||||
|
|
||||||
|
cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD);
|
||||||
|
finfo("Card detect : %d\n", cd_status);
|
||||||
|
|
||||||
|
sdio_mediachange(sdio_dev, cd_status);
|
||||||
|
#else
|
||||||
|
/* Assume that the SD card is inserted. What choice do we have? */
|
||||||
|
|
||||||
|
sdio_mediachange(sdio_dev, true);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* CONFIG_MMCSD */
|
|
@ -0,0 +1,429 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2018 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 <px4_log.h>
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <debug.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#include <nuttx/spi/spi.h>
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
#include <systemlib/px4_macros.h>
|
||||||
|
|
||||||
|
#include <up_arch.h>
|
||||||
|
#include <chip.h>
|
||||||
|
#include <stm32_gpio.h>
|
||||||
|
#include "board_config.h"
|
||||||
|
#include <systemlib/err.h>
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Pre-Processor Definitions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Configuration ************************************************************/
|
||||||
|
|
||||||
|
/* Debug ********************************************************************/
|
||||||
|
|
||||||
|
/* Define CS GPIO array */
|
||||||
|
static const uint32_t spi1selects_gpio[] = PX4_SENSOR1_BUS_CS_GPIO;
|
||||||
|
static const uint32_t spi2selects_gpio[] = PX4_SENSOR2_BUS_CS_GPIO;
|
||||||
|
static const uint32_t spi4selects_gpio[] = PX4_SENSOR4_BUS_CS_GPIO;
|
||||||
|
static const uint32_t spi5selects_gpio[] = PX4_SENSOR5_BUS_CS_GPIO;
|
||||||
|
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_spiinitialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT void stm32_spiinitialize(void)
|
||||||
|
{
|
||||||
|
board_gpio_init(spi1selects_gpio, arraySize(spi1selects_gpio));
|
||||||
|
board_gpio_init(spi2selects_gpio, arraySize(spi2selects_gpio));
|
||||||
|
board_gpio_init(spi4selects_gpio, arraySize(spi4selects_gpio));
|
||||||
|
board_gpio_init(spi5selects_gpio, arraySize(spi5selects_gpio));
|
||||||
|
}
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_spi_bus_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called to configure SPI buses on PX4FMU board.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
static struct spi_dev_s *spi_sensor1;
|
||||||
|
static struct spi_dev_s *spi_sensor2;
|
||||||
|
static struct spi_dev_s *spi_sensor4;
|
||||||
|
static struct spi_dev_s *spi_sensor5;
|
||||||
|
|
||||||
|
__EXPORT int stm32_spi_bus_initialize(void)
|
||||||
|
{
|
||||||
|
/* Configure SPI-based devices */
|
||||||
|
|
||||||
|
|
||||||
|
/* Get the SPI port for the Sensors */
|
||||||
|
spi_sensor1 = stm32_spibus_initialize(PX4_SPI_BUS_SENSOR1);
|
||||||
|
|
||||||
|
if (!spi_sensor1) {
|
||||||
|
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSOR1);
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Default PX4_SPI_BUS_SENSORS to 1MHz and de-assert the known chip selects. */
|
||||||
|
SPI_SETFREQUENCY(spi_sensor1, 1000000);
|
||||||
|
SPI_SETBITS(spi_sensor1, 16);
|
||||||
|
SPI_SETMODE(spi_sensor1, SPIDEV_MODE3);
|
||||||
|
|
||||||
|
for (int cs = PX4_SENSOR1_BUS_FIRST_CS; cs <= PX4_SENSOR1_BUS_LAST_CS; cs++) {
|
||||||
|
SPI_SELECT(spi_sensor1, cs, false);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/* Get the SPI port for the Memory */
|
||||||
|
spi_sensor2 = stm32_spibus_initialize(PX4_SPI_BUS_SENSOR2);
|
||||||
|
|
||||||
|
if (!spi_sensor2) {
|
||||||
|
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSOR2);
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Default PX4_SPI_BUS_SENSOR2 to 1MHz and de-assert the known chip selects. */
|
||||||
|
SPI_SETFREQUENCY(spi_sensor2, 1000000);
|
||||||
|
SPI_SETBITS(spi_sensor2, 8);
|
||||||
|
SPI_SETMODE(spi_sensor2, SPIDEV_MODE3);
|
||||||
|
|
||||||
|
for (int cs = PX4_SENSOR2_BUS_FIRST_CS; cs <= PX4_SENSOR2_BUS_LAST_CS; cs++) {
|
||||||
|
SPI_SELECT(spi_sensor2, cs, false);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/* Get the SPI port for the BARO */
|
||||||
|
spi_sensor4 = stm32_spibus_initialize(PX4_SPI_BUS_SENSOR4);
|
||||||
|
|
||||||
|
if (!spi_sensor4) {
|
||||||
|
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSOR4);
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
SPI_SETFREQUENCY(spi_sensor4, 1 * 1000 * 1000);
|
||||||
|
SPI_SETBITS(spi_sensor4, 8);
|
||||||
|
SPI_SETMODE(spi_sensor4, SPIDEV_MODE3);
|
||||||
|
|
||||||
|
for (int cs = PX4_SENSOR4_BUS_FIRST_CS; cs <= PX4_SENSOR4_BUS_LAST_CS; cs++) {
|
||||||
|
SPI_SELECT(spi_sensor4, cs, false);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/* Get the SPI port for the PX4_SPI_EXTERNAL1 */
|
||||||
|
spi_sensor5 = stm32_spibus_initialize(PX4_SPI_BUS_SENSOR5);
|
||||||
|
|
||||||
|
if (!spi_sensor5) {
|
||||||
|
PX4_ERR("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSOR5);
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
SPI_SETFREQUENCY(spi_sensor5, 1 * 1000 * 1000);
|
||||||
|
SPI_SETBITS(spi_sensor5, 8);
|
||||||
|
SPI_SETMODE(spi_sensor5, SPIDEV_MODE3);
|
||||||
|
|
||||||
|
for (int cs = PX4_SENSOR5_BUS_FIRST_CS; cs <= PX4_SENSOR5_BUS_LAST_CS; cs++) {
|
||||||
|
SPI_SELECT(spi_sensor5, cs, false);
|
||||||
|
}
|
||||||
|
|
||||||
|
return OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_spi1select and stm32_spi1status
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called by stm32 spi driver on bus 1.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||||
|
{
|
||||||
|
/* SPI select is active low, so write !selected to select the device */
|
||||||
|
int sel = (int) devid;
|
||||||
|
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_SENSOR1);
|
||||||
|
|
||||||
|
/* Making sure the other peripherals are not selected */
|
||||||
|
for (size_t cs = 0; arraySize(spi1selects_gpio) > 1 && cs < arraySize(spi1selects_gpio); cs++) {
|
||||||
|
if (spi1selects_gpio[cs] != 0) {
|
||||||
|
stm32_gpiowrite(spi1selects_gpio[cs], 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t gpio = spi1selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||||
|
|
||||||
|
if (gpio) {
|
||||||
|
stm32_gpiowrite(gpio, !selected);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||||
|
{
|
||||||
|
return SPI_STATUS_PRESENT;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_spi2select and stm32_spi2status
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called by stm32 spi driver on bus 2.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||||
|
{
|
||||||
|
/* SPI select is active low, so write !selected to select the device */
|
||||||
|
int sel = (int) devid;
|
||||||
|
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_SENSOR2);
|
||||||
|
|
||||||
|
/* Making sure the other peripherals are not selected */
|
||||||
|
|
||||||
|
for (int cs = 0; arraySize(spi2selects_gpio) > 1 && cs < arraySize(spi2selects_gpio); cs++) {
|
||||||
|
if (spi2selects_gpio[cs] != 0) {
|
||||||
|
stm32_gpiowrite(spi2selects_gpio[cs], 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t gpio = spi2selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||||
|
|
||||||
|
if (gpio) {
|
||||||
|
stm32_gpiowrite(gpio, !selected);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||||
|
{
|
||||||
|
return SPI_STATUS_PRESENT;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_spi4select and stm32_spi4status
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called by stm32 spi driver on bus 4.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||||
|
{
|
||||||
|
int sel = (int) devid;
|
||||||
|
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_SENSOR4);
|
||||||
|
|
||||||
|
/* Making sure the other peripherals are not selected */
|
||||||
|
for (size_t cs = 0; arraySize(spi4selects_gpio) > 1 && cs < arraySize(spi4selects_gpio); cs++) {
|
||||||
|
stm32_gpiowrite(spi4selects_gpio[cs], 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t gpio = spi4selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||||
|
|
||||||
|
if (gpio) {
|
||||||
|
stm32_gpiowrite(gpio, !selected);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||||
|
{
|
||||||
|
return SPI_STATUS_PRESENT;
|
||||||
|
}
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_spi5select and stm32_spi5status
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called by stm32 spi driver on bus 5.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT void stm32_spi5select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||||
|
{
|
||||||
|
/* SPI select is active low, so write !selected to select the device */
|
||||||
|
int sel = (int) devid;
|
||||||
|
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_SENSOR5);
|
||||||
|
|
||||||
|
/* Making sure the other peripherals are not selected */
|
||||||
|
for (size_t cs = 0; arraySize(spi5selects_gpio) > 1 && cs < arraySize(spi5selects_gpio); cs++) {
|
||||||
|
stm32_gpiowrite(spi5selects_gpio[cs], 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t gpio = spi5selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||||
|
|
||||||
|
if (gpio) {
|
||||||
|
stm32_gpiowrite(gpio, !selected);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
__EXPORT uint8_t stm32_spi5status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||||
|
{
|
||||||
|
return SPI_STATUS_PRESENT;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: board_spi_reset
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT void board_spi_reset(int ms)
|
||||||
|
{
|
||||||
|
/* disable SPI bus */
|
||||||
|
|
||||||
|
// SPI1
|
||||||
|
for (size_t cs = 0; arraySize(spi1selects_gpio) > 1 && cs < arraySize(spi1selects_gpio); cs++) {
|
||||||
|
if (spi1selects_gpio[cs] != 0) {
|
||||||
|
stm32_configgpio(_PIN_OFF(spi1selects_gpio[cs]));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stm32_configgpio(GPIO_SPI1_SCK_OFF);
|
||||||
|
stm32_configgpio(GPIO_SPI1_MISO_OFF);
|
||||||
|
stm32_configgpio(GPIO_SPI1_MOSI_OFF);
|
||||||
|
|
||||||
|
// SPI2
|
||||||
|
for (size_t cs = 0; arraySize(spi2selects_gpio) > 1 && cs < arraySize(spi2selects_gpio); cs++) {
|
||||||
|
if (spi2selects_gpio[cs] != 0) {
|
||||||
|
stm32_configgpio(_PIN_OFF(spi2selects_gpio[cs]));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stm32_configgpio(GPIO_SPI2_SCK_OFF);
|
||||||
|
stm32_configgpio(GPIO_SPI2_MISO_OFF);
|
||||||
|
stm32_configgpio(GPIO_SPI2_MOSI_OFF);
|
||||||
|
|
||||||
|
// SPI4
|
||||||
|
for (size_t cs = 0; arraySize(spi4selects_gpio) > 1 && cs < arraySize(spi4selects_gpio); cs++) {
|
||||||
|
if (spi4selects_gpio[cs] != 0) {
|
||||||
|
stm32_configgpio(_PIN_OFF(spi4selects_gpio[cs]));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stm32_configgpio(GPIO_SPI4_SCK_OFF);
|
||||||
|
stm32_configgpio(GPIO_SPI4_MISO_OFF);
|
||||||
|
stm32_configgpio(GPIO_SPI4_MOSI_OFF);
|
||||||
|
|
||||||
|
// SPI5
|
||||||
|
for (size_t cs = 0; arraySize(spi5selects_gpio) > 1 && cs < arraySize(spi5selects_gpio); cs++) {
|
||||||
|
if (spi5selects_gpio[cs] != 0) {
|
||||||
|
stm32_configgpio(_PIN_OFF(spi5selects_gpio[cs]));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stm32_configgpio(GPIO_SPI5_SCK_OFF);
|
||||||
|
stm32_configgpio(GPIO_SPI5_MISO_OFF);
|
||||||
|
stm32_configgpio(GPIO_SPI5_MOSI_OFF);
|
||||||
|
|
||||||
|
|
||||||
|
/* wait for the sensor rail to reach GND */
|
||||||
|
usleep(ms * 1000);
|
||||||
|
PX4_INFO("reset done, %d ms", ms);
|
||||||
|
|
||||||
|
/* re-enable power */
|
||||||
|
|
||||||
|
/* wait a bit before starting SPI, different times didn't influence results */
|
||||||
|
usleep(100);
|
||||||
|
|
||||||
|
/* reconfigure the SPI pins */
|
||||||
|
|
||||||
|
// SPI1
|
||||||
|
for (size_t cs = 0; arraySize(spi1selects_gpio) > 1 && cs < arraySize(spi1selects_gpio); cs++) {
|
||||||
|
if (spi1selects_gpio[cs] != 0) {
|
||||||
|
stm32_configgpio(spi1selects_gpio[cs]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stm32_configgpio(GPIO_SPI1_SCK);
|
||||||
|
stm32_configgpio(GPIO_SPI1_MISO);
|
||||||
|
stm32_configgpio(GPIO_SPI1_MOSI);
|
||||||
|
|
||||||
|
// SPI2
|
||||||
|
for (size_t cs = 0; arraySize(spi2selects_gpio) > 1 && cs < arraySize(spi2selects_gpio); cs++) {
|
||||||
|
if (spi2selects_gpio[cs] != 0) {
|
||||||
|
stm32_configgpio(spi2selects_gpio[cs]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stm32_configgpio(GPIO_SPI2_SCK);
|
||||||
|
stm32_configgpio(GPIO_SPI2_MISO);
|
||||||
|
stm32_configgpio(GPIO_SPI2_MOSI);
|
||||||
|
|
||||||
|
// SPI4
|
||||||
|
for (size_t cs = 0; arraySize(spi4selects_gpio) > 1 && cs < arraySize(spi4selects_gpio); cs++) {
|
||||||
|
if (spi4selects_gpio[cs] != 0) {
|
||||||
|
stm32_configgpio(spi4selects_gpio[cs]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stm32_configgpio(GPIO_SPI4_SCK);
|
||||||
|
stm32_configgpio(GPIO_SPI4_MISO);
|
||||||
|
stm32_configgpio(GPIO_SPI4_MOSI);
|
||||||
|
|
||||||
|
// SPI5
|
||||||
|
for (size_t cs = 0; arraySize(spi5selects_gpio) > 1 && cs < arraySize(spi5selects_gpio); cs++) {
|
||||||
|
if (spi5selects_gpio[cs] != 0) {
|
||||||
|
stm32_configgpio(spi5selects_gpio[cs]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
stm32_configgpio(GPIO_SPI5_SCK);
|
||||||
|
stm32_configgpio(GPIO_SPI5_MISO);
|
||||||
|
stm32_configgpio(GPIO_SPI5_MOSI);
|
||||||
|
|
||||||
|
}
|
|
@ -0,0 +1,173 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2018 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 <chip.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_TIM2_BASE,
|
||||||
|
.clock_register = STM32_RCC_APB1ENR,
|
||||||
|
.clock_bit = RCC_APB1ENR_TIM2EN,
|
||||||
|
.clock_freq = STM32_APB1_TIM2_CLKIN,
|
||||||
|
.first_channel_index = 3,
|
||||||
|
.last_channel_index = 3,
|
||||||
|
.handler = io_timer_handler1,
|
||||||
|
.vectorno = STM32_IRQ_TIM2,
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.base = STM32_TIM8_BASE,
|
||||||
|
.clock_register = STM32_RCC_APB1ENR,
|
||||||
|
.clock_bit = RCC_APB2ENR_TIM10EN,
|
||||||
|
.clock_freq = STM32_APB2_TIM8_CLKIN,
|
||||||
|
.first_channel_index = 3,
|
||||||
|
.last_channel_index = 3,
|
||||||
|
.handler = io_timer_handler2,
|
||||||
|
.vectorno = STM32_IRQ_TIM8CC, // REVIEW
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.base = STM32_TIM11_BASE,
|
||||||
|
.clock_register = STM32_RCC_APB1ENR,
|
||||||
|
.clock_bit = RCC_APB2ENR_TIM11EN,
|
||||||
|
.clock_freq = STM32_APB2_TIM11_CLKIN,
|
||||||
|
.first_channel_index = 2,
|
||||||
|
.last_channel_index = 2,
|
||||||
|
.handler = io_timer_handler3,
|
||||||
|
.vectorno = STM32_IRQ_TIM11,
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.base = STM32_TIM10_BASE,
|
||||||
|
.clock_register = STM32_RCC_APB2ENR,
|
||||||
|
.clock_bit = RCC_APB2ENR_TIM10EN,
|
||||||
|
.clock_freq = STM32_APB2_TIM10_CLKIN,
|
||||||
|
.first_channel_index = 0,
|
||||||
|
.last_channel_index = 0,
|
||||||
|
.handler = io_timer_handler4,
|
||||||
|
.vectorno = STM32_IRQ_TIM10,
|
||||||
|
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||||
|
{
|
||||||
|
.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_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_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_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_TIM2_CH4OUT,
|
||||||
|
.gpio_in = GPIO_TIM2_CH4IN,
|
||||||
|
.timer_index = 1,
|
||||||
|
.timer_channel = 4,
|
||||||
|
.ccr_offset = STM32_GTIM_CCR4_OFFSET,
|
||||||
|
.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.gpio_out = GPIO_TIM8_CH2OUT,
|
||||||
|
.gpio_in = GPIO_TIM8_CH2IN,
|
||||||
|
.timer_index = 2,
|
||||||
|
.timer_channel = 2,
|
||||||
|
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
|
||||||
|
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
|
||||||
|
},
|
||||||
|
// {
|
||||||
|
// .gpio_out = GPIO_TIM11_CH1OUT,
|
||||||
|
// .gpio_in = GPIO_TIM11_CH1IN,
|
||||||
|
// .timer_index = 3,
|
||||||
|
// .timer_channel = 1,
|
||||||
|
// .ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||||
|
// .masks = GTIM_SR_CC1IF | GTIM_SR_CC1F
|
||||||
|
// },
|
||||||
|
// {
|
||||||
|
// .gpio_out = GPIO_TIM10_CH1OUT,
|
||||||
|
// .gpio_in = GPIO_TIM10_CH1IN,
|
||||||
|
// .timer_index = 4,
|
||||||
|
// .timer_channel = 1,
|
||||||
|
// .ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||||
|
// .masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
|
||||||
|
// }
|
||||||
|
};
|
|
@ -224,4 +224,4 @@ PARAM_DEFINE_INT32(MOT_ORDERING, 0);
|
||||||
* @reboot_required true
|
* @reboot_required true
|
||||||
* @group System
|
* @group System
|
||||||
*/
|
*/
|
||||||
PARAM_DEFINE_INT32(SYS_FMU_TASK, 0);
|
PARAM_DEFINE_INT32(SYS_FMU_TASK, 1);
|
||||||
|
|
Loading…
Reference in New Issue