mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-10 06:39:25 +08:00
boards: add Radiolink PIX6 (#25562)
* boards: add Radiolink PIX6 * Fix newlines and format issues * Fix newlines issues * docs:add radiolink_pix6.md document * Subedit, prettier, get images * Add hero image * docs:Add some necessary instructions * Subedit --------- Co-authored-by: Ubuntu <diaohuayuan@radiolink.com.cn> Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
This commit is contained in:
@@ -0,0 +1,107 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_GOERTEK_SPA06=y
|
||||
CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6500=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y
|
||||
CONFIG_DRIVERS_IRLOCK=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_COMMON_OSD=y
|
||||
CONFIG_DRIVERS_OSD_MSP_OSD=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
|
||||
CONFIG_DRIVERS_PWM_INPUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_PX4IO=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=6
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_ESC_BATTERY=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_LAND_DETECTOR=y
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
|
||||
CONFIG_MODULES_LOAD_MON=y
|
||||
CONFIG_MODULES_LOGGER=y
|
||||
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MAVLINK=y
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
|
||||
CONFIG_MODULES_PAYLOAD_DELIVERER=y
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||
CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BL_UPDATE=y
|
||||
CONFIG_SYSTEMCMDS_BSONDUMP=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||
CONFIG_SYSTEMCMDS_GPIO=y
|
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_REFLECT=y
|
||||
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
|
||||
CONFIG_SYSTEMCMDS_VER=y
|
||||
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||
BIN
Binary file not shown.
@@ -0,0 +1,13 @@
|
||||
{
|
||||
"board_id": 1410,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the RadiolinkPIX6 board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "RadiolinkPIX6",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 2064384,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
@@ -0,0 +1,14 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
param set-default BAT1_V_DIV 18.1
|
||||
param set-default BAT2_V_DIV 18.1
|
||||
|
||||
param set-default BAT1_A_PER_V 36.367515152
|
||||
param set-default BAT2_A_PER_V 36.367515152
|
||||
|
||||
param set-default EKF2_MULTI_IMU 2
|
||||
param set-default SENS_IMU_MODE 0
|
||||
#safety_button start
|
||||
@@ -0,0 +1,9 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board extras init
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
if ! param compare OSD_ATXXXX_CFG 0
|
||||
then
|
||||
atxxxx start -s
|
||||
fi
|
||||
@@ -0,0 +1,53 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
set HAVE_PM2 yes
|
||||
|
||||
board_adc start
|
||||
|
||||
if param compare SENS_EN_INA226 1
|
||||
then
|
||||
if [ $HAVE_PM2 = yes ]
|
||||
then
|
||||
ina226 -X -b 2 -t 2 -k start
|
||||
fi
|
||||
|
||||
fi
|
||||
|
||||
if param compare SENS_EN_INA228 1
|
||||
then
|
||||
if [ $HAVE_PM2 = yes ]
|
||||
then
|
||||
ina228 -X -b 2 -t 2 -k start
|
||||
fi
|
||||
|
||||
fi
|
||||
|
||||
if param compare SENS_EN_INA238 1
|
||||
then
|
||||
if [ $HAVE_PM2 = yes ]
|
||||
then
|
||||
ina238 -X -b 2 -t 2 -k start
|
||||
fi
|
||||
|
||||
fi
|
||||
|
||||
# Internal SPI bus ICM42688p
|
||||
icm42688p -R 2 -s start
|
||||
|
||||
# Internal SPI BMI088
|
||||
bmi088 -A -R 4 -s start
|
||||
bmi088 -G -R 4 -s start
|
||||
|
||||
spa06 -I start
|
||||
|
||||
# internal compass
|
||||
ist8310 -I start
|
||||
|
||||
# External compass on GPS1/I2C1
|
||||
ist8310 -X start
|
||||
|
||||
# Possible internal Baro
|
||||
unset HAVE_PM2
|
||||
@@ -0,0 +1,17 @@
|
||||
#
|
||||
# For a description of the syntax of this configuration file,
|
||||
# see misc/tools/kconfig-language.txt.
|
||||
#
|
||||
config BOARD_HAS_PROBES
|
||||
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
|
||||
default y
|
||||
---help---
|
||||
This board provides GPIO FMU-CH1-8, CAP1 as PROBE_1-9 to provide timing signals from selected drivers.
|
||||
|
||||
config BOARD_USE_PROBES
|
||||
bool "Enable the use the board provided FMU-CH1-8, CAP1 as PROBE_1-9"
|
||||
default n
|
||||
depends on BOARD_HAS_PROBES
|
||||
|
||||
---help---
|
||||
Select to use GPIO FMU-CH1-8, CAP1 to provide timing signals from selected drivers.
|
||||
@@ -0,0 +1,455 @@
|
||||
/************************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016-2019 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.
|
||||
*
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
#include "board_dma_map.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_sdmmc.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The radiolink_pix6 board provides the following clock sources:
|
||||
*
|
||||
* 24 MHz crystal for HSE
|
||||
*
|
||||
* So we have these clock source available within the STM32
|
||||
*
|
||||
* HSI: 16 MHz RC factory-trimmed
|
||||
* HSE: 24 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 32768
|
||||
|
||||
/* 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 = (24,000,000 / 24) * 432 = 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 / 24) * 432)
|
||||
#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
|
||||
|
||||
/* 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
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* The radiolink_pix6 board has numerous LEDs but only three, LED_GREEN a Green LED, LED_BLUE
|
||||
* a Blue LED and LED_RED a Red LED, that can be controlled by software.
|
||||
*
|
||||
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.
|
||||
* The following definitions are used to access individual LEDs.
|
||||
*/
|
||||
|
||||
/* LED index values for use with board_userled() */
|
||||
|
||||
#define BOARD_LED1 0
|
||||
#define BOARD_LED2 1
|
||||
#define BOARD_LED3 2
|
||||
#define BOARD_NLEDS 3
|
||||
|
||||
#define BOARD_LED_RED BOARD_LED1
|
||||
#define BOARD_LED_GREEN BOARD_LED2
|
||||
#define BOARD_LED_BLUE BOARD_LED3
|
||||
|
||||
/* LED bits for use with board_userled_all() */
|
||||
|
||||
#define BOARD_LED1_BIT (1 << BOARD_LED1)
|
||||
#define BOARD_LED2_BIT (1 << BOARD_LED2)
|
||||
#define BOARD_LED3_BIT (1 << BOARD_LED3)
|
||||
|
||||
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
|
||||
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
|
||||
* events as follows:
|
||||
*
|
||||
*
|
||||
* SYMBOL Meaning LED state
|
||||
* Red Green Blue
|
||||
* ---------------------- -------------------------- ------ ------ ----*/
|
||||
|
||||
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
|
||||
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
|
||||
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
|
||||
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
|
||||
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
|
||||
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
|
||||
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
|
||||
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
|
||||
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */
|
||||
|
||||
/* Thus if the Green LED is statically on, NuttX has successfully booted and
|
||||
* is, apparently, running normally. If the Red LED is flashing at
|
||||
* approximately 2Hz, then a fatal error has been detected and the system
|
||||
* has halted.
|
||||
*/
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PB7 */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PB6 */
|
||||
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_2 /* PD3 */
|
||||
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
|
||||
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
|
||||
#define GPIO_USART3_CTS GPIO_USART3_CTS_2 /* PD11 */
|
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */
|
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_1 /* PE7 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */
|
||||
|
||||
/* UART8: has no remap
|
||||
*
|
||||
* GPIO_UART8_RX PE0
|
||||
* GPIO_UART8_TX PE1
|
||||
*/
|
||||
|
||||
|
||||
/* CAN
|
||||
*
|
||||
* CAN1 is routed to transceiver.
|
||||
* CAN2 is routed to transceiver.
|
||||
*/
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_2 /* PB13 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB5 */
|
||||
|
||||
/* SPI
|
||||
* SPI1 is sensors
|
||||
* SPI2 is OSD & RAMTRON
|
||||
* SPI4 is EXTERNAL1
|
||||
*
|
||||
*/
|
||||
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
|
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_2 /* PB3 */
|
||||
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */
|
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_1 /* PA9 */
|
||||
|
||||
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE13 */
|
||||
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE6 */
|
||||
#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 /* PE2 */
|
||||
|
||||
/* 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 /* PB8 */
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
|
||||
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */
|
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */
|
||||
|
||||
|
||||
/* SDMMC1
|
||||
*
|
||||
* VDD 3.3
|
||||
* GND
|
||||
* SDMMC1_CK PC12
|
||||
* SDMMC1_CMD PD2
|
||||
* SDMMC1_D0 PC8
|
||||
* SDMMC1_D1 PC9
|
||||
* SDMMC1_D2 PC10
|
||||
* SDMMC1_D3 PC11
|
||||
*/
|
||||
|
||||
// #define GPIO_SDMMC1_D0 GPIO_SDMMC1_D0
|
||||
// #define GPIO_SDMMC1_D1 GPIO_SDMMC1_D1
|
||||
// #define GPIO_SDMMC1_D2 GPIO_SDMMC1_D2
|
||||
// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3
|
||||
|
||||
/* The STM32 F7 connects to a TI DP83848TSQ/NOPB
|
||||
* using RMII
|
||||
*
|
||||
* STM32 F7 BOARD DP83848TSQ/NOPB
|
||||
* GPIO SIGNAL PIN NAME
|
||||
* -------- ------------ -------------
|
||||
* PA7 ETH_CRS_DV CRS_DV
|
||||
* PC1 ETH_MDC MDC
|
||||
* PA2 ETH_MDIO MDIO
|
||||
* PA1 ETH_REF_CL X1
|
||||
* PC4 ETH_RXD0 RX_D0
|
||||
* PC5 ETH_RXD1 RX_D1
|
||||
* PB11 ETH_TX_EN TX_EN
|
||||
* PG13 ETH_TXD0 TX_D0
|
||||
* PB13 ETH_TXD1 TX_D1
|
||||
*
|
||||
* The PHY address is 1, since COL/PHYAD0 features a pull up.
|
||||
*/
|
||||
|
||||
// #define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1
|
||||
// #define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2
|
||||
// #define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_1
|
||||
|
||||
|
||||
/* USB
|
||||
*
|
||||
* OTG_FS_DM PA11
|
||||
* OTG_FS_DP PA12
|
||||
* VBUS PA9
|
||||
*/
|
||||
|
||||
|
||||
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
|
||||
|
||||
#if defined(CONFIG_BOARD_USE_PROBES)
|
||||
# include "stm32_gpio.h"
|
||||
# define PROBE_N(n) (1<<((n)-1))
|
||||
# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14) /* PE14 AUX1 */
|
||||
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN10) /* PA10 AUX2 */
|
||||
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 AUX3 */
|
||||
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) /* PE9 AUX4 */
|
||||
# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) /* PA15 AUX5 */
|
||||
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN7) /* PA7 AUX6 */
|
||||
# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN6) /* PC6 AUX7 */
|
||||
# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3) /* PA3 AUX8 */
|
||||
# //define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 CAP1 */
|
||||
|
||||
# define PROBE_INIT(mask) \
|
||||
do { \
|
||||
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
|
||||
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
|
||||
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
|
||||
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
|
||||
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
|
||||
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
|
||||
if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \
|
||||
if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \
|
||||
/*if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \*/
|
||||
|
||||
} while (0)
|
||||
|
||||
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
|
||||
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
|
||||
#else
|
||||
# define PROBE_INIT(mask)
|
||||
# define PROBE(n,s)
|
||||
# define PROBE_MARK(n)
|
||||
#endif
|
||||
@@ -0,0 +1,39 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define DMAMAP_USART3_TX DMAMAP_USART3_TX_1 // DMA1, Stream 3, Channel 4 (TELEM2 RX)
|
||||
#define DMAMAP_SDMMC1 DMAMAP_SDMMC1_2 // DMA2, Stream 6, Channel 11
|
||||
#define DMAMAP_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3 (SPI sensors RX)
|
||||
#define DMAMAP_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 (SPI sensors TX)
|
||||
@@ -0,0 +1,259 @@
|
||||
#
|
||||
# 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_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_DISABLE_PTHREAD 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_CAT is not set
|
||||
# CONFIG_NSH_DISABLE_CD is not set
|
||||
# CONFIG_NSH_DISABLE_CP is not set
|
||||
# CONFIG_NSH_DISABLE_DATE is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_ECHO is not set
|
||||
# CONFIG_NSH_DISABLE_ENV is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXPORT is not set
|
||||
# CONFIG_NSH_DISABLE_FREE is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_HELP is not set
|
||||
# CONFIG_NSH_DISABLE_IFCONFIG is not set
|
||||
# CONFIG_NSH_DISABLE_IFUPDOWN is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_KILL is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_LS is not set
|
||||
# CONFIG_NSH_DISABLE_MKDIR is not set
|
||||
# CONFIG_NSH_DISABLE_MKFATFS is not set
|
||||
# CONFIG_NSH_DISABLE_MOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_MV is not set
|
||||
# CONFIG_NSH_DISABLE_PS is not set
|
||||
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
|
||||
# CONFIG_NSH_DISABLE_PWD is not set
|
||||
# CONFIG_NSH_DISABLE_RM is not set
|
||||
# CONFIG_NSH_DISABLE_RMDIR is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_SET is not set
|
||||
# CONFIG_NSH_DISABLE_SLEEP is not set
|
||||
# CONFIG_NSH_DISABLE_SOURCE is not set
|
||||
# CONFIG_NSH_DISABLE_TELNETD is not set
|
||||
# CONFIG_NSH_DISABLE_TEST is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
# CONFIG_NSH_DISABLE_UMOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_UNSET is not set
|
||||
# CONFIG_NSH_DISABLE_USLEEP is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/radiolink/PIX6/nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="radiolink"
|
||||
CONFIG_ARCH_CHIP="stm32f7"
|
||||
CONFIG_ARCH_CHIP_STM32F765II=y
|
||||
CONFIG_ARCH_CHIP_STM32F7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=768
|
||||
CONFIG_ARCH_STACKDUMP=y
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
CONFIG_ARMV7M_DCACHE=y
|
||||
CONFIG_ARMV7M_DTCM=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_ITCM=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU_EARLY_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
CONFIG_BOARD_CRASHDUMP=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=22114
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x0032
|
||||
CONFIG_CDCACM_PRODUCTSTR="radiolink PIX6"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x26ac
|
||||
CONFIG_CDCACM_VENDORSTR="radiolink"
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_DEV_FIFO_SIZE=0
|
||||
CONFIG_DEV_GPIO=y
|
||||
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_EXAMPLES_CALIB_UDELAY=y
|
||||
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_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
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_INIT_ENTRYPOINT="nsh_main"
|
||||
CONFIG_INIT_STACKSIZE=3194
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=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_PROGMEM=y
|
||||
CONFIG_MTD_RAMTRON=y
|
||||
CONFIG_NAME_MAX=40
|
||||
CONFIG_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
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_OTG_ID_GPIO_DISABLE=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5
|
||||
CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_SDMMC1_SDIO_MODE=y
|
||||
CONFIG_SDMMC1_SDIO_PULLUP=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=32
|
||||
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=256
|
||||
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_I2C2=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_AUTO_LSECLOCK_START_DRV_CAPABILITY=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_SPI1_DMA=y
|
||||
CONFIG_STM32F7_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32F7_SPI2=y
|
||||
#CONFIG_STM32F7_SPI2_DMA=y
|
||||
#CONFIG_STM32F7_SPI2_DMA_BUFFER=1024
|
||||
CONFIG_STM32F7_SPI4=y
|
||||
CONFIG_STM32F7_SPI_DMATHRESHOLD=8
|
||||
CONFIG_STM32F7_TIM5=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_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_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_TXBUFSIZE=1500
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=180
|
||||
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_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=3000
|
||||
CONFIG_USART3_IFLOWCONTROL=y
|
||||
CONFIG_USART3_OFLOWCONTROL=y
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_RXDMA=y
|
||||
CONFIG_USART3_TXBUFSIZE=3000
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
@@ -0,0 +1,146 @@
|
||||
/****************************************************************************
|
||||
* kernel-space.ld
|
||||
*
|
||||
* Copyright (C) 2015 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* NOTE: This depends on the memory.ld script having been included prior to
|
||||
* this script.
|
||||
*/
|
||||
|
||||
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)
|
||||
/*
|
||||
* TODO: Fill in the signature location into TOC from user-space elf
|
||||
EXTERN(_main_toc)
|
||||
*/
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
. = ALIGN(32);
|
||||
/*
|
||||
This signature provides the bootloader with a way to delay booting
|
||||
*/
|
||||
_bootdelay_signature = ABSOLUTE(.);
|
||||
FILL(0xffecc2925d7d05c5)
|
||||
. += 8;
|
||||
/*
|
||||
*(.main_toc)
|
||||
*/
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
} > kflash
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > kflash
|
||||
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > kflash
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > kflash
|
||||
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
} > ksram AT > kflash
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > ksram
|
||||
|
||||
/* 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) }
|
||||
|
||||
.ramfunc : {
|
||||
_sramfuncs = .;
|
||||
*(.ramfunc .ramfunc.*)
|
||||
. = ALIGN(4);
|
||||
_eramfuncs = .;
|
||||
} > ksram AT > kflash
|
||||
|
||||
_framfuncs = LOADADDR(.ramfunc);
|
||||
}
|
||||
@@ -0,0 +1,98 @@
|
||||
/****************************************************************************
|
||||
* scripts/memory.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 boot address */
|
||||
|
||||
itcm (rwx) : ORIGIN = 0x00208000, LENGTH = 2048K-32K
|
||||
|
||||
/* 2048KB FLASH, bootloader reserves the first 32kb */
|
||||
|
||||
kflash (rx) : ORIGIN = 0x08008000, LENGTH = 1024K-32K
|
||||
uflash (rx) : ORIGIN = 0x08100000, LENGTH = 1024K
|
||||
|
||||
/* ITCM RAM */
|
||||
|
||||
itcm_ram (rwx) : ORIGIN = 0x00000000, LENGTH = 16K
|
||||
|
||||
/* DTCM SRAM */
|
||||
|
||||
dtcm_ram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
|
||||
/* 368KB of contiguous SRAM1 */
|
||||
|
||||
ksram (rwx) : ORIGIN = 0x20020000, LENGTH = 128K
|
||||
usram (rwx) : ORIGIN = 0x20040000, LENGTH = 368K-128K
|
||||
|
||||
/* 16KB of SRAM2 */
|
||||
|
||||
sram2 (rwx) : ORIGIN = 0x2007c000, LENGTH = 16K
|
||||
}
|
||||
@@ -0,0 +1,181 @@
|
||||
/****************************************************************************
|
||||
* 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
|
||||
{
|
||||
FLASH_ITCM (rx) : ORIGIN = 0x00208000, LENGTH = 2016K
|
||||
FLASH_AXIM (rx) : ORIGIN = 0x08008000, LENGTH = 2016K
|
||||
|
||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K
|
||||
DTCM_RAM (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(.);
|
||||
|
||||
} > FLASH_AXIM
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > FLASH_AXIM
|
||||
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > FLASH_AXIM
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > FLASH_AXIM
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
} > SRAM1 AT > FLASH_AXIM
|
||||
|
||||
.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) }
|
||||
|
||||
.ramfunc : {
|
||||
_sramfuncs = .;
|
||||
*(.ramfunc .ramfunc.*)
|
||||
. = ALIGN(4);
|
||||
_eramfuncs = .;
|
||||
} > ITCM_RAM AT > FLASH_AXIM
|
||||
|
||||
_framfuncs = LOADADDR(.ramfunc);
|
||||
}
|
||||
@@ -0,0 +1,124 @@
|
||||
/****************************************************************************
|
||||
* user-space.ld
|
||||
*
|
||||
* Copyright (C) 2015 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* NOTE: This depends on the memory.ld script having been included prior to
|
||||
* this script.
|
||||
*/
|
||||
EXTERN(userspace)
|
||||
OUTPUT_ARCH(arm)
|
||||
SECTIONS
|
||||
{
|
||||
.userspace : {
|
||||
*(.userspace)
|
||||
} > uflash
|
||||
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
} > uflash
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > uflash
|
||||
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > uflash
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > uflash
|
||||
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
} > usram AT > uflash
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
/* Kernel heap start at _ebss, make _ebss MPU-friendly aligned */
|
||||
. = ALIGN(0x1000);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > usram
|
||||
|
||||
/* 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) }
|
||||
|
||||
/* Start of the image signature. This
|
||||
* has to be in the end of the image
|
||||
*/
|
||||
.signature : {
|
||||
_boot_signature = ALIGN(4);
|
||||
} > uflash
|
||||
}
|
||||
@@ -0,0 +1,55 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_library(drivers_board
|
||||
can.c
|
||||
i2c.cpp
|
||||
init.cpp
|
||||
led.c
|
||||
mtd.cpp
|
||||
sdio.c
|
||||
spi.cpp
|
||||
timer_config.cpp
|
||||
usb.c
|
||||
)
|
||||
add_dependencies(drivers_board arch_board_hw_info)
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
arch_io_pins
|
||||
arch_spi
|
||||
arch_board_hw_info
|
||||
drivers__led # drv_led_start
|
||||
nuttx_arch # sdio
|
||||
nuttx_drivers # sdio
|
||||
px4_layer
|
||||
)
|
||||
@@ -0,0 +1,293 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016-2022 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
|
||||
*
|
||||
* board internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <px4_platform/board_ctrl.h>
|
||||
#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/ttyS5"
|
||||
#define PX4IO_SERIAL_TX_GPIO GPIO_UART8_TX
|
||||
#define PX4IO_SERIAL_RX_GPIO GPIO_UART8_RX
|
||||
#define PX4IO_SERIAL_BASE STM32_UART8_BASE
|
||||
#define PX4IO_SERIAL_VECTOR STM32_IRQ_UART8
|
||||
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_UART8_TX
|
||||
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_UART8_RX
|
||||
#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB1ENR
|
||||
#define PX4IO_SERIAL_RCC_EN RCC_APB1ENR_UART8EN
|
||||
#define PX4IO_SERIAL_CLOCK STM32_PCLK1_FREQUENCY
|
||||
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
|
||||
|
||||
/* Configuration ************************************************************************************/
|
||||
|
||||
#define BOARD_HAS_STATIC_MANIFEST 1
|
||||
|
||||
#define BOARD_HAS_LTC44XX_VALIDS 0 // No LTC or N Bricks
|
||||
#define BOARD_HAS_USB_VALID 0 // LTC Has No USB valid
|
||||
#define BOARD_HAS_NBAT_V 1 // Only one Vbat to ADC
|
||||
#define BOARD_HAS_NBAT_I 0 // No Ibat ADC
|
||||
|
||||
/* LEDs */
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN14)
|
||||
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
|
||||
|
||||
#define GPIO_LED_RED GPIO_LED1
|
||||
#define GPIO_LED_GREEN GPIO_LED2
|
||||
#define GPIO_LED_BLUE GPIO_LED3
|
||||
|
||||
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
|
||||
#define BOARD_OVERLOAD_LED LED_RED
|
||||
#define BOARD_ARMED_LED LED_BLUE
|
||||
#define BOARD_ARMED_STATE_LED LED_GREEN
|
||||
|
||||
/* Safety Switch is HW version dependent on having an PX4IO
|
||||
* So we init to a benign state with the _INIT definition
|
||||
* and provide the the non _INIT one for the driver to make a run time
|
||||
* decision to use it.
|
||||
*/
|
||||
#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PB0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN0)
|
||||
/*
|
||||
* ADC channels
|
||||
*
|
||||
* These are the channel numbers of the ADCs of the microcontroller that
|
||||
* can be used by the Px4 Firmware in the adc driver
|
||||
*/
|
||||
|
||||
/* ADC defines to be used in sensors.cpp to read from a particular channel */
|
||||
|
||||
#define ADC1_CH(n) (n)
|
||||
#define ADC1_GPIO(n) GPIO_ADC1_IN##n
|
||||
|
||||
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
|
||||
|
||||
#define PX4_ADC_GPIO \
|
||||
/* PA2 */ ADC1_GPIO(2), \
|
||||
/* PA4 */ ADC1_GPIO(4), \
|
||||
/* PA5 */ ADC1_GPIO(5), \
|
||||
/* PC0 */ ADC1_GPIO(10), \
|
||||
/* PC2 */ ADC1_GPIO(12), \
|
||||
/* PC3 */ ADC1_GPIO(13)
|
||||
|
||||
/* Define Channel numbers must match above GPIO pin IN(n)*/
|
||||
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL /* PA2 */ ADC1_CH(2)
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL /* PA5 */ ADC1_CH(5)
|
||||
#define ADC_SCALED_V5_CHANNEL /* PC0 */ ADC1_CH(10)
|
||||
#define ADC_ADC1_6V6_CHANNEL /* PC2 */ ADC1_CH(12)
|
||||
#define ADC_ADC1_3V3_CHANNEL1 /* PC3 */ ADC1_CH(13)
|
||||
#define ADC_ADC1_3V3_CHANNEL2 /* PA4 */ ADC1_CH(4)
|
||||
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_ADC1_3V3_CHANNEL2) | \
|
||||
(1 << ADC_ADC1_6V6_CHANNEL) | \
|
||||
(1 << ADC_ADC1_3V3_CHANNEL1))
|
||||
|
||||
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
|
||||
|
||||
#define SYSTEM_ADC_BASE STM32_ADC1_BASE
|
||||
|
||||
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
|
||||
|
||||
//#define UAVCAN_NUM_IFACES_RUNTIME 1
|
||||
|
||||
/* PWM
|
||||
*/
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
|
||||
|
||||
#define GPIO_VDD_5V_PERIPH_nEN /* PC4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15)
|
||||
#define GPIO_VDD_5V_HIPOWER_nEN /* PD13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_VDD_5V_HIPOWER_nOC /* PE10 */ (GPIO_INPUT |GPIO_PULLUP|GPIO_PORTE|GPIO_PIN10)
|
||||
#define GPIO_VDD_3V3_SENSORS_EN /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
|
||||
|
||||
/* Define True logic Power Control in arch agnostic form */
|
||||
|
||||
#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true))
|
||||
#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true))
|
||||
#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, (on_true))
|
||||
#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true))
|
||||
#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN)
|
||||
|
||||
|
||||
/* Tone alarm output */
|
||||
|
||||
#define TONE_ALARM_TIMER 9 /* Timer 14 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* PE5 GPIO_TIM14_CH1OUT_2 */
|
||||
|
||||
#define GPIO_BUZZER_1 /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN5)
|
||||
|
||||
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
|
||||
#define GPIO_TONE_ALARM GPIO_TIM9_CH1OUT_2
|
||||
|
||||
#define HRT_TIMER 5 /* use timer5 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */
|
||||
/* USB OTG FS
|
||||
*
|
||||
* PA9 OTG_FS_VBUS VBUS sensing
|
||||
*/
|
||||
#define GPIO_nVDD_USB_VALID /* PB2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PORTB|GPIO_PIN2)
|
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
|
||||
#define PWMIN_TIMER 2
|
||||
#define PWMIN_TIMER_CHANNEL /* T2C1 */ 1
|
||||
#define GPIO_PWM_IN /* PA15 */ GPIO_TIM2_CH1IN_2
|
||||
#define SDIO_SLOTNO 0 /* Only one slot */
|
||||
#define SDIO_MINOR 0
|
||||
|
||||
/* SD card bringup does not work if performed on the IDLE thread because it
|
||||
* will cause waiting. Use either:
|
||||
*
|
||||
* CONFIG_BOARDCTL=y, OR
|
||||
* CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \
|
||||
!defined(CONFIG_BOARD_INITTHREAD)
|
||||
# warning SDIO initialization cannot be perfomed on the IDLE thread
|
||||
#endif
|
||||
|
||||
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
|
||||
* this board support the ADC system_power interface, and therefore
|
||||
* provides the true logic GPIO BOARD_ADC_xxxx macros.
|
||||
*/
|
||||
#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_nVDD_USB_VALID))
|
||||
#define BOARD_ADC_USB_VALID BOARD_ADC_USB_CONNECTED
|
||||
|
||||
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC))
|
||||
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC))
|
||||
|
||||
|
||||
/* 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 PX4_GPIO_INIT_LIST { \
|
||||
PX4_ADC_GPIO, \
|
||||
GPIO_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
GPIO_CAN2_TX, \
|
||||
GPIO_CAN2_RX, \
|
||||
GPIO_VDD_5V_PERIPH_nEN, \
|
||||
GPIO_VDD_5V_PERIPH_nOC, \
|
||||
GPIO_VDD_5V_HIPOWER_nEN, \
|
||||
GPIO_VDD_5V_HIPOWER_nOC, \
|
||||
GPIO_VDD_3V3_SENSORS_EN, \
|
||||
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_nVDD_USB_VALID, \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C1_SCL), \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C1_SDA), \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C2_SCL), \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C2_SDA), \
|
||||
}
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
#define BOARD_NUM_IO_TIMERS 3
|
||||
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public data
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_sdio_initialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize SDIO-based MMC/SD card support
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int stm32_sdio_initialize(void);
|
||||
|
||||
/****************************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the board.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
|
||||
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,124 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file can.c
|
||||
*
|
||||
* Board-specific CAN functions.
|
||||
*/
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/can/can.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "arm_internal.h"
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32_can.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#ifdef CONFIG_CAN
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration ********************************************************************/
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
|
||||
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
|
||||
# undef CONFIG_STM32_CAN2
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_CAN1
|
||||
# define CAN_PORT 1
|
||||
#else
|
||||
# define CAN_PORT 2
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
int can_devinit(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: can_devinit
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following interface to work with
|
||||
* examples/can.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int can_devinit(void)
|
||||
{
|
||||
static bool initialized = false;
|
||||
struct can_dev_s *can;
|
||||
int ret;
|
||||
|
||||
/* Check if we have already initialized */
|
||||
|
||||
if (!initialized) {
|
||||
/* Call stm32_caninitialize() to get an instance of the CAN interface */
|
||||
|
||||
can = stm32_caninitialize(CAN_PORT);
|
||||
|
||||
if (can == NULL) {
|
||||
canerr("ERROR: Failed to get CAN interface\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Register the CAN driver at "/dev/can0" */
|
||||
|
||||
ret = can_register("/dev/can0", can);
|
||||
|
||||
if (ret < 0) {
|
||||
canerr("ERROR: can_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif
|
||||
@@ -0,0 +1,39 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/i2c_hw_description.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusInternal(1),
|
||||
initI2CBusExternal(2),
|
||||
};
|
||||
@@ -0,0 +1,277 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file init.c
|
||||
*
|
||||
* PX4FMU-specific early startup code. This file implements the
|
||||
* 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 <syslog.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 "arm_internal.h"
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_board_led.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
#include <px4_arch/io_timer.h>
|
||||
#include <px4_platform_common/init.h>
|
||||
#include <px4_platform_common/px4_manifest.h>
|
||||
#include <px4_platform/gpio.h>
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
#define _GPIO_PULL_DOWN_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz))
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from arm_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_peripheral_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_peripheral_reset(int ms)
|
||||
{
|
||||
/* set the peripheral rails off */
|
||||
|
||||
VDD_5V_PERIPH_EN(false);
|
||||
board_control_spi_sensors_power(false, 0xffff);
|
||||
VDD_3V3_SENSORS4_EN(false);
|
||||
|
||||
bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN();
|
||||
/* Keep Spektum on to discharge rail*/
|
||||
VDD_3V3_SPEKTRUM_POWER_EN(false);
|
||||
|
||||
/* 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 */
|
||||
VDD_3V3_SPEKTRUM_POWER_EN(last);
|
||||
board_control_spi_sensors_power(true, 0xffff);
|
||||
VDD_3V3_SENSORS4_EN(true);
|
||||
VDD_5V_PERIPH_EN(true);
|
||||
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* 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)
|
||||
{
|
||||
for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
|
||||
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i)));
|
||||
}
|
||||
|
||||
if (status >= 0) {
|
||||
up_mdelay(100);
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the initialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
extern "C" __EXPORT void
|
||||
stm32_boardinitialize(void)
|
||||
{
|
||||
board_on_reset(-1); /* Reset PWM first thing */
|
||||
|
||||
/* configure LEDs */
|
||||
|
||||
board_autoled_initialize();
|
||||
|
||||
/* configure pins */
|
||||
|
||||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
|
||||
px4_gpio_init(gpio, arraySize(gpio));
|
||||
|
||||
board_control_spi_sensors_power_configgpio();
|
||||
|
||||
/* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
static struct spi_dev_s *spi4;
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
/* Power on Interfaces */
|
||||
VDD_5V_PERIPH_EN(true);
|
||||
VDD_5V_HIPOWER_EN(true);
|
||||
board_control_spi_sensors_power(true, 0xffff);
|
||||
VDD_3V3_SENSORS4_EN(true);
|
||||
VDD_3V3_SPEKTRUM_POWER_EN(true);
|
||||
|
||||
/* Need hrt running before using the ADC */
|
||||
|
||||
px4_platform_init();
|
||||
|
||||
/* Configure the Actual SPI interfaces (after we determined the HW version) */
|
||||
|
||||
stm32_spiinitialize();
|
||||
|
||||
spi4 = px4_spibus_initialize(4);
|
||||
|
||||
if (!spi4) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 4\n");
|
||||
board_autoled_on(LED_AMBER);
|
||||
}
|
||||
|
||||
/* Default SPI4 to 10MHz and de-assert the known chip selects. */
|
||||
SPI_SETFREQUENCY(spi4, 10000000);
|
||||
SPI_SETBITS(spi4, 8);
|
||||
SPI_SETMODE(spi4, SPIDEV_MODE3);
|
||||
up_udelay(20);
|
||||
|
||||
//board_spi_reset(10, 0xffff);
|
||||
|
||||
/* Configure the DMA allocator */
|
||||
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
#if defined(SERIAL_HAVE_RXDMA)
|
||||
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
|
||||
static struct hrt_call serial_dma_call;
|
||||
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
|
||||
#endif
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_RED);
|
||||
led_on(LED_GREEN); // Indicate Power.
|
||||
led_off(LED_BLUE);
|
||||
|
||||
if (board_hardfault_init(2, true) != 0) {
|
||||
led_on(LED_RED);
|
||||
}
|
||||
|
||||
#ifdef CONFIG_MMCSD
|
||||
int ret = stm32_sdio_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_RED);
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
|
||||
px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
}
|
||||
@@ -0,0 +1,227 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file led.c
|
||||
*
|
||||
* PX4FMU 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 arm_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
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
static bool nuttx_owns_leds = true;
|
||||
// B R S G
|
||||
// 0 1 2 3
|
||||
static const uint8_t xlatpx4[] = {1, 2, 4, 0};
|
||||
# define xlat(p) xlatpx4[(p)]
|
||||
static uint32_t g_ledmap[] = {
|
||||
GPIO_LED_GREEN, // Indexed by BOARD_LED_GREEN
|
||||
GPIO_LED_BLUE, // Indexed by BOARD_LED_BLUE
|
||||
GPIO_LED_RED, // Indexed by BOARD_LED_RED
|
||||
};
|
||||
|
||||
#else
|
||||
|
||||
# define xlat(p) (p)
|
||||
static uint32_t g_ledmap[] = {
|
||||
GPIO_LED_BLUE, // Indexed by LED_BLUE
|
||||
GPIO_LED_RED, // Indexed by LED_RED, LED_AMBER
|
||||
GPIO_nSAFETY_SWITCH_LED_OUT_INIT, // Indexed by LED_SAFETY (defaulted to an input)
|
||||
GPIO_LED_GREEN, // Indexed by LED_GREEN
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
__EXPORT void led_init(void)
|
||||
{
|
||||
|
||||
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
|
||||
stm32_configgpio(g_ledmap[l]);
|
||||
}
|
||||
}
|
||||
|
||||
static void phy_set_led(int led, bool state)
|
||||
{
|
||||
/* Drive Low to switch on */
|
||||
|
||||
stm32_gpiowrite(g_ledmap[led], !state);
|
||||
}
|
||||
|
||||
static bool phy_get_led(int led)
|
||||
{
|
||||
/* If Low it is on */
|
||||
return !stm32_gpioread(g_ledmap[led]);
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
phy_set_led(xlat(led), true);
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
phy_set_led(xlat(led), false);
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
phy_set_led(xlat(led), !phy_get_led(xlat(led)));
|
||||
}
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_initialize
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_initialize(void)
|
||||
{
|
||||
led_init();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_on
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_on(int led)
|
||||
{
|
||||
if (!nuttx_owns_leds) {
|
||||
return;
|
||||
}
|
||||
|
||||
switch (led) {
|
||||
default:
|
||||
break;
|
||||
|
||||
case LED_HEAPALLOCATE:
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_IRQSENABLED:
|
||||
phy_set_led(BOARD_LED_BLUE, false);
|
||||
phy_set_led(BOARD_LED_GREEN, true);
|
||||
break;
|
||||
|
||||
case LED_STACKCREATED:
|
||||
phy_set_led(BOARD_LED_GREEN, true);
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_INIRQ:
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_SIGNAL:
|
||||
phy_set_led(BOARD_LED_GREEN, true);
|
||||
break;
|
||||
|
||||
case LED_ASSERTION:
|
||||
phy_set_led(BOARD_LED_RED, true);
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_PANIC:
|
||||
phy_set_led(BOARD_LED_RED, true);
|
||||
break;
|
||||
|
||||
case LED_IDLE : /* IDLE */
|
||||
phy_set_led(BOARD_LED_RED, true);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_off
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_off(int led)
|
||||
{
|
||||
if (!nuttx_owns_leds) {
|
||||
return;
|
||||
}
|
||||
|
||||
switch (led) {
|
||||
default:
|
||||
break;
|
||||
|
||||
case LED_SIGNAL:
|
||||
phy_set_led(BOARD_LED_GREEN, false);
|
||||
break;
|
||||
|
||||
case LED_INIRQ:
|
||||
phy_set_led(BOARD_LED_BLUE, false);
|
||||
break;
|
||||
|
||||
case LED_ASSERTION:
|
||||
phy_set_led(BOARD_LED_RED, false);
|
||||
phy_set_led(BOARD_LED_BLUE, false);
|
||||
break;
|
||||
|
||||
case LED_PANIC:
|
||||
phy_set_led(BOARD_LED_RED, false);
|
||||
break;
|
||||
|
||||
case LED_IDLE : /* IDLE */
|
||||
phy_set_led(BOARD_LED_RED, false);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* CONFIG_ARCH_LEDS */
|
||||
@@ -0,0 +1,78 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
//TODO:Prepare for NxtDual
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <px4_platform_common/px4_manifest.h>
|
||||
// KiB BS nB
|
||||
static const px4_mft_device_t spi2 = { // FM25V02A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32)
|
||||
.bus_type = px4_mft_device_t::SPI,
|
||||
.devid = SPIDEV_FLASH(0)
|
||||
};
|
||||
|
||||
static const px4_mtd_entry_t fmum_fram = {
|
||||
.device = &spi2,
|
||||
.npart = 1,
|
||||
.partd = {
|
||||
{
|
||||
.type = MTD_PARAMETERS,
|
||||
.path = "/fs/mtd_params",
|
||||
.nblocks = 1024
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
static const px4_mtd_manifest_t board_mtd_config = {
|
||||
.nconfigs = 1,
|
||||
.entries = {
|
||||
&fmum_fram
|
||||
}
|
||||
};
|
||||
|
||||
static const px4_mft_entry_s mtd_mft = {
|
||||
.type = MTD,
|
||||
.pmft = (void *) &board_mtd_config,
|
||||
};
|
||||
|
||||
static const px4_mft_s mft = {
|
||||
.nmft = 1,
|
||||
.mfts = {
|
||||
&mtd_mft
|
||||
}
|
||||
};
|
||||
|
||||
const px4_mft_s *board_get_manifest(void)
|
||||
{
|
||||
return &mft;
|
||||
}
|
||||
@@ -0,0 +1,177 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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;
|
||||
|
||||
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,54 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2019-2022 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/spi_hw_description.h>
|
||||
#include <drivers/drv_sensor.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortB, GPIO::Pin12}),
|
||||
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortE, GPIO::Pin12}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortB, GPIO::Pin4}),
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin10}),
|
||||
initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortA, GPIO::Pin8}),
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI4, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortC, GPIO::Pin14}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortC, GPIO::Pin15}),
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
||||
@@ -0,0 +1,54 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/io_timer_hw_description.h>
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::Timer1, DMA{DMA::Index2, DMA::Stream5, DMA::Channel6}),
|
||||
initIOTimer(Timer::Timer2, DMA{DMA::Index1, DMA::Stream7, DMA::Channel3}),
|
||||
initIOTimer(Timer::Timer3, DMA{DMA::Index1, DMA::Stream2, DMA::Channel5}),
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortA, GPIO::Pin10}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel1}, {GPIO::PortA, GPIO::Pin15}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel2}, {GPIO::PortA, GPIO::Pin7}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel1}, {GPIO::PortC, GPIO::Pin6}),
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
initIOTimerChannelMapping(io_timers, timer_io_channels);
|
||||
@@ -0,0 +1,110 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4fmu_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 <arm_internal.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 PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbinitialize(void)
|
||||
{
|
||||
/* The OTG FS has an internal soft pull-up */
|
||||
|
||||
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
|
||||
|
||||
#ifdef CONFIG_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);
|
||||
}
|
||||
|
||||
__EXPORT int board_read_VBUS_state(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
Binary file not shown.
|
After Width: | Height: | Size: 52 KiB |
Binary file not shown.
|
After Width: | Height: | Size: 1.1 MiB |
Binary file not shown.
|
After Width: | Height: | Size: 153 KiB |
Binary file not shown.
|
After Width: | Height: | Size: 121 KiB |
Binary file not shown.
|
After Width: | Height: | Size: 51 KiB |
Binary file not shown.
|
After Width: | Height: | Size: 225 KiB |
@@ -184,6 +184,7 @@
|
||||
- [Wiring Quickstart](assembly/quick_start_holybro_pix32_v5.md)
|
||||
- [ModalAI VOXL 2](flight_controller/modalai_voxl_2.md)
|
||||
- [mRo Control Zero F7](flight_controller/mro_control_zero_f7.md)
|
||||
- [Radiolink PIX6](flight_controller/radiolink_pix6.md)
|
||||
- [Sky-Drones AIRLink](flight_controller/airlink.md)
|
||||
- [SPRacing SPRacingH7EXTREME](flight_controller/spracingh7extreme.md)
|
||||
- [ThePeach FCC-K1](flight_controller/thepeach_k1.md)
|
||||
|
||||
@@ -32,6 +32,7 @@ The boards in this category are:
|
||||
- [Holybro Pix32 v5](../flight_controller/holybro_pix32_v5.md)
|
||||
- [ModalAI VOXL 2](../flight_controller/modalai_voxl_2.md)
|
||||
- [mRo Control Zero](../flight_controller/mro_control_zero_f7.md)
|
||||
- [Radiolink PIX6](../flight_controller/radiolink_pix6.md)
|
||||
- [Sky-Drones AIRLink](../flight_controller/airlink.md)
|
||||
- [SPRacing SPRacingH7EXTREME](../flight_controller/spracingh7extreme.md)
|
||||
- [ThePeach FCC-K1](../flight_controller/thepeach_k1.md)
|
||||
|
||||
@@ -0,0 +1,346 @@
|
||||
# RadiolinkPIX6 Flight Controller
|
||||
|
||||
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
|
||||
|
||||
:::warning
|
||||
PX4 does not manufacture this (or any) autopilot.
|
||||
Contact the [manufacturer](https://radiolink.com.cn/) for hardware support or compliance issues.
|
||||
:::
|
||||
|
||||
The autopilot is recommended for commercial systems integration, but is also suitable for academic research and any other use.
|
||||
|
||||

|
||||
|
||||
The Radiolink PIX6 is a high-performance flight controller.
|
||||
Featuring STM32F7 CPU, vibration isolation of IMUs, redundant IMUs, integrated OSD chip, IMU heating, and DShot.
|
||||
|
||||
::: info
|
||||
This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md).
|
||||
:::
|
||||
|
||||
## Quick Summary
|
||||
|
||||
- Processor
|
||||
- 32-bit ARM Cortex M7 core with DPFPU - STM32F765VIT6
|
||||
- 216 MHz/512 KB RAM/2 MB Flash
|
||||
- 32-bit IOMCU co-processor - STM32F100
|
||||
- 32KB FRAM - FM25V02A
|
||||
- AT7456E OSD
|
||||
- Sensors
|
||||
- Bosh BMI088 IMU (accel, gyro)
|
||||
- InvenSense ICM-42688 IMU (accel, gyro)
|
||||
- SPA06 barometer
|
||||
- IST8310 magnetometer
|
||||
- Power
|
||||
- SMBUS/I2C Power Module Inputs (I2C)
|
||||
- voltage and current monitor inputs (Analog)
|
||||
- Interfaces
|
||||
- 16 PWM Outputs with independent power rail for external power source
|
||||
- 5x UART serial ports, 2 with HW flow control
|
||||
- Camera Input and Video Output
|
||||
- PPM/SBUS input, DSM/SBUS input
|
||||
- RSSI (PWM or voltage) input
|
||||
- I2C, SPI, 2x CAN, USB
|
||||
- 3.3V and 6.6V ADC inputs
|
||||
- Buzzer and Safety Switch
|
||||
- microSD card
|
||||
- Weight and Dimensions:
|
||||
- Weight 80g
|
||||
- Size 94mm x 51.5mm x 14.5mm
|
||||
|
||||
## Where to Buy
|
||||
|
||||
[Radiolink Amazon](https://www.radiolink.com.cn/pix6_where_to_buy)(International users)
|
||||
|
||||
[Radiolink Taobao](https://item.taobao.com/item.htm?spm=a21dvs.23580594.0.0.1d292c1bNMdSqV&ft=t&id=815993357068&skuId=5515756705284)(China Mainland user)
|
||||
|
||||
## Connector assignments
|
||||
|
||||
### Top View
|
||||
|
||||

|
||||
|
||||
### Left View
|
||||
|
||||

|
||||
|
||||
### Right View
|
||||
|
||||

|
||||
|
||||
### Rear View
|
||||
|
||||

|
||||
|
||||
## Pinouts
|
||||
|
||||
Unless noted otherwise all connectors are JST GH.
|
||||
|
||||
### TELEM1, TELEM2 ports
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------- | ----- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | TX(OUT) | +3.3V |
|
||||
| 3 | RX(IN) | +3.3V |
|
||||
| 4 | CTS | +3.3V |
|
||||
| 5 | RTS | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
### OSD
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------ | ----- |
|
||||
| 1 | GND | GND |
|
||||
| 2 | VOUT | +3.3V |
|
||||
| 3 | VCC | +5V |
|
||||
| 4 | GND | GND |
|
||||
| 5 | VCC | +5V |
|
||||
| 6 | VIN | +3.3V |
|
||||
|
||||
### I2C port
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------ | --------------- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | SCL | +3.3V (pullups) |
|
||||
| 3 | SDA | +3.3V (pullups) |
|
||||
| 4 | GND | GND |
|
||||
|
||||
### CAN1, CAN2 ports
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------ | ---- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | CAN_H | +12V |
|
||||
| 3 | CAN_L | +12V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
### GPS1 port
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------- | ----- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | TX(OUT) | +3.3V |
|
||||
| 3 | RX(IN) | +3.3V |
|
||||
| 4 | SCL | +3.3V |
|
||||
| 5 | SDA | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
### GPS2 Port
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------- | ----- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | TX(OUT) | +3.3V |
|
||||
| 3 | RX(IN) | +3.3V |
|
||||
| 4 | SCL | +3.3V |
|
||||
| 5 | SDA | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
### SPI
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | --------- | ----- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | SPI_SCK | +3.3V |
|
||||
| 3 | SPI_MISO | +3.3V |
|
||||
| 4 | SPI_MOSI | +3.3V |
|
||||
| 5 | !SPI_NSS1 | +3.3V |
|
||||
| 6 | !SPI_NSS2 | +3.3V |
|
||||
| 7 | DRDY | +3.3V |
|
||||
| 8 | GND | GND |
|
||||
|
||||
### POWER1 (HY2.0-6P)
|
||||
|
||||
Port for analog power monitors.
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------- | ----------- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | VCC | +5V |
|
||||
| 3 | CURRENT | up to +3.3V |
|
||||
| 4 | VOLTAGE | up to +3.3V |
|
||||
| 5 | GND | GND |
|
||||
| 6 | GND | GND |
|
||||
|
||||
### POWER2 (HY2.0-6P)
|
||||
|
||||
Port for digital (I2C) power monitor.
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------ | ----- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | VCC | +5V |
|
||||
| 3 | SCL | +3.3V |
|
||||
| 4 | SDA | +3.3V |
|
||||
| 5 | GND | GND |
|
||||
| 6 | GND | GND |
|
||||
|
||||
### ADC 3.3V
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------- | ----------- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | ADC IN1 | up to +3.3V |
|
||||
| 3 | GND | GND |
|
||||
| 4 | ADC IN2 | up to +3.3v |
|
||||
| 5 | GND | GND |
|
||||
|
||||
### ADC 6.6V
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------ | ---------- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | ADC IN | up to 6.6V |
|
||||
| 3 | GND | GND |
|
||||
|
||||
### USB remote port
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------- | ----- |
|
||||
| 1 | USB VDD | +5V |
|
||||
| 2 | DM | +3.3V |
|
||||
| 3 | DP | +3.3V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
### SWITCH
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | -------------- | ----- |
|
||||
| 1 | VCC | +3.3V |
|
||||
| 2 | !IO_LED_SAFETY | GND |
|
||||
| 3 | SAFETY | GND |
|
||||
|
||||
### Buzzer port
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------- | ---- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | BUZZER- | +5V |
|
||||
|
||||
### Spektrum/DSM Port (PH1.25-3P)
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | ------ | ----- |
|
||||
| 1 | VCC | +3.3V |
|
||||
| 2 | GND | GND |
|
||||
| 3 | Signal | +3.3V |
|
||||
|
||||
### Debug port (SH1.0-8P)
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| --- | --------- | ----- |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | FMU_SWCLK | +3.3V |
|
||||
| 3 | FMU_SWDIO | +3.3V |
|
||||
| 4 | TX(UART7) | +3.3V |
|
||||
| 5 | RX(UART7) | +3.3V |
|
||||
| 6 | IO_SWCLK | +3.3V |
|
||||
| 7 | IO_SWDIO | +3.3V |
|
||||
| 8 | GND | GND |
|
||||
|
||||
## Building Firmware
|
||||
|
||||
To [build PX4](../dev_setup/building_px4.md) for this target:
|
||||
|
||||
```sh
|
||||
make radiolink_PIX6_default
|
||||
```
|
||||
|
||||
## Installing PX4 Firmware
|
||||
|
||||
The firmware can be installed in any of the normal ways:
|
||||
|
||||
- Build and upload the source
|
||||
|
||||
```sh
|
||||
make radiolink_PIX6_default upload
|
||||
```
|
||||
|
||||
- [Load the firmware](../config/firmware.md) using _QGroundControl_.
|
||||
You can use either pre-built firmware or your own custom firmware.
|
||||
|
||||
::: info
|
||||
At time of writing the only pre-built software is `PX4 main` (see [Installing PX4 Main, Beta or Custom Firmware](../config/firmware.md#installing-px4-main-beta-or-custom-firmware)).
|
||||
Release builds will be supported for PX4 v1.17 and later.
|
||||
:::
|
||||
|
||||
## PX4 Configuration
|
||||
|
||||
In addition to the [basic configuration](../config/index.md), the following parameters are important:
|
||||
|
||||
| Parameter | Setting |
|
||||
| -------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------- |
|
||||
| [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG) | This should be disabled since the board does not have an internal mag. You can enable it if you attach an external mag. |
|
||||
|
||||
### Powering the PIX6
|
||||
|
||||
The PIX6 has 2 dedicated power monitor ports, each with a 6 pin connector.
|
||||
One is the Analog power monitor (`POWER1`), and the others is the I2C power monitor (`POWER2`).
|
||||
|
||||
The power module that comes with the flight controller with a wide voltage input range of 2-12S (7.4-50.4V), a maximum detection current of 90A (single ESC maximum detection current is 22.5A), a BEC output voltage of 5.3±0.2V, and a BEC output current of 2A.
|
||||
|
||||

|
||||
|
||||
The PIX6 also supports power modules from other manufacturers, such as [holybro_pm02d](../power_module/holybro_pm02d.md).
|
||||
|
||||
## Recommended Accessories
|
||||
|
||||
### GPS Modules
|
||||
|
||||
Radiolink manufactures a variety of high-performance GPS,Dual Anti-interference Technology Worry-free of UAV High-power Image Transmission, High-Voltage Lines, or Other Strong Signal Interference.
|
||||
|
||||
The PIX6 has 2 dedicated GPS ports, `GPS1` and `GPS2`, each with a 6 pin connector.
|
||||
|
||||
Recommended modules include:
|
||||
|
||||
- [Radiolink SE100](https://radiolink.com.cn/se100)
|
||||
- [Radiolink TS100](https://radiolink.com.cn/ts100v2)
|
||||
- [Radiolink RTK F9P](https://radiolink.com.cn/rtk_f9p)
|
||||
|
||||
## Serial Port Mapping
|
||||
|
||||
| UART | Device | Port |
|
||||
| ------ | ---------- | --------------------- |
|
||||
| UART1 | /dev/ttyS0 | GPS1 |
|
||||
| USART2 | /dev/ttyS1 | TELEM1 (flow control) |
|
||||
| USART3 | /dev/ttyS2 | TELEM2 (flow control) |
|
||||
| UART4 | /dev/ttyS3 | GPS2 |
|
||||
| UART7 | /dev/ttyS4 | Debug Console |
|
||||
| UART8 | /dev/ttyS5 | PX4IO |
|
||||
|
||||
## Analog inputs
|
||||
|
||||
The Radiolink PIX6 has 3 analog inputs, one 6V tolerant and two 3.3V tolerant.
|
||||
|
||||
- ADC Pin12 -> ADC 6.6V Sense
|
||||
- ADC Pin4 -> ADC IN1 3.3V Sense
|
||||
- ADC Pin13 -> ADC IN2 3.3V Sense
|
||||
|
||||
## Radio Control
|
||||
|
||||
A [Radio Control (RC)](../getting_started/rc_transmitter_receiver.md) system is required if you want to _manually_ control your vehicle (PX4 does not require a radio system for autonomous flight modes).
|
||||
|
||||
You will need to [select a compatible transmitter/receiver](../getting_started/rc_transmitter_receiver.md) and then _bind_ them so that they communicate (read the instructions that come with your specific transmitter/receiver).
|
||||
|
||||
- Spektrum/DSM receivers connect to the **DSM/SBUS RC** input.
|
||||
- PPM or SBUS receivers connect to the **RC IN** input port.
|
||||
- CRSF receiver must be wired to a spare port (UART) on the Flight Controller.
|
||||
Then you can bind the transmitter and receiver together.
|
||||
|
||||
#### CRSF Parameter Configuration
|
||||
|
||||
[Find and set](../advanced_config/parameters.md) the following parameters:
|
||||
|
||||
1. Set [RC_CRSF_PRT_CFG](../advanced_config/parameter_reference.md#RC_CRSF_PRT_CFG) to the port that is connected to the CRSF receiver (such as `TELEM1`).
|
||||
|
||||
This [configures the serial port](../peripherals/serial_configuration.md) to use the CRSF protocol.
|
||||
Note that some serial ports may already have a [default serial port mapping](../peripherals/serial_configuration.md#default-serial-port-configuration) or [default MAVLink serial port mapping](../peripherals/mavlink_peripherals.md#default-mavlink-ports) that you will have to un-map before you can assign the port to CRSF.
|
||||
For example, if you want to use `TELEM1` or `TELEM2` you first need to modify [MAV_0_CONFIG](../advanced_config/parameter_reference.md#MAV_0_CONFIG) or [MAV_1_CONFIG](../advanced_config/parameter_reference.md#MAV_1_CONFIG) to stop setting those ports.
|
||||
|
||||
There is no need to set the baud rate for the port, as this is configured by the driver.
|
||||
|
||||
1. Enable [RC_CRSF_TEL_EN](../advanced_config/parameter_reference.md#RC_CRSF_TEL_EN) to activate Crossfire telemetry.
|
||||
|
||||
For more information about selecting a radio system, receiver compatibility, and binding your transmitter/receiver pair, see: [Remote Control Transmitters & Receivers](../getting_started/rc_transmitter_receiver.md).
|
||||
Reference in New Issue
Block a user