mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 11:06:04 +08:00
mRo x2.1 777 board support
This commit is contained in:
@@ -37,8 +37,13 @@ pipeline {
|
|||||||
"px4_fmu-v5_default", "px4_fmu-v5_fixedwing", "px4_fmu-v5_multicopter", "px4_fmu-v5_rover", "px4_fmu-v5_rtps", "px4_fmu-v5_stackcheck",
|
"px4_fmu-v5_default", "px4_fmu-v5_fixedwing", "px4_fmu-v5_multicopter", "px4_fmu-v5_rover", "px4_fmu-v5_rtps", "px4_fmu-v5_stackcheck",
|
||||||
"px4_fmu-v5x_default",
|
"px4_fmu-v5x_default",
|
||||||
"intel_aerofc-v1_default", "auav_x21_default", "av_x-v1_default", "bitcraze_crazyflie_default", "airmind_mindpx-v2_default",
|
"intel_aerofc-v1_default", "auav_x21_default", "av_x-v1_default", "bitcraze_crazyflie_default", "airmind_mindpx-v2_default",
|
||||||
"holybro_kakutef7", "holybro_durandal-v1_default", "holybro_durandal-v1_stackcheck", "modalai_fc-v1_default", "mro_ctrl-zero-f7_default", "nxp_fmuk66-v3_default", "omnibus_f4sd_default",
|
"holybro_kakutef7", "holybro_durandal-v1_default", "holybro_durandal-v1_stackcheck",
|
||||||
"uvify_core_default"],
|
"modalai_fc-v1_default",
|
||||||
|
"mro_ctrl-zero-f7_default", "mro_x21-777_default",
|
||||||
|
"nxp_fmuk66-v3_default",
|
||||||
|
"omnibus_f4sd_default",
|
||||||
|
"uvify_core_default"
|
||||||
|
],
|
||||||
image: docker_images.nuttx,
|
image: docker_images.nuttx,
|
||||||
archive: true
|
archive: true
|
||||||
]
|
]
|
||||||
|
|||||||
@@ -0,0 +1,118 @@
|
|||||||
|
|
||||||
|
px4_add_board(
|
||||||
|
PLATFORM nuttx
|
||||||
|
VENDOR mro
|
||||||
|
MODEL x21-777
|
||||||
|
LABEL default
|
||||||
|
TOOLCHAIN arm-none-eabi
|
||||||
|
ARCHITECTURE cortex-m7
|
||||||
|
ROMFSROOT px4fmu_common
|
||||||
|
IO px4_io-v2_default
|
||||||
|
TESTING
|
||||||
|
UAVCAN_INTERFACES 1
|
||||||
|
SERIAL_PORTS
|
||||||
|
GPS1:/dev/ttyS3
|
||||||
|
TEL1:/dev/ttyS1
|
||||||
|
TEL2:/dev/ttyS2
|
||||||
|
DRIVERS
|
||||||
|
adc
|
||||||
|
barometer # all available barometer drivers
|
||||||
|
batt_smbus
|
||||||
|
camera_capture
|
||||||
|
camera_trigger
|
||||||
|
differential_pressure # all available differential pressure drivers
|
||||||
|
distance_sensor # all available distance sensor drivers
|
||||||
|
#dshot
|
||||||
|
gps
|
||||||
|
#imu # all available imu drivers
|
||||||
|
imu/mpu6000
|
||||||
|
imu/mpu9250
|
||||||
|
irlock
|
||||||
|
lights/blinkm
|
||||||
|
lights/rgbled
|
||||||
|
lights/rgbled_ncp5623c
|
||||||
|
magnetometer # all available magnetometer drivers
|
||||||
|
mkblctrl
|
||||||
|
#optical_flow # all available optical flow drivers
|
||||||
|
#osd
|
||||||
|
pca9685
|
||||||
|
power_monitor/ina226
|
||||||
|
#protocol_splitter
|
||||||
|
pwm_input
|
||||||
|
pwm_out_sim
|
||||||
|
px4fmu
|
||||||
|
px4io
|
||||||
|
roboclaw
|
||||||
|
tap_esc
|
||||||
|
telemetry # all available telemetry drivers
|
||||||
|
test_ppm
|
||||||
|
tone_alarm
|
||||||
|
uavcan
|
||||||
|
MODULES
|
||||||
|
airspeed_selector
|
||||||
|
attitude_estimator_q
|
||||||
|
battery_status
|
||||||
|
camera_feedback
|
||||||
|
commander
|
||||||
|
dataman
|
||||||
|
ekf2
|
||||||
|
events
|
||||||
|
fw_att_control
|
||||||
|
fw_pos_control_l1
|
||||||
|
land_detector
|
||||||
|
landing_target_estimator
|
||||||
|
load_mon
|
||||||
|
local_position_estimator
|
||||||
|
logger
|
||||||
|
mavlink
|
||||||
|
mc_att_control
|
||||||
|
mc_pos_control
|
||||||
|
mc_rate_control
|
||||||
|
#micrortps_bridge
|
||||||
|
navigator
|
||||||
|
rc_update
|
||||||
|
rover_pos_control
|
||||||
|
sensors
|
||||||
|
sih
|
||||||
|
temperature_compensation
|
||||||
|
vmount
|
||||||
|
vtol_att_control
|
||||||
|
SYSTEMCMDS
|
||||||
|
bl_update
|
||||||
|
config
|
||||||
|
dmesg
|
||||||
|
dumpfile
|
||||||
|
esc_calib
|
||||||
|
hardfault_log
|
||||||
|
i2cdetect
|
||||||
|
led_control
|
||||||
|
mixer
|
||||||
|
motor_ramp
|
||||||
|
motor_test
|
||||||
|
mtd
|
||||||
|
nshterm
|
||||||
|
param
|
||||||
|
perf
|
||||||
|
pwm
|
||||||
|
reboot
|
||||||
|
reflect
|
||||||
|
sd_bench
|
||||||
|
shutdown
|
||||||
|
tests # tests and test runner
|
||||||
|
top
|
||||||
|
topic_listener
|
||||||
|
tune_control
|
||||||
|
usb_connected
|
||||||
|
ver
|
||||||
|
work_queue
|
||||||
|
EXAMPLES
|
||||||
|
bottle_drop # OBC challenge
|
||||||
|
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
||||||
|
hello
|
||||||
|
hwtest # Hardware test
|
||||||
|
#matlab_csv_serial
|
||||||
|
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||||
|
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||||
|
rover_steering_control # Rover example app
|
||||||
|
uuv_example_app
|
||||||
|
)
|
||||||
@@ -0,0 +1,13 @@
|
|||||||
|
{
|
||||||
|
"board_id": 136,
|
||||||
|
"magic": "MROX21777",
|
||||||
|
"description": "Firmware for the mRO X2.1-777 board",
|
||||||
|
"image": "",
|
||||||
|
"build_time": 0,
|
||||||
|
"summary": "mRO x2.1-777",
|
||||||
|
"version": "0.1",
|
||||||
|
"image_size": 0,
|
||||||
|
"image_maxsize": 2080768,
|
||||||
|
"git_identity": "",
|
||||||
|
"board_revision": 0
|
||||||
|
}
|
||||||
@@ -0,0 +1,12 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
#
|
||||||
|
# mRo x21-777 specific board defaults
|
||||||
|
#------------------------------------------------------------------------------
|
||||||
|
|
||||||
|
|
||||||
|
if [ $AUTOCNF = yes ]
|
||||||
|
then
|
||||||
|
|
||||||
|
fi
|
||||||
|
|
||||||
|
set LOGGER_BUF 64
|
||||||
@@ -0,0 +1,27 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
#
|
||||||
|
# mRo x21-777 specific board sensors init
|
||||||
|
#------------------------------------------------------------------------------
|
||||||
|
|
||||||
|
adc start
|
||||||
|
|
||||||
|
# External I2C bus
|
||||||
|
hmc5883 -C -T -X start
|
||||||
|
lis3mdl -X start
|
||||||
|
ist8310 -C start
|
||||||
|
|
||||||
|
# Internal SPI bus ICM-20608-G is rotated 90 deg yaw
|
||||||
|
mpu6000 -R 2 -T 20608 start
|
||||||
|
|
||||||
|
# Internal SPI bus ICM-20602-G is rotated 90 deg yaw
|
||||||
|
mpu6000 -R 2 -T 20602 start
|
||||||
|
|
||||||
|
# Internal SPI bus mpu9250 is rotated 90 deg yaw
|
||||||
|
mpu9250 -R 2 start
|
||||||
|
|
||||||
|
# Possible external compasses
|
||||||
|
ist8310 -C -b 1 start
|
||||||
|
ist8310 -C -b 2 start
|
||||||
|
hmc5883 -C -T -X start
|
||||||
|
qmc5883 -X start
|
||||||
|
lis3mdl -X start
|
||||||
@@ -0,0 +1,373 @@
|
|||||||
|
/************************************************************************************
|
||||||
|
* board.h
|
||||||
|
*
|
||||||
|
* Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
|
||||||
|
* Authors: David Sidrane <david_s5@nscdg.com>
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
#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 mRo x2.1 777 board provides the following clock sources:
|
||||||
|
*
|
||||||
|
* X301: 16 MHz crystal for HSE
|
||||||
|
*
|
||||||
|
* So we have these clock source available within the STM32
|
||||||
|
*
|
||||||
|
* HSI: 16 MHz RC factory-trimmed
|
||||||
|
* HSE: 16 MHz crystal for HSE
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define STM32_BOARD_XTAL 24000000ul
|
||||||
|
|
||||||
|
#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 = 24,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
|
||||||
|
*
|
||||||
|
* USB OTG FS, SDMMC and RNG Clock = PLL_VCO / PLLQ
|
||||||
|
* Subject to
|
||||||
|
* The USB OTG FS requires a 48 MHz clock to work correctly. The SDMMC
|
||||||
|
* and the random number generator need a frequency lower than or equal
|
||||||
|
* to 48 MHz to work correctly.
|
||||||
|
*
|
||||||
|
* 2 <= PLLQ <= 15
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Highest SYSCLK with USB OTG FS clock = 48 MHz
|
||||||
|
*
|
||||||
|
* PLL_VCO = (16,000,000 / 8) * 216 = 432 MHz
|
||||||
|
* SYSCLK = 432 MHz / 2 = 216 MHz
|
||||||
|
* USB OTG FS, SDMMC and RNG Clock = 432 MHz / 9 = 48 MHz
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24)
|
||||||
|
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(432)
|
||||||
|
#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_1 /* Console in from IO */
|
||||||
|
#define GPIO_USART1_TX 0 /* USART1 is RX-only */
|
||||||
|
|
||||||
|
#define GPIO_USART2_RX GPIO_USART2_RX_2
|
||||||
|
#define GPIO_USART2_TX GPIO_USART2_TX_2
|
||||||
|
#define GPIO_USART2_RTS GPIO_USART2_RTS_2
|
||||||
|
#define GPIO_USART2_CTS GPIO_USART2_CTS_2
|
||||||
|
|
||||||
|
#define GPIO_USART3_RX GPIO_USART3_RX_3
|
||||||
|
#define GPIO_USART3_TX GPIO_USART3_TX_3
|
||||||
|
#define GPIO_USART3_RTS GPIO_USART3_RTS_2
|
||||||
|
#define GPIO_USART3_CTS GPIO_USART3_CTS_2
|
||||||
|
|
||||||
|
#define GPIO_UART4_RX GPIO_UART4_RX_1
|
||||||
|
#define GPIO_UART4_TX GPIO_UART4_TX_1
|
||||||
|
|
||||||
|
#define GPIO_USART6_RX GPIO_USART6_RX_1
|
||||||
|
#define GPIO_USART6_TX GPIO_USART6_TX_1
|
||||||
|
|
||||||
|
#define GPIO_UART7_RX GPIO_UART7_RX_1
|
||||||
|
#define GPIO_UART7_TX GPIO_UART7_TX_1
|
||||||
|
|
||||||
|
|
||||||
|
/* UART8 has no alternate pin config */
|
||||||
|
|
||||||
|
/* UART RX DMA configurations */
|
||||||
|
|
||||||
|
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
|
||||||
|
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
|
||||||
|
|
||||||
|
/*
|
||||||
|
* CAN
|
||||||
|
*
|
||||||
|
* CAN1 is routed to the onboard transceiver.
|
||||||
|
*/
|
||||||
|
#define GPIO_CAN1_RX GPIO_CAN1_RX_3
|
||||||
|
#define GPIO_CAN1_TX GPIO_CAN1_TX_3
|
||||||
|
|
||||||
|
/*
|
||||||
|
* I2C
|
||||||
|
*
|
||||||
|
* The optional _GPIO configurations allow the I2C driver to manually
|
||||||
|
* reset the bus to clear stuck slaves. They match the pin configuration,
|
||||||
|
* but are normally-high GPIOs.
|
||||||
|
*/
|
||||||
|
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2
|
||||||
|
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
|
||||||
|
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
|
||||||
|
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
|
||||||
|
|
||||||
|
/*
|
||||||
|
* SPI
|
||||||
|
*
|
||||||
|
* There are sensors on SPI1, and SPI2 is connected to the FRAM.
|
||||||
|
*/
|
||||||
|
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
|
||||||
|
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
|
||||||
|
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
|
||||||
|
|
||||||
|
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1
|
||||||
|
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1
|
||||||
|
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2
|
||||||
|
|
||||||
|
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_1
|
||||||
|
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1
|
||||||
|
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Public Data
|
||||||
|
************************************************************************************/
|
||||||
|
#ifndef __ASSEMBLY__
|
||||||
|
|
||||||
|
#undef EXTERN
|
||||||
|
#if defined(__cplusplus)
|
||||||
|
#define EXTERN extern "C"
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#else
|
||||||
|
#define EXTERN extern
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* 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,249 @@
|
|||||||
|
#
|
||||||
|
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||||
|
#
|
||||||
|
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||||
|
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||||
|
# modifications.
|
||||||
|
#
|
||||||
|
# CONFIG_DISABLE_OS_API is not set
|
||||||
|
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||||
|
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||||
|
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||||
|
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||||
|
# CONFIG_MMCSD_SPI is not set
|
||||||
|
# CONFIG_NSH_DISABLEBG is not set
|
||||||
|
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||||
|
# CONFIG_NSH_DISABLE_DF is not set
|
||||||
|
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||||
|
# CONFIG_NSH_DISABLE_EXIT is not set
|
||||||
|
# CONFIG_NSH_DISABLE_GET is not set
|
||||||
|
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||||
|
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||||
|
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||||
|
# CONFIG_NSH_DISABLE_TIME is not set
|
||||||
|
CONFIG_ARCH="arm"
|
||||||
|
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||||
|
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config"
|
||||||
|
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||||
|
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||||
|
CONFIG_ARCH_CHIP="stm32f7"
|
||||||
|
CONFIG_ARCH_CHIP_STM32F777NI=y
|
||||||
|
CONFIG_ARCH_CHIP_STM32F7=y
|
||||||
|
CONFIG_ARCH_INTERRUPTSTACK=512
|
||||||
|
CONFIG_ARCH_STACKDUMP=y
|
||||||
|
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||||
|
CONFIG_ARMV7M_DCACHE=y
|
||||||
|
CONFIG_ARMV7M_DTCM=y
|
||||||
|
CONFIG_ARMV7M_ICACHE=y
|
||||||
|
CONFIG_ARMV7M_MEMCPY=y
|
||||||
|
CONFIG_ARMV7M_USEBASEPRI=y
|
||||||
|
CONFIG_BOARDCTL_RESET=y
|
||||||
|
CONFIG_BOARD_CRASHDUMP=y
|
||||||
|
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||||
|
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||||
|
CONFIG_BUILTIN=y
|
||||||
|
CONFIG_C99_BOOL8=y
|
||||||
|
CONFIG_CDCACM=y
|
||||||
|
CONFIG_CDCACM_PRODUCTID=0x0088
|
||||||
|
CONFIG_CDCACM_PRODUCTSTR="mRo x2.1-777"
|
||||||
|
CONFIG_CDCACM_RXBUFSIZE=600
|
||||||
|
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||||
|
CONFIG_CDCACM_VENDORID=0x26ac
|
||||||
|
CONFIG_CDCACM_VENDORSTR="mRo"
|
||||||
|
CONFIG_CLOCK_MONOTONIC=y
|
||||||
|
CONFIG_DEBUG_FULLOPT=y
|
||||||
|
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||||
|
CONFIG_DEBUG_SYMBOLS=y
|
||||||
|
CONFIG_DEFAULT_SMALL=y
|
||||||
|
CONFIG_DEV_FIFO_SIZE=0
|
||||||
|
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||||
|
CONFIG_DEV_PIPE_SIZE=70
|
||||||
|
CONFIG_FAT_DMAMEMORY=y
|
||||||
|
CONFIG_FAT_LCNAMES=y
|
||||||
|
CONFIG_FAT_LFN=y
|
||||||
|
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||||
|
CONFIG_FDCLONE_STDIO=y
|
||||||
|
CONFIG_FS_BINFS=y
|
||||||
|
CONFIG_FS_CROMFS=y
|
||||||
|
CONFIG_FS_FAT=y
|
||||||
|
CONFIG_FS_FATTIME=y
|
||||||
|
CONFIG_FS_PROCFS=y
|
||||||
|
CONFIG_FS_PROCFS_EXCLUDE_BLOCKS=y
|
||||||
|
CONFIG_FS_PROCFS_EXCLUDE_MOUNT=y
|
||||||
|
CONFIG_FS_PROCFS_EXCLUDE_MOUNTS=y
|
||||||
|
CONFIG_FS_PROCFS_EXCLUDE_PARTITIONS=y
|
||||||
|
CONFIG_FS_PROCFS_EXCLUDE_USAGE=y
|
||||||
|
CONFIG_FS_PROCFS_REGISTER=y
|
||||||
|
CONFIG_FS_ROMFS=y
|
||||||
|
CONFIG_GRAN=y
|
||||||
|
CONFIG_GRAN_INTR=y
|
||||||
|
CONFIG_HAVE_CXX=y
|
||||||
|
CONFIG_HAVE_CXXINITIALIZE=y
|
||||||
|
CONFIG_I2C=y
|
||||||
|
CONFIG_I2C_RESET=y
|
||||||
|
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||||
|
CONFIG_LIBC_FLOATINGPOINT=y
|
||||||
|
CONFIG_LIBC_LONG_LONG=y
|
||||||
|
CONFIG_LIBC_STRERROR=y
|
||||||
|
CONFIG_MAX_TASKS=64
|
||||||
|
CONFIG_MAX_WDOGPARMS=2
|
||||||
|
CONFIG_MEMSET_64BIT=y
|
||||||
|
CONFIG_MEMSET_OPTSPEED=y
|
||||||
|
CONFIG_MMCSD=y
|
||||||
|
CONFIG_MMCSD_MULTIBLOCK_DISABLE=y
|
||||||
|
CONFIG_MMCSD_SDIO=y
|
||||||
|
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
|
||||||
|
CONFIG_MM_REGIONS=3
|
||||||
|
CONFIG_MTD=y
|
||||||
|
CONFIG_MTD_BYTE_WRITE=y
|
||||||
|
CONFIG_MTD_PARTITION=y
|
||||||
|
CONFIG_MTD_RAMTRON=y
|
||||||
|
CONFIG_NFILE_DESCRIPTORS=20
|
||||||
|
CONFIG_NFILE_STREAMS=8
|
||||||
|
CONFIG_NSH_ARCHINIT=y
|
||||||
|
CONFIG_NSH_ARCHROMFS=y
|
||||||
|
CONFIG_NSH_ARGCAT=y
|
||||||
|
CONFIG_NSH_BUILTIN_APPS=y
|
||||||
|
CONFIG_NSH_CMDPARMS=y
|
||||||
|
CONFIG_NSH_CROMFSETC=y
|
||||||
|
CONFIG_NSH_DISABLE_IFCONFIG=y
|
||||||
|
CONFIG_NSH_DISABLE_IFUPDOWN=y
|
||||||
|
CONFIG_NSH_DISABLE_MB=y
|
||||||
|
CONFIG_NSH_DISABLE_MH=y
|
||||||
|
CONFIG_NSH_DISABLE_TELNETD=y
|
||||||
|
CONFIG_NSH_LINELEN=128
|
||||||
|
CONFIG_NSH_MAXARGUMENTS=12
|
||||||
|
CONFIG_NSH_NESTDEPTH=8
|
||||||
|
CONFIG_NSH_QUOTE=y
|
||||||
|
CONFIG_NSH_ROMFSETC=y
|
||||||
|
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||||
|
CONFIG_NSH_STRERROR=y
|
||||||
|
CONFIG_NSH_VARS=y
|
||||||
|
CONFIG_NXFONTS_DISABLE_16BPP=y
|
||||||
|
CONFIG_NXFONTS_DISABLE_1BPP=y
|
||||||
|
CONFIG_NXFONTS_DISABLE_24BPP=y
|
||||||
|
CONFIG_NXFONTS_DISABLE_2BPP=y
|
||||||
|
CONFIG_NXFONTS_DISABLE_32BPP=y
|
||||||
|
CONFIG_NXFONTS_DISABLE_4BPP=y
|
||||||
|
CONFIG_NXFONTS_DISABLE_8BPP=y
|
||||||
|
CONFIG_PIPES=y
|
||||||
|
CONFIG_PREALLOC_MQ_MSGS=4
|
||||||
|
CONFIG_PREALLOC_TIMERS=50
|
||||||
|
CONFIG_PREALLOC_WDOGS=50
|
||||||
|
CONFIG_PRIORITY_INHERITANCE=y
|
||||||
|
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||||
|
CONFIG_PTHREAD_STACK_MIN=512
|
||||||
|
CONFIG_RAMTRON_SETSPEED=y
|
||||||
|
CONFIG_RAMTRON_WRITEWAIT=y
|
||||||
|
CONFIG_RAM_SIZE=245760
|
||||||
|
CONFIG_RAM_START=0x20010000
|
||||||
|
CONFIG_RAW_BINARY=y
|
||||||
|
CONFIG_RTC_DATETIME=y
|
||||||
|
CONFIG_SCHED_ATEXIT=y
|
||||||
|
CONFIG_SCHED_HPWORK=y
|
||||||
|
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||||
|
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||||
|
CONFIG_SCHED_INSTRUMENTATION=y
|
||||||
|
CONFIG_SCHED_LPWORK=y
|
||||||
|
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||||
|
CONFIG_SCHED_LPWORKSTACKSIZE=1536
|
||||||
|
CONFIG_SCHED_WAITPID=y
|
||||||
|
CONFIG_SDCLONE_DISABLE=y
|
||||||
|
CONFIG_SDMMC1_SDIO_MODE=y
|
||||||
|
CONFIG_SDMMC1_SDIO_PULLUP=y
|
||||||
|
CONFIG_SEM_NNESTPRIO=8
|
||||||
|
CONFIG_SEM_PREALLOCHOLDERS=0
|
||||||
|
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||||
|
CONFIG_SERIAL_TERMIOS=y
|
||||||
|
CONFIG_SIG_DEFAULT=y
|
||||||
|
CONFIG_SIG_SIGALRM_ACTION=y
|
||||||
|
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||||
|
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||||
|
CONFIG_SIG_SIGWORK=4
|
||||||
|
CONFIG_STACK_COLORATION=y
|
||||||
|
CONFIG_START_DAY=30
|
||||||
|
CONFIG_START_MONTH=11
|
||||||
|
CONFIG_STDIO_BUFFER_SIZE=32
|
||||||
|
CONFIG_STM32F7_ADC1=y
|
||||||
|
CONFIG_STM32F7_BBSRAM=y
|
||||||
|
CONFIG_STM32F7_BBSRAM_FILES=5
|
||||||
|
CONFIG_STM32F7_BKPSRAM=y
|
||||||
|
CONFIG_STM32F7_DMA1=y
|
||||||
|
CONFIG_STM32F7_DMA2=y
|
||||||
|
CONFIG_STM32F7_DMACAPABLE=y
|
||||||
|
CONFIG_STM32F7_FLOWCONTROL_BROKEN=y
|
||||||
|
CONFIG_STM32F7_I2C1=y
|
||||||
|
CONFIG_STM32F7_I2C_DYNTIMEO=y
|
||||||
|
CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10
|
||||||
|
CONFIG_STM32F7_OTGFS=y
|
||||||
|
CONFIG_STM32F7_PROGMEM=y
|
||||||
|
CONFIG_STM32F7_PWR=y
|
||||||
|
CONFIG_STM32F7_RTC=y
|
||||||
|
CONFIG_STM32F7_RTC_HSECLOCK=y
|
||||||
|
CONFIG_STM32F7_RTC_MAGIC_REG=1
|
||||||
|
CONFIG_STM32F7_SAVE_CRASHDUMP=y
|
||||||
|
CONFIG_STM32F7_SDMMC1=y
|
||||||
|
CONFIG_STM32F7_SDMMC_DMA=y
|
||||||
|
CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y
|
||||||
|
CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y
|
||||||
|
CONFIG_STM32F7_SPI1=y
|
||||||
|
CONFIG_STM32F7_SPI2=y
|
||||||
|
CONFIG_STM32F7_TIM10=y
|
||||||
|
CONFIG_STM32F7_TIM1=y
|
||||||
|
CONFIG_STM32F7_TIM3=y
|
||||||
|
CONFIG_STM32F7_TIM4=y
|
||||||
|
CONFIG_STM32F7_TIM9=y
|
||||||
|
CONFIG_STM32F7_UART4=y
|
||||||
|
CONFIG_STM32F7_UART7=y
|
||||||
|
CONFIG_STM32F7_UART8=y
|
||||||
|
CONFIG_STM32F7_USART1=y
|
||||||
|
CONFIG_STM32F7_USART2=y
|
||||||
|
CONFIG_STM32F7_USART3=y
|
||||||
|
CONFIG_STM32F7_USART6=y
|
||||||
|
CONFIG_STM32F7_USART_BREAKS=y
|
||||||
|
CONFIG_STM32F7_USART_INVERT=y
|
||||||
|
CONFIG_STM32F7_USART_SINGLEWIRE=y
|
||||||
|
CONFIG_STM32F7_USART_SWAP=y
|
||||||
|
CONFIG_STM32F7_WWDG=y
|
||||||
|
CONFIG_SYSTEM_CDCACM=y
|
||||||
|
CONFIG_SYSTEM_NSH=y
|
||||||
|
CONFIG_TASK_NAME_SIZE=24
|
||||||
|
CONFIG_TIME_EXTENDED=y
|
||||||
|
CONFIG_UART4_BAUD=57600
|
||||||
|
CONFIG_UART4_RXBUFSIZE=600
|
||||||
|
CONFIG_UART4_RXDMA=y
|
||||||
|
CONFIG_UART4_TXBUFSIZE=1500
|
||||||
|
CONFIG_UART7_BAUD=57600
|
||||||
|
CONFIG_UART7_RXBUFSIZE=600
|
||||||
|
CONFIG_UART7_SERIAL_CONSOLE=y
|
||||||
|
CONFIG_UART7_TXBUFSIZE=1500
|
||||||
|
CONFIG_UART8_BAUD=57600
|
||||||
|
CONFIG_UART8_RXBUFSIZE=600
|
||||||
|
CONFIG_UART8_RXDMA=y
|
||||||
|
CONFIG_UART8_TXBUFSIZE=1500
|
||||||
|
CONFIG_USART1_BAUD=57600
|
||||||
|
CONFIG_USART1_RXBUFSIZE=600
|
||||||
|
CONFIG_USART1_RXDMA=y
|
||||||
|
CONFIG_USART1_TXBUFSIZE=1500
|
||||||
|
CONFIG_USART2_BAUD=57600
|
||||||
|
CONFIG_USART2_IFLOWCONTROL=y
|
||||||
|
CONFIG_USART2_OFLOWCONTROL=y
|
||||||
|
CONFIG_USART2_RXBUFSIZE=600
|
||||||
|
CONFIG_USART2_RXDMA=y
|
||||||
|
CONFIG_USART2_TXBUFSIZE=1500
|
||||||
|
CONFIG_USART3_BAUD=57600
|
||||||
|
CONFIG_USART3_IFLOWCONTROL=y
|
||||||
|
CONFIG_USART3_OFLOWCONTROL=y
|
||||||
|
CONFIG_USART3_RXBUFSIZE=600
|
||||||
|
CONFIG_USART3_RXDMA=y
|
||||||
|
CONFIG_USART3_TXBUFSIZE=3000
|
||||||
|
CONFIG_USART6_BAUD=57600
|
||||||
|
CONFIG_USART6_RXBUFSIZE=600
|
||||||
|
CONFIG_USART6_RXDMA=y
|
||||||
|
CONFIG_USART6_TXBUFSIZE=1500
|
||||||
|
CONFIG_USBDEV=y
|
||||||
|
CONFIG_USBDEV_BUSPOWERED=y
|
||||||
|
CONFIG_USBDEV_MAXPOWER=500
|
||||||
|
CONFIG_USEC_PER_TICK=1000
|
||||||
|
CONFIG_USERMAIN_STACKSIZE=2624
|
||||||
|
CONFIG_USER_ENTRYPOINT="nsh_main"
|
||||||
@@ -0,0 +1,183 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* 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,51 @@
|
|||||||
|
############################################################################
|
||||||
|
#
|
||||||
|
# Copyright (c) 2019 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.
|
||||||
|
#
|
||||||
|
############################################################################
|
||||||
|
|
||||||
|
add_library(drivers_board
|
||||||
|
init.c
|
||||||
|
led.c
|
||||||
|
sdio.c
|
||||||
|
spi.cpp
|
||||||
|
timer_config.c
|
||||||
|
usb.c
|
||||||
|
)
|
||||||
|
add_dependencies(drivers_board arch_board_hw_info)
|
||||||
|
|
||||||
|
target_link_libraries(drivers_board
|
||||||
|
PRIVATE
|
||||||
|
arch_board_hw_info
|
||||||
|
drivers__led # drv_led_start
|
||||||
|
nuttx_arch # sdio
|
||||||
|
nuttx_drivers # sdio
|
||||||
|
px4_layer
|
||||||
|
)
|
||||||
@@ -0,0 +1,273 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 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
|
||||||
|
*
|
||||||
|
* mRo x2.1 777 internal definitions
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
/****************************************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************************************/
|
||||||
|
|
||||||
|
#include <px4_platform_common/px4_config.h>
|
||||||
|
#include <nuttx/compiler.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include <stm32_gpio.h>
|
||||||
|
|
||||||
|
/****************************************************************************************************
|
||||||
|
* Definitions
|
||||||
|
****************************************************************************************************/
|
||||||
|
|
||||||
|
/* PX4IO connection configuration */
|
||||||
|
|
||||||
|
#define BOARD_USES_PX4IO_VERSION 2
|
||||||
|
#define PX4IO_SERIAL_DEVICE "/dev/ttyS4"
|
||||||
|
#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
|
||||||
|
#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
|
||||||
|
#define PX4IO_SERIAL_BASE STM32_USART6_BASE
|
||||||
|
#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
|
||||||
|
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX_2
|
||||||
|
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX_2
|
||||||
|
#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR
|
||||||
|
#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN
|
||||||
|
#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
|
||||||
|
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
|
||||||
|
|
||||||
|
|
||||||
|
/* PX4FMU GPIOs ***********************************************************************************/
|
||||||
|
/* LEDs */
|
||||||
|
|
||||||
|
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12)
|
||||||
|
#define BOARD_OVERLOAD_LED LED_RED
|
||||||
|
|
||||||
|
/* External interrupts but on board*/
|
||||||
|
#define GPIO_EXTI_MPU_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15)
|
||||||
|
|
||||||
|
/* Data ready pins but on board */
|
||||||
|
|
||||||
|
#define GPIO_EXTI_ICM_2060X_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14)
|
||||||
|
|
||||||
|
/* Data ready pins off */
|
||||||
|
#define GPIO_EXTI_MPU_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15)
|
||||||
|
#define GPIO_EXTI_ICM_2060X_DRDY_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_EXTI|GPIO_PORTC|GPIO_PIN14)
|
||||||
|
|
||||||
|
/* SPI1 off */
|
||||||
|
#define GPIO_SPI1_SCK_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN5)
|
||||||
|
#define GPIO_SPI1_MISO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN6)
|
||||||
|
#define GPIO_SPI1_MOSI_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN7)
|
||||||
|
|
||||||
|
/* SPI1 chip selects off */
|
||||||
|
#define GPIO_SPI_CS_ICM_2060X_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN15)
|
||||||
|
#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTD|GPIO_PIN7)
|
||||||
|
#define GPIO_SPI_CS_MPU_OFF (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz|GPIO_PORTC|GPIO_PIN2)
|
||||||
|
|
||||||
|
/* SPI chip selects */
|
||||||
|
#define GPIO_SPI_CS_ICM_2060X (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
|
||||||
|
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
|
||||||
|
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
|
||||||
|
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
|
||||||
|
|
||||||
|
#define PX4_SPI_BUS_SENSORS 1
|
||||||
|
#define PX4_SPI_BUS_RAMTRON 2
|
||||||
|
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS
|
||||||
|
|
||||||
|
/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */
|
||||||
|
#define PX4_SPIDEV_ICM_20602 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 1)
|
||||||
|
#define PX4_SPIDEV_ICM_20608 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 2)
|
||||||
|
#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 3)
|
||||||
|
#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 4)
|
||||||
|
|
||||||
|
/* I2C busses */
|
||||||
|
|
||||||
|
/* There is no I2C2 so there is not notion of internal / external*/
|
||||||
|
#define PX4_I2C_BUS_EXPANSION 1
|
||||||
|
#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION
|
||||||
|
|
||||||
|
/*
|
||||||
|
* ADC channels
|
||||||
|
*
|
||||||
|
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver
|
||||||
|
*/
|
||||||
|
#define ADC_CHANNELS (1 << 2) | (1 << 3) | (1 << 4) | (1 << 13) | (1 << 14) | (1 << 15)
|
||||||
|
|
||||||
|
// ADC defines to be used in sensors.cpp to read from a particular channel
|
||||||
|
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
|
||||||
|
#define ADC_BATTERY_CURRENT_CHANNEL 3
|
||||||
|
#define ADC_5V_RAIL_SENSE 4
|
||||||
|
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
|
||||||
|
|
||||||
|
/* User GPIOs
|
||||||
|
*
|
||||||
|
* GPIO0-5 are the PWM servo outputs.
|
||||||
|
*/
|
||||||
|
#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN14)
|
||||||
|
#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN13)
|
||||||
|
#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11)
|
||||||
|
#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN9)
|
||||||
|
#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
|
||||||
|
#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
|
||||||
|
#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14)
|
||||||
|
#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN13)
|
||||||
|
#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11)
|
||||||
|
#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9)
|
||||||
|
#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
|
||||||
|
#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
|
||||||
|
|
||||||
|
/* Power supply control and monitoring GPIOs */
|
||||||
|
// Signal is not connected
|
||||||
|
#define GPIO_VDD_5V_PERIPH_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN8)
|
||||||
|
#define GPIO_VDD_BRICK_VALID (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||||
|
#define GPIO_VDD_3V3_SENSORS_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
|
||||||
|
#define GPIO_VDD_5V_PERIPH_OC (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15)
|
||||||
|
|
||||||
|
/* Tone alarm output */
|
||||||
|
#define TONE_ALARM_TIMER 2 /* timer 2 */
|
||||||
|
#define TONE_ALARM_CHANNEL 1 /* channel 1 */
|
||||||
|
#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
|
||||||
|
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15)
|
||||||
|
|
||||||
|
/* PWM
|
||||||
|
*
|
||||||
|
* Six PWM outputs are configured.
|
||||||
|
*
|
||||||
|
* Pins:
|
||||||
|
*
|
||||||
|
* CH1 : PE14 : TIM1_CH4
|
||||||
|
* CH2 : PE13 : TIM1_CH3
|
||||||
|
* CH3 : PE11 : TIM1_CH2
|
||||||
|
* CH4 : PE9 : TIM1_CH1
|
||||||
|
* CH5 : PD13 : TIM4_CH2
|
||||||
|
* CH6 : PD14 : TIM4_CH3
|
||||||
|
*/
|
||||||
|
#define GPIO_TIM1_CH1OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN9)
|
||||||
|
#define GPIO_TIM1_CH2OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11)
|
||||||
|
#define GPIO_TIM1_CH3OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13)
|
||||||
|
#define GPIO_TIM1_CH4OUT (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14)
|
||||||
|
#define GPIO_TIM4_CH2OUT (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN13)
|
||||||
|
#define GPIO_TIM4_CH3OUT (GPIO_ALT|GPIO_AF2|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN14)
|
||||||
|
#define DIRECT_PWM_OUTPUT_CHANNELS 6
|
||||||
|
|
||||||
|
#define GPIO_TIM1_CH1IN GPIO_TIM1_CH1IN_2
|
||||||
|
#define GPIO_TIM1_CH2IN GPIO_TIM1_CH2IN_2
|
||||||
|
#define GPIO_TIM1_CH3IN GPIO_TIM1_CH3IN_2
|
||||||
|
#define GPIO_TIM1_CH4IN GPIO_TIM1_CH4IN_2
|
||||||
|
#define GPIO_TIM4_CH2IN GPIO_TIM4_CH2IN_2
|
||||||
|
#define GPIO_TIM4_CH3IN GPIO_TIM4_CH3IN_2
|
||||||
|
#define DIRECT_INPUT_TIMER_CHANNELS 6
|
||||||
|
|
||||||
|
/* USB OTG FS
|
||||||
|
*
|
||||||
|
* PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED)
|
||||||
|
*/
|
||||||
|
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
|
||||||
|
|
||||||
|
/* High-resolution timer */
|
||||||
|
#define HRT_TIMER 8 /* use timer8 for the HRT */
|
||||||
|
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
|
||||||
|
|
||||||
|
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
|
||||||
|
#define PWMIN_TIMER 4
|
||||||
|
#define PWMIN_TIMER_CHANNEL 2
|
||||||
|
#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2
|
||||||
|
|
||||||
|
/* By Providing BOARD_ADC_USB_CONNECTED this board support the ADC
|
||||||
|
* system_power interface, and therefore provides the true logic
|
||||||
|
* GPIO BOARD_ADC_xxxx macros.
|
||||||
|
*/
|
||||||
|
#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS))
|
||||||
|
#define BOARD_ADC_BRICK_VALID (!px4_arch_gpioread(GPIO_VDD_BRICK_VALID))
|
||||||
|
#define BOARD_ADC_SERVO_VALID (1)
|
||||||
|
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_OC))
|
||||||
|
#define BOARD_ADC_HIPOWER_5V_OC (0)
|
||||||
|
|
||||||
|
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||||
|
|
||||||
|
/* 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
|
||||||
|
|
||||||
|
|
||||||
|
#define SDIO_SLOTNO 0 /* Only one slot */
|
||||||
|
#define SDIO_MINOR 0
|
||||||
|
|
||||||
|
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||||
|
|
||||||
|
#define BOARD_NUM_IO_TIMERS 3
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
|
#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);
|
||||||
|
|
||||||
|
void board_spi_reset(int ms);
|
||||||
|
|
||||||
|
extern void stm32_usbinitialize(void);
|
||||||
|
|
||||||
|
extern void board_peripheral_reset(int ms);
|
||||||
|
|
||||||
|
#include <px4_platform_common/board_common.h>
|
||||||
|
|
||||||
|
#endif /* __ASSEMBLY__ */
|
||||||
|
|
||||||
|
__END_DECLS
|
||||||
@@ -0,0 +1,340 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 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
|
||||||
|
*
|
||||||
|
* mRO x2.1 777 specific early startup code. This file implements the
|
||||||
|
* board_app_initialize() 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 initialization.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <debug.h>
|
||||||
|
#include <errno.h>
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
#include <nuttx/board.h>
|
||||||
|
#include <nuttx/spi/spi.h>
|
||||||
|
#include <nuttx/sdio.h>
|
||||||
|
#include <nuttx/mmcsd.h>
|
||||||
|
#include <nuttx/analog/adc.h>
|
||||||
|
#include <nuttx/mm/gran.h>
|
||||||
|
#include <chip.h>
|
||||||
|
#include <stm32_uart.h>
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
#include "up_internal.h"
|
||||||
|
|
||||||
|
#include <drivers/drv_hrt.h>
|
||||||
|
#include <drivers/drv_board_led.h>
|
||||||
|
#include <systemlib/px4_macros.h>
|
||||||
|
#include <px4_platform_common/init.h>
|
||||||
|
#include <px4_platform/gpio.h>
|
||||||
|
#include <px4_platform/board_dma_alloc.h>
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Pre-Processor Definitions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Configuration ************************************************************/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Ideally we'd be able to get these from up_internal.h,
|
||||||
|
* but since we want to be able to disable the NuttX use
|
||||||
|
* of leds for system indication at will and there is no
|
||||||
|
* separate switch, we need to build independent of the
|
||||||
|
* CONFIG_ARCH_LEDS configuration switch.
|
||||||
|
*/
|
||||||
|
__BEGIN_DECLS
|
||||||
|
extern void led_init(void);
|
||||||
|
extern void led_on(int led);
|
||||||
|
extern void led_off(int led);
|
||||||
|
__END_DECLS
|
||||||
|
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: board_rc_input
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* All boards my optionally provide this API to invert the Serial RC input.
|
||||||
|
* This is needed on SoCs that support the notion RXINV or TXINV as apposed to
|
||||||
|
* and external XOR controlled by a GPIO
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT void board_rc_input(bool invert_on, uint32_t uxart_base)
|
||||||
|
{
|
||||||
|
|
||||||
|
irqstate_t irqstate = px4_enter_critical_section();
|
||||||
|
|
||||||
|
uint32_t cr1 = getreg32(STM32_USART_CR1_OFFSET + uxart_base);
|
||||||
|
uint32_t cr2 = getreg32(STM32_USART_CR2_OFFSET + uxart_base);
|
||||||
|
uint32_t regval = cr1;
|
||||||
|
|
||||||
|
/* {R|T}XINV bit fields can only be written when the USART is disabled (UE=0). */
|
||||||
|
|
||||||
|
regval &= ~USART_CR1_UE;
|
||||||
|
|
||||||
|
putreg32(regval, STM32_USART_CR1_OFFSET + uxart_base);
|
||||||
|
|
||||||
|
if (invert_on) {
|
||||||
|
#if defined(BOARD_HAS_RX_TX_SWAP) && RC_SERIAL_PORT_IS_SWAPED == 1
|
||||||
|
|
||||||
|
/* This is only ever turned on */
|
||||||
|
|
||||||
|
cr2 |= (USART_CR2_RXINV | USART_CR2_TXINV | USART_CR2_SWAP);
|
||||||
|
#else
|
||||||
|
cr2 |= (USART_CR2_RXINV | USART_CR2_TXINV);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
} else {
|
||||||
|
cr2 &= ~(USART_CR2_RXINV | USART_CR2_TXINV);
|
||||||
|
}
|
||||||
|
|
||||||
|
putreg32(cr2, STM32_USART_CR2_OFFSET + uxart_base);
|
||||||
|
putreg32(cr1, STM32_USART_CR1_OFFSET + uxart_base);
|
||||||
|
|
||||||
|
leave_critical_section(irqstate);
|
||||||
|
}
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: board_peripheral_reset
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
__EXPORT void board_peripheral_reset(int ms)
|
||||||
|
{
|
||||||
|
/* set the peripheral rails off */
|
||||||
|
stm32_configgpio(GPIO_VDD_5V_PERIPH_EN);
|
||||||
|
stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 1);
|
||||||
|
|
||||||
|
/* wait for the peripheral rail to reach GND */
|
||||||
|
usleep(ms * 1000);
|
||||||
|
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||||
|
|
||||||
|
/* re-enable power */
|
||||||
|
|
||||||
|
/* switch the peripheral rail back on */
|
||||||
|
stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* 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.
|
||||||
|
stm32_configgpio(GPIO_GPIO0_OUTPUT);
|
||||||
|
stm32_configgpio(GPIO_GPIO1_OUTPUT);
|
||||||
|
stm32_configgpio(GPIO_GPIO2_OUTPUT);
|
||||||
|
stm32_configgpio(GPIO_GPIO3_OUTPUT);
|
||||||
|
stm32_configgpio(GPIO_GPIO4_OUTPUT);
|
||||||
|
stm32_configgpio(GPIO_GPIO5_OUTPUT);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* On resets invoked from system (not boot) insure we establish a low
|
||||||
|
* output state (discharge the pins) on PWM pins before they become inputs.
|
||||||
|
*/
|
||||||
|
|
||||||
|
if (status >= 0) {
|
||||||
|
up_mdelay(6);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_app_finalinitialize
|
||||||
|
*
|
||||||
|
* 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_FINALINIT.
|
||||||
|
*
|
||||||
|
* Input Parameters:
|
||||||
|
* arg - The argument has no meaning.
|
||||||
|
*
|
||||||
|
* Returned Value:
|
||||||
|
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||||
|
* any failure to indicate the nature of the failure.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#ifdef CONFIG_BOARDCTL_FINALINIT
|
||||||
|
int board_app_finalinitialize(uintptr_t arg)
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* 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 */
|
||||||
|
|
||||||
|
/* configure ADC pins */
|
||||||
|
px4_arch_configgpio(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */
|
||||||
|
px4_arch_configgpio(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */
|
||||||
|
px4_arch_configgpio(GPIO_ADC1_IN4); /* VDD_5V_SENS */
|
||||||
|
px4_arch_configgpio(GPIO_ADC1_IN13); /* FMU_AUX_ADC_1 */
|
||||||
|
px4_arch_configgpio(GPIO_ADC1_IN14); /* FMU_AUX_ADC_2 */
|
||||||
|
px4_arch_configgpio(GPIO_ADC1_IN15); /* PRESSURE_SENS */
|
||||||
|
|
||||||
|
/* configure power supply control/sense pins */
|
||||||
|
px4_arch_configgpio(GPIO_VDD_5V_PERIPH_EN);
|
||||||
|
px4_arch_configgpio(GPIO_VDD_3V3_SENSORS_EN);
|
||||||
|
px4_arch_configgpio(GPIO_VDD_BRICK_VALID);
|
||||||
|
px4_arch_configgpio(GPIO_VDD_5V_PERIPH_OC);
|
||||||
|
|
||||||
|
/* configure CAN interface */
|
||||||
|
px4_arch_configgpio(GPIO_CAN1_RX);
|
||||||
|
px4_arch_configgpio(GPIO_CAN1_TX);
|
||||||
|
|
||||||
|
/* configure SPI interfaces */
|
||||||
|
|
||||||
|
stm32_spiinitialize();
|
||||||
|
|
||||||
|
/* configure USB interfaces */
|
||||||
|
|
||||||
|
stm32_usbinitialize();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_app_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Perform application specific initialization. This function is never
|
||||||
|
* called directly from application code, but only indirectly via the
|
||||||
|
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
|
||||||
|
*
|
||||||
|
* Input Parameters:
|
||||||
|
* arg - The boardctl() argument is passed to the board_app_initialize()
|
||||||
|
* implementation without modification. The argument has no
|
||||||
|
* meaning to NuttX; the meaning of the argument is a contract
|
||||||
|
* between the board-specific initalization logic and the the
|
||||||
|
* matching application logic. The value cold be such things as a
|
||||||
|
* mode enumeration value, a set of DIP switch switch settings, a
|
||||||
|
* pointer to configuration data read from a file or serial FLASH,
|
||||||
|
* or whatever you would like to do with it. Every implementation
|
||||||
|
* should accept zero/NULL as a default configuration.
|
||||||
|
*
|
||||||
|
* Returned Value:
|
||||||
|
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||||
|
* any failure to indicate the nature of the failure.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
|
||||||
|
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||||
|
{
|
||||||
|
px4_platform_init();
|
||||||
|
|
||||||
|
/* configure the DMA allocator */
|
||||||
|
|
||||||
|
if (board_dma_alloc_init() < 0) {
|
||||||
|
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
/* set up the serial DMA polling */
|
||||||
|
static struct hrt_call serial_dma_call;
|
||||||
|
struct timespec ts;
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Poll at 1ms intervals for received bytes that have not triggered
|
||||||
|
* a DMA event.
|
||||||
|
*/
|
||||||
|
ts.tv_sec = 0;
|
||||||
|
ts.tv_nsec = 1000000;
|
||||||
|
|
||||||
|
hrt_call_every(&serial_dma_call,
|
||||||
|
ts_to_abstime(&ts),
|
||||||
|
ts_to_abstime(&ts),
|
||||||
|
(hrt_callout)stm32_serial_dma_poll,
|
||||||
|
NULL);
|
||||||
|
|
||||||
|
|
||||||
|
/* initial LED state */
|
||||||
|
drv_led_start();
|
||||||
|
led_off(LED_AMBER);
|
||||||
|
|
||||||
|
if (board_hardfault_init(2, true) != 0) {
|
||||||
|
led_on(LED_AMBER);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef CONFIG_MMCSD
|
||||||
|
int ret = stm32_sdio_initialize();
|
||||||
|
|
||||||
|
if (ret != OK) {
|
||||||
|
led_on(LED_RED);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* CONFIG_MMCSD */
|
||||||
|
|
||||||
|
return OK;
|
||||||
|
}
|
||||||
@@ -0,0 +1,98 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 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 led.c
|
||||||
|
*
|
||||||
|
* LED backend.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <px4_platform_common/px4_config.h>
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#include "chip.h"
|
||||||
|
#include "stm32_gpio.h"
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#include <nuttx/board.h>
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Ideally we'd be able to get these from up_internal.h,
|
||||||
|
* but since we want to be able to disable the NuttX use
|
||||||
|
* of leds for system indication at will and there is no
|
||||||
|
* separate switch, we need to build independent of the
|
||||||
|
* CONFIG_ARCH_LEDS configuration switch.
|
||||||
|
*/
|
||||||
|
__BEGIN_DECLS
|
||||||
|
extern void led_init(void);
|
||||||
|
extern void led_on(int led);
|
||||||
|
extern void led_off(int led);
|
||||||
|
extern void led_toggle(int led);
|
||||||
|
__END_DECLS
|
||||||
|
|
||||||
|
__EXPORT void led_init()
|
||||||
|
{
|
||||||
|
/* Configure LED1 GPIO for output */
|
||||||
|
|
||||||
|
px4_arch_configgpio(GPIO_LED1);
|
||||||
|
}
|
||||||
|
|
||||||
|
__EXPORT void led_on(int led)
|
||||||
|
{
|
||||||
|
if (led == 1) {
|
||||||
|
/* Pull down to switch on */
|
||||||
|
px4_arch_gpiowrite(GPIO_LED1, false);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
__EXPORT void led_off(int led)
|
||||||
|
{
|
||||||
|
if (led == 1) {
|
||||||
|
/* Pull up to switch off */
|
||||||
|
px4_arch_gpiowrite(GPIO_LED1, true);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
__EXPORT void led_toggle(int led)
|
||||||
|
{
|
||||||
|
if (led == 1) {
|
||||||
|
if (px4_arch_gpioread(GPIO_LED1)) {
|
||||||
|
px4_arch_gpiowrite(GPIO_LED1, false);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
px4_arch_gpiowrite(GPIO_LED1, true);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,171 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* 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 <nuttx/config.h>
|
||||||
|
#include <board_config.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 = !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) {
|
||||||
|
syslog(LOG_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) {
|
||||||
|
syslog(LOG_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,197 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2019 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 spi.cpp
|
||||||
|
*
|
||||||
|
* Board-specific SPI functions.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Included Files
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
#include <board_config.h>
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <debug.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#include <nuttx/spi/spi.h>
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
#include <systemlib/px4_macros.h>
|
||||||
|
|
||||||
|
#include <up_arch.h>
|
||||||
|
#include <chip.h>
|
||||||
|
#include <stm32_gpio.h>
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_spiinitialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT void stm32_spiinitialize(void)
|
||||||
|
{
|
||||||
|
#ifdef CONFIG_STM32F7_SPI1
|
||||||
|
px4_arch_configgpio(GPIO_SPI_CS_ICM_2060X);
|
||||||
|
px4_arch_configgpio(GPIO_SPI_CS_BARO);
|
||||||
|
px4_arch_configgpio(GPIO_SPI_CS_MPU);
|
||||||
|
|
||||||
|
px4_arch_configgpio(GPIO_EXTI_MPU_DRDY);
|
||||||
|
px4_arch_configgpio(GPIO_EXTI_ICM_2060X_DRDY);
|
||||||
|
#endif /* CONFIG_STM32F7_SPI1 */
|
||||||
|
|
||||||
|
#ifdef CONFIG_STM32F7_SPI2
|
||||||
|
px4_arch_configgpio(GPIO_SPI_CS_FRAM);
|
||||||
|
#endif /* CONFIG_STM32F7_SPI2 */
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
__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 */
|
||||||
|
|
||||||
|
switch (devid) {
|
||||||
|
|
||||||
|
/* intended fallthrough */
|
||||||
|
case PX4_SPIDEV_ICM_20602:
|
||||||
|
|
||||||
|
/* intended fallthrough */
|
||||||
|
case PX4_SPIDEV_ICM_20608:
|
||||||
|
/* Making sure the other peripherals are not selected */
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_ICM_2060X, !selected);
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case PX4_SPIDEV_BARO:
|
||||||
|
/* Making sure the other peripherals are not selected */
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_ICM_2060X, 1);
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_BARO, !selected);
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case PX4_SPIDEV_MPU:
|
||||||
|
/* Making sure the other peripherals are not selected */
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_ICM_2060X, 1);
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_MPU, !selected);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||||
|
{
|
||||||
|
return SPI_STATUS_PRESENT;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef CONFIG_STM32F7_SPI2
|
||||||
|
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||||
|
{
|
||||||
|
/* there can only be one device on this bus, so always select it */
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_FRAM, !selected);
|
||||||
|
}
|
||||||
|
|
||||||
|
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||||
|
{
|
||||||
|
/* FRAM is always present */
|
||||||
|
return SPI_STATUS_PRESENT;
|
||||||
|
}
|
||||||
|
#endif /* CONFIG_STM32F7_SPI2 */
|
||||||
|
|
||||||
|
|
||||||
|
__EXPORT void board_spi_reset(int ms)
|
||||||
|
{
|
||||||
|
/* disable SPI bus */
|
||||||
|
px4_arch_configgpio(GPIO_SPI_CS_ICM_2060X_OFF);
|
||||||
|
px4_arch_configgpio(GPIO_SPI_CS_BARO_OFF);
|
||||||
|
px4_arch_configgpio(GPIO_SPI_CS_MPU_OFF);
|
||||||
|
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_ICM_2060X_OFF, 0);
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_BARO_OFF, 0);
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI_CS_MPU_OFF, 0);
|
||||||
|
|
||||||
|
px4_arch_configgpio(GPIO_SPI1_SCK_OFF);
|
||||||
|
px4_arch_configgpio(GPIO_SPI1_MISO_OFF);
|
||||||
|
px4_arch_configgpio(GPIO_SPI1_MOSI_OFF);
|
||||||
|
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI1_SCK_OFF, 0);
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI1_MISO_OFF, 0);
|
||||||
|
px4_arch_gpiowrite(GPIO_SPI1_MOSI_OFF, 0);
|
||||||
|
|
||||||
|
px4_arch_configgpio(GPIO_EXTI_ICM_2060X_DRDY_OFF);
|
||||||
|
px4_arch_configgpio(GPIO_EXTI_MPU_DRDY_OFF);
|
||||||
|
|
||||||
|
px4_arch_gpiowrite(GPIO_EXTI_ICM_2060X_DRDY_OFF, 0);
|
||||||
|
px4_arch_gpiowrite(GPIO_EXTI_MPU_DRDY_OFF, 0);
|
||||||
|
|
||||||
|
/* set the sensor rail off */
|
||||||
|
px4_arch_configgpio(GPIO_VDD_3V3_SENSORS_EN);
|
||||||
|
px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0);
|
||||||
|
|
||||||
|
/* wait for the sensor rail to reach GND */
|
||||||
|
usleep(ms * 1000);
|
||||||
|
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||||
|
|
||||||
|
/* re-enable power */
|
||||||
|
|
||||||
|
/* switch the sensor rail back on */
|
||||||
|
px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1);
|
||||||
|
|
||||||
|
/* wait a bit before starting SPI, different times didn't influence results */
|
||||||
|
usleep(100);
|
||||||
|
|
||||||
|
/* reconfigure the SPI pins */
|
||||||
|
#ifdef CONFIG_STM32F7_SPI1
|
||||||
|
px4_arch_configgpio(GPIO_SPI_CS_ICM_2060X);
|
||||||
|
px4_arch_configgpio(GPIO_SPI_CS_BARO);
|
||||||
|
px4_arch_configgpio(GPIO_SPI_CS_MPU);
|
||||||
|
|
||||||
|
px4_arch_configgpio(GPIO_SPI1_SCK);
|
||||||
|
px4_arch_configgpio(GPIO_SPI1_MISO);
|
||||||
|
px4_arch_configgpio(GPIO_SPI1_MOSI);
|
||||||
|
|
||||||
|
// // XXX bring up the EXTI pins again
|
||||||
|
// px4_arch_configgpio(GPIO_EXTI_MPU_DRDY);
|
||||||
|
// px4_arch_configgpio(GPIO_EXTI_ICM_2060X_DRDY);
|
||||||
|
|
||||||
|
#endif /* CONFIG_STM32F7_SPI1 */
|
||||||
|
}
|
||||||
@@ -0,0 +1,125 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2019 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 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 <px4_arch/io_timer.h>
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
__EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||||
|
{
|
||||||
|
.base = STM32_TIM1_BASE,
|
||||||
|
.clock_register = STM32_RCC_APB2ENR,
|
||||||
|
.clock_bit = RCC_APB2ENR_TIM1EN,
|
||||||
|
.clock_freq = STM32_APB2_TIM1_CLKIN,
|
||||||
|
.first_channel_index = 0,
|
||||||
|
.last_channel_index = 3,
|
||||||
|
.handler = io_timer_handler0,
|
||||||
|
.vectorno = STM32_IRQ_TIM1CC,
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.base = STM32_TIM4_BASE,
|
||||||
|
.clock_register = STM32_RCC_APB1ENR,
|
||||||
|
.clock_bit = RCC_APB1ENR_TIM4EN,
|
||||||
|
.clock_freq = STM32_APB1_TIM4_CLKIN,
|
||||||
|
.first_channel_index = 4,
|
||||||
|
.last_channel_index = 5,
|
||||||
|
.handler = io_timer_handler1,
|
||||||
|
.vectorno = STM32_IRQ_TIM4
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||||
|
{
|
||||||
|
.gpio_out = GPIO_TIM1_CH4OUT,
|
||||||
|
.gpio_in = GPIO_TIM1_CH4IN,
|
||||||
|
.timer_index = 0,
|
||||||
|
.timer_channel = 4,
|
||||||
|
.ccr_offset = STM32_GTIM_CCR4_OFFSET,
|
||||||
|
.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.gpio_out = GPIO_TIM1_CH3OUT,
|
||||||
|
.gpio_in = GPIO_TIM1_CH3IN,
|
||||||
|
.timer_index = 0,
|
||||||
|
.timer_channel = 3,
|
||||||
|
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
|
||||||
|
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.gpio_out = GPIO_TIM1_CH2OUT,
|
||||||
|
.gpio_in = GPIO_TIM1_CH2IN,
|
||||||
|
.timer_index = 0,
|
||||||
|
.timer_channel = 2,
|
||||||
|
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
|
||||||
|
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.gpio_out = GPIO_TIM1_CH1OUT,
|
||||||
|
.gpio_in = GPIO_TIM1_CH1IN,
|
||||||
|
.timer_index = 0,
|
||||||
|
.timer_channel = 1,
|
||||||
|
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||||
|
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.gpio_out = GPIO_TIM4_CH2OUT,
|
||||||
|
.gpio_in = GPIO_TIM4_CH2IN,
|
||||||
|
.timer_index = 1,
|
||||||
|
.timer_channel = 2,
|
||||||
|
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
|
||||||
|
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.gpio_out = GPIO_TIM4_CH3OUT,
|
||||||
|
.gpio_in = GPIO_TIM4_CH3IN,
|
||||||
|
.timer_index = 1,
|
||||||
|
.timer_channel = 3,
|
||||||
|
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
|
||||||
|
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
|
||||||
|
}
|
||||||
|
};
|
||||||
@@ -0,0 +1,105 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2019 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 usb.c
|
||||||
|
*
|
||||||
|
* Board-specific USB functions.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Included Files
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
#include <px4_platform_common/px4_config.h>
|
||||||
|
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <debug.h>
|
||||||
|
|
||||||
|
#include <nuttx/usb/usbdev.h>
|
||||||
|
#include <nuttx/usb/usbdev_trace.h>
|
||||||
|
|
||||||
|
#include <up_arch.h>
|
||||||
|
#include <chip.h>
|
||||||
|
#include <stm32_gpio.h>
|
||||||
|
#include <stm32_otg.h>
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Definitions
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Private Functions
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_usbinitialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called to setup USB-related GPIO pins for the board.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT void stm32_usbinitialize(void)
|
||||||
|
{
|
||||||
|
/* The OTG FS has an internal soft pull-up */
|
||||||
|
|
||||||
|
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
|
||||||
|
|
||||||
|
#ifdef CONFIG_STM32F7_OTGFS
|
||||||
|
stm32_configgpio(GPIO_OTGFS_VBUS);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: stm32_usbsuspend
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
|
||||||
|
* used. This function is called whenever the USB enters or leaves suspend mode.
|
||||||
|
* This is an opportunity for the board logic to shutdown clocks, power, etc.
|
||||||
|
* while the USB is suspended.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||||
|
{
|
||||||
|
uinfo("resume: %d\n", resume);
|
||||||
|
}
|
||||||
@@ -220,15 +220,19 @@ if(NOT PX4_BOARD MATCHES "px4_io-v2")
|
|||||||
elseif(CONFIG_ARCH_CHIP_STM32H743ZI)
|
elseif(CONFIG_ARCH_CHIP_STM32H743ZI)
|
||||||
set(DEBUG_DEVICE "STM32H743ZI")
|
set(DEBUG_DEVICE "STM32H743ZI")
|
||||||
set(DEBUG_SVD_FILE "STM32H7x3.svd")
|
set(DEBUG_SVD_FILE "STM32H7x3.svd")
|
||||||
|
else()
|
||||||
|
set(DEBUG_DEVICE "")
|
||||||
|
set(DEBUG_SVD_FILE "unknown")
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
file(GLOB_RECURSE DEBUG_SVD_FILE_PATH ${CMAKE_SOURCE_DIR}/../cmsis-svd/*/${DEBUG_SVD_FILE})
|
file(GLOB_RECURSE DEBUG_SVD_FILE_PATH
|
||||||
if(DEBUG_SVD_FILE-NOTFOUND)
|
LIST_DIRECTORIES false
|
||||||
set(DEBUG_SVD_FILE "")
|
${CMAKE_SOURCE_DIR}/../cmsis-svd/data/*/${DEBUG_SVD_FILE}
|
||||||
else()
|
)
|
||||||
|
if(DEBUG_SVD_FILE)
|
||||||
message(STATUS "Found SVD: ${DEBUG_SVD_FILE_PATH}")
|
message(STATUS "Found SVD: ${DEBUG_SVD_FILE_PATH}")
|
||||||
endif()
|
|
||||||
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/Debug/launch.json.in ${PX4_SOURCE_DIR}/.vscode/launch.json @ONLY)
|
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/Debug/launch.json.in ${PX4_SOURCE_DIR}/.vscode/launch.json @ONLY)
|
||||||
|
endif()
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
add_custom_target(debug
|
add_custom_target(debug
|
||||||
|
|||||||
Reference in New Issue
Block a user