mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 13:02:25 +08:00
feat(boards): add CubeRed primary and secondary
This commit is contained in:
Vendored
+10
@@ -351,6 +351,16 @@ CONFIG:
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: cubepilot_cubeorangeplus_test
|
||||
cubepilot_cubered-primary_default:
|
||||
short: cubepilot_cubered-primary
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: cubepilot_cubered-primary_default
|
||||
cubepilot_cubered-secondary_default:
|
||||
short: cubepilot_cubered-secondary
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: cubepilot_cubered-primary_default
|
||||
emlid_navio2_default:
|
||||
short: emlid_navio2
|
||||
buildType: MinSizeRel
|
||||
|
||||
@@ -0,0 +1,41 @@
|
||||
# PX4 on CubePilot CubeRed
|
||||
|
||||
CubePilot CubeRed is a dual-MCU autopilot built around two STM32H743 MCUs:
|
||||
|
||||
- **Primary** (`cubepilot_cubered-primary`) runs the main PX4 flight stack
|
||||
and the `cubered_bridge_primary` driver
|
||||
(`src/drivers/cubered_bridge/primary`).
|
||||
- **Secondary** (`cubepilot_cubered-secondary`) runs the
|
||||
`cubered_bridge_secondary` driver
|
||||
(`src/drivers/cubered_bridge/secondary`), which speaks the PX4IO register
|
||||
protocol so the primary can drive PWM/RC over the UART7 link between the
|
||||
two MCUs.
|
||||
|
||||
References:
|
||||
- [Hardware overview](https://docs.cubepilot.org/user-guides/autopilot/cube-red)
|
||||
- [Carrier board pinout](https://docs.cubepilot.org/user-guides/carrier-boards/cube-red-standard-carrier-board-pinout)
|
||||
|
||||
## Bootloader
|
||||
|
||||
PX4 currently uses the **ArduPilot bootloader** on this board. A native PX4
|
||||
bootloader is not yet available, so the upload protocol is driven through
|
||||
ArduPilot's bootloader and the secondary is exposed as the second device of
|
||||
the primary's composite USB bootloader.
|
||||
|
||||
## Building and flashing
|
||||
|
||||
Both MCUs need to be flashed. Build and upload the secondary first, then
|
||||
the primary:
|
||||
|
||||
```sh
|
||||
make cubepilot_cubered-secondary_default upload && \
|
||||
make cubepilot_cubered-primary_default upload
|
||||
```
|
||||
|
||||
A manual power cycle is currently required between the secondary upload
|
||||
finishing and the secondary rebooting into application mode.
|
||||
|
||||
## Console
|
||||
|
||||
- Primary console is on the carrier's GPS2 connector (UART4) at 57600 baud.
|
||||
- Secondary console is on the carrier's CONS connector (UART8) at 57600 baud.
|
||||
@@ -0,0 +1,100 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_ETHERNET=y
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
|
||||
CONFIG_BOARD_EXTERNAL_FLASH=y
|
||||
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=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_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
|
||||
CONFIG_COMMON_INS=y
|
||||
CONFIG_DRIVERS_IRLOCK=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
#CONFIG_DRIVERS_PCA9685_PWM_OUT=y
|
||||
#CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_PWM_INPUT=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
#CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_DRIVERS_TRANSPONDER_SAGETECH_MXS=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=4
|
||||
CONFIG_DRIVERS_CUBERED_BRIDGE_PRIMARY=y
|
||||
#CONFIG_MODULES_AIRSPEED_SELECTOR=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_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
#CONFIG_MODULES_TEMPERATURE_COMPENSATION=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_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_NETMAN=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=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
|
||||
CONFIG_SYSTEMCMDS_MICROBENCH=y
|
||||
CONFIG_SYSTEMCMDS_SD_STRESS=y
|
||||
Binary file not shown.
@@ -0,0 +1,13 @@
|
||||
{
|
||||
"board_id": 1069,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the CubePilot CubeRed Primary board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "CubeRed-Primary",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 1966080,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
@@ -0,0 +1,17 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
param set-default BAT1_V_DIV 10.1
|
||||
param set-default BAT2_V_DIV 10.1
|
||||
|
||||
param set-default BAT1_A_PER_V 17
|
||||
param set-default BAT2_A_PER_V 17
|
||||
|
||||
# Disable IMU thermal control
|
||||
param set-default SENS_EN_THERMAL 0
|
||||
|
||||
param set-default -s SENS_TEMP_ID 2621474
|
||||
|
||||
#set IOFW "/etc/extras/cubepilot_io-v2_default.bin"
|
||||
@@ -0,0 +1,2 @@
|
||||
#!/bin/sh
|
||||
|
||||
@@ -0,0 +1,34 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# Board specific sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
# TODO: start all three instances
|
||||
board_adc start
|
||||
|
||||
|
||||
# SPI1, SPI2 isolated
|
||||
# SPI4 fixed
|
||||
|
||||
# SPI1
|
||||
ms5611 -s -b 1 start -c 13
|
||||
if ! icm42688p -s -b 1 -q -R 2 -c 9 start
|
||||
then
|
||||
icm45686 -s -b 1 -R 2 -c 9 start
|
||||
fi
|
||||
|
||||
# SPI2
|
||||
rm3100 -s -b 2 -R 6 start -c 15
|
||||
if ! icm42688p -s -b 2 -q -R 10 -c 14 start
|
||||
then
|
||||
icm45686 -s -b 2 -R 10 -c 14 start
|
||||
fi
|
||||
|
||||
# SPI4
|
||||
if ! icm20649 -s -b 4 -q -R 10 -c 5 start
|
||||
then
|
||||
icm45686 -s -b 4 -R 12 -c 5 start
|
||||
fi
|
||||
ms5611 -s -b 4 start -c 2
|
||||
|
||||
# Start the bridge driver that talks to the CubeRed Secondary over UART7.
|
||||
cubered_bridge_primary start
|
||||
@@ -0,0 +1,290 @@
|
||||
/************************************************************************************
|
||||
* nuttx-config/include/board.h
|
||||
*
|
||||
* Copyright (C) 2020 Gregory Nutt. All rights reserved.
|
||||
* Authors: David Sidrane <david.sidrane@nscdg.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
************************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#include "board_dma_map.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_sdmmc.h"
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The board provides the following clock sources:
|
||||
*
|
||||
* X1: 24 MHz crystal for HSE
|
||||
*
|
||||
* So we have these clock source available within the STM32
|
||||
*
|
||||
* HSI: 16 MHz RC factory-trimmed internal oscillator
|
||||
* 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
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
* PLL source is HSE = 24,000,000
|
||||
*
|
||||
* PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN
|
||||
* Subject to:
|
||||
*
|
||||
* 1 <= PLLM <= 63
|
||||
* 4 <= PLLN <= 512
|
||||
* 150 MHz <= PLL_VCOL <= 420MHz
|
||||
* 192 MHz <= PLL_VCOH <= 836MHz
|
||||
*
|
||||
* SYSCLK = PLL_VCO / PLLP
|
||||
* CPUCLK = SYSCLK / D1CPRE
|
||||
* Subject to
|
||||
*
|
||||
* PLLP1 = {2, 4, 6, 8, ..., 128}
|
||||
* PLLP2,3 = {2, 3, 4, ..., 128}
|
||||
* CPUCLK <= 480 MHz
|
||||
*/
|
||||
|
||||
/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR
|
||||
*
|
||||
* PLL1_VCO = (24,000,000 / 3) * 100 = 800 MHz
|
||||
*
|
||||
* PLL1P = PLL1_VCO/2 = 800 MHz / 2 = 400 MHz
|
||||
* PLL1Q = PLL1_VCO/8 = 800 MHz / 8 = 100 MHz
|
||||
* PLL1R = PLL1_VCO/2 = 800 MHz / 2 = 400 MHz
|
||||
*/
|
||||
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE|RCC_PLLCFGR_PLL1RGE_4_8_MHZ|RCC_PLLCFGR_DIVP1EN|RCC_PLLCFGR_DIVQ1EN|RCC_PLLCFGR_DIVR1EN)
|
||||
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(3)
|
||||
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(100)
|
||||
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
|
||||
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(10)
|
||||
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(2)
|
||||
|
||||
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 3) * 100)
|
||||
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
|
||||
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 10)
|
||||
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
|
||||
|
||||
/* PLL2 */
|
||||
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE|RCC_PLLCFGR_PLL2RGE_8_16_MHZ|RCC_PLLCFGR_DIVP2EN|RCC_PLLCFGR_DIVQ2EN|RCC_PLLCFGR_DIVR2EN)
|
||||
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(2)
|
||||
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(50)
|
||||
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(3)
|
||||
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(6)
|
||||
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(3)
|
||||
|
||||
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 50)
|
||||
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 3)
|
||||
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 6)
|
||||
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 3)
|
||||
|
||||
/* PLL3 */
|
||||
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE|RCC_PLLCFGR_PLL3RGE_4_8_MHZ|RCC_PLLCFGR_DIVQ3EN)
|
||||
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(6)
|
||||
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(72)
|
||||
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(3)
|
||||
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(6)
|
||||
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(9)
|
||||
|
||||
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 6) * 72)
|
||||
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 3)
|
||||
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 6)
|
||||
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 9)
|
||||
|
||||
/* SYSCLK = PLL1P = 400MHz
|
||||
* CPUCLK = SYSCLK / 1 = 400 MHz
|
||||
*/
|
||||
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
|
||||
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
|
||||
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1)
|
||||
|
||||
/* Configure Clock Assignments */
|
||||
|
||||
/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max)
|
||||
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 200
|
||||
*/
|
||||
#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */
|
||||
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */
|
||||
#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */
|
||||
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
|
||||
|
||||
/* APB1 clock (PCLK1) is HCLK/4 (120 MHz) */
|
||||
#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
|
||||
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */
|
||||
#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
|
||||
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */
|
||||
#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */
|
||||
#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */
|
||||
#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */
|
||||
#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* Timer clock frequencies */
|
||||
|
||||
/* 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)
|
||||
|
||||
/* 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_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* Kernel Clock Configuration
|
||||
* Note: look at Table 54 in ST Manual
|
||||
*/
|
||||
#define STM32_RCC_D1CCIPR_SDMMCSEL RCC_D1CCIPR_SDMMC_PLL1
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */
|
||||
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 /* SPI123 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 /* SPI45 clock source */
|
||||
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 /* USB 1 and 2 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */
|
||||
|
||||
#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */
|
||||
|
||||
/* UART clock selection */
|
||||
/* reset to default to overwrite any changes done by any bootloader */
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC
|
||||
#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC
|
||||
|
||||
|
||||
/* FLASH wait states */
|
||||
#define BOARD_FLASH_WAITSTATES 2
|
||||
|
||||
/* SDMMC definitions ********************************************************/
|
||||
/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */
|
||||
#define STM32_SDMMC_INIT_CLKDIV (125 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
|
||||
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
|
||||
* div = 100 / (2*25)
|
||||
*/
|
||||
#define STM32_SDMMC_MMCXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#define STM32_SDMMC_SDXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
|
||||
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
|
||||
|
||||
|
||||
/* Ethernet phy */
|
||||
#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 /* PB11 */
|
||||
#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_1 /* PB12 */
|
||||
#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_1 /* PB13 */
|
||||
//#define GPIO_ETH_RMII_RXD0 GPIO_ETH_RMII_RXD0 /* PC4 */
|
||||
//#define GPIO_ETH_RMII_RXD1 GPIO_ETH_RMII_RXD1 /* PC5 */
|
||||
|
||||
/* UART/USART */
|
||||
|
||||
// USART2 -> /dev/ttyS0 -> Telem1
|
||||
// USART3 -> /dev/ttyS1 -> GPS1
|
||||
// UART4 -> /dev/ttyS2 -> GPS2
|
||||
// USART6 -> /dev/ttyS3 -> Telem2
|
||||
// UART7 -> /dev/ttyS4 -> to Secondary (but swapped because not crossed over in hardware)
|
||||
// UART8 -> /dev/ttyS5 -> console
|
||||
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
|
||||
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
#define GPIO_USART6_CTS GPIO_USART6_CTS_NSS_2 /* PG15 */
|
||||
#define GPIO_USART6_RTS GPIO_USART6_RTS_2 /* PG8 */
|
||||
|
||||
// Defined normal but needs swapping in software!
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
|
||||
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
|
||||
|
||||
/* CAN */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_2 /* PB8 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_2 /* PB9 */
|
||||
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_2 /* PB5 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_2 /* PB6 */
|
||||
|
||||
|
||||
/* SPI */
|
||||
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
|
||||
|
||||
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_2) /* PB3 */
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_2 /* PB4 */
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
|
||||
|
||||
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_2) /* PA9 */
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */
|
||||
|
||||
#define GPIO_SPI4_SCK ADJ_SLEW_RATE(GPIO_SPI4_SCK_1) /* PE12 */
|
||||
#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE5 */
|
||||
#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_2 /* PE6 */
|
||||
|
||||
|
||||
/* I2C */
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */
|
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */
|
||||
|
||||
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
|
||||
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
|
||||
@@ -0,0 +1,55 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
|
||||
// DMAMUX1
|
||||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0
|
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0
|
||||
|
||||
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0
|
||||
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0
|
||||
|
||||
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_0
|
||||
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_0
|
||||
|
||||
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_0
|
||||
#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_0
|
||||
|
||||
//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 */
|
||||
//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 */
|
||||
|
||||
// DMA 2
|
||||
// Timer 1
|
||||
// Timer 2
|
||||
// Timer 3
|
||||
@@ -0,0 +1,314 @@
|
||||
#
|
||||
# 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_ARP 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_EXIT 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_NSLOOKUP 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/cubepilot/cubered-primary/nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H747XI=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=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_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=79954
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x1059
|
||||
CONFIG_CDCACM_PRODUCTSTR="CubeRed"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x2DAE
|
||||
CONFIG_CDCACM_VENDORSTR="CubePilot"
|
||||
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_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_DEV_URANDOM=y
|
||||
CONFIG_ETH0_PHY_LAN8720=y
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FSUTILS_IPCFG=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_IOB_NBUFFERS=24
|
||||
CONFIG_IOB_THROTTLE=0
|
||||
CONFIG_IPCFG_BINARY=y
|
||||
CONFIG_IPCFG_CHARDEV=y
|
||||
CONFIG_IPCFG_PATH="/fs/microsd/mtd_net"
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_MAX_EXITFUNS=1
|
||||
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=4
|
||||
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_NET=y
|
||||
CONFIG_NETDB_DNSCLIENT=y
|
||||
CONFIG_NETDB_DNSCLIENT_ENTRIES=8
|
||||
CONFIG_NETDB_DNSSERVER_NOADDR=y
|
||||
CONFIG_NETDEV_PHY_IOCTL=y
|
||||
CONFIG_NETINIT_DHCPC=y
|
||||
CONFIG_NETINIT_DNS=y
|
||||
CONFIG_NETINIT_DNSIPADDR=0xA290AFE
|
||||
CONFIG_NETINIT_DRIPADDR=0xA290AFE
|
||||
CONFIG_NETINIT_MONITOR=y
|
||||
CONFIG_NETINIT_THREAD=y
|
||||
CONFIG_NETINIT_THREAD_PRIORITY=49
|
||||
CONFIG_NETUTILS_TELNETD=y
|
||||
CONFIG_NET_ARP_IPIN=y
|
||||
CONFIG_NET_ARP_SEND=y
|
||||
CONFIG_NET_BROADCAST=y
|
||||
CONFIG_NET_ETH_PKTSIZE=1518
|
||||
CONFIG_NET_ICMP=y
|
||||
CONFIG_NET_ICMP_SOCKET=y
|
||||
CONFIG_NET_NACTIVESOCKETS=16
|
||||
CONFIG_NET_SOLINGER=y
|
||||
CONFIG_NET_TCP=y
|
||||
CONFIG_NET_TCPBACKLOG=y
|
||||
CONFIG_NET_TCP_DELAYED_ACK=y
|
||||
CONFIG_NET_TCP_WRITE_BUFFERS=y
|
||||
CONFIG_NET_UDP=y
|
||||
CONFIG_NET_UDP_CHECKSUMS=y
|
||||
CONFIG_NET_UDP_WRITE_BUFFERS=y
|
||||
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_TELNET=y
|
||||
CONFIG_NSH_TELNET_LOGIN=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_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_STM32H7_ADC1=y
|
||||
CONFIG_STM32H7_ADC3=y
|
||||
CONFIG_STM32H7_BBSRAM=y
|
||||
CONFIG_STM32H7_BBSRAM_FILES=5
|
||||
CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_ETHMAC=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C2=y
|
||||
CONFIG_STM32H7_I2C4=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PHYADDR=0
|
||||
CONFIG_STM32H7_PHYSR=31
|
||||
CONFIG_STM32H7_PHYSR_100MBPS=0x8
|
||||
CONFIG_STM32H7_PHYSR_FULLDUPLEX=0x10
|
||||
CONFIG_STM32H7_PHYSR_MODE=0x10
|
||||
CONFIG_STM32H7_PHYSR_SPEED=0x8
|
||||
CONFIG_STM32H7_PHY_POLLING=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_PWR_DIRECT_SMPS_SUPPLY=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_HSECLOCK=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SDMMC1=y
|
||||
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32H7_SPI1=y
|
||||
CONFIG_STM32H7_SPI1_DMA=y
|
||||
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI2=y
|
||||
CONFIG_STM32H7_SPI2_DMA=y
|
||||
CONFIG_STM32H7_SPI2_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI4=y
|
||||
CONFIG_STM32H7_SPI4_DMA=y
|
||||
CONFIG_STM32H7_SPI4_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_TIM12=y
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM2=y
|
||||
CONFIG_STM32H7_TIM3=y
|
||||
CONFIG_STM32H7_UART4=y
|
||||
CONFIG_STM32H7_UART7=y
|
||||
CONFIG_STM32H7_UART8=y
|
||||
CONFIG_STM32H7_USART2=y
|
||||
CONFIG_STM32H7_USART3=y
|
||||
CONFIG_STM32H7_USART6=y
|
||||
CONFIG_STM32H7_USART_BREAKS=y
|
||||
CONFIG_STM32H7_USART_INVERT=y
|
||||
CONFIG_STM32H7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32H7_USART_SWAP=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_SYSTEM_DHCPC_RENEW=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TTY_SIGINT=y
|
||||
CONFIG_TTY_SIGINT_CHAR=0x03
|
||||
CONFIG_SYSTEM_PING=y
|
||||
CONFIG_SYSTEM_SYSTEM=y
|
||||
CONFIG_TTY_SIGTSTP=y
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_TXBUFSIZE=1500
|
||||
CONFIG_UART4_SERIAL_CONSOLE=y
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=600
|
||||
CONFIG_UART7_TXBUFSIZE=1500
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=600
|
||||
CONFIG_UART8_TXBUFSIZE=1500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_TXBUFSIZE=1500
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_TXBUFSIZE=3000
|
||||
CONFIG_USART6_BAUD=57600
|
||||
CONFIG_USART6_IFLOWCONTROL=y
|
||||
CONFIG_USART6_OFLOWCONTROL=y
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_WATCHDOG=y
|
||||
@@ -0,0 +1,239 @@
|
||||
/****************************************************************************
|
||||
* scripts/script.ld
|
||||
*
|
||||
* Copyright (C) 2020 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 board uses an STM32H757ZI and has 2048Kb of main FLASH memory.
|
||||
* The flash memory is partitioned into a User Flash memory and a System
|
||||
* Flash memory. Each of these memories has two banks:
|
||||
*
|
||||
* 1) User Flash memory:
|
||||
*
|
||||
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each
|
||||
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each
|
||||
*
|
||||
* 2) System Flash memory:
|
||||
*
|
||||
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector
|
||||
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector
|
||||
*
|
||||
* 3) User option bytes for user configuration, only in Bank 1.
|
||||
*
|
||||
* In the STM32H757ZI, 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 memory at 0x0800:0000
|
||||
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
|
||||
* ST programmed value: System bootloader at 0x1FF0:0000
|
||||
*
|
||||
* There's a switch on board, the BOOT0 pin is at ground so by default,
|
||||
* the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is
|
||||
* drepresed, then the boot will be from 0x1FF0:0000
|
||||
*
|
||||
* The STM32H757ZI also has 1024Kb of data SRAM.
|
||||
* SRAM is split up into several blocks and into three power domains:
|
||||
*
|
||||
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with
|
||||
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus
|
||||
*
|
||||
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000
|
||||
*
|
||||
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit
|
||||
* DTCM ports. The DTCM-RAM could be used for critical real-time
|
||||
* data, such as interrupt service routines or stack / heap memory.
|
||||
* Both DTCM-RAMs can be used in parallel (for load/store operations)
|
||||
* thanks to the Cortex-M7 dual issue capability.
|
||||
*
|
||||
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000
|
||||
*
|
||||
* This RAM is connected to ITCM 64-bit interface designed for
|
||||
* execution of critical real-times routines by the CPU.
|
||||
*
|
||||
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA
|
||||
* through D1 domain AXI bus matrix
|
||||
*
|
||||
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000
|
||||
*
|
||||
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA
|
||||
* through D2 domain AHB bus matrix
|
||||
*
|
||||
* 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000
|
||||
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000
|
||||
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000
|
||||
*
|
||||
* SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000
|
||||
*
|
||||
* 4) AHB SRAM (D3 domain) accessible by most of system masters
|
||||
* through D3 domain AHB bus matrix
|
||||
*
|
||||
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000
|
||||
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000
|
||||
*
|
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
|
||||
* where the code expects to begin execution by jumping to the entry point in
|
||||
* the 0x0800:0000 address range.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1664K /* 2 sectors of 128K following for params) */
|
||||
EXT_FLASH (rx) : ORIGIN = 0x90000000, LENGTH = 32768K
|
||||
|
||||
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
|
||||
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
|
||||
SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */
|
||||
SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */
|
||||
SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */
|
||||
SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */
|
||||
BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
|
||||
}
|
||||
|
||||
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
|
||||
{
|
||||
startup : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.vectors)
|
||||
. = ALIGN(32);
|
||||
/*
|
||||
This signature provides the bootloader with a way to delay booting
|
||||
*/
|
||||
_bootdelay_signature = ABSOLUTE(.);
|
||||
FILL(0xffecc2925d7d05c5)
|
||||
. += 8;
|
||||
} > FLASH
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > FLASH
|
||||
|
||||
/* External Flash area if defined */
|
||||
.extflash : ALIGN(4) SUBALIGN(4)
|
||||
{
|
||||
*libromfs.a:*.*(.text* .rodata*)
|
||||
*libmodules__mavlink.a:*.*(.text* .rodata*)
|
||||
*(.extflash)
|
||||
_etext = ABSOLUTE(.);
|
||||
} > EXT_FLASH
|
||||
|
||||
.text : {
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
} > FLASH
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > FLASH
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > FLASH
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
|
||||
/* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */
|
||||
. = ALIGN(16);
|
||||
FILL(0xffff)
|
||||
. += 16;
|
||||
} > AXI_SRAM AT > FLASH = 0xffff
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > AXI_SRAM
|
||||
|
||||
/* Emit the the D3 power domain section for locating BDMA data */
|
||||
|
||||
.sram4_reserve (NOLOAD) :
|
||||
{
|
||||
*(.sram4)
|
||||
. = ALIGN(4);
|
||||
_sram4_heap_start = ABSOLUTE(.);
|
||||
} > SRAM4
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
||||
@@ -0,0 +1,65 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
|
||||
add_library(drivers_board
|
||||
bootloader_main.c
|
||||
usb.c
|
||||
)
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
nuttx_arch
|
||||
nuttx_drivers
|
||||
bootloader
|
||||
)
|
||||
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common)
|
||||
|
||||
else()
|
||||
add_library(drivers_board
|
||||
i2c.cpp
|
||||
init.c
|
||||
led.c
|
||||
spi.cpp
|
||||
timer_config.cpp
|
||||
usb.c
|
||||
)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
arch_io_pins
|
||||
arch_spi
|
||||
drivers__led
|
||||
nuttx_arch
|
||||
nuttx_drivers
|
||||
px4_layer
|
||||
)
|
||||
endif()
|
||||
@@ -0,0 +1,199 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 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
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
/**
|
||||
* If NuttX is built without support for SMPS it can brick the hardware.
|
||||
* Therefore, we make sure the NuttX headers are correct.
|
||||
*/
|
||||
#include "hardware/stm32h7x3xx_pwr.h"
|
||||
#if STM32_PWR_CR3_SMPSEXTHP != (1 << 3)
|
||||
# error "No SMPS support in NuttX submodule");
|
||||
#endif
|
||||
|
||||
|
||||
/* PX4IO connection configuration */
|
||||
#define BOARD_USES_PX4IO_VERSION 2
|
||||
#define PX4IO_SERIAL_DEVICE "/dev/ttyS4"
|
||||
#define PX4IO_SERIAL_TX_GPIO GPIO_UART7_TX
|
||||
#define PX4IO_SERIAL_RX_GPIO GPIO_UART7_RX
|
||||
#define PX4IO_SERIAL_BASE STM32_UART7_BASE
|
||||
#define PX4IO_SERIAL_VECTOR STM32_IRQ_UART7
|
||||
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_UART7_TX
|
||||
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_UART7_RX
|
||||
#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB1ENR
|
||||
#define PX4IO_SERIAL_RCC_EN RCC_APB1LENR_UART7EN
|
||||
#define PX4IO_SERIAL_CLOCK STM32_PCLK1_FREQUENCY
|
||||
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
|
||||
#define PX4IO_SERIAL_SWAPPED
|
||||
|
||||
|
||||
/* LEDs */
|
||||
#define GPIO_nLED_AMBER /* PG5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN5)
|
||||
|
||||
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
|
||||
#define BOARD_ARMED_LED LED_AMBER
|
||||
|
||||
|
||||
/* ADC channels */
|
||||
#define PX4_ADC_GPIO \
|
||||
/* PF11 */ GPIO_ADC1_INP2, \
|
||||
/* PC0 */ GPIO_ADC123_INP10, \
|
||||
/* PF13 */ GPIO_ADC2_INP2, \
|
||||
/* PB1 */ GPIO_ADC12_INP5, \
|
||||
/* PF12 */ GPIO_ADC1_INP6, \
|
||||
/* PF3 */ GPIO_ADC3_INP5
|
||||
|
||||
/* Define Channel numbers must match above GPIO pins */
|
||||
#define ADC_BATTERY1_VOLTAGE_CHANNEL 2 /* PF11: BATT_VOLTAGE_SENS */
|
||||
#define ADC_BATTERY1_CURRENT_CHANNEL 10 /* PC0: BATT_CURRENT_SENS */
|
||||
#define ADC_SCALED_V5_CHANNEL 2 /* PF13: VDD_5V_SENS */
|
||||
#define ADC_BATTERY2_VOLTAGE_CHANNEL 5 /* PB1: FMU_AUX_POWER_ADC1 */
|
||||
#define ADC_BATTERY2_CURRENT_CHANNEL 6 /* PF12: FMU_AUX_ADC2 */
|
||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 5 /* PF3: PRESSURE_SENS */
|
||||
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY1_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY1_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_AIRSPEED_VOLTAGE_CHANNEL))
|
||||
|
||||
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
|
||||
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
|
||||
|
||||
/* PWM */
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 6
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
#define BOARD_NUMBER_BRICKS 2
|
||||
#define GPIO_nVDD_BRICK1_VALID /* PE15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15) // VDD_BRICK_nVALID
|
||||
#define GPIO_nVDD_BRICK2_VALID /* PE4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN4) // VDD_BRICK2_nVALID
|
||||
#define GPIO_nVDD_USB_VALID /* PE3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN3) // VBUS_nVALID
|
||||
#define GPIO_VDD_3V3_SENSORS_EN /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) // VDD_3V3_SENSORS_EN
|
||||
#define GPIO_nVDD_5V_PERIPH_EN /* PF2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN2) // nVDD_5V_PERIPH_EN
|
||||
//#define GPIO_nVDD_5V_PERIPH_OC /* PD10 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN10) // VDD_5V_PERIPH_nOC
|
||||
//#define GPIO_nVDD_5V_HIPOWER_OC /* PF4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN4) // VDD_5V_HIPOWER_nOC
|
||||
#define GPIO_ICM42688P_CLKIN_EN /* PA8 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN8)
|
||||
|
||||
/* Tone alarm output */
|
||||
#define TONE_ALARM_TIMER 5 /* timer 5 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* PA0 TIM5_CH1 */
|
||||
|
||||
#define GPIO_BUZZER_1 /* PA0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0) // ALARM
|
||||
|
||||
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
|
||||
#define GPIO_TONE_ALARM GPIO_TIM5_CH1OUT_1
|
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer3 channel 1 */
|
||||
#define PWMIN_TIMER 3
|
||||
#define PWMIN_TIMER_CHANNEL /* T3C1 */ 1
|
||||
#define GPIO_PWM_IN /* PA6 */ GPIO_TIM3_CH1IN_1
|
||||
|
||||
/* 3 timers for PWM out */
|
||||
#define BOARD_NUM_IO_TIMERS 3
|
||||
|
||||
/* USB OTG VBUS is not connected, we use GPIO_nVDD_USB_VALID instead to determine USB being connected. */
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 12 /* use timer12 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
|
||||
#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID))
|
||||
#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
|
||||
#define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID))
|
||||
//#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_PERIPH_OC))
|
||||
//#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_nVDD_5V_HIPOWER_OC))
|
||||
|
||||
/* 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 BOARD_HAS_STATIC_MANIFEST 1
|
||||
|
||||
/* There is no FRAM/EEPROM */
|
||||
#define FLASH_BASED_PARAMS
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
#define PX4_GPIO_INIT_LIST { \
|
||||
PX4_ADC_GPIO, \
|
||||
GPIO_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
GPIO_CAN2_TX, \
|
||||
GPIO_CAN2_RX, \
|
||||
GPIO_nVDD_BRICK1_VALID, \
|
||||
GPIO_nVDD_BRICK1_VALID, \
|
||||
GPIO_nVDD_USB_VALID, \
|
||||
GPIO_VDD_3V3_SENSORS_EN, \
|
||||
GPIO_nVDD_5V_PERIPH_EN, \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C2_SCL), \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C2_SDA), \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C4_SCL), \
|
||||
PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C4_SDA), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D0), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D1), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D2), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_D3), \
|
||||
PX4_GPIO_PIN_OFF(GPIO_SDMMC1_CMD),\
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_ICM42688P_CLKIN_EN, \
|
||||
}
|
||||
|
||||
//GPIO_nVDD_5V_PERIPH_OC,
|
||||
//GPIO_nVDD_5V_HIPOWER_OC,
|
||||
|
||||
__BEGIN_DECLS
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
extern void board_peripheral_reset(int ms);
|
||||
|
||||
#include <px4_platform_common/board_common.h>
|
||||
#endif /* __ASSEMBLY__ */
|
||||
__END_DECLS
|
||||
@@ -0,0 +1,135 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 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
|
||||
|
||||
/****************************************************************************
|
||||
* 10-8--2016:
|
||||
* To simplify the ripple effect on the tools, we will be using
|
||||
* /dev/serial/by-id/<asterisk>PX4<asterisk> to locate PX4 devices. Therefore
|
||||
* moving forward all Bootloaders must contain the prefix "PX4 BL "
|
||||
* in the USBDEVICESTRING
|
||||
* This Change will be made in an upcoming BL release
|
||||
****************************************************************************/
|
||||
/*
|
||||
* Define usage to configure a bootloader
|
||||
*
|
||||
*
|
||||
* Constant example Usage
|
||||
* APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed
|
||||
* BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request
|
||||
* BOARD_FMUV2
|
||||
* INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading
|
||||
* INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading
|
||||
* USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string
|
||||
* USBPRODUCTID 0x0011 - PID Should match defconfig
|
||||
* BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom
|
||||
* delay provided by an APP FW
|
||||
* BOARD_TYPE 9 - Must match .prototype boad_id
|
||||
* _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection
|
||||
* BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector
|
||||
* BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector
|
||||
* BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time.
|
||||
* (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted
|
||||
* programmatically
|
||||
*
|
||||
* BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing.
|
||||
* This is to allow sectors to be reserved for app fw usage. That will NOT be erased
|
||||
* during a FW upgrade.
|
||||
* The default is 0, and selects the first sector to be erased, as the 0th entry in the
|
||||
* flash_sectors table. Which is the second physical sector of FLASH in the device.
|
||||
* The first physical sector of FLASH is used by the bootloader, and is not defined
|
||||
* in the table.
|
||||
*
|
||||
* APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus
|
||||
* BOOTLOADER_RESERVATION_SIZE will be deducted from
|
||||
* BOARD_FLASH_SIZE to determine the size of the App FW
|
||||
* and hence the address space of FLASH to erase and program.
|
||||
* USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.)
|
||||
* SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL
|
||||
*
|
||||
* * Other defines are somewhat self explanatory.
|
||||
*/
|
||||
|
||||
/* Boot device selection list*/
|
||||
#define USB0_DEV 0x01
|
||||
#define SERIAL0_DEV 0x02
|
||||
#define SERIAL1_DEV 0x04
|
||||
|
||||
#define APP_LOAD_ADDRESS 0x08020000
|
||||
#define BOOTLOADER_DELAY 5000
|
||||
#define INTERFACE_USB 1
|
||||
#define INTERFACE_USB_CONFIG "/dev/ttyACM0"
|
||||
#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS)
|
||||
|
||||
//#define USE_VBUS_PULL_DOWN
|
||||
#define INTERFACE_USART 1
|
||||
#define INTERFACE_USART_CONFIG "/dev/ttyS0,115200"
|
||||
#define BOOT_DELAY_ADDRESS 0x000001a0
|
||||
#define BOARD_TYPE 1069
|
||||
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
|
||||
#define BOARD_FLASH_SECTORS (14)
|
||||
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)
|
||||
|
||||
#define OSC_FREQ 24
|
||||
|
||||
#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_AMBER
|
||||
#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_AMBER
|
||||
#define BOARD_LED_ON 0
|
||||
#define BOARD_LED_OFF 1
|
||||
|
||||
#define SERIAL_BREAK_DETECT_DISABLED 1
|
||||
|
||||
#if !defined(ARCH_SN_MAX_LENGTH)
|
||||
# define ARCH_SN_MAX_LENGTH 12
|
||||
#endif
|
||||
|
||||
#if !defined(APP_RESERVATION_SIZE)
|
||||
# define APP_RESERVATION_SIZE 0
|
||||
#endif
|
||||
|
||||
#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE)
|
||||
# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1
|
||||
#endif
|
||||
|
||||
#if !defined(USB_DATA_ALIGN)
|
||||
# define USB_DATA_ALIGN
|
||||
#endif
|
||||
|
||||
#ifndef BOOT_DEVICES_SELECTION
|
||||
# define BOOT_DEVICES_SELECTION (USB0_DEV|SERIAL0_DEV|SERIAL1_DEV)
|
||||
#endif
|
||||
|
||||
#ifndef BOOT_DEVICES_FILTER_ONUSB
|
||||
# define BOOT_DEVICES_FILTER_ONUSB (USB0_DEV|SERIAL0_DEV|SERIAL1_DEV)
|
||||
#endif
|
||||
@@ -0,0 +1,39 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 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] = {
|
||||
initI2CBusExternal(2),
|
||||
initI2CBusExternal(4),
|
||||
};
|
||||
@@ -0,0 +1,221 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file init.c
|
||||
*
|
||||
* board-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 initialisation.
|
||||
*/
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#include <syslog.h>
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/sdio.h>
|
||||
#include <nuttx/mmcsd.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/gpio.h>
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
# include <parameters/flashparams/flashfs.h>
|
||||
#endif
|
||||
|
||||
#include <mpu.h>
|
||||
|
||||
__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)
|
||||
{
|
||||
/* Power off Interfaces */
|
||||
stm32_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, true);
|
||||
|
||||
/* wait for the peripheral rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||
|
||||
/* re-enable power */
|
||||
stm32_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, false);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* 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(6);
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the initialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void stm32_boardinitialize(void)
|
||||
{
|
||||
/* Reset PWM first thing */
|
||||
board_on_reset(-1);
|
||||
|
||||
/* configure pins */
|
||||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
|
||||
px4_gpio_init(gpio, arraySize(gpio));
|
||||
board_control_spi_sensors_power_configgpio();
|
||||
|
||||
/* configure LEDs */
|
||||
board_autoled_initialize();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* 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;
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||
* any failure to indicate the nature of the failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
/* Power on Interfaces */
|
||||
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, true);
|
||||
stm32_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, false);
|
||||
board_control_spi_sensors_power(true, 0xffff);
|
||||
|
||||
px4_platform_init();
|
||||
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_AMBER);
|
||||
|
||||
if (board_hardfault_init(2, true) != 0) {
|
||||
led_on(LED_AMBER);
|
||||
}
|
||||
|
||||
#ifdef CONFIG_MMCSD
|
||||
/* Mount the SDIO-based MMC/SD block driver */
|
||||
/* First, get an instance of the SDIO interface */
|
||||
struct sdio_dev_s *sdio_dev = sdio_initialize(0); // SDIO_SLOTNO 0 Only one slot
|
||||
|
||||
if (!sdio_dev) {
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0);
|
||||
}
|
||||
|
||||
if (mmcsd_slotinitialize(0, sdio_dev) != OK) {
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n");
|
||||
}
|
||||
|
||||
/* Assume that the SD card is inserted. What choice do we have? */
|
||||
sdio_mediachange(sdio_dev, true);
|
||||
#endif /* CONFIG_MMCSD */
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
static sector_descriptor_t params_sector_map[] = {
|
||||
{14, 128 * 1024, 0x081C0000},
|
||||
//{2, 32 * 1024, 0x081C8000}, -> MTD
|
||||
{0, 0, 0},
|
||||
};
|
||||
|
||||
/* Initialize the flashfs layer to use heap allocated memory */
|
||||
int result = parameter_flashfs_init(params_sector_map, NULL, 0);
|
||||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
led_on(LED_AMBER);
|
||||
return result;
|
||||
}
|
||||
|
||||
#endif /* FLASH_BASED_PARAMS */
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
|
||||
px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
}
|
||||
@@ -0,0 +1,110 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file led.c
|
||||
*
|
||||
* LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32_gpio.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from 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
|
||||
|
||||
# define xlat(p) (p)
|
||||
static uint32_t g_ledmap[] = {
|
||||
GPIO_nLED_AMBER,
|
||||
};
|
||||
|
||||
__EXPORT void led_init(void)
|
||||
{
|
||||
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
|
||||
if (g_ledmap[l] != 0) {
|
||||
stm32_configgpio(g_ledmap[l]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void phy_set_led(int led, bool state)
|
||||
{
|
||||
/* Drive Low to switch on */
|
||||
if (g_ledmap[led] != 0) {
|
||||
stm32_gpiowrite(g_ledmap[led], !state);
|
||||
}
|
||||
}
|
||||
|
||||
static bool phy_get_led(int led)
|
||||
{
|
||||
/* If Low it is on */
|
||||
if (g_ledmap[led] != 0) {
|
||||
return !stm32_gpioread(g_ledmap[led]);
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
__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)));
|
||||
}
|
||||
@@ -0,0 +1,60 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 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_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortE, GPIO::Pin9}), // ICM42688_0_CS
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortE, GPIO::Pin9}), // ICM42688_0_CS
|
||||
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortE, GPIO::Pin13}), // BARO_0_CS
|
||||
}),
|
||||
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
//initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin10}), // FRAM_CS
|
||||
initSPIDevice(DRV_MAG_DEVTYPE_RM3100, SPI::CS{GPIO::PortD, GPIO::Pin15}), // RM3100_CS
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortD, GPIO::Pin14}), // ICM42688_1_CS
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortD, GPIO::Pin14}), // ICM42688_1_CS
|
||||
|
||||
}),
|
||||
|
||||
initSPIBus(SPI::Bus::SPI4, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortF, GPIO::Pin5}), // ICM_2_CS
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortF, GPIO::Pin5}), // ICM_2_CS
|
||||
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortC, GPIO::Pin2}), // BARO_1_CS
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
||||
@@ -0,0 +1,52 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 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}),
|
||||
initIOTimer(Timer::Timer2, DMA{DMA::Index2}),
|
||||
initIOTimer(Timer::Timer3, DMA{DMA::Index2})
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}),
|
||||
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::Channel1}, {GPIO::PortA, GPIO::Pin6}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0})
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
initIOTimerChannelMapping(io_timers, timer_io_channels);
|
||||
@@ -0,0 +1,65 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file usb.c
|
||||
*
|
||||
* Board-specific USB functions.
|
||||
*/
|
||||
|
||||
#include "board_config.h"
|
||||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
#include <stm32_otg.h>
|
||||
#include <debug.h>
|
||||
#include <syslog.h>
|
||||
|
||||
/************************************************************************************
|
||||
* 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);
|
||||
}
|
||||
|
||||
int board_read_VBUS_state(void)
|
||||
{
|
||||
return BOARD_ADC_USB_VALID ? 0 : -1;
|
||||
}
|
||||
@@ -0,0 +1,33 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
|
||||
CONFIG_BOARD_OVERRIDE_UPLOAD_TARGET=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_DRIVERS_CUBERED_BRIDGE_SECONDARY=y
|
||||
CONFIG_MODULES_LOAD_MON=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BSONDUMP=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_GPIO=y
|
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=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_SYSTEM_TIME=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_VER=y
|
||||
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||
CONFIG_SYSTEMCMDS_MICROBENCH=y
|
||||
@@ -0,0 +1,13 @@
|
||||
{
|
||||
"board_id": 1070,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the CubePilot CubeRed Secondary board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "CubeRed-Secondary",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 1966080,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
@@ -0,0 +1,17 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
param set-default BAT1_V_DIV 10.1
|
||||
param set-default BAT2_V_DIV 10.1
|
||||
|
||||
param set-default BAT1_A_PER_V 17
|
||||
param set-default BAT2_A_PER_V 17
|
||||
|
||||
# Disable IMU thermal control
|
||||
param set-default SENS_EN_THERMAL 0
|
||||
|
||||
param set-default -s SENS_TEMP_ID 2621474
|
||||
|
||||
#set IOFW "/etc/extras/cubepilot_io-v2_default.bin"
|
||||
@@ -0,0 +1,6 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board specific extras
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
cubered_bridge_secondary start
|
||||
@@ -0,0 +1,2 @@
|
||||
#!/bin/sh
|
||||
|
||||
@@ -0,0 +1,13 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# Board specific sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
# TODO: start all three instances
|
||||
board_adc start
|
||||
|
||||
|
||||
# SPI2
|
||||
if ! icm42688p -s -b 2 -R 10 -c 12 -q start
|
||||
then
|
||||
icm45686 -s -b 2 -R 10 -c 12 start
|
||||
fi
|
||||
@@ -0,0 +1,258 @@
|
||||
/************************************************************************************
|
||||
* nuttx-config/include/board.h
|
||||
*
|
||||
* Copyright (C) 2020 Gregory Nutt. All rights reserved.
|
||||
* Authors: David Sidrane <david.sidrane@nscdg.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
************************************************************************************/
|
||||
#pragma once
|
||||
|
||||
#include "board_dma_map.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_sdmmc.h"
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The board provides the following clock sources:
|
||||
*
|
||||
* X1: 24 MHz crystal for HSE
|
||||
*
|
||||
* So we have these clock source available within the STM32
|
||||
*
|
||||
* HSI: 16 MHz RC factory-trimmed internal oscillator
|
||||
* 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
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
* PLL source is HSE = 24,000,000
|
||||
*
|
||||
* PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN
|
||||
* Subject to:
|
||||
*
|
||||
* 1 <= PLLM <= 63
|
||||
* 4 <= PLLN <= 512
|
||||
* 150 MHz <= PLL_VCOL <= 420MHz
|
||||
* 192 MHz <= PLL_VCOH <= 836MHz
|
||||
*
|
||||
* SYSCLK = PLL_VCO / PLLP
|
||||
* CPUCLK = SYSCLK / D1CPRE
|
||||
* Subject to
|
||||
*
|
||||
* PLLP1 = {2, 4, 6, 8, ..., 128}
|
||||
* PLLP2,3 = {2, 3, 4, ..., 128}
|
||||
* CPUCLK <= 480 MHz
|
||||
*/
|
||||
|
||||
/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR
|
||||
*
|
||||
* PLL1_VCO = (24,000,000 / 3) * 100 = 800 MHz
|
||||
*
|
||||
* PLL1P = PLL1_VCO/2 = 800 MHz / 2 = 400 MHz
|
||||
* PLL1Q = PLL1_VCO/8 = 800 MHz / 8 = 100 MHz
|
||||
* PLL1R = PLL1_VCO/2 = 800 MHz / 2 = 400 MHz
|
||||
*/
|
||||
#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE|RCC_PLLCFGR_PLL1RGE_4_8_MHZ|RCC_PLLCFGR_DIVP1EN|RCC_PLLCFGR_DIVQ1EN|RCC_PLLCFGR_DIVR1EN)
|
||||
#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(3)
|
||||
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(100)
|
||||
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
|
||||
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(10)
|
||||
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(2)
|
||||
|
||||
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 3) * 100)
|
||||
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
|
||||
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 10)
|
||||
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
|
||||
|
||||
/* PLL2 */
|
||||
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE|RCC_PLLCFGR_PLL2RGE_8_16_MHZ|RCC_PLLCFGR_DIVP2EN|RCC_PLLCFGR_DIVQ2EN|RCC_PLLCFGR_DIVR2EN)
|
||||
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(2)
|
||||
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(50)
|
||||
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(3)
|
||||
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(6)
|
||||
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(3)
|
||||
|
||||
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 50)
|
||||
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 3)
|
||||
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 6)
|
||||
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 3)
|
||||
|
||||
/* PLL3 */
|
||||
#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE|RCC_PLLCFGR_PLL3RGE_4_8_MHZ|RCC_PLLCFGR_DIVQ3EN)
|
||||
#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(6)
|
||||
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(72)
|
||||
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(3)
|
||||
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(6)
|
||||
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(9)
|
||||
|
||||
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 6) * 72)
|
||||
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 3)
|
||||
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 6)
|
||||
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 9)
|
||||
|
||||
/* SYSCLK = PLL1P = 400MHz
|
||||
* CPUCLK = SYSCLK / 1 = 400 MHz
|
||||
*/
|
||||
#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK)
|
||||
#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY)
|
||||
#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1)
|
||||
|
||||
/* Configure Clock Assignments */
|
||||
|
||||
/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max)
|
||||
* HCLK1 = HCLK2 = HCLK3 = HCLK4 = 200
|
||||
*/
|
||||
#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */
|
||||
#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */
|
||||
#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */
|
||||
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
|
||||
|
||||
/* APB1 clock (PCLK1) is HCLK/4 (120 MHz) */
|
||||
#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */
|
||||
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */
|
||||
#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
|
||||
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */
|
||||
#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */
|
||||
#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */
|
||||
#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */
|
||||
#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2)
|
||||
|
||||
/* Timer clock frequencies */
|
||||
|
||||
/* 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)
|
||||
|
||||
/* 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_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY)
|
||||
|
||||
/* Kernel Clock Configuration
|
||||
* Note: look at Table 54 in ST Manual
|
||||
*/
|
||||
#define STM32_RCC_D1CCIPR_SDMMCSEL RCC_D1CCIPR_SDMMC_PLL1
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI /* I2C123 clock source */
|
||||
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 /* SPI123 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 /* SPI45 clock source */
|
||||
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 /* USB 1 and 2 clock source */
|
||||
#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */
|
||||
|
||||
#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 /* ADC 1 2 3 clock source */
|
||||
|
||||
/* UART clock selection */
|
||||
/* reset to default to overwrite any changes done by any bootloader */
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC
|
||||
#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC
|
||||
|
||||
|
||||
/* FLASH wait states */
|
||||
#define BOARD_FLASH_WAITSTATES 2
|
||||
|
||||
/* UART/USART */
|
||||
|
||||
// USART2 -> /dev/ttyS0 -> ?
|
||||
// USART3 -> /dev/ttyS1 -> debug/SWD connector
|
||||
// UART4 -> /dev/ttyS2 -> ?
|
||||
// USART6 -> /dev/ttyS3 -> ?
|
||||
// UART7 -> /dev/ttyS4 -> to Primary
|
||||
// UART8 -> /dev/ttyS5 -> CONS
|
||||
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_2 /* PC10 */
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_2 /* PC11 */
|
||||
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_5 /* PD1 */
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_5 /* PD0 */
|
||||
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
#define GPIO_USART6_CTS GPIO_USART6_CTS_NSS_2 /* PG15 */
|
||||
#define GPIO_USART6_RTS GPIO_USART6_RTS_2 /* PG8 */
|
||||
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
|
||||
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
|
||||
|
||||
/* CAN */
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_2 /* PB8 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_1 /* PA12 */
|
||||
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_2 /* PB5 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_2 /* PB6 */
|
||||
|
||||
|
||||
/* SPI */
|
||||
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
|
||||
|
||||
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_2) /* PB3 */
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_2 /* PB4 */
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */
|
||||
|
||||
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_4) /* PB13 */
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_2 /* PC2 */
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_2 /* PC1 */
|
||||
|
||||
@@ -0,0 +1,54 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
|
||||
// DMA 1
|
||||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0
|
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0
|
||||
|
||||
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0
|
||||
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0
|
||||
|
||||
#define DMAMAP_SPI4_RX DMAMAP_DMA12_SPI4RX_0
|
||||
#define DMAMAP_SPI4_TX DMAMAP_DMA12_SPI4TX_0
|
||||
|
||||
// Note: the UART7_RX must not be on DMA channel 1. Channels 0, 2, 3, ... seem to be ok.
|
||||
// if it is on channel 1 we see weird cache coherency issues. Suddenly the last two chars are
|
||||
// "leftovers" from previous FIFO buffer rounds.
|
||||
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_0
|
||||
#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_0
|
||||
|
||||
// DMA 2
|
||||
// Timer 1
|
||||
// Timer 2
|
||||
@@ -0,0 +1,212 @@
|
||||
#
|
||||
# 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_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/cubepilot/cubered-secondary/nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H747XI=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=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_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=79954
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
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_PIPE_MAXSIZE=1024
|
||||
CONFIG_DEV_PIPE_SIZE=70
|
||||
CONFIG_DEV_URANDOM=y
|
||||
CONFIG_EXPERIMENTAL=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_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_INIT_ENTRYPOINT="nsh_main"
|
||||
CONFIG_INIT_STACKSIZE=3194
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_MAX_EXITFUNS=1
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MM_REGIONS=4
|
||||
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_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_SEM_PREALLOCHOLDERS=32
|
||||
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_STM32H7_ADC1=y
|
||||
CONFIG_STM32H7_ADC3=y
|
||||
CONFIG_STM32H7_BBSRAM=y
|
||||
CONFIG_STM32H7_BBSRAM_FILES=5
|
||||
CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_PWR_DIRECT_SMPS_SUPPLY=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_HSECLOCK=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
|
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32H7_SPI2=y
|
||||
CONFIG_STM32H7_SPI2_DMA=y
|
||||
CONFIG_STM32H7_SPI2_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_TIM12=y
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM2=y
|
||||
CONFIG_STM32H7_TIM3=y
|
||||
CONFIG_STM32H7_UART7=y
|
||||
CONFIG_STM32H7_UART8=y
|
||||
CONFIG_STM32H7_USART3=y
|
||||
CONFIG_STM32H7_USART_BREAKS=y
|
||||
CONFIG_STM32H7_USART_INVERT=y
|
||||
CONFIG_STM32H7_USART_SINGLEWIRE=y
|
||||
CONFIG_STM32H7_USART_SWAP=y
|
||||
CONFIG_SYSTEM_NSH=y
|
||||
CONFIG_SYSTEM_SYSTEM=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TTY_SIGINT=y
|
||||
CONFIG_TTY_SIGTSTP=y
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_RXBUFSIZE=600
|
||||
CONFIG_UART7_TXBUFSIZE=1500
|
||||
CONFIG_UART7_RXDMA=y
|
||||
CONFIG_UART7_TXDMA=y
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=600
|
||||
CONFIG_UART8_SERIAL_CONSOLE=y
|
||||
CONFIG_UART8_TXBUFSIZE=1500
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_RXBUFSIZE=600
|
||||
CONFIG_USART3_TXBUFSIZE=3000
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
CONFIG_WATCHDOG=y
|
||||
@@ -0,0 +1,228 @@
|
||||
/****************************************************************************
|
||||
* scripts/script.ld
|
||||
*
|
||||
* Copyright (C) 2020 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 board uses an STM32H757ZI and has 2048Kb of main FLASH memory.
|
||||
* The flash memory is partitioned into a User Flash memory and a System
|
||||
* Flash memory. Each of these memories has two banks:
|
||||
*
|
||||
* 1) User Flash memory:
|
||||
*
|
||||
* Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each
|
||||
* Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each
|
||||
*
|
||||
* 2) System Flash memory:
|
||||
*
|
||||
* Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector
|
||||
* Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector
|
||||
*
|
||||
* 3) User option bytes for user configuration, only in Bank 1.
|
||||
*
|
||||
* In the STM32H757ZI, 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 memory at 0x0800:0000
|
||||
* 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0].
|
||||
* ST programmed value: System bootloader at 0x1FF0:0000
|
||||
*
|
||||
* There's a switch on board, the BOOT0 pin is at ground so by default,
|
||||
* the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is
|
||||
* drepresed, then the boot will be from 0x1FF0:0000
|
||||
*
|
||||
* The STM32H757ZI also has 1024Kb of data SRAM.
|
||||
* SRAM is split up into several blocks and into three power domains:
|
||||
*
|
||||
* 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with
|
||||
* 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus
|
||||
*
|
||||
* 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000
|
||||
*
|
||||
* The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit
|
||||
* DTCM ports. The DTCM-RAM could be used for critical real-time
|
||||
* data, such as interrupt service routines or stack / heap memory.
|
||||
* Both DTCM-RAMs can be used in parallel (for load/store operations)
|
||||
* thanks to the Cortex-M7 dual issue capability.
|
||||
*
|
||||
* 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000
|
||||
*
|
||||
* This RAM is connected to ITCM 64-bit interface designed for
|
||||
* execution of critical real-times routines by the CPU.
|
||||
*
|
||||
* 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA
|
||||
* through D1 domain AXI bus matrix
|
||||
*
|
||||
* 2.1) 512Kb of SRAM beginning at address 0x2400:0000
|
||||
*
|
||||
* 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA
|
||||
* through D2 domain AHB bus matrix
|
||||
*
|
||||
* 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000
|
||||
* 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000
|
||||
* 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000
|
||||
*
|
||||
* SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000
|
||||
*
|
||||
* 4) AHB SRAM (D3 domain) accessible by most of system masters
|
||||
* through D3 domain AHB bus matrix
|
||||
*
|
||||
* 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000
|
||||
* 4.1) 4Kb of backup RAM beginning at address 0x3880:0000
|
||||
*
|
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
|
||||
* where the code expects to begin execution by jumping to the entry point in
|
||||
* the 0x0800:0000 address range.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1664K /* params in last two sectors */
|
||||
|
||||
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
|
||||
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
|
||||
SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */
|
||||
SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */
|
||||
SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */
|
||||
SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */
|
||||
BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
|
||||
}
|
||||
|
||||
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
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > FLASH
|
||||
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > FLASH
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > FLASH
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
|
||||
/* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */
|
||||
. = ALIGN(16);
|
||||
FILL(0xffff)
|
||||
. += 16;
|
||||
} > AXI_SRAM AT > FLASH = 0xffff
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > AXI_SRAM
|
||||
|
||||
/* Emit the the D3 power domain section for locating BDMA data */
|
||||
|
||||
.sram4_reserve (NOLOAD) :
|
||||
{
|
||||
*(.sram4)
|
||||
. = ALIGN(4);
|
||||
_sram4_heap_start = ABSOLUTE(.);
|
||||
} > SRAM4
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
||||
@@ -0,0 +1,63 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2025 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.
|
||||
#
|
||||
############################################################################
|
||||
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
|
||||
add_library(drivers_board
|
||||
bootloader_main.c
|
||||
usb.c
|
||||
)
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
nuttx_arch
|
||||
nuttx_drivers
|
||||
bootloader
|
||||
)
|
||||
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common)
|
||||
|
||||
else()
|
||||
add_library(drivers_board
|
||||
init.c
|
||||
spi.cpp
|
||||
timer_config.cpp
|
||||
led.c
|
||||
)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
arch_io_pins
|
||||
arch_spi
|
||||
drivers__led
|
||||
nuttx_arch
|
||||
nuttx_drivers
|
||||
px4_layer
|
||||
)
|
||||
endif()
|
||||
@@ -0,0 +1,153 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2025 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
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
/**
|
||||
* If NuttX is built without support for SMPS it can brick the hardware.
|
||||
* Therefore, we make sure the NuttX headers are correct.
|
||||
*/
|
||||
#include "hardware/stm32h7x3xx_pwr.h"
|
||||
#if STM32_PWR_CR3_SMPSEXTHP != (1 << 3)
|
||||
# error "No SMPS support in NuttX submodule";
|
||||
#endif
|
||||
|
||||
|
||||
/* LEDs */
|
||||
#define GPIO_nLED_AMBER /* PD10 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
|
||||
#define GPIO_nLED_SAFETY /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5)
|
||||
|
||||
//#define BOARD_HAS_CONTROL_STATUS_LEDS 1
|
||||
//#define BOARD_ARMED_LED LED_AMBER
|
||||
|
||||
|
||||
/* ADC channels */
|
||||
#define PX4_ADC_GPIO \
|
||||
/* PA6 */ GPIO_ADC12_INP3, \
|
||||
/* PF11 */ GPIO_ADC1_INP2
|
||||
|
||||
#define ADC_RSSI_IN_CHANNEL 3
|
||||
#define ADC_SERVO_SENSE_CHANNEL 2
|
||||
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_RSSI_IN_CHANNEL) | \
|
||||
(1 << ADC_SERVO_SENSE_CHANNEL))
|
||||
|
||||
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
|
||||
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
|
||||
|
||||
/* PWM */
|
||||
// For now, just support the basic 8 output channels, see timer_config.cpp for the rest.
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
#define BOARD_NUMBER_BRICKS 2
|
||||
#define GPIO_VDD_BRICK1_VALID /* PG0 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_VDD_BRICK2_VALID /* PG5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN5) // Backup
|
||||
|
||||
|
||||
/* 3 timers for PWM out */
|
||||
#define BOARD_NUM_IO_TIMERS 5
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 12 /* use timer12 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
|
||||
#define BOARD_ADC_BRICK1_VALID (px4_arch_gpioread(GPIO_VDD_BRICK1_VALID))
|
||||
#define BOARD_ADC_BRICK2_VALID (px4_arch_gpioread(GPIO_VDD_BRICK2_VALID))
|
||||
|
||||
/* 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
|
||||
|
||||
/* Debug GPIOs for testing - PC7 for UART IDLE debugging */
|
||||
#define GPIO_UART_IDLE_DEBUG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN7) // PC7
|
||||
//#define GPIO_UART_IDLE_DEBUG_READ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTA|GPIO_PIN3)
|
||||
|
||||
|
||||
// #define GPIO_VOLT_SET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN1)
|
||||
|
||||
// PWM Direction Control - CRITICAL: Must match hardware requirements!
|
||||
// For driving Opto's (unidirectional output): BIDIR=LOW, UNIDIR=HIGH
|
||||
// For bidirectional with input monitoring: BIDIR=HIGH, UNIDIR=LOW
|
||||
// DANGER: Never enable both simultaneously - will damage hardware!
|
||||
//
|
||||
// Current config: Unidirectional mode (matches ArduPilot)
|
||||
// PB0 BIDIR_ENABLED OUTPUT LOW GPIO(4)
|
||||
// PA7 HP_UNIDIR_ENABLED OUTPUT HIGH GPIO(5)
|
||||
#define GPIO_BIDIR_DISABLED (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_UNIDIR_ENABLED (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN7)
|
||||
|
||||
|
||||
//#define BOARD_HAS_STATIC_MANIFEST 1
|
||||
|
||||
/* There is no FRAM/EEPROM */
|
||||
#define FLASH_BASED_PARAMS
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
#define PX4_GPIO_INIT_LIST { \
|
||||
PX4_ADC_GPIO, \
|
||||
GPIO_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
GPIO_CAN2_TX, \
|
||||
GPIO_CAN2_RX, \
|
||||
GPIO_VDD_BRICK1_VALID, \
|
||||
GPIO_VDD_BRICK2_VALID, \
|
||||
GPIO_UART_IDLE_DEBUG, \
|
||||
GPIO_BIDIR_DISABLED, \
|
||||
GPIO_UNIDIR_ENABLED, \
|
||||
}
|
||||
|
||||
__BEGIN_DECLS
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
extern void board_peripheral_reset(int ms);
|
||||
|
||||
#include <px4_platform_common/board_common.h>
|
||||
#endif /* __ASSEMBLY__ */
|
||||
__END_DECLS
|
||||
@@ -0,0 +1,135 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 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
|
||||
|
||||
/****************************************************************************
|
||||
* 10-8--2016:
|
||||
* To simplify the ripple effect on the tools, we will be using
|
||||
* /dev/serial/by-id/<asterisk>PX4<asterisk> to locate PX4 devices. Therefore
|
||||
* moving forward all Bootloaders must contain the prefix "PX4 BL "
|
||||
* in the USBDEVICESTRING
|
||||
* This Change will be made in an upcoming BL release
|
||||
****************************************************************************/
|
||||
/*
|
||||
* Define usage to configure a bootloader
|
||||
*
|
||||
*
|
||||
* Constant example Usage
|
||||
* APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed
|
||||
* BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request
|
||||
* BOARD_FMUV2
|
||||
* INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading
|
||||
* INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading
|
||||
* USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string
|
||||
* USBPRODUCTID 0x0011 - PID Should match defconfig
|
||||
* BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom
|
||||
* delay provided by an APP FW
|
||||
* BOARD_TYPE 9 - Must match .prototype boad_id
|
||||
* _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection
|
||||
* BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector
|
||||
* BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector
|
||||
* BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time.
|
||||
* (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted
|
||||
* programmatically
|
||||
*
|
||||
* BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing.
|
||||
* This is to allow sectors to be reserved for app fw usage. That will NOT be erased
|
||||
* during a FW upgrade.
|
||||
* The default is 0, and selects the first sector to be erased, as the 0th entry in the
|
||||
* flash_sectors table. Which is the second physical sector of FLASH in the device.
|
||||
* The first physical sector of FLASH is used by the bootloader, and is not defined
|
||||
* in the table.
|
||||
*
|
||||
* APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus
|
||||
* BOOTLOADER_RESERVATION_SIZE will be deducted from
|
||||
* BOARD_FLASH_SIZE to determine the size of the App FW
|
||||
* and hence the address space of FLASH to erase and program.
|
||||
* USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.)
|
||||
* SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL
|
||||
*
|
||||
* * Other defines are somewhat self explanatory.
|
||||
*/
|
||||
|
||||
/* Boot device selection list*/
|
||||
#define USB0_DEV 0x01
|
||||
#define SERIAL0_DEV 0x02
|
||||
#define SERIAL1_DEV 0x04
|
||||
|
||||
#define APP_LOAD_ADDRESS 0x08020000
|
||||
#define BOOTLOADER_DELAY 5000
|
||||
#define INTERFACE_USB 1
|
||||
#define INTERFACE_USB_CONFIG "/dev/ttyACM0"
|
||||
#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS)
|
||||
|
||||
//#define USE_VBUS_PULL_DOWN
|
||||
#define INTERFACE_USART 1
|
||||
#define INTERFACE_USART_CONFIG "/dev/ttyS0,115200"
|
||||
#define BOOT_DELAY_ADDRESS 0x000001a0
|
||||
#define BOARD_TYPE 1069
|
||||
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
|
||||
#define BOARD_FLASH_SECTORS (14)
|
||||
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)
|
||||
|
||||
#define OSC_FREQ 24
|
||||
|
||||
#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_AMBER
|
||||
#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_AMBER
|
||||
#define BOARD_LED_ON 0
|
||||
#define BOARD_LED_OFF 1
|
||||
|
||||
#define SERIAL_BREAK_DETECT_DISABLED 1
|
||||
|
||||
#if !defined(ARCH_SN_MAX_LENGTH)
|
||||
# define ARCH_SN_MAX_LENGTH 12
|
||||
#endif
|
||||
|
||||
#if !defined(APP_RESERVATION_SIZE)
|
||||
# define APP_RESERVATION_SIZE 0
|
||||
#endif
|
||||
|
||||
#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE)
|
||||
# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1
|
||||
#endif
|
||||
|
||||
#if !defined(USB_DATA_ALIGN)
|
||||
# define USB_DATA_ALIGN
|
||||
#endif
|
||||
|
||||
#ifndef BOOT_DEVICES_SELECTION
|
||||
# define BOOT_DEVICES_SELECTION (USB0_DEV|SERIAL0_DEV|SERIAL1_DEV)
|
||||
#endif
|
||||
|
||||
#ifndef BOOT_DEVICES_FILTER_ONUSB
|
||||
# define BOOT_DEVICES_FILTER_ONUSB (USB0_DEV|SERIAL0_DEV|SERIAL1_DEV)
|
||||
#endif
|
||||
@@ -0,0 +1,194 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file init.c
|
||||
*
|
||||
* board-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 initialisation.
|
||||
*/
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#include <syslog.h>
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/sdio.h>
|
||||
#include <nuttx/mmcsd.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/gpio.h>
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
# include <parameters/flashparams/flashfs.h>
|
||||
#endif
|
||||
|
||||
#include <mpu.h>
|
||||
|
||||
__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)
|
||||
{
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* 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(6);
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the initialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void stm32_boardinitialize(void)
|
||||
{
|
||||
/* Reset PWM first thing */
|
||||
board_on_reset(-1);
|
||||
|
||||
/* configure pins */
|
||||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
|
||||
px4_gpio_init(gpio, arraySize(gpio));
|
||||
board_control_spi_sensors_power_configgpio();
|
||||
|
||||
/* configure LEDs */
|
||||
board_autoled_initialize();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* 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;
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||
* any failure to indicate the nature of the failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
/* Power on Interfaces */
|
||||
board_control_spi_sensors_power(true, 0xffff);
|
||||
|
||||
px4_platform_init();
|
||||
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_AMBER);
|
||||
led_off(LED_SAFETY);
|
||||
|
||||
if (board_hardfault_init(2, true) != 0) {
|
||||
led_on(LED_AMBER);
|
||||
}
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
static sector_descriptor_t params_sector_map[] = {
|
||||
{14, 128 * 1024, 0x081C0000},
|
||||
//{2, 32 * 1024, 0x081C8000}, -> MTD
|
||||
{0, 0, 0},
|
||||
};
|
||||
|
||||
/* Initialize the flashfs layer to use heap allocated memory */
|
||||
int result = parameter_flashfs_init(params_sector_map, NULL, 0);
|
||||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
led_on(LED_AMBER);
|
||||
return result;
|
||||
}
|
||||
|
||||
#endif /* FLASH_BASED_PARAMS */
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
|
||||
px4_platform_configure();
|
||||
|
||||
return OK;
|
||||
}
|
||||
@@ -0,0 +1,111 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file led.c
|
||||
*
|
||||
* LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32_gpio.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from 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
|
||||
|
||||
# define xlat(p) (p)
|
||||
static uint32_t g_ledmap[] = {
|
||||
GPIO_nLED_AMBER,
|
||||
GPIO_nLED_SAFETY,
|
||||
};
|
||||
|
||||
__EXPORT void led_init(void)
|
||||
{
|
||||
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
|
||||
if (g_ledmap[l] != 0) {
|
||||
stm32_configgpio(g_ledmap[l]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void phy_set_led(int led, bool state)
|
||||
{
|
||||
/* Drive Low to switch on */
|
||||
if (g_ledmap[led] != 0) {
|
||||
stm32_gpiowrite(g_ledmap[led], !state);
|
||||
}
|
||||
}
|
||||
|
||||
static bool phy_get_led(int led)
|
||||
{
|
||||
/* If Low it is on */
|
||||
if (g_ledmap[led] != 0) {
|
||||
return !stm32_gpioread(g_ledmap[led]);
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
__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)));
|
||||
}
|
||||
@@ -0,0 +1,45 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 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::SPI2, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortB, GPIO::Pin12}),
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortB, GPIO::Pin12}),
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
||||
@@ -0,0 +1,79 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2025 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>
|
||||
|
||||
// CubeRed Secondary IO Board - 8 PWM output channels
|
||||
//
|
||||
// Hardware design: Each PWM output has dual timer pins routed through level shifters
|
||||
// with direction control via PA7 (unidirectional enable) and PB0 (bidirectional enable).
|
||||
//
|
||||
// Active timers:
|
||||
// - Timer1 CH1-4: PWM outputs 1-4 (PA8, PA9, PA10, PA11)
|
||||
// - Timer2 CH1-4: PWM outputs 5-8 (PA5, PA1, PB10, PB11)
|
||||
//
|
||||
// Inactive timers (commented below):
|
||||
// - Timer3/4/5: Alternative timer pins for PWM monitoring in bidirectional mode
|
||||
// These are not currently used, but kept for potential future bidirectional support.
|
||||
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::Timer1, DMA{DMA::Index2}),
|
||||
initIOTimer(Timer::Timer2, DMA{DMA::Index2}),
|
||||
//initIOTimer(Timer::Timer3),
|
||||
//initIOTimer(Timer::Timer4),
|
||||
//initIOTimer(Timer::Timer5),
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortA, GPIO::Pin8}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortA, GPIO::Pin9}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortA, GPIO::Pin10}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortA, GPIO::Pin11}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel1}, {GPIO::PortA, GPIO::Pin5}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel2}, {GPIO::PortA, GPIO::Pin1}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel3}, {GPIO::PortB, GPIO::Pin10}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortB, GPIO::Pin11}),
|
||||
// Alternative timer channels for potential bidirectional PWM monitoring:
|
||||
//initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortC, GPIO::Pin9}),
|
||||
//initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel1}, {GPIO::PortD, GPIO::Pin12}),
|
||||
//initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortB, GPIO::Pin7}),
|
||||
//initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}),
|
||||
//initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel4}, {GPIO::PortB, GPIO::Pin9}),
|
||||
//initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortA, GPIO::Pin0}),
|
||||
//initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortA, GPIO::Pin2}),
|
||||
//initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}),
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
initIOTimerChannelMapping(io_timers, timer_io_channels);
|
||||
@@ -0,0 +1,3 @@
|
||||
menu "CubeRed bridge"
|
||||
rsource "*/Kconfig"
|
||||
endmenu
|
||||
@@ -0,0 +1,49 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE drivers__cubered_bridge_primary
|
||||
MAIN cubered_bridge_primary
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
cubered_bridge_primary.cpp
|
||||
cubered_bridge_primary_serial.cpp
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
cubered_bridge_primary_params.yaml
|
||||
DEPENDS
|
||||
arch_px4io_serial
|
||||
button_publisher
|
||||
circuit_breaker
|
||||
mixer_module
|
||||
)
|
||||
@@ -0,0 +1,8 @@
|
||||
menuconfig DRIVERS_CUBERED_BRIDGE_PRIMARY
|
||||
bool "cubered_bridge_primary"
|
||||
default n
|
||||
depends on PLATFORM_NUTTX
|
||||
---help---
|
||||
Enable the CubeRed bridge driver running on the primary MCU.
|
||||
Talks over the IO serial link to the cubered_bridge_secondary
|
||||
running on the secondary MCU, using the PX4IO register protocol.
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,48 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4io_driver.h
|
||||
*
|
||||
* Interface for PX4IO
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#ifdef PX4IO_SERIAL_BASE
|
||||
#include <drivers/device/device.h>
|
||||
|
||||
device::Device *PX4IO_serial_interface();
|
||||
#endif
|
||||
@@ -0,0 +1,10 @@
|
||||
module_name: px4io
|
||||
parameters:
|
||||
- group: PWM Outputs
|
||||
definitions:
|
||||
PWM_SBUS_MODE:
|
||||
description:
|
||||
short: S.BUS out
|
||||
long: Set to 1 to enable S.BUS version 1 output instead of RSSI.
|
||||
type: boolean
|
||||
default: 0
|
||||
@@ -0,0 +1,223 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2015 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4io_serial.cpp
|
||||
*
|
||||
* Serial interface for PX4IO
|
||||
*/
|
||||
|
||||
#include "cubered_bridge_primary_driver.h"
|
||||
|
||||
#include <px4_arch/px4io_serial.h>
|
||||
|
||||
static PX4IO_serial *g_interface;
|
||||
|
||||
device::Device
|
||||
*PX4IO_serial_interface()
|
||||
{
|
||||
return new ArchPX4IOSerial();
|
||||
}
|
||||
|
||||
PX4IO_serial::PX4IO_serial() :
|
||||
Device("PX4IO_serial"),
|
||||
_pc_txns(perf_alloc(PC_ELAPSED, MODULE_NAME": txns")),
|
||||
_pc_retries(perf_alloc(PC_COUNT, MODULE_NAME": retries")),
|
||||
_pc_timeouts(perf_alloc(PC_COUNT, MODULE_NAME": timeouts")),
|
||||
_pc_crcerrs(perf_alloc(PC_COUNT, MODULE_NAME": crcerrs")),
|
||||
_pc_protoerrs(perf_alloc(PC_COUNT, MODULE_NAME": protoerrs")),
|
||||
_pc_uerrs(perf_alloc(PC_COUNT, MODULE_NAME": uarterrs")),
|
||||
_pc_idle(perf_alloc(PC_COUNT, MODULE_NAME": idle")),
|
||||
_pc_badidle(perf_alloc(PC_COUNT, MODULE_NAME": badidle")),
|
||||
_bus_semaphore(SEM_INITIALIZER(0))
|
||||
{
|
||||
g_interface = this;
|
||||
}
|
||||
|
||||
PX4IO_serial::~PX4IO_serial()
|
||||
{
|
||||
/* kill our semaphores */
|
||||
px4_sem_destroy(&_bus_semaphore);
|
||||
|
||||
perf_free(_pc_txns);
|
||||
perf_free(_pc_retries);
|
||||
perf_free(_pc_timeouts);
|
||||
perf_free(_pc_crcerrs);
|
||||
perf_free(_pc_protoerrs);
|
||||
perf_free(_pc_uerrs);
|
||||
perf_free(_pc_idle);
|
||||
perf_free(_pc_badidle);
|
||||
|
||||
if (g_interface == this) {
|
||||
g_interface = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_serial::init(IOPacket *io_buffer)
|
||||
{
|
||||
_io_buffer_ptr = io_buffer;
|
||||
/* create semaphores */
|
||||
// in case the sub-class impl fails, the semaphore is cleaned up by destructor.
|
||||
px4_sem_init(&_bus_semaphore, 0, 1);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_serial::write(unsigned address, void *data, unsigned count)
|
||||
{
|
||||
uint8_t page = address >> 8;
|
||||
uint8_t offset = address & 0xff;
|
||||
const uint16_t *values = reinterpret_cast<const uint16_t *>(data);
|
||||
|
||||
if (count > PKT_MAX_REGS) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
px4_sem_wait(&_bus_semaphore);
|
||||
|
||||
int result;
|
||||
|
||||
for (unsigned retries = 0; retries < 3; retries++) {
|
||||
_io_buffer_ptr->count_code = count | PKT_CODE_WRITE;
|
||||
_io_buffer_ptr->page = page;
|
||||
_io_buffer_ptr->offset = offset;
|
||||
memcpy((void *)&_io_buffer_ptr->regs[0], (void *)values, (2 * count));
|
||||
|
||||
for (unsigned i = count; i < PKT_MAX_REGS; i++) {
|
||||
_io_buffer_ptr->regs[i] = 0x55aa;
|
||||
}
|
||||
|
||||
_io_buffer_ptr->crc = 0;
|
||||
_io_buffer_ptr->crc = crc_packet(_io_buffer_ptr);
|
||||
|
||||
/* start the transaction and wait for it to complete */
|
||||
result = _bus_exchange(_io_buffer_ptr);
|
||||
|
||||
/* successful transaction? */
|
||||
if (result == OK) {
|
||||
|
||||
/* check result in packet */
|
||||
if (PKT_CODE(*_io_buffer_ptr) == PKT_CODE_ERROR) {
|
||||
|
||||
/* IO didn't like it - no point retrying */
|
||||
result = -EINVAL;
|
||||
perf_count(_pc_protoerrs);
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
perf_count(_pc_retries);
|
||||
}
|
||||
|
||||
px4_sem_post(&_bus_semaphore);
|
||||
|
||||
if (result == OK) {
|
||||
result = count;
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_serial::read(unsigned address, void *data, unsigned count)
|
||||
{
|
||||
uint8_t page = address >> 8;
|
||||
uint8_t offset = address & 0xff;
|
||||
uint16_t *values = reinterpret_cast<uint16_t *>(data);
|
||||
|
||||
if (count > PKT_MAX_REGS) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
px4_sem_wait(&_bus_semaphore);
|
||||
|
||||
int result;
|
||||
|
||||
for (unsigned retries = 0; retries < 3; retries++) {
|
||||
|
||||
/* Clear the entire packet to ensure no stale data */
|
||||
memset(_io_buffer_ptr, 0, sizeof(IOPacket));
|
||||
|
||||
_io_buffer_ptr->count_code = count | PKT_CODE_READ;
|
||||
_io_buffer_ptr->page = page;
|
||||
_io_buffer_ptr->offset = offset;
|
||||
|
||||
_io_buffer_ptr->crc = 0;
|
||||
_io_buffer_ptr->crc = crc_packet(_io_buffer_ptr);
|
||||
|
||||
/* start the transaction and wait for it to complete */
|
||||
result = _bus_exchange(_io_buffer_ptr);
|
||||
|
||||
/* successful transaction? */
|
||||
if (result == OK) {
|
||||
|
||||
/* check result in packet */
|
||||
if (PKT_CODE(*_io_buffer_ptr) == PKT_CODE_ERROR) {
|
||||
|
||||
/* IO didn't like it - no point retrying */
|
||||
result = -EINVAL;
|
||||
perf_count(_pc_protoerrs);
|
||||
|
||||
/* compare the received count with the expected count */
|
||||
|
||||
} else if (PKT_COUNT(*_io_buffer_ptr) != count) {
|
||||
|
||||
/* IO returned the wrong number of registers - no point retrying */
|
||||
result = -EIO;
|
||||
perf_count(_pc_protoerrs);
|
||||
|
||||
/* successful read */
|
||||
|
||||
} else {
|
||||
|
||||
/* copy back the result */
|
||||
memcpy(values, &_io_buffer_ptr->regs[0], (2 * count));
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
perf_count(_pc_retries);
|
||||
}
|
||||
|
||||
px4_sem_post(&_bus_semaphore);
|
||||
|
||||
if (result == OK) {
|
||||
result = count;
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
@@ -0,0 +1,30 @@
|
||||
module_name: PWM MAIN
|
||||
actuator_output:
|
||||
output_groups:
|
||||
- generator: pwm
|
||||
param_prefix: PWM_MAIN
|
||||
channel_labels: ['MAIN', 'Capture']
|
||||
channel_label_module_name_prefix: false
|
||||
timer_config_file: "boards/cubepilot/cubered-secondary/src/timer_config.cpp"
|
||||
standard_params:
|
||||
disarmed: { min: 800, max: 2200, default: 1000 }
|
||||
min: { min: 800, max: 1400, default: 1000 }
|
||||
center: { min: 800, max: 2200}
|
||||
max: { min: 1600, max: 2200, default: 2000 }
|
||||
failsafe: { min: 800, max: 2200 }
|
||||
pwm_timer_param:
|
||||
description:
|
||||
short: Output Protocol Configuration for ${label}
|
||||
long: |
|
||||
Select which Output Protocol to use for outputs ${label}.
|
||||
|
||||
Custom PWM rates can be used by directly setting any value >0.
|
||||
type: enum
|
||||
default: 400
|
||||
values:
|
||||
-1: OneShot
|
||||
50: PWM 50 Hz
|
||||
100: PWM 100 Hz
|
||||
200: PWM 200 Hz
|
||||
400: PWM 400 Hz
|
||||
reboot_required: true
|
||||
@@ -0,0 +1,41 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
px4_add_module(
|
||||
MODULE drivers__cubered_bridge_secondary
|
||||
MAIN cubered_bridge_secondary
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
cubered_bridge_secondary.cpp
|
||||
cubered_bridge_secondary.h
|
||||
)
|
||||
@@ -0,0 +1,5 @@
|
||||
menuconfig DRIVERS_CUBERED_BRIDGE_SECONDARY
|
||||
bool "cubered_bridge_secondary"
|
||||
default n
|
||||
---help---
|
||||
Enable support for CubeRed IO module - PX4IO simulation for CubeRed Secondary
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,132 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2025 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 cubered_bridge_secondary.h
|
||||
*
|
||||
* CubeRed IO Module - PX4IO simulation for CubeRed Secondary
|
||||
*
|
||||
* This module simulates PX4IO functionality on the CubeRed Secondary
|
||||
* by providing low-latency serial communication on ttyS4.
|
||||
*
|
||||
* @author PX4 Development Team
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/defines.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
|
||||
#include <px4_platform_common/posix.h>
|
||||
|
||||
#include <board_config.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <px4_arch/io_timer.h>
|
||||
#include <px4_platform/gpio.h>
|
||||
|
||||
// Include PX4IO protocol definitions
|
||||
#include <modules/px4iofirmware/protocol.h>
|
||||
|
||||
#include <termios.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <poll.h>
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
class CuberedBridgeSecondary : public ModuleBase
|
||||
{
|
||||
public:
|
||||
static Descriptor desc;
|
||||
|
||||
CuberedBridgeSecondary();
|
||||
~CuberedBridgeSecondary() override;
|
||||
|
||||
/** @see ModuleBase */
|
||||
static int task_spawn(int argc, char *argv[]);
|
||||
|
||||
static int run_trampoline(int argc, char *argv[]);
|
||||
|
||||
static CuberedBridgeSecondary *instantiate(int argc, char *argv[]);
|
||||
|
||||
/** @see ModuleBase */
|
||||
static int custom_command(int argc, char *argv[])
|
||||
{
|
||||
return print_usage("unknown command");
|
||||
}
|
||||
|
||||
/** @see ModuleBase */
|
||||
static int print_usage(const char *reason = nullptr);
|
||||
|
||||
/** @see ModuleBase */
|
||||
int print_status() override;
|
||||
|
||||
bool init();
|
||||
void run() override;
|
||||
|
||||
private:
|
||||
static constexpr const char *DEVICE_NAME = "/dev/ttyS1";
|
||||
static constexpr speed_t BAUDRATE = B1500000;
|
||||
static constexpr int POLL_TIMEOUT_MS = 1; // 1ms timeout for low latency
|
||||
|
||||
int _serial_fd{-1};
|
||||
|
||||
perf_counter_t _loop_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": loop")};
|
||||
perf_counter_t _loop_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": loop interval")};
|
||||
|
||||
// PWM output state
|
||||
bool _pwm_initialized{false};
|
||||
bool _pwm_armed{false};
|
||||
uint32_t _pwm_mask{0};
|
||||
int _timer_rates[MAX_IO_TIMERS] {};
|
||||
|
||||
void poll_and_process();
|
||||
void process_received_data(IOPacket &packet);
|
||||
void send_response(IOPacket &packet);
|
||||
void send_packet(IOPacket &packet);
|
||||
void send_error_response();
|
||||
void send_corrupt_response();
|
||||
void handle_read_request(IOPacket &packet);
|
||||
void handle_write_request(IOPacket &packet);
|
||||
bool validate_crc(IOPacket &packet);
|
||||
uint8_t calculate_crc(IOPacket &packet);
|
||||
|
||||
int init_serial();
|
||||
int init_pwm();
|
||||
void update_pwm_outputs();
|
||||
void set_pwm_armed(bool armed);
|
||||
};
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user