mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-24 21:37:34 +08:00
Compare commits
29 Commits
beta
...
autotune_enable
| Author | SHA1 | Date | |
|---|---|---|---|
| 728b10e0e0 | |||
| 36bbb4a190 | |||
| 1297780d28 | |||
| 59f6c69067 | |||
| 71f56df23b | |||
| d30fa62f40 | |||
| 65c5bd6906 | |||
| 056289892c | |||
| ead1cf00ff | |||
| 0d0bfc1937 | |||
| 66e73528a2 | |||
| 444b31be21 | |||
| b3acde4899 | |||
| 8ca8f12a24 | |||
| 0b63b8317a | |||
| 6e8f61c551 | |||
| d2d433290a | |||
| 7418d84001 | |||
| dc0af1ab9d | |||
| f03131cfd3 | |||
| faee1da630 | |||
| 104759b90c | |||
| 42c4e6b4fb | |||
| 54866b886e | |||
| 9c1f3306a4 | |||
| 1ca80ae6f6 | |||
| 3e3bb82331 | |||
| f32c3024b8 | |||
| 2297e66a9d |
Vendored
+15
@@ -141,6 +141,11 @@ CONFIG:
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: ark_can-flow_canbootloader
|
||||
ark_can-flow-mr_default:
|
||||
short: ark_can-flow-mr_default
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: ark_can-flow-mr_default
|
||||
ark_can-flow-mr_canbootloader:
|
||||
short: ark_can-flow-mr_canbootloader
|
||||
buildType: MinSizeRel
|
||||
@@ -486,3 +491,13 @@ CONFIG:
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: x-mav_ap-h743v2_default
|
||||
svehicle_e2_bootloader:
|
||||
short: svehicle_e2_bootloader
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: svehicle_e2_bootloader
|
||||
svehicle_e2_default:
|
||||
short: svehicle_e2
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: svehicle_e2_default
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
BSD 3-Clause License
|
||||
|
||||
Copyright (c) 2012 - 2023, PX4 Development Team
|
||||
Copyright (c) 2012 - 2025, PX4 Development Team
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
|
||||
@@ -26,6 +26,7 @@ param set-default EKF2_MAG_ACCLIM 0
|
||||
param set-default EKF2_REQ_EPH 10
|
||||
param set-default EKF2_REQ_EPV 10
|
||||
param set-default EKF2_REQ_HDRIFT 0.5
|
||||
param set-default EKF2_REQ_PDOP 4
|
||||
param set-default EKF2_REQ_SACC 1
|
||||
param set-default EKF2_REQ_VDRIFT 1
|
||||
param set-default EKF2_RNG_QLTY_T 3
|
||||
|
||||
@@ -15,4 +15,4 @@ ignore-exclude-errors-x
|
||||
lineend=linux
|
||||
exclude=EASTL
|
||||
add-brackets
|
||||
max-code-length=120
|
||||
max-code-length=140
|
||||
|
||||
+1
-1
Submodule Tools/simulation/gz updated: b6127f4ec2...ee3835184c
@@ -0,0 +1,30 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m4"
|
||||
CONFIG_BOARD_ROMFSROOT="cannode"
|
||||
CONFIG_BOARD_CONSTRAINED_FLASH=y
|
||||
CONFIG_BOARD_NO_HELP=y
|
||||
CONFIG_BOARD_CONSTRAINED_MEMORY=y
|
||||
CONFIG_DRIVERS_BOOTLOADERS=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y
|
||||
CONFIG_DRIVERS_OPTICAL_FLOW_PAA3905=y
|
||||
CONFIG_BOARD_UAVCAN_INTERFACES=1
|
||||
CONFIG_DRIVERS_UAVCANNODE=y
|
||||
CONFIG_UAVCANNODE_FLOW_MEASUREMENT=y
|
||||
CONFIG_UAVCANNODE_RANGE_SENSOR_MEASUREMENT=y
|
||||
CONFIG_UAVCANNODE_RAW_IMU=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set
|
||||
# CONFIG_SENSORS_VEHICLE_AIR_DATA is not set
|
||||
# CONFIG_SENSORS_VEHICLE_ACCELERATION is not set
|
||||
# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set
|
||||
# CONFIG_SENSORS_VEHICLE_MAGNETOMETER is not set
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
CONFIG_SYSTEMCMDS_UORB=y
|
||||
CONFIG_SYSTEMCMDS_VER=y
|
||||
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||
@@ -8,9 +8,8 @@ param set-default SENS_FLOW_RATE 150
|
||||
param set-default SENS_IMU_CLPNOTI 0
|
||||
|
||||
param set-default SENS_AFBR_S_RATE 25
|
||||
param set-default SENS_AFBR_L_RATE 10
|
||||
param set-default SENS_AFBR_THRESH 8
|
||||
param set-default SENS_AFBR_HYSTER 2
|
||||
param set-default SENS_AFBR_L_RATE 5
|
||||
param set-default SENS_AFBR_MODE 1
|
||||
|
||||
# Internal SPI
|
||||
paa3905 -s start -Y 180
|
||||
|
||||
@@ -0,0 +1,34 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(pwm_voltage)
|
||||
@@ -0,0 +1,3 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_ROMFSROOT=""
|
||||
@@ -0,0 +1,99 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_ETHERNET=y
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3"
|
||||
CONFIG_DRIVERS_ADC_ADS1115=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
CONFIG_DRIVERS_BAROMETER_MS5611=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_HEATER=y
|
||||
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_PX4IO=y
|
||||
CONFIG_COMMON_RC=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_TONE_ALARM=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2
|
||||
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_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_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_MAVLINK_DIALECT="development"
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
|
||||
CONFIG_MODULES_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_BSONDUMP=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
CONFIG_SYSTEMCMDS_GPIO=y
|
||||
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
|
||||
CONFIG_SYSTEMCMDS_I2C_LAUNCHER=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_VER=y
|
||||
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||
Binary file not shown.
Binary file not shown.
@@ -0,0 +1,13 @@
|
||||
{
|
||||
"board_id": 6110,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the SVehicleE2 board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "SVehicleE2",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 1966080,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
@@ -0,0 +1,29 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# By disabling all 3 INA modules, we use the
|
||||
# i2c_launcher instead.
|
||||
param set-default SENS_EN_INA238 0
|
||||
param set-default SENS_EN_INA228 0
|
||||
param set-default SENS_EN_INA226 0
|
||||
|
||||
# Mavlink ethernet (CFG 1000)
|
||||
param set-default MAV_2_CONFIG 1000
|
||||
param set-default MAV_2_BROADCAST 1
|
||||
param set-default MAV_2_MODE 0
|
||||
param set-default MAV_2_RADIO_CTL 0
|
||||
param set-default MAV_2_RATE 100000
|
||||
param set-default MAV_2_REMOTE_PRT 14550
|
||||
param set-default MAV_2_UDP_PRT 14550
|
||||
|
||||
param set-default BAT1_V_DIV 21.5
|
||||
param set-default BAT1_A_PER_V 33.33
|
||||
|
||||
param set-default SENS_EXT_I2C_PRB 0
|
||||
|
||||
safety_button start
|
||||
|
||||
# pwm voltage 3.3V/5V switch
|
||||
pwm_voltage_apply start
|
||||
@@ -0,0 +1,34 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# SVehicle E2 specific board sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
if param compare -s ADC_ADS1115_EN 1
|
||||
then
|
||||
ads1115 start -X
|
||||
board_adc start -n
|
||||
else
|
||||
board_adc start
|
||||
fi
|
||||
|
||||
if param compare SENS_EN_INA228 1
|
||||
then
|
||||
# Start Digital power monitors
|
||||
ina228 -X start
|
||||
fi
|
||||
|
||||
bmi088 -A -R 4 -s -b 3 start
|
||||
bmi088 -G -R 4 -s -b 3 start
|
||||
|
||||
icm42688p -R 6 -s start
|
||||
|
||||
# Internal SPI bus ICM-20649 (hard-mounted)
|
||||
icm20649 -R 14 -s start
|
||||
|
||||
# Internal magnetometer on I2c
|
||||
rm3100 -I -R 12 start
|
||||
|
||||
bmm150 -I -R 4 start
|
||||
|
||||
icp201xx -X start
|
||||
icp201xx -I -a 0x64 start
|
||||
@@ -0,0 +1,17 @@
|
||||
#
|
||||
# For a description of the syntax of this configuration file,
|
||||
# see misc/tools/kconfig-language.txt.
|
||||
#
|
||||
config BOARD_HAS_PROBES
|
||||
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
|
||||
default y
|
||||
---help---
|
||||
This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers.
|
||||
|
||||
config BOARD_USE_PROBES
|
||||
bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11"
|
||||
default n
|
||||
depends on BOARD_HAS_PROBES
|
||||
|
||||
---help---
|
||||
Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers.
|
||||
@@ -0,0 +1,95 @@
|
||||
#
|
||||
# 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_DEV_CONSOLE is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_DISABLE_PTHREAD is not set
|
||||
# CONFIG_SPI_EXCHANGE is not set
|
||||
# CONFIG_STM32H7_SYSCFG is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/svehicle/e2/nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="svehicle"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H753II=y
|
||||
CONFIG_ARCH_CHIP_STM32H7=y
|
||||
CONFIG_ARCH_INTERRUPTSTACK=768
|
||||
CONFIG_ARMV7M_BASEPRI_WAR=y
|
||||
CONFIG_ARMV7M_ICACHE=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_BOARDCTL=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
CONFIG_BOARD_INITTHREAD_PRIORITY=254
|
||||
CONFIG_BOARD_LATE_INITIALIZE=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=95150
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x41F8
|
||||
CONFIG_CDCACM_PRODUCTSTR="SVehicle BL E2.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x20A3
|
||||
CONFIG_CDCACM_VENDORSTR="SVehicle"
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_SYMBOLS=y
|
||||
CONFIG_DEBUG_TCBINFO=y
|
||||
CONFIG_DEFAULT_SMALL=y
|
||||
CONFIG_EXPERIMENTAL=y
|
||||
CONFIG_FDCLONE_DISABLE=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_INIT_ENTRYPOINT="bootloader_main"
|
||||
CONFIG_INIT_STACKSIZE=3194
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=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_SPI=y
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=32
|
||||
CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_UART5=y
|
||||
CONFIG_SYSTEMTICK_HOOK=y
|
||||
CONFIG_SYSTEM_CDCACM=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_TTY_SIGINT=y
|
||||
CONFIG_TTY_SIGINT_CHAR=0x03
|
||||
CONFIG_TTY_SIGTSTP=y
|
||||
CONFIG_UART5_RXBUFSIZE=512
|
||||
CONFIG_UART5_RXDMA=y
|
||||
CONFIG_UART5_TXBUFSIZE=512
|
||||
CONFIG_UART5_TXDMA=y
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
@@ -0,0 +1,562 @@
|
||||
/************************************************************************************
|
||||
* nuttx-configs/px4_fmu-v6x/include/board.h
|
||||
*
|
||||
* Copyright (C) 2016-2019 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
#ifndef __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H
|
||||
#define __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include "board_dma_map.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include "stm32_rcc.h"
|
||||
#include "stm32_sdmmc.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* Clocking *************************************************************************/
|
||||
/* The px4_fmu-v6X board provides the following clock sources:
|
||||
*
|
||||
* X1: 16 MHz crystal for HSE
|
||||
*
|
||||
* So we have these clock source available within the STM32
|
||||
*
|
||||
* HSI: 16 MHz RC factory-trimmed
|
||||
* HSE: 16 MHz crystal for HSE
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_XTAL 16000000ul
|
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul
|
||||
#define STM32_LSI_FREQUENCY 32000
|
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
|
||||
#define STM32_LSE_FREQUENCY 32768
|
||||
|
||||
/* Main PLL Configuration.
|
||||
*
|
||||
* PLL source is HSE = 16,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
|
||||
*/
|
||||
|
||||
#define STM32_BOARD_USEHSE
|
||||
|
||||
#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE
|
||||
|
||||
/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR
|
||||
*
|
||||
* PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz
|
||||
*
|
||||
* PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz
|
||||
* PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz
|
||||
* PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 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(1)
|
||||
#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60)
|
||||
#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2)
|
||||
#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4)
|
||||
#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8)
|
||||
|
||||
#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60)
|
||||
#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2)
|
||||
#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4)
|
||||
#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8)
|
||||
|
||||
/* PLL2 */
|
||||
|
||||
#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \
|
||||
RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \
|
||||
RCC_PLLCFGR_DIVP2EN | \
|
||||
RCC_PLLCFGR_DIVQ2EN | \
|
||||
RCC_PLLCFGR_DIVR2EN)
|
||||
#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4)
|
||||
#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48)
|
||||
#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2)
|
||||
#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2)
|
||||
#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2)
|
||||
|
||||
#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48)
|
||||
#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
|
||||
#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
|
||||
#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2)
|
||||
|
||||
/* 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(4)
|
||||
#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48)
|
||||
#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2)
|
||||
#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4)
|
||||
#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2)
|
||||
|
||||
#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48)
|
||||
#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
|
||||
#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4)
|
||||
#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2)
|
||||
|
||||
/* SYSCLK = PLL1P = 480MHz
|
||||
* CPUCLK = SYSCLK / 1 = 480 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 = 240
|
||||
*/
|
||||
|
||||
#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/2 (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
|
||||
*/
|
||||
|
||||
/* I2C123 clock source */
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI
|
||||
|
||||
/* I2C4 clock source */
|
||||
|
||||
#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI
|
||||
|
||||
/* SPI123 clock source */
|
||||
|
||||
#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2
|
||||
|
||||
/* SPI45 clock source */
|
||||
|
||||
#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2
|
||||
|
||||
/* SPI6 clock source */
|
||||
|
||||
#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2
|
||||
|
||||
/* USB 1 and 2 clock source */
|
||||
|
||||
#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3
|
||||
|
||||
/* ADC 1 2 3 clock source */
|
||||
|
||||
#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2
|
||||
|
||||
/* 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
|
||||
|
||||
/* FDCAN 1 2 clock source */
|
||||
|
||||
#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */
|
||||
|
||||
#define STM32_FDCANCLK STM32_HSE_FREQUENCY
|
||||
|
||||
/* FLASH wait states
|
||||
*
|
||||
* ------------ ---------- -----------
|
||||
* Vcore MAX ACLK WAIT STATES
|
||||
* ------------ ---------- -----------
|
||||
* 1.15-1.26 V 70 MHz 0
|
||||
* (VOS1 level) 140 MHz 1
|
||||
* 210 MHz 2
|
||||
* 1.05-1.15 V 55 MHz 0
|
||||
* (VOS2 level) 110 MHz 1
|
||||
* 165 MHz 2
|
||||
* 220 MHz 3
|
||||
* 0.95-1.05 V 45 MHz 0
|
||||
* (VOS3 level) 90 MHz 1
|
||||
* 135 MHz 2
|
||||
* 180 MHz 3
|
||||
* 225 MHz 4
|
||||
* ------------ ---------- -----------
|
||||
*/
|
||||
|
||||
#define BOARD_FLASH_WAITSTATES 2
|
||||
|
||||
/* SDMMC definitions ********************************************************/
|
||||
|
||||
/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */
|
||||
|
||||
#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
|
||||
/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq)
|
||||
* div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
|
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA)
|
||||
# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#else
|
||||
# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT)
|
||||
#endif
|
||||
|
||||
#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* The PX4 FMUV6X board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and
|
||||
* LED_RED a Red LED, that can be controlled by software.
|
||||
*
|
||||
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.
|
||||
* The following definitions are used to access individual LEDs.
|
||||
*/
|
||||
|
||||
/* LED index values for use with board_userled() */
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* The px4_fmu-v6x board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and
|
||||
* LED_RED a Red LED, that can be controlled by software.
|
||||
*
|
||||
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way.
|
||||
* The following definitions are used to access individual LEDs.
|
||||
*/
|
||||
|
||||
/* LED index values for use with board_userled() */
|
||||
|
||||
#define BOARD_LED1 0
|
||||
#define BOARD_LED2 1
|
||||
#define BOARD_LED3 2
|
||||
#define BOARD_NLEDS 3
|
||||
|
||||
#define BOARD_LED_RED BOARD_LED1
|
||||
#define BOARD_LED_GREEN BOARD_LED2
|
||||
#define BOARD_LED_BLUE BOARD_LED3
|
||||
|
||||
/* LED bits for use with board_userled_all() */
|
||||
|
||||
#define BOARD_LED1_BIT (1 << BOARD_LED1)
|
||||
#define BOARD_LED2_BIT (1 << BOARD_LED2)
|
||||
#define BOARD_LED3_BIT (1 << BOARD_LED3)
|
||||
|
||||
/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in
|
||||
* include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related
|
||||
* events as follows:
|
||||
*
|
||||
*
|
||||
* SYMBOL Meaning LED state
|
||||
* Red Green Blue
|
||||
* ---------------------- -------------------------- ------ ------ ----*/
|
||||
|
||||
#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */
|
||||
#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */
|
||||
#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */
|
||||
#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */
|
||||
#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */
|
||||
#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */
|
||||
#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */
|
||||
#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */
|
||||
#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */
|
||||
|
||||
/* Thus if the Green LED is statically on, NuttX has successfully booted and
|
||||
* is, apparently, running normally. If the Red LED is flashing at
|
||||
* approximately 2Hz, then a fatal error has been detected and the system
|
||||
* has halted.
|
||||
*/
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
||||
#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */
|
||||
#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */
|
||||
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */
|
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
|
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
|
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
|
||||
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
|
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
|
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */
|
||||
#define GPIO_UART4_TX GPIO_UART4_TX_6 /* PH13 */
|
||||
|
||||
#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */
|
||||
#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */
|
||||
#undef GPIO_UART5_CTS
|
||||
#define GPIO_UART5_CTS ((GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN9) | GPIO_PULLDOWN) /* PC9 */
|
||||
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
|
||||
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
|
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */
|
||||
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
|
||||
#define GPIO_UART7_RTS (GPIO_UART7_RTS_2 | GPIO_PULLDOWN) /* PF8 */
|
||||
#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */
|
||||
|
||||
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
|
||||
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
|
||||
|
||||
|
||||
/* CAN
|
||||
*
|
||||
* CAN1 is routed to transceiver.
|
||||
* CAN2 is routed to transceiver.
|
||||
*/
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
|
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
|
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */
|
||||
|
||||
/* SPI
|
||||
* SPI1 is sensors1
|
||||
* SPI2 is sensors2
|
||||
* SPI3 is sensors3
|
||||
* SPI4 is Not Used
|
||||
* SPI5 is FRAM
|
||||
* SPI6 is EXTERNAL1
|
||||
*
|
||||
*/
|
||||
|
||||
#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz))
|
||||
|
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_3 /* PG9 */
|
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */
|
||||
#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */
|
||||
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
|
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */
|
||||
#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */
|
||||
|
||||
#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */
|
||||
#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */
|
||||
#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */
|
||||
|
||||
#define GPIO_SPI5_MISO GPIO_SPI5_MISO_2 /* PH7 */
|
||||
#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF11 */
|
||||
#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */
|
||||
|
||||
#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */
|
||||
#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */
|
||||
#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_3) /* PB3 */
|
||||
|
||||
/* I2C
|
||||
*
|
||||
* The optional _GPIO configurations allow the I2C driver to manually
|
||||
* reset the bus to clear stuck slaves. They match the pin configuration,
|
||||
* but are normally-high GPIOs.
|
||||
*
|
||||
*/
|
||||
|
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */
|
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */
|
||||
|
||||
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8)
|
||||
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9)
|
||||
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */
|
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */
|
||||
|
||||
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1)
|
||||
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0)
|
||||
|
||||
#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 /* PA8 */
|
||||
#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */
|
||||
|
||||
#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN8)
|
||||
#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8)
|
||||
|
||||
#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */
|
||||
#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */
|
||||
|
||||
#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14)
|
||||
#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15)
|
||||
|
||||
/* SDMMC2
|
||||
*
|
||||
* VDD 3.3
|
||||
* GND
|
||||
* SDMMC2_CK PD6
|
||||
* SDMMC2_CMD PD7
|
||||
* SDMMC2_D0 PB14
|
||||
* SDMMC2_D1 PB15
|
||||
* SDMMC2_D2 PG11
|
||||
* SDMMC2_D3 PB4
|
||||
*/
|
||||
|
||||
#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_1 /* PD6 */
|
||||
#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */
|
||||
// GPIO_SDMMC2_D0 No Remap /* PB14 */
|
||||
// GPIO_SDMMC2_D1 No Remap /* PB15 */
|
||||
#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 /* PG11 */
|
||||
// GPIO_SDMMC2_D3 No Remap /* PB4 */
|
||||
|
||||
/* The STM32 H7 connects to a TI DP83848TSQ/NOPB
|
||||
* using RMII
|
||||
*
|
||||
* STM32 H7 BOARD DP83848TSQ/NOPB
|
||||
* GPIO SIGNAL PIN NAME
|
||||
* -------- ------------ -------------
|
||||
* PA7 ETH_CRS_DV CRS_DV
|
||||
* PC1 ETH_MDC MDC
|
||||
* PA2 ETH_MDIO MDIO
|
||||
* PA1 ETH_REF_CL X1
|
||||
* PC4 ETH_RXD0 RX_D0
|
||||
* PC5 ETH_RXD1 RX_D1
|
||||
* PB11 ETH_TX_EN TX_EN
|
||||
* PG13 ETH_TXD0 TX_D0
|
||||
* PG12 ETH_TXD1 TX_D1
|
||||
*
|
||||
* The PHY address is 1, since COL/PHYAD0 features a pull up.
|
||||
*/
|
||||
|
||||
#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 /* PB11 */
|
||||
#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2 /* PG13 */
|
||||
#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_2 /* PG12 */
|
||||
|
||||
|
||||
/* USB
|
||||
*
|
||||
* OTG_FS_DM PA11
|
||||
* OTG_FS_DP PA12
|
||||
* VBUS PA9
|
||||
*/
|
||||
|
||||
|
||||
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
|
||||
|
||||
#if defined(CONFIG_BOARD_USE_PROBES)
|
||||
# include "stm32_gpio.h"
|
||||
# define PROBE_N(n) (1<<((n)-1))
|
||||
# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */
|
||||
# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */
|
||||
# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */
|
||||
# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */
|
||||
# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */
|
||||
# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */
|
||||
# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */
|
||||
|
||||
# define PROBE_INIT(mask) \
|
||||
do { \
|
||||
if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
|
||||
if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
|
||||
if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
|
||||
if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \
|
||||
if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \
|
||||
if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \
|
||||
if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \
|
||||
if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \
|
||||
if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \
|
||||
} while(0)
|
||||
|
||||
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
|
||||
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
|
||||
#else
|
||||
# define PROBE_INIT(mask)
|
||||
# define PROBE(n,s)
|
||||
# define PROBE_MARK(n)
|
||||
#endif
|
||||
|
||||
#endif /*__NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H */
|
||||
@@ -0,0 +1,87 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 Using at most 8 Channels on DMA1 -------- Assigned
|
||||
// V
|
||||
|
||||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 ICM-20649 */
|
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 ICM-20649 */
|
||||
|
||||
#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */
|
||||
#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */
|
||||
|
||||
//#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */
|
||||
//#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */
|
||||
|
||||
//#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 Telem3 */
|
||||
//#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 Telem3 */
|
||||
|
||||
//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */
|
||||
//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */
|
||||
|
||||
//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 EXT2 */
|
||||
//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 EXT2 */
|
||||
|
||||
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */
|
||||
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */
|
||||
|
||||
// Assigned in timer_config.cpp
|
||||
|
||||
// Timer 4 /* 7 DMA1:32 TIM4UP */
|
||||
// Timer 5 /* 8 DMA1:50 TIM5UP */
|
||||
|
||||
// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned
|
||||
// V
|
||||
|
||||
#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */
|
||||
#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */
|
||||
|
||||
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */
|
||||
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */
|
||||
|
||||
#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */
|
||||
#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */
|
||||
|
||||
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */
|
||||
#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */
|
||||
|
||||
//#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_1 /* DMA1:81 GPS2 */
|
||||
//#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_1 /* DMA1:82 GPS2 */
|
||||
|
||||
// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned
|
||||
// V
|
||||
|
||||
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */
|
||||
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */
|
||||
@@ -0,0 +1,330 @@
|
||||
#
|
||||
# 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_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/svehicle/e2/nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="svehicle"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H753II=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=95751
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_CDCACM=y
|
||||
CONFIG_CDCACM_IFLOWCONTROL=y
|
||||
CONFIG_CDCACM_PRODUCTID=0x41F8
|
||||
CONFIG_CDCACM_PRODUCTSTR="SVehicle E2.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x20A3
|
||||
CONFIG_CDCACM_VENDORSTR="SVehicle"
|
||||
CONFIG_DEBUG_FULLOPT=y
|
||||
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||
CONFIG_DEBUG_MEMFAULT=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_ETH0_PHY_LAN8742A=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/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_SDMMC2_SDIO_PULLUP=y
|
||||
CONFIG_SEM_PREALLOCHOLDERS=32
|
||||
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
|
||||
CONFIG_SERIAL_TERMIOS=y
|
||||
CONFIG_SIG_DEFAULT=y
|
||||
CONFIG_SIG_SIGALRM_ACTION=y
|
||||
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||
CONFIG_SIG_SIGWORK=4
|
||||
CONFIG_STACK_COLORATION=y
|
||||
CONFIG_START_DAY=30
|
||||
CONFIG_START_MONTH=11
|
||||
CONFIG_STDIO_BUFFER_SIZE=256
|
||||
CONFIG_STM32H7_ADC1=y
|
||||
CONFIG_STM32H7_ADC3=y
|
||||
CONFIG_STM32H7_BBSRAM=y
|
||||
CONFIG_STM32H7_BBSRAM_FILES=5
|
||||
CONFIG_STM32H7_BDMA=y
|
||||
CONFIG_STM32H7_BKPSRAM=y
|
||||
CONFIG_STM32H7_DMA1=y
|
||||
CONFIG_STM32H7_DMA2=y
|
||||
CONFIG_STM32H7_DMACAPABLE=y
|
||||
CONFIG_STM32H7_ETHMAC=y
|
||||
CONFIG_STM32H7_FLASH_OVERRIDE_I=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C2=y
|
||||
CONFIG_STM32H7_I2C3=y
|
||||
CONFIG_STM32H7_I2C4=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
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_RTC=y
|
||||
CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SDMMC2=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=4096
|
||||
CONFIG_STM32H7_SPI3=y
|
||||
CONFIG_STM32H7_SPI3_DMA=y
|
||||
CONFIG_STM32H7_SPI3_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_SPI5=y
|
||||
CONFIG_STM32H7_SPI6=y
|
||||
CONFIG_STM32H7_SPI6_DMA=y
|
||||
CONFIG_STM32H7_SPI6_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_TIM12=y
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM4=y
|
||||
CONFIG_STM32H7_TIM5=y
|
||||
CONFIG_STM32H7_UART4=y
|
||||
CONFIG_STM32H7_UART5=y
|
||||
CONFIG_STM32H7_UART7=y
|
||||
CONFIG_STM32H7_UART8=y
|
||||
CONFIG_STM32H7_USART1=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_SYSTEM_PING=y
|
||||
CONFIG_SYSTEM_SYSTEM=y
|
||||
CONFIG_TASK_NAME_SIZE=24
|
||||
CONFIG_UART4_BAUD=57600
|
||||
CONFIG_UART4_RXBUFSIZE=600
|
||||
CONFIG_UART4_TXBUFSIZE=1500
|
||||
CONFIG_UART5_IFLOWCONTROL=y
|
||||
CONFIG_UART5_OFLOWCONTROL=y
|
||||
CONFIG_UART5_RXDMA=y
|
||||
CONFIG_UART5_TXBUFSIZE=10000
|
||||
CONFIG_UART5_TXDMA=y
|
||||
CONFIG_UART7_BAUD=57600
|
||||
CONFIG_UART7_IFLOWCONTROL=y
|
||||
CONFIG_UART7_OFLOWCONTROL=y
|
||||
CONFIG_UART7_RXBUFSIZE=600
|
||||
CONFIG_UART7_RXDMA=y
|
||||
CONFIG_UART7_TXBUFSIZE=3000
|
||||
CONFIG_UART7_TXDMA=y
|
||||
CONFIG_UART8_BAUD=57600
|
||||
CONFIG_UART8_RXBUFSIZE=600
|
||||
CONFIG_UART8_TXBUFSIZE=1500
|
||||
CONFIG_USART1_BAUD=57600
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_TXBUFSIZE=1500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_IFLOWCONTROL=y
|
||||
CONFIG_USART2_OFLOWCONTROL=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_TXBUFSIZE=3000
|
||||
CONFIG_USART3_BAUD=57600
|
||||
CONFIG_USART3_RXBUFSIZE=180
|
||||
CONFIG_USART3_RXDMA=y
|
||||
CONFIG_USART3_SERIAL_CONSOLE=y
|
||||
CONFIG_USART3_TXBUFSIZE=1500
|
||||
CONFIG_USART3_TXDMA=y
|
||||
CONFIG_USART6_BAUD=57600
|
||||
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,215 @@
|
||||
/****************************************************************************
|
||||
* scripts/script.ld
|
||||
*
|
||||
* Copyright (C) 2016, 2019 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 PX4 FMUV6X uses an STM32H753II 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 STM32H743II, 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
|
||||
*
|
||||
* The PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by
|
||||
* default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test
|
||||
* point is pulled to 3.3V.then the boot will be from 0x1FF0:0000
|
||||
*
|
||||
* The STM32H743II 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.
|
||||
*
|
||||
* The bootloader uses the first sector of the flash, which is 128K in length.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||
flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K
|
||||
dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
|
||||
sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K
|
||||
sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K
|
||||
sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K
|
||||
sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K
|
||||
sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K
|
||||
bbram (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(.);
|
||||
} > sram AT > flash
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > sram
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
||||
@@ -0,0 +1,229 @@
|
||||
/****************************************************************************
|
||||
* scripts/script.ld
|
||||
*
|
||||
* Copyright (C) 2016, 2019 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 PX4 FMUV6X uses an STM32H753II 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 STM32H743II, 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
|
||||
*
|
||||
* The PX4 FMUV6X has a test point on board, the BOOT0 pin is at ground so by
|
||||
* default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test
|
||||
* point is pulled to 3.3V.then the boot will be from 0x1FF0:0000
|
||||
*
|
||||
* The STM32H743II 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 = 1920K
|
||||
|
||||
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)
|
||||
EXTERN(board_get_manifest)
|
||||
|
||||
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,42 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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 modules__pwm_voltage_apply
|
||||
MAIN pwm_voltage_apply
|
||||
|
||||
SRCS
|
||||
pwm_voltage.cpp
|
||||
DEPENDS
|
||||
px4_work_queue
|
||||
)
|
||||
@@ -0,0 +1,43 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Control PWM output voltage
|
||||
*
|
||||
* @value 0 3.3V
|
||||
* @value 1 5.0V
|
||||
*
|
||||
* @reboot_required true
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_VOLT_SEL, 0);
|
||||
@@ -0,0 +1,56 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 <inttypes.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/module_params.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
extern "C" int pwm_voltage_apply_main(int argc, char *argv[])
|
||||
{
|
||||
int32_t pwm_volt_sel = 0;
|
||||
|
||||
param_get(param_find("PWM_VOLT_SEL"), &pwm_volt_sel);
|
||||
|
||||
if (pwm_volt_sel != 0) {
|
||||
PWM_5V_VOLT_SEL(true);
|
||||
|
||||
} else {
|
||||
PWM_5V_VOLT_SEL(false);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -0,0 +1,75 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
if("${PX4_BOARD_LABEL}" STREQUAL "bootloader")
|
||||
add_compile_definitions(BOOTLOADER)
|
||||
add_library(drivers_board
|
||||
bootloader_main.c
|
||||
init.c
|
||||
usb.c
|
||||
timer_config.cpp
|
||||
)
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
nuttx_arch # sdio
|
||||
nuttx_drivers # sdio
|
||||
px4_layer #gpio
|
||||
arch_io_pins # iotimer
|
||||
bootloader
|
||||
)
|
||||
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common)
|
||||
|
||||
else()
|
||||
add_library(drivers_board
|
||||
can.c
|
||||
i2c.cpp
|
||||
init.c
|
||||
led.c
|
||||
mtd.cpp
|
||||
sdio.c
|
||||
spi.cpp
|
||||
timer_config.cpp
|
||||
usb.c
|
||||
)
|
||||
add_dependencies(drivers_board arch_board_hw_info)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
PRIVATE
|
||||
arch_io_pins
|
||||
arch_spi
|
||||
arch_board_hw_info
|
||||
drivers__led # drv_led_start
|
||||
nuttx_arch # sdio
|
||||
nuttx_drivers # sdio
|
||||
px4_layer
|
||||
)
|
||||
endif()
|
||||
@@ -0,0 +1,484 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016-2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file board_config.h
|
||||
*
|
||||
* PX4FMU-v6x internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
#include <stm32_gpio.h>
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
#undef TRACE_PINS
|
||||
|
||||
/* PX4IO connection configuration */
|
||||
|
||||
#define BOARD_USES_PX4IO_VERSION 2
|
||||
#define PX4IO_SERIAL_DEVICE "/dev/ttyS5"
|
||||
#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
|
||||
#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
|
||||
#define PX4IO_SERIAL_BASE STM32_USART6_BASE
|
||||
#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
|
||||
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX
|
||||
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX
|
||||
#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR
|
||||
#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN
|
||||
#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
|
||||
#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */
|
||||
|
||||
/* Configuration ************************************************************************************/
|
||||
|
||||
#define BOARD_HAS_LTC44XX_VALIDS 2 // N Bricks
|
||||
#define BOARD_HAS_USB_VALID 1 // LTC Has USB valid
|
||||
#define BOARD_HAS_NBAT_V 2 // one is adc,another is Digital Voltage(iic or can)
|
||||
#define BOARD_HAS_NBAT_I 2 // one is adc,another is Digital Current(iic or can)
|
||||
|
||||
/* PX4FMU GPIOs ***********************************************************************************/
|
||||
|
||||
/* Trace Clock and D0-D3 are available on the trace connector
|
||||
*
|
||||
* TRACECLK PE2 - Dedicated - Trace Connector Pin 1
|
||||
* TRACED0 PE3 - nLED_RED - Trace Connector Pin 3
|
||||
* TRACED1 PE4 - nLED_GREEN - Trace Connector Pin 5
|
||||
* TRACED2 PE5 - nLED_BLUE - Trace Connector Pin 7
|
||||
* TRACED3 PE6 - nARMED - Trace Connector Pin 8
|
||||
|
||||
*/
|
||||
|
||||
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */
|
||||
|
||||
#if !defined(TRACE_PINS)
|
||||
# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
|
||||
# define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
|
||||
# define GPIO_nLED_BLUE /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5)
|
||||
|
||||
# define BOARD_HAS_CONTROL_STATUS_LEDS 1
|
||||
# define BOARD_OVERLOAD_LED LED_RED
|
||||
# define BOARD_ARMED_STATE_LED LED_BLUE
|
||||
|
||||
#else
|
||||
|
||||
# define GPIO_TRACECLK1 (GPIO_TRACECLK |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2)
|
||||
# define GPIO_TRACED0 (GPIO_TRACED0_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3)
|
||||
# define GPIO_TRACED1 (GPIO_TRACED1_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4)
|
||||
# define GPIO_TRACED2 (GPIO_TRACED2_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5)
|
||||
# define GPIO_TRACED3 (GPIO_TRACED3_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6)
|
||||
//#define GPIO_TRACESWO //(GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3)
|
||||
|
||||
# undef BOARD_HAS_CONTROL_STATUS_LEDS
|
||||
# undef BOARD_OVERLOAD_LED
|
||||
# undef BOARD_ARMED_STATE_LED
|
||||
|
||||
# define GPIO_nLED_RED GPIO_TRACED0
|
||||
# define GPIO_nLED_GREEN GPIO_TRACED1
|
||||
# define GPIO_nLED_BLUE GPIO_TRACED2
|
||||
# define GPIO_nARMED GPIO_TRACED3
|
||||
# define GPIO_nARMED_INIT GPIO_TRACED3
|
||||
#endif
|
||||
|
||||
/* I2C busses */
|
||||
|
||||
/* Devices on the onboard buses.
|
||||
*
|
||||
* Note that these are unshifted addresses.
|
||||
*/
|
||||
#define BOARD_MTD_NUM_EEPROM 2 /* MTD: base_eeprom, imu_eeprom*/
|
||||
|
||||
#define PX4_I2C_OBDEV_SE050 0x48
|
||||
|
||||
#define GPIO_I2C2_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5)
|
||||
|
||||
/*
|
||||
* ADC channels
|
||||
*
|
||||
* These are the channel numbers of the ADCs of the microcontroller that
|
||||
* can be used by the Px4 Firmware in the adc driver
|
||||
*/
|
||||
|
||||
/* ADC defines to be used in sensors.cpp to read from a particular channel */
|
||||
|
||||
#define ADC1_CH(n) (n)
|
||||
|
||||
/* N.B. there is no offset mapping needed for ADC3 because */
|
||||
#define ADC3_CH(n) (n)
|
||||
|
||||
/* We are only use ADC3 for REV/VER.
|
||||
* ADC3_6V6 and ADC3_3V3 are mapped back to ADC1
|
||||
* To do this We are relying on PC2_C, PC3_C being connected to PC2, PC3
|
||||
* respectively by the SYSCFG_PMCR default of setting for PC3SO PC2SO PA1SO
|
||||
* PA0SO of 0.
|
||||
*
|
||||
* 0 Analog switch closed (pads are connected through the analog switch)
|
||||
*
|
||||
* So ADC3_INP0 is GPIO_ADC123_INP12
|
||||
* ADC3_INP1 is GPIO_ADC12_INP13
|
||||
*/
|
||||
|
||||
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
|
||||
|
||||
#define PX4_ADC_GPIO \
|
||||
/* PA0 */ GPIO_ADC1_INP16, \
|
||||
/* PA4 */ GPIO_ADC12_INP18, \
|
||||
/* PB0 */ GPIO_ADC12_INP9, \
|
||||
/* PB1 */ GPIO_ADC12_INP5, \
|
||||
/* PC2 */ GPIO_ADC123_INP12, \
|
||||
/* PC3 */ GPIO_ADC12_INP13, \
|
||||
/* PF12 */ GPIO_ADC1_INP6, \
|
||||
/* PH3 */ GPIO_ADC3_INP14, \
|
||||
/* PH4 */ GPIO_ADC3_INP15
|
||||
|
||||
/* Define Channel numbers must match above GPIO pin IN(n)*/
|
||||
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL /* PF12 */ ADC1_CH(6)
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL /* PB0 */ ADC1_CH(9)
|
||||
#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(16)
|
||||
#define ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL /* PA4 */ ADC1_CH(18)
|
||||
#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5)
|
||||
#define ADC_ADC3_6V6_CHANNEL /* PC2 */ ADC3_CH(12)
|
||||
#define ADC_ADC3_3V3_CHANNEL /* PC3 */ ADC3_CH(13)
|
||||
#define ADC_HW_VER_SENSE_CHANNEL /* PH3 */ ADC3_CH(14)
|
||||
#define ADC_HW_REV_SENSE_CHANNEL /* PH4 */ ADC3_CH(15)
|
||||
|
||||
#define ADC_CHANNELS \
|
||||
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
|
||||
(1 << ADC_BATTERY_CURRENT_CHANNEL) | \
|
||||
(1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_ADC3_6V6_CHANNEL) | \
|
||||
(1 << ADC_ADC3_3V3_CHANNEL)) | \
|
||||
(1 << ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL)
|
||||
|
||||
|
||||
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
|
||||
|
||||
#define HW_REV_VER_ADC_BASE STM32_ADC3_BASE
|
||||
|
||||
#define SYSTEM_ADC_BASE STM32_ADC1_BASE
|
||||
|
||||
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
|
||||
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
|
||||
|
||||
// // /* HW Version and Revision drive signals Default to 1 to detect */
|
||||
// #define BOARD_HAS_HW_SPLIT_VERSIONING
|
||||
|
||||
#define BOARD_HAS_STATIC_MANIFEST 1
|
||||
|
||||
#define PX4_MFT_HW_SUPPORTED_PX4_MFT_CAN2 1
|
||||
|
||||
#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0)
|
||||
#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15
|
||||
#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14
|
||||
|
||||
#define UAVCAN_NUM_IFACES_RUNTIME 1
|
||||
|
||||
/* HEATER
|
||||
* PWM in future
|
||||
*/
|
||||
#define GPIO_HEATER_OUTPUT /* PB10 T2CH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
|
||||
#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true))
|
||||
|
||||
/* PE6 is nARMED
|
||||
* The GPIO will be set as input while not armed HW will have external HW Pull UP.
|
||||
* While armed it shall be configured at a GPIO OUT set LOW
|
||||
*/
|
||||
#if !defined(TRACE_PINS)
|
||||
#define GPIO_nARMED_INIT /* PE6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN6)
|
||||
#define GPIO_nARMED /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6)
|
||||
#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT)
|
||||
#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED)
|
||||
#endif
|
||||
|
||||
|
||||
/* PWM
|
||||
*/
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 9
|
||||
|
||||
/* PWM Power */
|
||||
#define GPIO_PWM_VOLT_SEL /* PG6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN6)
|
||||
#define PWM_5V_VOLT_SEL(on_true) px4_arch_gpiowrite(GPIO_PWM_VOLT_SEL, (on_true))
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
|
||||
#define GPIO_nPOWER_IN_A /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1)
|
||||
#define GPIO_nPOWER_IN_B /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2)
|
||||
#define GPIO_nPOWER_IN_C /* PG3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN3)
|
||||
|
||||
#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */
|
||||
#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */
|
||||
#define BOARD_NUMBER_BRICKS 1
|
||||
#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */
|
||||
|
||||
#define GPIO_VDD_5V_PERIPH_nEN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4)
|
||||
#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN15)
|
||||
#define GPIO_VDD_5V_HIPOWER_nEN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10)
|
||||
#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13)
|
||||
#define GPIO_VDD_3V3_SENSORS4_EN /* PG8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8)
|
||||
#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2)
|
||||
#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
|
||||
|
||||
/* ETHERNET GPIO */
|
||||
|
||||
#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15)
|
||||
|
||||
/* NFC GPIO */
|
||||
|
||||
#define GPIO_NFC_GPIO /* PC0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN0)
|
||||
|
||||
|
||||
/* Define True logic Power Control in arch agnostic form */
|
||||
|
||||
#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true))
|
||||
#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true))
|
||||
#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true))
|
||||
#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true))
|
||||
#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN)
|
||||
#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true))
|
||||
#define VDD_3V3_ETH_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_ETH_POWER_EN, (on_true))
|
||||
|
||||
|
||||
/* Tone alarm output */
|
||||
|
||||
#define TONE_ALARM_TIMER 14 /* Timer 14 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* PF9 GPIO_TIM14_CH1OUT_2 */
|
||||
|
||||
#define GPIO_BUZZER_1 /* PF9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9)
|
||||
|
||||
#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1
|
||||
#define GPIO_TONE_ALARM GPIO_TIM14_CH1OUT_2
|
||||
|
||||
/* USB OTG FS
|
||||
*
|
||||
* PA9 OTG_FS_VBUS VBUS sensing
|
||||
*/
|
||||
#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9)
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 8 /* use timer8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */
|
||||
|
||||
#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */
|
||||
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
|
||||
/* Input Capture Channels. */
|
||||
#define INPUT_CAP1_TIMER 1
|
||||
#define INPUT_CAP1_CHANNEL /* T1C2 */ 2
|
||||
#define GPIO_INPUT_CAP1 /* PE11 */ GPIO_TIM1_CH2IN
|
||||
|
||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
|
||||
#define PWMIN_TIMER 4
|
||||
#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2
|
||||
#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN_2
|
||||
|
||||
/* Safety Switch is HW version dependent on having an PX4IO
|
||||
* So we init to a benign state with the _INIT definition
|
||||
* and provide the the non _INIT one for the driver to make a run time
|
||||
* decision to use it.
|
||||
*/
|
||||
#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN10)
|
||||
#define GPIO_nSAFETY_SWITCH_LED_OUT /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
|
||||
|
||||
/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */
|
||||
#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT
|
||||
|
||||
#define GPIO_SAFETY_SWITCH_IN /* PF5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN5)
|
||||
/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */
|
||||
#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */
|
||||
|
||||
/* Power switch controls ******************************************************/
|
||||
|
||||
#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true)
|
||||
|
||||
/*
|
||||
* FMUv6X has a separate RC_IN
|
||||
*
|
||||
* GPIO PPM_IN on PI5 T8CH1
|
||||
* SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7
|
||||
* Inversion is possible in the UART and can drive GPIO PPM_IN as an output
|
||||
*/
|
||||
|
||||
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
|
||||
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
|
||||
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
|
||||
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
|
||||
|
||||
#define SDIO_SLOTNO 0 /* Only one slot */
|
||||
#define SDIO_MINOR 0
|
||||
|
||||
/* SD card bringup does not work if performed on the IDLE thread because it
|
||||
* will cause waiting. Use either:
|
||||
*
|
||||
* CONFIG_BOARDCTL=y, OR
|
||||
* CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \
|
||||
!defined(CONFIG_BOARD_INITTHREAD)
|
||||
# warning SDIO initialization cannot be perfomed on the IDLE thread
|
||||
#endif
|
||||
|
||||
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
|
||||
* this board support the ADC system_power interface, and therefore
|
||||
* provides the true logic GPIO BOARD_ADC_xxxx macros.
|
||||
*/
|
||||
#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS))
|
||||
#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID))
|
||||
|
||||
/* FMUv6X never powers off the Servo rail */
|
||||
|
||||
#define BOARD_ADC_SERVO_VALID (1)
|
||||
|
||||
|
||||
#define BOARD_ADC_BRICK_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
|
||||
|
||||
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC))
|
||||
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC))
|
||||
|
||||
|
||||
/* This board provides a DMA pool and APIs */
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||
|
||||
/* This board provides the board_on_reset interface */
|
||||
|
||||
#define BOARD_HAS_ON_RESET 1
|
||||
|
||||
#if defined(TRACE_PINS)
|
||||
#define GPIO_TRACE \
|
||||
GPIO_TRACECLK1, \
|
||||
GPIO_TRACED0, \
|
||||
GPIO_TRACED1, \
|
||||
GPIO_TRACED2, \
|
||||
GPIO_TRACED3
|
||||
#else
|
||||
#define GPIO_TRACE (GPIO_OUTPUT|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2)
|
||||
#endif
|
||||
|
||||
#define PX4_GPIO_INIT_LIST { \
|
||||
GPIO_TRACE, \
|
||||
PX4_ADC_GPIO, \
|
||||
GPIO_HW_VER_REV_DRIVE, \
|
||||
GPIO_CAN1_TX, \
|
||||
GPIO_CAN1_RX, \
|
||||
GPIO_CAN2_TX, \
|
||||
GPIO_CAN2_RX, \
|
||||
GPIO_HEATER_OUTPUT, \
|
||||
GPIO_nPOWER_IN_A, \
|
||||
GPIO_nPOWER_IN_B, \
|
||||
GPIO_nPOWER_IN_C, \
|
||||
GPIO_VDD_5V_PERIPH_nEN, \
|
||||
GPIO_VDD_5V_PERIPH_nOC, \
|
||||
GPIO_VDD_5V_HIPOWER_nEN, \
|
||||
GPIO_VDD_5V_HIPOWER_nOC, \
|
||||
GPIO_VDD_3V3_SENSORS4_EN, \
|
||||
GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \
|
||||
GPIO_VDD_3V3_SD_CARD_EN, \
|
||||
GPIO_ETH_POWER_EN, \
|
||||
GPIO_NFC_GPIO, \
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \
|
||||
GPIO_SAFETY_SWITCH_IN, \
|
||||
GPIO_nARMED_INIT, \
|
||||
GPIO_PWM_VOLT_SEL \
|
||||
}
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
#define PX4_I2C_BUS_MTD 4,5
|
||||
|
||||
|
||||
#define BOARD_NUM_IO_TIMERS 5
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public data
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_sdio_initialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize SDIO-based MMC/SD card support
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int stm32_sdio_initialize(void);
|
||||
|
||||
/****************************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
|
||||
extern void stm32_usbinitialize(void);
|
||||
|
||||
extern void board_peripheral_reset(int ms);
|
||||
|
||||
#include <px4_platform_common/board_common.h>
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
||||
@@ -0,0 +1,62 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2019-2021 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 bootloader_main.c
|
||||
*
|
||||
* FMU-specific early startup code for bootloader
|
||||
*/
|
||||
|
||||
#include "board_config.h"
|
||||
#include "bl.h"
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_uart.h>
|
||||
#include <arch/board/board.h>
|
||||
#include "arm_internal.h"
|
||||
#include <px4_platform_common/init.h>
|
||||
|
||||
extern int sercon_main(int c, char **argv);
|
||||
|
||||
void board_late_initialize(void)
|
||||
{
|
||||
sercon_main(0, NULL);
|
||||
}
|
||||
|
||||
extern void sys_tick_handler(void);
|
||||
void board_timerhook(void)
|
||||
{
|
||||
sys_tick_handler();
|
||||
}
|
||||
@@ -0,0 +1,142 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4fmu_can.c
|
||||
*
|
||||
* Board-specific CAN functions.
|
||||
*/
|
||||
|
||||
#if !defined(CONFIG_CAN)
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
|
||||
__EXPORT
|
||||
uint16_t board_get_can_interfaces(void)
|
||||
{
|
||||
uint16_t enabled_interfaces = 0x3;
|
||||
|
||||
if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN2)) {
|
||||
enabled_interfaces &= ~(1 << 1);
|
||||
}
|
||||
|
||||
return enabled_interfaces;
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/can/can.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "arm_internal.h"
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32_can.h"
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration ********************************************************************/
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
|
||||
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
|
||||
# undef CONFIG_STM32_CAN2
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_CAN1
|
||||
# define CAN_PORT 1
|
||||
#else
|
||||
# define CAN_PORT 2
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
int can_devinit(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: can_devinit
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following interface to work with
|
||||
* examples/can.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int can_devinit(void)
|
||||
{
|
||||
static bool initialized = false;
|
||||
struct can_dev_s *can;
|
||||
int ret;
|
||||
|
||||
/* Check if we have already initialized */
|
||||
|
||||
if (!initialized) {
|
||||
/* Call stm32_caninitialize() to get an instance of the CAN interface */
|
||||
|
||||
can = stm32_caninitialize(CAN_PORT);
|
||||
|
||||
if (can == NULL) {
|
||||
canerr("ERROR: Failed to get CAN interface\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Register the CAN driver at "/dev/can0" */
|
||||
|
||||
ret = can_register("/dev/can0", can);
|
||||
|
||||
if (ret < 0) {
|
||||
canerr("ERROR: can_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
#endif /* CONFIG_CAN */
|
||||
@@ -0,0 +1,128 @@
|
||||
/*
|
||||
* hw_config.h
|
||||
*
|
||||
* Created on: May 17, 2015
|
||||
* Author: david_s5
|
||||
*/
|
||||
|
||||
#ifndef HW_CONFIG_H_
|
||||
#define HW_CONFIG_H_
|
||||
|
||||
/****************************************************************************
|
||||
* 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,1500000"
|
||||
#define BOOT_DELAY_ADDRESS 0x000001a0
|
||||
#define BOARD_TYPE 6110
|
||||
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
|
||||
#define BOARD_FLASH_SECTORS (15)
|
||||
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)//1024
|
||||
|
||||
#define OSC_FREQ 16
|
||||
|
||||
#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE
|
||||
#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN
|
||||
#define BOARD_LED_ON 0
|
||||
#define BOARD_LED_OFF 1
|
||||
|
||||
#define SERIAL_BREAK_DETECT_DISABLED 1
|
||||
|
||||
/*
|
||||
* Uncommenting this allows to force the bootloader through
|
||||
* a PWM output pin. As this can accidentally initialize
|
||||
* an ESC prematurely, it is not recommended. This feature
|
||||
* has not been used and hence defaults now to off.
|
||||
*
|
||||
* # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14)
|
||||
* # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11)
|
||||
*
|
||||
* # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
|
||||
* # define BOARD_POWER_ON 1
|
||||
* # define BOARD_POWER_OFF 0
|
||||
* # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power)
|
||||
*
|
||||
*/
|
||||
|
||||
#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
|
||||
|
||||
#endif /* HW_CONFIG_H_ */
|
||||
@@ -0,0 +1,41 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/i2c_hw_description.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusExternal(1),
|
||||
initI2CBusExternal(2),
|
||||
initI2CBusExternal(3),
|
||||
initI2CBusInternal(4),
|
||||
};
|
||||
@@ -0,0 +1,276 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file init.c
|
||||
*
|
||||
* PX4FMU-specific early startup code. This file implements the
|
||||
* board_app_initialize() function that is called early by nsh during startup.
|
||||
*
|
||||
* Code here is run before the rcS script is invoked; it should start required
|
||||
* subsystems and perform board-specific initialization.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/sdio.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
#include <nuttx/mm/gran.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_uart.h>
|
||||
#include <arch/board/board.h>
|
||||
#include "arm_internal.h"
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_board_led.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
#include <px4_arch/io_timer.h>
|
||||
#include <px4_platform_common/init.h>
|
||||
#include <px4_platform_common/px4_manifest.h>
|
||||
#include <px4_platform/gpio.h>
|
||||
#include <px4_platform/board_determine_hw_info.h>
|
||||
#include <px4_platform/board_dma_alloc.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from arm_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
__END_DECLS
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_peripheral_reset
|
||||
*
|
||||
* Description:
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_peripheral_reset(int ms)
|
||||
{
|
||||
/* set the peripheral rails off */
|
||||
|
||||
VDD_5V_PERIPH_EN(false);
|
||||
board_control_spi_sensors_power(false, 0xffff);
|
||||
|
||||
/* wait for the peripheral rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||
|
||||
/* re-enable power */
|
||||
|
||||
/* switch the peripheral rail back on */
|
||||
board_control_spi_sensors_power(true, 0xffff);
|
||||
VDD_5V_PERIPH_EN(true);
|
||||
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_on_reset
|
||||
*
|
||||
* Description:
|
||||
* Optionally provided function called on entry to board_system_reset
|
||||
* It should perform any house keeping prior to the rest.
|
||||
*
|
||||
* status - 1 if resetting to boot loader
|
||||
* 0 if just resetting
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_on_reset(int status)
|
||||
{
|
||||
for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
|
||||
px4_arch_configgpio(io_timer_channel_get_gpio_output(i));
|
||||
}
|
||||
|
||||
/*
|
||||
* On resets invoked from system (not boot) ensure we establish a low
|
||||
* output state on PWM pins to disarm the ESC and prevent the reset from potentially
|
||||
* spinning up the motors.
|
||||
*/
|
||||
if (status >= 0) {
|
||||
up_mdelay(100);
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the initialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void
|
||||
stm32_boardinitialize(void)
|
||||
{
|
||||
board_on_reset(-1); /* Reset PWM first thing */
|
||||
|
||||
/* configure LEDs */
|
||||
|
||||
board_autoled_initialize();
|
||||
|
||||
/* configure pins */
|
||||
|
||||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
|
||||
px4_gpio_init(gpio, arraySize(gpio));
|
||||
|
||||
/* configure USB interfaces */
|
||||
|
||||
stm32_usbinitialize();
|
||||
|
||||
VDD_3V3_ETH_POWER_EN(true);
|
||||
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_app_initialize
|
||||
*
|
||||
* Description:
|
||||
* Perform application specific initialization. This function is never
|
||||
* called directly from application code, but only indirectly via the
|
||||
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
|
||||
*
|
||||
* Input Parameters:
|
||||
* arg - The boardctl() argument is passed to the board_app_initialize()
|
||||
* implementation without modification. The argument has no
|
||||
* meaning to NuttX; the meaning of the argument is a contract
|
||||
* between the board-specific initalization logic and the the
|
||||
* matching application logic. The value cold be such things as a
|
||||
* mode enumeration value, a set of DIP switch switch settings, a
|
||||
* pointer to configuration data read from a file or serial FLASH,
|
||||
* or whatever you would like to do with it. Every implementation
|
||||
* should accept zero/NULL as a default configuration.
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||
* any failure to indicate the nature of the failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
#if !defined(BOOTLOADER)
|
||||
|
||||
/* Power on Interfaces */
|
||||
VDD_3V3_SD_CARD_EN(true);
|
||||
VDD_5V_PERIPH_EN(true);
|
||||
VDD_5V_HIPOWER_EN(true);
|
||||
VDD_3V3_SENSORS4_EN(true);
|
||||
VDD_3V3_SPEKTRUM_POWER_EN(true);
|
||||
|
||||
/* Need hrt running before using the ADC */
|
||||
|
||||
px4_platform_init();
|
||||
|
||||
// Use the default HW_VER_REV(0x0,0x0) for Ramtron
|
||||
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
|
||||
px4_platform_configure();
|
||||
|
||||
/* Configure the Actual SPI interfaces (after we determined the HW version) */
|
||||
|
||||
stm32_spiinitialize();
|
||||
|
||||
board_spi_reset(10, 0xffff);
|
||||
|
||||
/* Configure the DMA allocator */
|
||||
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
syslog(LOG_ERR, "[boot] DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
# if defined(SERIAL_HAVE_RXDMA)
|
||||
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
|
||||
static struct hrt_call serial_dma_call;
|
||||
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL);
|
||||
# endif
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_RED);
|
||||
led_on(LED_GREEN); // Indicate Power.
|
||||
led_off(LED_BLUE);
|
||||
|
||||
if (board_hardfault_init(2, true) != 0) {
|
||||
led_on(LED_RED);
|
||||
}
|
||||
|
||||
// Ensure Power is off for > 10 mS
|
||||
usleep(15 * 1000);
|
||||
VDD_3V3_SD_CARD_EN(true);
|
||||
usleep(500 * 1000);
|
||||
|
||||
# ifdef CONFIG_MMCSD
|
||||
int ret = stm32_sdio_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
led_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
# endif /* CONFIG_MMCSD */
|
||||
|
||||
#endif /* !defined(BOOTLOADER) */
|
||||
|
||||
return OK;
|
||||
}
|
||||
@@ -0,0 +1,235 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4fmu2_led.c
|
||||
*
|
||||
* PX4FMU LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32_gpio.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from arm_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
static bool nuttx_owns_leds = true;
|
||||
// B R S G
|
||||
// 0 1 2 3
|
||||
static const uint8_t xlatpx4[] = {1, 2, 4, 0};
|
||||
# define xlat(p) xlatpx4[(p)]
|
||||
static uint32_t g_ledmap[] = {
|
||||
GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN
|
||||
GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE
|
||||
GPIO_nLED_RED, // Indexed by BOARD_LED_RED
|
||||
GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4
|
||||
};
|
||||
|
||||
#else
|
||||
|
||||
# define xlat(p) (p)
|
||||
static uint32_t g_ledmap[] = {
|
||||
GPIO_nLED_BLUE, // Indexed by LED_BLUE
|
||||
GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER
|
||||
0, // Indexed by LED_SAFETY (defaulted to an input)
|
||||
GPIO_nLED_GREEN, // Indexed by LED_GREEN
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
__EXPORT void led_init(void)
|
||||
{
|
||||
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
|
||||
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)));
|
||||
}
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_initialize
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_initialize(void)
|
||||
{
|
||||
led_init();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_on
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_on(int led)
|
||||
{
|
||||
if (!nuttx_owns_leds) {
|
||||
return;
|
||||
}
|
||||
|
||||
switch (led) {
|
||||
default:
|
||||
break;
|
||||
|
||||
case LED_HEAPALLOCATE:
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_IRQSENABLED:
|
||||
phy_set_led(BOARD_LED_BLUE, false);
|
||||
phy_set_led(BOARD_LED_GREEN, true);
|
||||
break;
|
||||
|
||||
case LED_STACKCREATED:
|
||||
phy_set_led(BOARD_LED_GREEN, true);
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_INIRQ:
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_SIGNAL:
|
||||
phy_set_led(BOARD_LED_GREEN, true);
|
||||
break;
|
||||
|
||||
case LED_ASSERTION:
|
||||
phy_set_led(BOARD_LED_RED, true);
|
||||
phy_set_led(BOARD_LED_BLUE, true);
|
||||
break;
|
||||
|
||||
case LED_PANIC:
|
||||
phy_set_led(BOARD_LED_RED, true);
|
||||
break;
|
||||
|
||||
case LED_IDLE : /* IDLE */
|
||||
phy_set_led(BOARD_LED_RED, true);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_off
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_off(int led)
|
||||
{
|
||||
if (!nuttx_owns_leds) {
|
||||
return;
|
||||
}
|
||||
|
||||
switch (led) {
|
||||
default:
|
||||
break;
|
||||
|
||||
case LED_SIGNAL:
|
||||
phy_set_led(BOARD_LED_GREEN, false);
|
||||
break;
|
||||
|
||||
case LED_INIRQ:
|
||||
phy_set_led(BOARD_LED_BLUE, false);
|
||||
break;
|
||||
|
||||
case LED_ASSERTION:
|
||||
phy_set_led(BOARD_LED_RED, false);
|
||||
phy_set_led(BOARD_LED_BLUE, false);
|
||||
break;
|
||||
|
||||
case LED_PANIC:
|
||||
phy_set_led(BOARD_LED_RED, false);
|
||||
break;
|
||||
|
||||
case LED_IDLE : /* IDLE */
|
||||
phy_set_led(BOARD_LED_RED, false);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* CONFIG_ARCH_LEDS */
|
||||
@@ -0,0 +1,130 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <px4_platform_common/px4_manifest.h>
|
||||
// KiB BS nB
|
||||
static const px4_mft_device_t spi5 = { // FM25V02A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32)
|
||||
.bus_type = px4_mft_device_t::SPI,
|
||||
.devid = SPIDEV_FLASH(0)
|
||||
};
|
||||
static const px4_mft_device_t i2c3 = { // 24LC64T on Base 8K 32 X 256
|
||||
.bus_type = px4_mft_device_t::I2C,
|
||||
.devid = PX4_MK_I2C_DEVID(3, 0x51)
|
||||
};
|
||||
static const px4_mft_device_t i2c4 = { // 24LC64T on IMU 8K 32 X 256
|
||||
.bus_type = px4_mft_device_t::I2C,
|
||||
.devid = PX4_MK_I2C_DEVID(4, 0x50)
|
||||
};
|
||||
|
||||
|
||||
static const px4_mtd_entry_t fmum_fram = {
|
||||
.device = &spi5,
|
||||
.npart = 1,
|
||||
.partd = {
|
||||
{
|
||||
.type = MTD_PARAMETERS,
|
||||
.path = "/fs/mtd_params",
|
||||
.nblocks = (32768 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT))
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
static const px4_mtd_entry_t base_eeprom = {
|
||||
.device = &i2c3,
|
||||
.npart = 2,
|
||||
.partd = {
|
||||
{
|
||||
.type = MTD_MFT_VER,
|
||||
.path = "/fs/mtd_mft_ver",
|
||||
.nblocks = 248
|
||||
},
|
||||
{
|
||||
.type = MTD_NET,
|
||||
.path = "/fs/mtd_net",
|
||||
.nblocks = 8 // 256 = 32 * 8
|
||||
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
static const px4_mtd_entry_t imu_eeprom = {
|
||||
.device = &i2c4,
|
||||
.npart = 3,
|
||||
.partd = {
|
||||
{
|
||||
.type = MTD_CALDATA,
|
||||
.path = "/fs/mtd_caldata",
|
||||
.nblocks = 240
|
||||
},
|
||||
{
|
||||
.type = MTD_MFT_REV,
|
||||
.path = "/fs/mtd_mft_rev",
|
||||
.nblocks = 8
|
||||
},
|
||||
{
|
||||
.type = MTD_ID,
|
||||
.path = "/fs/mtd_id",
|
||||
.nblocks = 8 // 256 = 32 * 8
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
static const px4_mtd_manifest_t board_mtd_config = {
|
||||
.nconfigs = 3,
|
||||
.entries = {
|
||||
&fmum_fram,
|
||||
&base_eeprom,
|
||||
&imu_eeprom
|
||||
}
|
||||
};
|
||||
|
||||
static const px4_mft_entry_s mtd_mft = {
|
||||
.type = MTD,
|
||||
.pmft = (void *) &board_mtd_config,
|
||||
};
|
||||
|
||||
static const px4_mft_s mft = {
|
||||
.nmft = 1,
|
||||
.mfts = {
|
||||
&mtd_mft,
|
||||
}
|
||||
};
|
||||
|
||||
const px4_mft_s *board_get_manifest(void)
|
||||
{
|
||||
return &mft;
|
||||
}
|
||||
@@ -0,0 +1,177 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/sdio.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "board_config.h"
|
||||
#include "stm32_gpio.h"
|
||||
#include "stm32_sdmmc.h"
|
||||
|
||||
#ifdef CONFIG_MMCSD
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Card detections requires card support and a card detection GPIO */
|
||||
|
||||
#define HAVE_NCD 1
|
||||
#if !defined(GPIO_SDMMC1_NCD)
|
||||
# undef HAVE_NCD
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
static FAR struct sdio_dev_s *sdio_dev;
|
||||
#ifdef HAVE_NCD
|
||||
static bool g_sd_inserted = 0xff; /* Impossible value */
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_ncd_interrupt
|
||||
*
|
||||
* Description:
|
||||
* Card detect interrupt handler.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef HAVE_NCD
|
||||
static int stm32_ncd_interrupt(int irq, FAR void *context)
|
||||
{
|
||||
bool present;
|
||||
|
||||
present = !stm32_gpioread(GPIO_SDMMC1_NCD);
|
||||
|
||||
if (sdio_dev && present != g_sd_inserted) {
|
||||
sdio_mediachange(sdio_dev, present);
|
||||
g_sd_inserted = present;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_sdio_initialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize SDIO-based MMC/SD card support
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int stm32_sdio_initialize(void)
|
||||
{
|
||||
int ret;
|
||||
|
||||
#ifdef HAVE_NCD
|
||||
/* Card detect */
|
||||
|
||||
bool cd_status;
|
||||
|
||||
/* Configure the card detect GPIO */
|
||||
|
||||
stm32_configgpio(GPIO_SDMMC1_NCD);
|
||||
|
||||
/* Register an interrupt handler for the card detect pin */
|
||||
|
||||
stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt);
|
||||
#endif
|
||||
|
||||
/* Mount the SDIO-based MMC/SD block driver */
|
||||
/* First, get an instance of the SDIO interface */
|
||||
|
||||
finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO);
|
||||
|
||||
sdio_dev = sdio_initialize(SDIO_SLOTNO);
|
||||
|
||||
if (!sdio_dev) {
|
||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Now bind the SDIO interface to the MMC/SD driver */
|
||||
|
||||
finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR);
|
||||
|
||||
ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev);
|
||||
|
||||
if (ret != OK) {
|
||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
finfo("Successfully bound SDIO to the MMC/SD driver\n");
|
||||
|
||||
#ifdef HAVE_NCD
|
||||
/* Use SD card detect pin to check if a card is g_sd_inserted */
|
||||
|
||||
cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD);
|
||||
finfo("Card detect : %d\n", cd_status);
|
||||
|
||||
sdio_mediachange(sdio_dev, cd_status);
|
||||
#else
|
||||
/* Assume that the SD card is inserted. What choice do we have? */
|
||||
|
||||
sdio_mediachange(sdio_dev, true);
|
||||
#endif
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_MMCSD */
|
||||
@@ -0,0 +1,58 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2020, 2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/spi_hw_description.h>
|
||||
#include <drivers/drv_sensor.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
|
||||
}, {GPIO::PortI, GPIO::Pin11}),
|
||||
initSPIBus(SPI::Bus::SPI2, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}),
|
||||
}, {GPIO::PortF, GPIO::Pin4}),
|
||||
initSPIBus(SPI::Bus::SPI3, {
|
||||
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}),
|
||||
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}),
|
||||
}, {GPIO::PortE, GPIO::Pin7}),
|
||||
initSPIBus(SPI::Bus::SPI5, {
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7})
|
||||
}),
|
||||
initSPIBusExternal(SPI::Bus::SPI6, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}),
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
||||
@@ -0,0 +1,80 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/io_timer_hw_description.h>
|
||||
|
||||
/* Timer allocation
|
||||
*
|
||||
* TIM5_CH4 T FMU_CH1
|
||||
* TIM5_CH3 T FMU_CH2
|
||||
* TIM5_CH2 T FMU_CH3
|
||||
* TIM5_CH1 T FMU_CH4
|
||||
*
|
||||
* TIM4_CH2 T FMU_CH5
|
||||
* TIM4_CH3 T FMU_CH6
|
||||
*
|
||||
* TIM12_CH1 T FMU_CH7
|
||||
* TIM12_CH2 T FMU_CH8
|
||||
*
|
||||
* TIM1_CH2 T FMU_CAP1 < Capture
|
||||
* TIM1_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT
|
||||
* TIM1_CH1 T SPIX_SYNC > Pulse or GPIO strobe
|
||||
*
|
||||
* TIM2_CH3 T HEATER > PWM OUT or GPIO
|
||||
*
|
||||
* TIM14_CH1 T BUZZER_1 - Driven by other driver
|
||||
* TIM8_CH1_IN T FMU_PPM_INPUT - Sampled byt HRT by other driver
|
||||
*/
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::Timer5, DMA{DMA::Index1}),
|
||||
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
|
||||
initIOTimer(Timer::Timer12),
|
||||
initIOTimer(Timer::Timer1),
|
||||
initIOTimer(Timer::Timer2),
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}),
|
||||
initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}),
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
initIOTimerChannelMapping(io_timers, timer_io_channels);
|
||||
@@ -0,0 +1,105 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4fmu_usb.c
|
||||
*
|
||||
* Board-specific USB functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
|
||||
#include <arm_internal.h>
|
||||
#include <chip.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include <stm32_otg.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to setup USB-related GPIO pins for the PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbinitialize(void)
|
||||
{
|
||||
/* The OTG FS has an internal soft pull-up */
|
||||
|
||||
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
|
||||
|
||||
#ifdef CONFIG_STM32H7_OTGFS
|
||||
stm32_configgpio(GPIO_OTGFS_VBUS);
|
||||
#endif
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbsuspend
|
||||
*
|
||||
* Description:
|
||||
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
|
||||
* used. This function is called whenever the USB enters or leaves suspend mode.
|
||||
* This is an opportunity for the board logic to shutdown clocks, power, etc.
|
||||
* while the USB is suspended.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||
{
|
||||
uinfo("resume: %d\n", resume);
|
||||
}
|
||||
Binary file not shown.
|
After Width: | Height: | Size: 32 KiB |
Binary file not shown.
|
After Width: | Height: | Size: 13 KiB |
Binary file not shown.
|
After Width: | Height: | Size: 22 KiB |
Binary file not shown.
|
After Width: | Height: | Size: 16 KiB |
Binary file not shown.
|
After Width: | Height: | Size: 30 KiB |
@@ -0,0 +1,221 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!DOCTYPE svg PUBLIC "-//W3C//DTD SVG 1.1//EN" "http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd">
|
||||
<!-- Generated by Microsoft Visio, SVG Export PX4 Zenoh arch.svg Page-1 -->
|
||||
<svg xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" xmlns:ev="http://www.w3.org/2001/xml-events"
|
||||
xmlns:v="http://schemas.microsoft.com/visio/2003/SVGExtensions/" width="8.02362in" height="2.43307in"
|
||||
viewBox="0 0 577.701 175.181" xml:space="preserve" color-interpolation-filters="sRGB" class="st9">
|
||||
<v:documentProperties v:langID="1033" v:metric="true" v:viewMarkup="false">
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="msvSubprocessMaster" v:prompt="" v:val="VT4(Rectangle)"/>
|
||||
<v:ud v:nameU="msvNoAutoConnect" v:val="VT0(1):26"/>
|
||||
</v:userDefs>
|
||||
</v:documentProperties>
|
||||
|
||||
<style type="text/css">
|
||||
<![CDATA[
|
||||
.st1 {fill:#ffffff;stroke:#41719c;stroke-width:0.75}
|
||||
.st2 {fill:#41719c;font-family:Calibri;font-size:0.833336em}
|
||||
.st3 {font-family:Courier New;font-size:1em}
|
||||
.st4 {font-size:1em}
|
||||
.st5 {marker-end:url(#mrkr4-62);marker-start:url(#mrkr4-60);stroke:#41719c;stroke-linecap:round;stroke-linejoin:round;stroke-width:1}
|
||||
.st6 {fill:#41719c;fill-opacity:1;stroke:#41719c;stroke-opacity:1;stroke-width:0.28409090909091}
|
||||
.st7 {fill:none;stroke:none;stroke-width:0.25}
|
||||
.st8 {fill:#41719c;font-family:Calibri;font-size:1.00001em}
|
||||
.st9 {fill:none;fill-rule:evenodd;font-size:12px;overflow:visible;stroke-linecap:square;stroke-miterlimit:3}
|
||||
]]>
|
||||
</style>
|
||||
|
||||
<defs id="Markers">
|
||||
<g id="lend4">
|
||||
<path d="M 2 1 L 0 0 L 2 -1 L 2 1 " style="stroke:none"/>
|
||||
</g>
|
||||
<marker id="mrkr4-60" class="st6" v:arrowType="4" v:arrowSize="2" v:setback="6.68" refX="6.68" orient="auto"
|
||||
markerUnits="strokeWidth" overflow="visible">
|
||||
<use xlink:href="#lend4" transform="scale(3.52) "/>
|
||||
</marker>
|
||||
<marker id="mrkr4-62" class="st6" v:arrowType="4" v:arrowSize="2" v:setback="7.04" refX="-7.04" orient="auto"
|
||||
markerUnits="strokeWidth" overflow="visible">
|
||||
<use xlink:href="#lend4" transform="scale(-3.52,-3.52) "/>
|
||||
</marker>
|
||||
</defs>
|
||||
<g v:mID="0" v:index="1" v:groupContext="foregroundPage">
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="msvThemeOrder" v:val="VT0(0):26"/>
|
||||
</v:userDefs>
|
||||
<title>Page-1</title>
|
||||
<v:pageProperties v:drawingScale="0.0393701" v:pageScale="0.0393701" v:drawingUnits="24" v:shadowOffsetX="8.50394"
|
||||
v:shadowOffsetY="-8.50394"/>
|
||||
<v:layer v:name="Connector" v:index="0"/>
|
||||
<g id="shape1-1" v:mID="1" v:groupContext="shape" transform="translate(429.165,-50.4584)">
|
||||
<title>Rectangle</title>
|
||||
<desc>Zenoh RMW implementation rmw_zenoh</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="68.5984" cy="158.173" width="137.2" height="34.0157"/>
|
||||
<rect x="0" y="141.165" width="137.197" height="34.0157" class="st1"/>
|
||||
<text x="9.51" y="155.08" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>Zenoh RMW implementation<v:newlineChar/><tspan
|
||||
x="41.59" dy="1.213em" class="st3">rmw_zenoh</tspan></text> </g>
|
||||
<g id="shape2-5" v:mID="2" v:groupContext="shape" transform="translate(429.165,-90.1434)">
|
||||
<title>Rectangle.2</title>
|
||||
<desc>ROS Middleware (RMW) API</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="68.5984" cy="158.173" width="137.2" height="34.0157"/>
|
||||
<rect x="0" y="141.165" width="137.197" height="34.0157" class="st1"/>
|
||||
<text x="11.17" y="161.17" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>ROS Middleware (RMW) API</text> </g>
|
||||
<g id="shape4-8" v:mID="4" v:groupContext="shape" transform="translate(509.953,-129.828)">
|
||||
<title>Rectangle.4</title>
|
||||
<desc>ROS 2 Node</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="28.2047" cy="157.891" width="56.41" height="34.581"/>
|
||||
<rect x="0" y="140.6" width="56.4094" height="34.581" class="st1"/>
|
||||
<text x="16.22" y="154.89" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>ROS 2<v:newlineChar/><tspan
|
||||
x="17.23" dy="1.2em" class="st4">Node</tspan></text> </g>
|
||||
<g id="shape5-12" v:mID="5" v:groupContext="shape" transform="translate(429.165,-129.828)">
|
||||
<title>Rectangle.5</title>
|
||||
<desc>ROS 2 Node</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="28.2047" cy="157.891" width="56.41" height="34.581"/>
|
||||
<rect x="0" y="140.6" width="56.4094" height="34.581" class="st1"/>
|
||||
<text x="16.22" y="154.89" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>ROS 2<v:newlineChar/><tspan
|
||||
x="17.23" dy="1.2em" class="st4">Node</tspan></text> </g>
|
||||
<g id="shape6-16" v:mID="6" v:groupContext="shape" transform="translate(93.027,-51.0236)">
|
||||
<title>Rectangle.6</title>
|
||||
<desc>PX4 Zenoh-Pico Node</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="41.644" cy="118.488" width="83.29" height="113.386"/>
|
||||
<rect x="0" y="61.7953" width="83.288" height="113.386" class="st1"/>
|
||||
<text x="10.07" y="115.49" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>PX4 Zenoh-Pico <tspan
|
||||
x="30.67" dy="1.2em" class="st4">Node</tspan></text> </g>
|
||||
<g id="shape7-20" v:mID="7" v:groupContext="shape" transform="translate(13.6063,-130.394)">
|
||||
<title>Rectangle.7</title>
|
||||
<desc>uORB Topic α</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="37.5591" cy="158.173" width="75.12" height="34.0157"/>
|
||||
<rect x="0" y="141.165" width="75.1181" height="34.0157" class="st1"/>
|
||||
<text x="10.13" y="161.17" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>uORB Topic <tspan
|
||||
class="st4" v:langID="1032">α</tspan></text> </g>
|
||||
<g id="shape8-24" v:mID="8" v:groupContext="shape" transform="translate(13.6063,-90.7087)">
|
||||
<title>Rectangle.8</title>
|
||||
<desc>uORB Topic β</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="37.5591" cy="158.173" width="75.12" height="34.0157"/>
|
||||
<rect x="0" y="141.165" width="75.1181" height="34.0157" class="st1"/>
|
||||
<text x="10.31" y="161.17" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>uORB Topic <tspan
|
||||
class="st4" v:langID="1032">β</tspan></text> </g>
|
||||
<g id="shape9-28" v:mID="9" v:groupContext="shape" transform="translate(13.6063,-51.0236)">
|
||||
<title>Rectangle.9</title>
|
||||
<desc>uORB Topic γ</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="37.5591" cy="158.173" width="75.12" height="34.0157"/>
|
||||
<rect x="0" y="141.165" width="75.1181" height="34.0157" class="st1"/>
|
||||
<text x="10.73" y="161.17" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>uORB Topic <tspan
|
||||
class="st4" v:langID="1032">γ</tspan></text> </g>
|
||||
<g id="shape10-32" v:mID="10" v:groupContext="shape" transform="translate(183.128,-130.394)">
|
||||
<title>Rectangle.10</title>
|
||||
<desc>ROS2 Topic α</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="37.5591" cy="158.173" width="75.12" height="34.0157"/>
|
||||
<rect x="0" y="141.165" width="75.1181" height="34.0157" class="st1"/>
|
||||
<text x="10.64" y="161.17" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>ROS2 Topic <tspan
|
||||
class="st4" v:langID="1032">α</tspan></text> </g>
|
||||
<g id="shape11-36" v:mID="11" v:groupContext="shape" transform="translate(183.128,-90.7087)">
|
||||
<title>Rectangle.11</title>
|
||||
<desc>ROS2 Topic β</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="37.5591" cy="158.173" width="75.12" height="34.0157"/>
|
||||
<rect x="0" y="141.165" width="75.1181" height="34.0157" class="st1"/>
|
||||
<text x="10.82" y="161.17" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>ROS2 Topic <tspan
|
||||
class="st4" v:langID="1032">β</tspan></text> </g>
|
||||
<g id="shape12-40" v:mID="12" v:groupContext="shape" transform="translate(183.128,-51.0236)">
|
||||
<title>Rectangle.12</title>
|
||||
<desc>ROS2 Topic γ</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="37.5591" cy="158.173" width="75.12" height="34.0157"/>
|
||||
<rect x="0" y="141.165" width="75.1181" height="34.0157" class="st1"/>
|
||||
<text x="11.25" y="161.17" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>ROS2 Topic <tspan
|
||||
class="st4" v:langID="1032">γ</tspan></text> </g>
|
||||
<g id="shape18-44" v:mID="18" v:groupContext="shape" transform="translate(13.6063,-11.3386)">
|
||||
<title>Rectangle.18</title>
|
||||
<desc>PX4</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="122.598" cy="158.173" width="245.2" height="34.0157"/>
|
||||
<rect x="0" y="141.165" width="245.197" height="34.0157" class="st1"/>
|
||||
<text x="114.89" y="161.17" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>PX4</text> </g>
|
||||
<g id="shape19-47" v:mID="19" v:groupContext="shape" transform="translate(322.583,-49.8088)">
|
||||
<title>Rectangle.19</title>
|
||||
<desc>Zenoh Router zenohd</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="48.3661" cy="138.907" width="96.74" height="72.5492"/>
|
||||
<rect x="0" y="102.632" width="96.7323" height="72.5492" class="st1"/>
|
||||
<text x="20.63" y="135.82" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>Zenoh Router<v:newlineChar/><tspan
|
||||
x="30.36" dy="1.213em" class="st3">zenohd</tspan></text> </g>
|
||||
<g id="shape20-51" v:mID="20" v:groupContext="shape" transform="translate(322.583,-10.1237)">
|
||||
<title>Rectangle.20</title>
|
||||
<desc>Linux</desc>
|
||||
<v:userDefs>
|
||||
<v:ud v:nameU="visVersion" v:val="VT0(15):26"/>
|
||||
</v:userDefs>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="122.598" cy="158.173" width="245.2" height="34.0157"/>
|
||||
<rect x="0" y="141.165" width="245.197" height="34.0157" class="st1"/>
|
||||
<text x="111.93" y="161.17" class="st2" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>Linux</text> </g>
|
||||
<g id="shape21-54" v:mID="21" v:groupContext="shape" v:layerMember="0" transform="translate(258.246,-147.402)">
|
||||
<title>Dynamic connector</title>
|
||||
<path d="M6.68 175.18 L7.04 175.18 L30.89 175.18 L30.89 236.5 L57.3 236.5" class="st5"/>
|
||||
</g>
|
||||
<g id="shape22-63" v:mID="22" v:groupContext="shape" v:layerMember="0" transform="translate(258.246,-107.717)">
|
||||
<title>Dynamic connector.22</title>
|
||||
<path d="M6.68 175.18 L7.04 175.18 L30.89 175.18 L30.89 196.81 L57.3 196.81" class="st5"/>
|
||||
</g>
|
||||
<g id="shape23-70" v:mID="23" v:groupContext="shape" v:layerMember="0" transform="translate(258.246,-68.0315)">
|
||||
<title>Dynamic connector.23</title>
|
||||
<path d="M6.68 175.18 L7.04 175.18 L30.89 175.18 L30.89 157.13 L57.3 157.13" class="st5"/>
|
||||
</g>
|
||||
<g id="shape24-77" v:mID="24" v:groupContext="shape" transform="translate(251.717,-17.1438)">
|
||||
<title>Sheet.24</title>
|
||||
<desc>UART TCP UDP</desc>
|
||||
<v:textBlock v:margins="rect(4,4,4,4)" v:tabSpace="42.5197"/>
|
||||
<v:textRect cx="37.5591" cy="151.863" width="75.12" height="46.6357"/>
|
||||
<rect x="0" y="128.545" width="75.1181" height="46.6357" class="st7"/>
|
||||
<text x="24.06" y="141.06" class="st8" v:langID="1033"><v:paragraph v:horizAlign="1"/><v:tabList/>UART<v:newlineChar/><tspan
|
||||
x="28.34" dy="1.2em" class="st4">TCP<v:newlineChar/></tspan><tspan x="26.92" dy="1.2em" class="st4">UDP</tspan></text> </g>
|
||||
</g>
|
||||
</svg>
|
||||
|
After Width: | Height: | Size: 12 KiB |
@@ -187,6 +187,7 @@
|
||||
- [Radiolink PIX6](flight_controller/radiolink_pix6.md)
|
||||
- [Sky-Drones AIRLink](flight_controller/airlink.md)
|
||||
- [SPRacing SPRacingH7EXTREME](flight_controller/spracingh7extreme.md)
|
||||
- [SVehicle E2](flight_controller/svehicle_e2.md)
|
||||
- [ThePeach FCC-K1](flight_controller/thepeach_k1.md)
|
||||
- [ThePeach FCC-R1](flight_controller/thepeach_r1.md)
|
||||
- [Experimental Autopilots](flight_controller/autopilot_experimental.md)
|
||||
@@ -744,6 +745,7 @@
|
||||
- [Standard Modes Protocol](mavlink/standard_modes.md)
|
||||
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md)
|
||||
- [UORB Bridged to ROS 2](middleware/dds_topics.md)
|
||||
- [Zenoh (PX4 ROS 2)](middleware/zenoh.md)
|
||||
- [Modules & Commands](modules/modules_main.md)
|
||||
- [Autotune](modules/modules_autotune.md)
|
||||
- [Commands](modules/modules_command.md)
|
||||
|
||||
@@ -83,9 +83,10 @@ This is done using the the parameters named like `UAVCAN_SUB_*` in the parameter
|
||||
|
||||
On the ARK CANnode, you may need to configure the following parameters:
|
||||
|
||||
| Parameter | Description |
|
||||
| ----------------------------------------------------------------------------------------------- | ----------------------------- |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
| Parameter | Description |
|
||||
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
|
||||
## LED Meanings
|
||||
|
||||
|
||||
@@ -110,9 +110,10 @@ When optical flow is the only source of horizontal position/velocity, then lower
|
||||
|
||||
On the ARK Flow, you may need to configure the following parameters:
|
||||
|
||||
| Parameter | Description |
|
||||
| ----------------------------------------------------------------------------------------------- | ----------------------------- |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
| Parameter | Description |
|
||||
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
|
||||
## LED Meanings
|
||||
|
||||
|
||||
@@ -105,9 +105,10 @@ Set the following parameters in _QGroundControl_:
|
||||
|
||||
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK Flow MR itself:
|
||||
|
||||
| Parameter | Description |
|
||||
| ----------------------------------------------------------------------------------------------- | ----------------------------- |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
| Parameter | Description |
|
||||
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
|
||||
## LED Meanings
|
||||
|
||||
|
||||
@@ -91,9 +91,17 @@ If the sensor is not centred within the vehicle you will also need to define sen
|
||||
|
||||
- Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true.
|
||||
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
|
||||
- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` if this is that last node on the CAN bus.
|
||||
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK GPS from the vehicles centre of gravity.
|
||||
|
||||
### ARK GPS Configuration
|
||||
|
||||
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK GPS itself:
|
||||
|
||||
| Parameter | Description |
|
||||
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. |
|
||||
|
||||
## LED Meanings
|
||||
|
||||
You will see green, blue and red LEDs on the ARK GPS when it is being flashed, and a blinking green LED if it is running properly.
|
||||
|
||||
@@ -85,7 +85,15 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if
|
||||
- Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked).
|
||||
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
|
||||
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity.
|
||||
- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus.
|
||||
|
||||
### ARK RTK GPS Configuration
|
||||
|
||||
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS itself:
|
||||
|
||||
| Parameter | Description |
|
||||
| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. |
|
||||
|
||||
### Setting Up Rover and Fixed Base
|
||||
|
||||
|
||||
@@ -96,6 +96,10 @@ If the DNA is still running and certain devices need to be manually configured,
|
||||
::: info
|
||||
The PX4 node ID can be configured using the [UAVCAN_NODE_ID](../advanced_config/parameter_reference.md#UAVCAN_NODE_ID) parameter.
|
||||
The parameter is set to 1 by default.
|
||||
|
||||
Devices running the [PX4 DroneCAN firmware](px4_cannode_fw.md) (such as [ARK CANnode](ark_cannode.md)) can use the
|
||||
[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter to set a static node ID.
|
||||
Set it to 0 (default) for dynamic allocation, or to a value between 1-127 to use a specific static node ID.
|
||||
:::
|
||||
|
||||
:::warning
|
||||
@@ -282,6 +286,11 @@ For example, the screenshot below shows the parameters for a CAN GPS with node i
|
||||
|
||||

|
||||
|
||||
Common CANNODE parameters that you can configure include:
|
||||
|
||||
- [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID): Set a static node ID (1-127) or use 0 for dynamic allocation. See [PX4 DroneCAN Firmware > Static Node ID](px4_cannode_fw.md#static-node-id) for more information.
|
||||
- [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM): Enable CAN bus termination on the last node in the bus.
|
||||
|
||||
## Device Specific Setup
|
||||
|
||||
Most DroneCAN nodes require no further setup, unless specifically noted in their device-specific documentation.
|
||||
|
||||
@@ -20,6 +20,26 @@ make ark_can-flow_default
|
||||
|
||||
This will create an output in **build/ark_can-flow_default** named **XX-X.X.XXXXXXXX.uavcan.bin**. Follow the instructions at [DroneCAN firmware update](index.md#firmware-update) to flash the firmware.
|
||||
|
||||
## Configuration
|
||||
|
||||
### Static Node ID
|
||||
|
||||
By default, DroneCAN devices use [Dynamic Node Allocation (DNA)](index.md#node-id-allocation) to automatically obtain a unique node ID from the flight controller.
|
||||
However, you can configure a static node ID using the [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter.
|
||||
|
||||
To configure a static node ID:
|
||||
|
||||
1. Set [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) to a value between 1-127 using [QGroundControl](index.md#qgc-cannode-parameter-configuration)
|
||||
2. Reboot the device
|
||||
|
||||
To return to dynamic allocation, set `CANNODE_NODE_ID` back to 0.
|
||||
Note that when switching back to dynamic allocation, the flight controller will typically continue to allocate the same node ID that was previously used (this is normal DNA behavior).
|
||||
|
||||
:::warning
|
||||
When using static node IDs, you must ensure that each device on the CAN bus has a unique node ID.
|
||||
Configuring two devices with the same ID will cause communication conflicts.
|
||||
:::
|
||||
|
||||
## Developer Information
|
||||
|
||||
This section has information that is relevant to developers who want to add support for new DroneCAN hardware to the PX4 Autopilot.
|
||||
|
||||
@@ -35,5 +35,6 @@ The boards in this category are:
|
||||
- [Radiolink PIX6](../flight_controller/radiolink_pix6.md)
|
||||
- [Sky-Drones AIRLink](../flight_controller/airlink.md)
|
||||
- [SPRacing SPRacingH7EXTREME](../flight_controller/spracingh7extreme.md)
|
||||
- [Svehicle E2](../flight_controller/svehicle_e2.md)
|
||||
- [ThePeach FCC-K1](../flight_controller/thepeach_k1.md)
|
||||
- [ThePeach FCC-R1](../flight_controller/thepeach_r1.md)
|
||||
|
||||
@@ -0,0 +1,175 @@
|
||||
# S-Vehicle E2
|
||||
|
||||
:::warning
|
||||
PX4 does not manufacture this (or any) autopilot.
|
||||
:::
|
||||
|
||||
The _E2_ is an advanced autopilot manufactured by S-Vehicle<sup>®</sup>.
|
||||
|
||||
The autopilot is recommended for commercial system integration, but is also suitable for academic research and any other applications.
|
||||
It brings you ultimate performance, stability, and reliability in every aspect.
|
||||
|
||||

|
||||
|
||||
::: info
|
||||
These flight controllers are [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md).
|
||||
:::
|
||||
|
||||
### Processors & Sensors
|
||||
|
||||
- FMU Processor: STM32H753IIK6
|
||||
- 32 Bit Arm® Cortex®-M7, 480MHz, 2MB flash memory, 1MB RAM
|
||||
- IO Processor: STM32F103
|
||||
- 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM
|
||||
- On-board sensors
|
||||
- Accel/Gyro: BMI088
|
||||
- Accel/Gyro: ICM-42688-P
|
||||
- Accel/Gyro: ICM-20649
|
||||
- Mag: RM3100
|
||||
- Barometer: 2x ICP-20100
|
||||
|
||||
### Interfaces
|
||||
|
||||
- 14x PWM Servo Outputs
|
||||
- 1x Dedicated R/C Input for Spektrum / DSM and S.Bus
|
||||
- 1x Analog/PWM RSSI Input
|
||||
- 2x TELEM Ports (with full flow control)
|
||||
- 1x UART4 Port
|
||||
- 2x GPS Ports
|
||||
- 1x Full GPS plus Safety Switch Port (GPS1)
|
||||
- 1x Basic GPS Port (with I2C, GPS2)
|
||||
- 1x USB Port (TYPE-C)
|
||||
- 1x Ethernet Port
|
||||
- Transformerless application
|
||||
- 100Mbps
|
||||
- 3x I2C Bus Ports
|
||||
- 1x SPI Bus
|
||||
- 1x Chip Select Line
|
||||
- 1x Data Ready Line
|
||||
- 1x SPI Reset Line
|
||||
- 2x CAN Ports
|
||||
- 3x Power Input Ports
|
||||
- ADC Power Input
|
||||
- I2C Power Input
|
||||
- DroneCAN/UAVCAN Power Input
|
||||
- 2x AD Ports
|
||||
- Analog Input (3.3V)
|
||||
- Analog Input (6.6V - not supported by PX4)
|
||||
- 1x Dedicated Debug Port
|
||||
- FMU Debug
|
||||
|
||||
## Purchase Channels
|
||||
|
||||
Order from [S-Vehicle](https://svehicle.cn/).
|
||||
|
||||
## Radio Control
|
||||
A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes).
|
||||
|
||||
You will need to select a compatible transmitter/receiver and then bind them so that they communicate (read the instructions that come with your specific transmitter/receiver).
|
||||
|
||||
Spektrum/DSM receivers connect to the DSM/SBUS RC input.
|
||||
PPM or SBUS receivers connect to the RC IN input port.
|
||||
CRSF receiver must be wired to a spare port (UART) on the Flight Controller. Then you can bind the transmitter and receiver together.
|
||||
|
||||
## Serial Port Mapping
|
||||
|
||||
| UART | Device | Port |
|
||||
| ------ | ---------- | ------------- |
|
||||
| USART1 | /dev/ttyS0 | GPS |
|
||||
| USART2 | /dev/ttyS1 | TELEM3 |
|
||||
| USART3 | /dev/ttyS2 | Debug Console |
|
||||
| UART4 | /dev/ttyS3 | UART4 |
|
||||
| UART5 | /dev/ttyS4 | TELEM2 |
|
||||
| USART6 | /dev/ttyS5 | PX4IO/RC |
|
||||
| UART7 | /dev/ttyS6 | TELEM1 |
|
||||
| UART8 | /dev/ttyS7 | GPS2 |
|
||||
|
||||
## PWM Output
|
||||
|
||||
The E2-Plus flight controller supports up to 14 PWM outputs.
|
||||
The first 8 outputs (labelled M1 to M8) are controlled by a dedicated STM32F103 IOMCU controller.
|
||||
The remaining 6 outputs (labelled 9 to 14) are the "auxiliary" outputs.
|
||||
These are directly attached to the STM32H753 FMU controller .
|
||||
|
||||
The 14 PWM outputs are:
|
||||
|
||||
M1 - M8 are connected to the IOMCU
|
||||
A1 - A6 are connected to the FMU
|
||||
|
||||
M1 - M8 support DShot and are in 3 groups:
|
||||
|
||||
- M1, M2 in group 1
|
||||
- M3, M4 in group 2
|
||||
- M5, M6, M7, M8 in group 3
|
||||
|
||||
The 6 FMU PWM outputs are in 2 groups:
|
||||
|
||||
A1 - A4 are in one group.
|
||||
A5, A6 are in a 2nd group.
|
||||
|
||||
Channels within the same group need to use the same output rate.
|
||||
If any channel in a group uses DShot then all channels in the group need to use DShot.
|
||||
|
||||
### Electrical data
|
||||
|
||||
- Voltage Ratings:
|
||||
- Max input voltage: 5.7V
|
||||
- USB Power Input: 4.75\~5.25V
|
||||
- Servo Rail Input: 0\~9.9V
|
||||
- Current Ratings:
|
||||
- TELEM1 and GPS2 combined output current limiter: 1.5A
|
||||
- All other port combined output current limiter: 1.5A
|
||||
|
||||
## Battery Monitoring
|
||||
|
||||
The board has connectors for 3 power monitors.
|
||||
|
||||
- POWER1 -- ADC
|
||||
- POWER2 -- DroneCAN
|
||||
- POWER3 -- I2C
|
||||
|
||||
The board is configure by default for a analog power monitor, and also has DroneCAN power monitor and I2C defaults configured which is enabled.
|
||||
|
||||
The default PDB included with the E2+ is analog and must be connected to `POWER1`.
|
||||
|
||||
## Building Firmware
|
||||
|
||||
To [build PX4](../dev_setup/building_px4.md) for this target, execute:
|
||||
|
||||
```sh
|
||||
make svehicle_e2_default
|
||||
```
|
||||
|
||||
## Debug Port
|
||||
|
||||
The [PX4 System Console](../debug/system_console.md) and [SWD Interface](../debug/swd_debug.md) operate on the **FMU Debug** port.
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| ------- | -------------- | ----- |
|
||||
| 1 (red) | 5V+ | +5V |
|
||||
| 2 (blk) | DEBUG TX (OUT) | +3.3V |
|
||||
| 3 (blk) | DEBUG RX (IN) | +3.3V |
|
||||
| 4 (blk) | FMU_SWDIO | +3.3V |
|
||||
| 5 (blk) | FMU_SWCLK | +3.3V |
|
||||
| 6 (blk) | GND | GND |
|
||||
|
||||
For information about using this port see:
|
||||
|
||||
- [SWD Debug Port](../debug/swd_debug.md)
|
||||
- [PX4 System Console](../debug/system_console.md) (Note, the FMU console maps to USART3).
|
||||
- All ports use GH1.25 ,power ports use ports on E2 uses the 6 circuit [2.00mm Pitch CLIK-Mate Wire-to-Board PCB Receptacle](https://www.molex.com/en-us/products/part-detail/5024430670).
|
||||
|
||||
## Pinouts
|
||||
|
||||

|
||||
|
||||

|
||||
|
||||

|
||||
|
||||

|
||||
|
||||
## Supported Platforms / Airframes
|
||||
|
||||
Any multirotor/airplane/rover or boat that can be controlled using normal RC servos or Futaba S-Bus servos.
|
||||
The complete set of supported configurations can be found in the [Airframe Reference](../airframes/airframe_reference.md).
|
||||
@@ -5,7 +5,7 @@ This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main
|
||||
:::
|
||||
|
||||
|
||||
The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default).
|
||||
The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) and/or [zenoh](../modules/modules_driver.md#zenoh) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default).
|
||||
|
||||
This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on.
|
||||
|
||||
@@ -13,7 +13,7 @@ This document shows a markdown-rendered version of [dds_topics.yaml](https://git
|
||||
|
||||
Topic | Type| Rate Limit
|
||||
--- | --- | ---
|
||||
`/fmu/out/register_ext_component_reply` | [px4_msgs::msg::RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md) |
|
||||
`/fmu/out/register_ext_component_reply` | [px4_msgs::msg::RegisterExtComponentReply](../msg_docs/RegisterExtComponentReply.md) |
|
||||
`/fmu/out/arming_check_request` | [px4_msgs::msg::ArmingCheckRequest](../msg_docs/ArmingCheckRequest.md) | 5.0
|
||||
`/fmu/out/mode_completed` | [px4_msgs::msg::ModeCompleted](../msg_docs/ModeCompleted.md) | 50.0
|
||||
`/fmu/out/battery_status` | [px4_msgs::msg::BatteryStatus](../msg_docs/BatteryStatus.md) | 1.0
|
||||
@@ -21,21 +21,21 @@ Topic | Type| Rate Limit
|
||||
`/fmu/out/estimator_status_flags` | [px4_msgs::msg::EstimatorStatusFlags](../msg_docs/EstimatorStatusFlags.md) | 5.0
|
||||
`/fmu/out/failsafe_flags` | [px4_msgs::msg::FailsafeFlags](../msg_docs/FailsafeFlags.md) | 5.0
|
||||
`/fmu/out/manual_control_setpoint` | [px4_msgs::msg::ManualControlSetpoint](../msg_docs/ManualControlSetpoint.md) | 25.0
|
||||
`/fmu/out/message_format_response` | [px4_msgs::msg::MessageFormatResponse](../msg_docs/MessageFormatResponse.md) |
|
||||
`/fmu/out/message_format_response` | [px4_msgs::msg::MessageFormatResponse](../msg_docs/MessageFormatResponse.md) |
|
||||
`/fmu/out/position_setpoint_triplet` | [px4_msgs::msg::PositionSetpointTriplet](../msg_docs/PositionSetpointTriplet.md) | 5.0
|
||||
`/fmu/out/sensor_combined` | [px4_msgs::msg::SensorCombined](../msg_docs/SensorCombined.md) |
|
||||
`/fmu/out/sensor_combined` | [px4_msgs::msg::SensorCombined](../msg_docs/SensorCombined.md) |
|
||||
`/fmu/out/timesync_status` | [px4_msgs::msg::TimesyncStatus](../msg_docs/TimesyncStatus.md) | 10.0
|
||||
`/fmu/out/vehicle_land_detected` | [px4_msgs::msg::VehicleLandDetected](../msg_docs/VehicleLandDetected.md) | 5.0
|
||||
`/fmu/out/vehicle_attitude` | [px4_msgs::msg::VehicleAttitude](../msg_docs/VehicleAttitude.md) |
|
||||
`/fmu/out/vehicle_attitude` | [px4_msgs::msg::VehicleAttitude](../msg_docs/VehicleAttitude.md) |
|
||||
`/fmu/out/vehicle_control_mode` | [px4_msgs::msg::VehicleControlMode](../msg_docs/VehicleControlMode.md) | 50.0
|
||||
`/fmu/out/vehicle_command_ack` | [px4_msgs::msg::VehicleCommandAck](../msg_docs/VehicleCommandAck.md) |
|
||||
`/fmu/out/vehicle_command_ack` | [px4_msgs::msg::VehicleCommandAck](../msg_docs/VehicleCommandAck.md) |
|
||||
`/fmu/out/vehicle_global_position` | [px4_msgs::msg::VehicleGlobalPosition](../msg_docs/VehicleGlobalPosition.md) | 50.0
|
||||
`/fmu/out/vehicle_gps_position` | [px4_msgs::msg::SensorGps](../msg_docs/SensorGps.md) | 50.0
|
||||
`/fmu/out/vehicle_local_position` | [px4_msgs::msg::VehicleLocalPosition](../msg_docs/VehicleLocalPosition.md) | 50.0
|
||||
`/fmu/out/vehicle_odometry` | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) |
|
||||
`/fmu/out/vehicle_odometry` | [px4_msgs::msg::VehicleOdometry](../msg_docs/VehicleOdometry.md) |
|
||||
`/fmu/out/vehicle_status` | [px4_msgs::msg::VehicleStatus](../msg_docs/VehicleStatus.md) | 5.0
|
||||
`/fmu/out/airspeed_validated` | [px4_msgs::msg::AirspeedValidated](../msg_docs/AirspeedValidated.md) | 50.0
|
||||
`/fmu/out/vtol_vehicle_status` | [px4_msgs::msg::VtolVehicleStatus](../msg_docs/VtolVehicleStatus.md) |
|
||||
`/fmu/out/vtol_vehicle_status` | [px4_msgs::msg::VtolVehicleStatus](../msg_docs/VtolVehicleStatus.md) |
|
||||
`/fmu/out/home_position` | [px4_msgs::msg::HomePosition](../msg_docs/HomePosition.md) | 5.0
|
||||
|
||||
## Subscriptions
|
||||
|
||||
@@ -0,0 +1,200 @@
|
||||
# Zenoh (PX4 ROS 2 rmw_zenoh)
|
||||
|
||||
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
|
||||
|
||||
:::warning Experimental
|
||||
At the time of writing, PX4 Zenoh-pico is experimental, and hence subject to change.
|
||||
:::
|
||||
|
||||
PX4 supports Zenoh as an alternative mechanism (to DDS) for bridging uORB topics to [ROS 2](../ros2/user_guide.md) (via the ROS 2 [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh) middleware).
|
||||
This allows uORB messages to be published and subscribed on a companion computer as though they were ROS 2 topics.
|
||||
It provides a fast and lightweight way to connect PX4 to ROS 2, making it easier for applications to access vehicle telemetry and send control commands.
|
||||
|
||||
The following guide describes the architecture and various options for setting up the Zenoh client and router.
|
||||
In particular, it covers the options that are most important to PX4 users exploring Zenoh as an alternative communication layer for ROS 2.
|
||||
|
||||
## Architecture
|
||||
|
||||
The Zenoh-based middleware consists of a client running on PX4 and a Zenoh router running on the companion computer, with bi-directional data exchange between them over a UART, TCP, UDP, or multicast-UDP link.
|
||||
The router acts as a broker and discovery service, enabling PX4 to publish and subscribe to topics in the global Zenoh data space.
|
||||
This allows seamless integration with ROS 2 nodes using [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh), and supports flexible deployment across distributed systems.
|
||||
|
||||

|
||||
|
||||
The client is the _PX4 Zenoh-Pico Node_ referred to above, which is implemented in the [PX4 `zenoh` module](../modules/modules_driver.md#zenoh).
|
||||
This is based on Zenoh-Pico, a minimalistic version of [Eclipse Zenoh](https://zenoh.io/) (a data-centric protocol designed for real-time, distributed, and resource-constrained environments).
|
||||
|
||||
The router suggested above is [zenohd](https://github.com/eclipse-zenoh/zenoh/tree/main/zenohd).
|
||||
|
||||
:::info
|
||||
UART is supported by Zenoh but has not yet implemented in the PX4 Zenoh-Pico node.
|
||||
:::
|
||||
|
||||
## ROS 2 Zenoh Bring-up on Linux Companion
|
||||
|
||||
In order for PX4 uORB topics to be shared with ROS 2 applications, you will need the PX4 Zenoh-Pico Node client running on your FMU, connected to a Zenoh router running on the companion computer (or elsewhere in the network).
|
||||
|
||||
First select Zenoh as the ROS 2 transport by setting the `RMW_IMPLEMENTATION` environment variable as shown:
|
||||
|
||||
```sh
|
||||
export RMW_IMPLEMENTATION=rmw_zenoh_cpp
|
||||
```
|
||||
|
||||
Then start the Zenoh router using the command:
|
||||
|
||||
```sh
|
||||
ros2 run rmw_zenoh_cpp rmw_zenohd
|
||||
```
|
||||
|
||||
For more information about the Zenoh Router see the [rmw_zenoh](https://github.com/ros2/rmw_zenoh?tab=readme-ov-file#start-the-zenoh-router) documentation.
|
||||
|
||||
## PX4 Zenoh-Pico Node Setup
|
||||
|
||||
### PX4 Firmware
|
||||
|
||||
Before setting up the Zenoh communication, first make sure that your firmware contains the driver that implements the [`zenoh` driver](../modules/modules_driver.md#zenoh), which provides the implementation of the _PX4 Zenoh-Pico Node_.
|
||||
|
||||
You can check if the module is present on your board by searching for the key `CONFIG_MODULES_ZENOH=y` in your board's `default.px4board` KConfig file.
|
||||
For example, you can see that the module is present in `px4_fmu-v6xrt` build targets from [/boards/px4/fmu-v6xrt/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6xrt/default.px4board#L91).
|
||||
|
||||
If `CONFIG_MODULES_ZENOH=y` is not preset you can add this key to your board configuration and rebuild.
|
||||
Note that due to flash constraints you may need to remove other components in order to include the module (such as the [`uxrce_dds_client` module](../modules/modules_system.md#uxrce-dds-client), which you will not need if you are using Zenoh).
|
||||
|
||||
The table below shows some of the PX4 targets that include Zenoh by default.
|
||||
|
||||
| PX4 Target | Notes |
|
||||
| ---------------------- | ------------------------------------------------------------------------------------------- |
|
||||
| `px4_fmu-v6xrt` | For [FMUv6X-RT](../flight_controller/nxp_mr_vmu_rt1176.md) (reference platform for testing) |
|
||||
| `nxp_tropic-community` | |
|
||||
| `nxp_mr-tropic` | |
|
||||
| `nxp_mr-canhubk344` | |
|
||||
| `px4_sitl_zenoh` | Zenoh-enabled simulation build |
|
||||
| `px4_fmu-v6x_zenoh` | Zenoh-enabled firmware for FMUv6X |
|
||||
|
||||
Zenoh is not included in the default `px4_fmu-` targets for any firmware other than `px4_fmu-v6xrt` (`px4_sitl_zenoh` and `px4_fmu-v6x_zenoh` [are build variants](../dev_setup/building_px4.md#px4-make-build-targets)).
|
||||
|
||||
::: tip
|
||||
You can check if Zenoh is present at runtime by using QGroundControl to [find the parameter](../advanced_config/parameters.md#finding-a-parameter) [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE).
|
||||
If present, the module is installed.
|
||||
:::
|
||||
|
||||
### Enable Zenoh on PX4 Startup
|
||||
|
||||
Set the [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE) parameter to `1` to enable Zenoh on PX4 startup.
|
||||
|
||||
### Configure Zenoh Network
|
||||
|
||||
Set up PX4 to connect to the companion computer running `zenohd`.
|
||||
|
||||
PX4's default IP address of the Zenoh daemon host is `10.41.10.1`.
|
||||
If you're using a different IP for the Zenoh daemon, run the following command (replacing the address) in a PX4 shell and then reboot:
|
||||
|
||||
```sh
|
||||
zenoh config net client tcp/10.41.10.1:7447#iface=eth0
|
||||
```
|
||||
|
||||
Note that for the simulation target with Zeroh (`px4_sitl_zenoh`) you won't need to make any changes because the default IP address of the Zenoh daemon is set to `localhost`.
|
||||
|
||||
:::warning
|
||||
Any changes to the network configuration require a PX4 system reboot to take effect.
|
||||
:::
|
||||
|
||||
:::tip
|
||||
See [PX4 Ethernet Setup](../advanced_config/ethernet_setup.md) for more information about Ethernet configuration.
|
||||
:::
|
||||
|
||||
### PX4 Zenoh-pico Node configuration
|
||||
|
||||
The **default configuration** is auto-generated from the [dds_topics.yaml](../middleware/dds_topics.md) file in the PX4 repository.
|
||||
This file specifies which uORB message definitions are to be published/subscribed by ROS 2 applications, and hence (indirectly) which topics are compiled into the zenoh module.
|
||||
|
||||
To inspect the current Zenoh configuration:
|
||||
|
||||
```sh
|
||||
zenoh config
|
||||
```
|
||||
|
||||
The PX4 Zenoh-pico node stores its configuration on the **SD card** under the `zenoh` folder.
|
||||
This folder contains three key files:
|
||||
|
||||
- **`net.txt`** – Defines the **Zenoh network configuration**.
|
||||
- **`pub.csv`** – Maps **uORB topics to ROS2 topics** (used for publishing).
|
||||
- **`sub.csv`** – Maps **ROS2 topics to uORB topics** (used for subscribing).
|
||||
|
||||
### 4. Modifying Topic Mappings
|
||||
|
||||
Zenoh topic mappings define how data flows between PX4's internal uORB topics and external ROS2 topics via Zenoh.
|
||||
These mappings are stored in `pub.csv` and `sub.csv` on the SD card, and can be modified at runtime using the `zenoh config` CLI tool.
|
||||
|
||||
:::warning
|
||||
Any changes to the topic mappings require a PX4 system reboot to take effect.
|
||||
:::
|
||||
|
||||
There are two types of mappings you can modify:
|
||||
|
||||
- **Publisher mappings**: Forward data from a uORB topic to a Zenoh topic.
|
||||
- **Subscriber mappings**: Receive data from a Zenoh topic and publish it to a uORB topic.
|
||||
|
||||
The main operations and their commands are:
|
||||
|
||||
- Publish a uORB topic to a Zenoh topic:
|
||||
|
||||
```sh
|
||||
zenoh config add publisher <zenoh_topic> <uorb_topic> [uorb_instance]
|
||||
```
|
||||
|
||||
- Subscribe to a Zenoh topic and forward it to a uORB topic:
|
||||
|
||||
```sh
|
||||
zenoh config add subscriber <zenoh_topic> <uorb_topic> [uorb_instance]
|
||||
```
|
||||
|
||||
- Remove existing mappings:
|
||||
|
||||
```sh
|
||||
zenoh config delete publisher <zenoh_topic>
|
||||
zenoh config delete subscriber <zenoh_topic>
|
||||
```
|
||||
|
||||
After modifying the mappings, reboot PX4 to apply the changes.
|
||||
The updated configuration will be loaded from the SD card during startup.
|
||||
|
||||
## Communicating with PX4 from ROS 2 via Zenoh
|
||||
|
||||
Once your PX4 FMU is publishing data into ROS 2, you can inspect the available topics and their contents using standard ROS 2 CLI tools:
|
||||
|
||||
```sh
|
||||
ros2 topic list
|
||||
```
|
||||
|
||||
Check topic type and publishers/subscribers:
|
||||
|
||||
```sh
|
||||
ros2 topic info -v /fmu/out/vehicle_status
|
||||
Type: px4_msgs/msg/VehicleStatus
|
||||
|
||||
Publisher count: 1
|
||||
|
||||
Node name: px4_aabbcc00000000000000000000000000
|
||||
Node namespace: /
|
||||
Topic type: px4_msgs/msg/VehicleStatus
|
||||
Topic type hash: RIHS01_828bddbb7d4c2aa6ad93757955f6893be1ec5d8f11885ec7715bcdd76b5226c9
|
||||
Endpoint type: PUBLISHER
|
||||
GID: 82.99.74.2c.b6.7d.93.44.91.4d.fe.14.93.58.40.16
|
||||
QoS profile:
|
||||
Reliability: RELIABLE
|
||||
History (Depth): KEEP_LAST (7)
|
||||
Durability: VOLATILE
|
||||
Lifespan: Infinite
|
||||
Deadline: Infinite
|
||||
Liveliness: AUTOMATIC
|
||||
Liveliness lease duration: Infinite
|
||||
|
||||
Subscription count: 0
|
||||
```
|
||||
|
||||
### PX4 ROS 2 Interface with Zenoh
|
||||
|
||||
The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) works out of the box with Zenoh as a transport backend.
|
||||
This means you can publish and subscribe to PX4 topics over Zenoh without changing your ROS 2 nodes or dealing with DDS configuration.
|
||||
For setup details and supported message types, refer to the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md).
|
||||
@@ -286,6 +286,7 @@
|
||||
- [CubePilot Here+ (Discontined)](gps_compass/rtk_gps_hex_hereplus.md)
|
||||
- [INS (Inertial Navigation/GNSS)](sensor/inertial_navigation_systems.md)
|
||||
- [InertialLabs](sensor/inertiallabs.md)
|
||||
- [MicroStrain](sensor/microstrain.md)
|
||||
- [sbgECom](sensor/sbgecom.md)
|
||||
- [VectorNav](sensor/vectornav.md)
|
||||
- [광류 센서](sensor/optical_flow.md)
|
||||
@@ -701,6 +702,7 @@
|
||||
- [SensorCombined](msg_docs/SensorCombined.md)
|
||||
- [SensorCorrection](msg_docs/SensorCorrection.md)
|
||||
- [SensorGnssRelative](msg_docs/SensorGnssRelative.md)
|
||||
- [SensorGnssStatus](msg_docs/SensorGnssStatus.md)
|
||||
- [SensorGps](msg_docs/SensorGps.md)
|
||||
- [SensorGyro](msg_docs/SensorGyro.md)
|
||||
- [SensorGyroFft](msg_docs/SensorGyroFft.md)
|
||||
@@ -762,6 +764,7 @@
|
||||
- [Standard Modes Protocol](mavlink/standard_modes.md)
|
||||
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md)
|
||||
- [UORB Bridged to ROS 2](middleware/dds_topics.md)
|
||||
- [Zenoh (PX4 ROS 2)](middleware/zenoh.md)
|
||||
- [모듈과 명령어](modules/modules_main.md)
|
||||
- [자동 튜닝](modules/modules_autotune.md)
|
||||
- [명령어](modules/modules_command.md)
|
||||
|
||||
@@ -618,6 +618,10 @@ div.frame_variant td, div.frame_variant th {
|
||||
<td><a href="https://www.axialadventure.com/product/1-10-scx10-ii-trail-honcho-4wd-rock-crawler-brushed-rtr/AXID9059.html">Axial SCX10 2 Trail Honcho</a></td>
|
||||
<td>유지보수: John Doe <john@example.com><p><code>SYS_AUTOSTART</code> = 51001</p></td>
|
||||
</tr>
|
||||
<tr id="rover_rover_nxp_b3rb_rover_ackermann">
|
||||
<td>NXP B3RB Rover Ackermann</td>
|
||||
<td>유지보수: John Doe <john@example.com><p><code>SYS_AUTOSTART</code> = 51002</p></td>
|
||||
</tr>
|
||||
<tr id="rover_rover_generic_rover_mecanum">
|
||||
<td>Generic Rover Mecanum</td>
|
||||
<td>유지보수: John Doe <john@example.com><p><code>SYS_AUTOSTART</code> = 52000</p></td>
|
||||
|
||||
@@ -276,12 +276,12 @@ The relevant parameters are listed in the table below.
|
||||
|
||||
## 고장 감지기
|
||||
|
||||
고장 감지기를 사용하여 차량의 예기치 않게 전복되거나 외부의 고장 감지 시스템에 따른 보호 조치를 할 수 있습니다.
|
||||
The failure detector allows a vehicle to take protective actions if it unexpectedly flips, detects a motor failure, or if it is notified by an external failure detection system.
|
||||
|
||||
During **flight**, the failure detector can be used to trigger [flight termination](../advanced_config/flight_termination.md) if failure conditions are met, which may then launch a [parachute](../peripherals/parachute.md) or perform some other action.
|
||||
|
||||
:::info
|
||||
Failure detection during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)).
|
||||
Acting on a detected failure during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)).
|
||||
:::
|
||||
|
||||
During **takeoff** the failure detector [attitude trigger](#attitude-trigger) invokes the [disarm action](#act_disarm) if the vehicle flips (disarm kills the motors but, unlike flight termination, will not launch a parachute or perform other failure actions).
|
||||
@@ -303,6 +303,26 @@ The failure detector is active in all vehicle types and modes, except for those
|
||||
| <a id="FD_FAIL_P_TTRI"></a>[FD_FAIL_P_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_P_TTRI) | Time to exceed [FD_FAIL_P](#FD_FAIL_P) for failure detection (default 0.3s). |
|
||||
| <a id="FD_FAIL_R_TTRI"></a>[FD_FAIL_R_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_R_TTRI) | Time to exceed [FD_FAIL_R](#FD_FAIL_R) for failure detection (default 0.3s). |
|
||||
|
||||
### Motor Failure Trigger
|
||||
|
||||
The failure detector can be configured to detect a motor failure while armed (and trigger an associated action) in the following conditions:
|
||||
|
||||
- A 300 ms timeout occurs in telemetry from an ESC that was previously available.
|
||||
- The input current in the telemetry of an ESC which was previously positive gets too low for more than [`FD_ACT_MOT_TOUT`](FD_ACT_MOT_TOUT) ms.
|
||||
The "too low" condition is defined by:
|
||||
|
||||
```text
|
||||
{esc current} < {parameter FD_ACT_MOT_C2T} * {motor command between 0 and 1}
|
||||
```
|
||||
|
||||
| 매개변수 | 설명 |
|
||||
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="FD_ACT_EN"></a>[FD_ACT_EN](../advanced_config/parameter_reference.md#FD_ACT_EN) | Enable/disable the motor failure trigger completely. |
|
||||
| <a id="FD_ACT_MOT_THR"></a>[FD_ACT_MOT_THR](../advanced_config/parameter_reference.md#FD_ACT_MOT_THR) | Minimum normalized [0,1] motor command below which motor under current is ignored. |
|
||||
| <a id="FD_ACT_MOT_C2T"></a>[FD_ACT_MOT_C2T](../advanced_config/parameter_reference.md#FD_ACT_MOT_C2T) | Scale between normalized [0,1] motor command and expected minimally reported currrent when the rotor is healthy. |
|
||||
| <a id="FD_ACT_MOT_TOUT"></a>[FD_ACT_MOT_TOUT](../advanced_config/parameter_reference.md#FD_ACT_MOT_TOUT) | Time in miliseconds for which the under current detection condition needs to stay true. |
|
||||
| <a id="CA_FAILURE_MODE"></a>[CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) | Configure to not only warn about a motor failure but remove the first motor that detects a failure from the allocation effectiveness which turns off the motor and tries to operate the vehicle without it until disarming the next time. |
|
||||
|
||||
### 외부 자동 작동 시스템 (ATS)
|
||||
|
||||
The [failure detector](#failure-detector), if [enabled](#CBRK_FLIGHTTERM), can also be triggered by an external ATS system.
|
||||
|
||||
@@ -19,7 +19,7 @@ At time of writing (PX4 v1.14):
|
||||
|
||||
## 장애 시스템 명령
|
||||
|
||||
Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 console/shell, specifying both the target and type of the failure.
|
||||
Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 [console/shell](../debug/consoles.md) (such as the [QGC MAVLink Console](../debug/mavlink_shell.md#qgroundcontrol-mavlink-console) or SITL _pxh shell_), specifying both the target and type of the failure.
|
||||
|
||||
### 구문
|
||||
|
||||
@@ -61,11 +61,18 @@ failure <component> <failure_type> [-i <instance_number>]
|
||||
- _instance number_ (optional): Instance number of affected sensor.
|
||||
0 (기본값) 지정된 유형의 모든 센서를 나타냅니다.
|
||||
|
||||
### Example
|
||||
## MAVSDK 실패 플러그인
|
||||
|
||||
The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures.
|
||||
It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)).
|
||||
|
||||
The plugin API is a direct mapping of the failure command shown above, with a few additional error signals related to the connection.
|
||||
|
||||
## Example: RC signal
|
||||
|
||||
To simulate losing RC signal without having to turn off your RC controller:
|
||||
|
||||
1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). And specifically to turn off motors also [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE).
|
||||
1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter.
|
||||
2. Enter the following commands on the MAVLink console or SITL _pxh shell_:
|
||||
|
||||
```sh
|
||||
@@ -76,9 +83,18 @@ To simulate losing RC signal without having to turn off your RC controller:
|
||||
failure rc_signal ok
|
||||
```
|
||||
|
||||
## MAVSDK 실패 플러그인
|
||||
## Example: Motor
|
||||
|
||||
The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures.
|
||||
It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)).
|
||||
To stop a motor mid-flight without the system anticipating it or excluding it from allocation effectiveness:
|
||||
|
||||
The plugin API is a direct mapping of the failure command shown above, with a few additional error signals related to the connection.
|
||||
1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter.
|
||||
2. Enable [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) parameter to allow turning off motors.
|
||||
3. Enter the following commands on the MAVLink console or SITL _pxh shell_:
|
||||
|
||||
```sh
|
||||
# Turn off first motor
|
||||
failure motor off -i 1
|
||||
|
||||
# Turn it back on
|
||||
failure motor ok -i 1
|
||||
```
|
||||
|
||||
@@ -160,7 +160,7 @@ ulog 스트리밍을 지원하는 다양한 클라이언트가 있습니다.
|
||||
|
||||
- If log streaming does not start, make sure the `logger` is running (see above), and inspect the console output while starting.
|
||||
- 그래도 작동하지 않으면, MAVLink 2를 사용하고 있는지 확인하십시오.
|
||||
Enforce it by setting `MAV_PROTO_VER` to 2.
|
||||
`MAV_PROTO_VER` needs to be set to 2.
|
||||
- Log streaming uses a maximum of 70% of the configured MAVLink rate (`-r` parameter).
|
||||
더 큰 전송율이 요구되는 상황에서는, 메세지가 사라집니다.
|
||||
The currently used percentage can be inspected with `mavlink status` (1.8% is used in this example):
|
||||
|
||||
@@ -83,9 +83,10 @@ This is done using the the parameters named like `UAVCAN_SUB_*` in the parameter
|
||||
|
||||
On the ARK CANnode, you may need to configure the following parameters:
|
||||
|
||||
| 매개변수 | 설명 |
|
||||
| -------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
| 매개변수 | 설명 |
|
||||
| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
|
||||
## LED 신호의 의미
|
||||
|
||||
|
||||
@@ -109,9 +109,10 @@ When optical flow is the only source of horizontal position/velocity, then lower
|
||||
|
||||
On the ARK Flow, you may need to configure the following parameters:
|
||||
|
||||
| 매개변수 | 설명 |
|
||||
| -------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
| 매개변수 | 설명 |
|
||||
| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
|
||||
## LED 신호의 의미
|
||||
|
||||
|
||||
@@ -104,9 +104,10 @@ Set the following parameters in _QGroundControl_:
|
||||
|
||||
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK Flow MR itself:
|
||||
|
||||
| 매개변수 | 설명 |
|
||||
| -------------------------------------------------------------------------------------------------------------------- | --------------------------------------------- |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
| 매개변수 | 설명 |
|
||||
| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. |
|
||||
|
||||
## LED 신호의 의미
|
||||
|
||||
|
||||
@@ -91,9 +91,17 @@ If the sensor is not centred within the vehicle you will also need to define sen
|
||||
|
||||
- Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true.
|
||||
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
|
||||
- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` if this is that last node on the CAN bus.
|
||||
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK GPS from the vehicles centre of gravity.
|
||||
|
||||
### ARK GPS Configuration
|
||||
|
||||
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK GPS itself:
|
||||
|
||||
| 매개변수 | 설명 |
|
||||
| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. |
|
||||
|
||||
## LED 신호의 의미
|
||||
|
||||
You will see green, blue and red LEDs on the ARK GPS when it is being flashed, and a blinking green LED if it is running properly.
|
||||
|
||||
@@ -85,7 +85,15 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if
|
||||
- Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked).
|
||||
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
|
||||
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity.
|
||||
- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus.
|
||||
|
||||
### ARK RTK GPS Configuration
|
||||
|
||||
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS itself:
|
||||
|
||||
| 매개변수 | 설명 |
|
||||
| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. |
|
||||
|
||||
### Setting Up Rover and Fixed Base
|
||||
|
||||
|
||||
@@ -102,6 +102,10 @@ If the DNA is still running and certain devices need to be manually configured,
|
||||
:::info
|
||||
The PX4 node ID can be configured using the [UAVCAN_NODE_ID](../advanced_config/parameter_reference.md#UAVCAN_NODE_ID) parameter.
|
||||
The parameter is set to 1 by default.
|
||||
|
||||
Devices running the [PX4 DroneCAN firmware](px4_cannode_fw.md) (such as [ARK CANnode](ark_cannode.md)) can use the
|
||||
[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter to set a static node ID.
|
||||
Set it to 0 (default) for dynamic allocation, or to a value between 1-127 to use a specific static node ID.
|
||||
:::
|
||||
|
||||
:::warning
|
||||
@@ -288,6 +292,11 @@ For example, the screenshot below shows the parameters for a CAN GPS with node i
|
||||
|
||||

|
||||
|
||||
Common CANNODE parameters that you can configure include:
|
||||
|
||||
- [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID): Set a static node ID (1-127) or use 0 for dynamic allocation. See [PX4 DroneCAN Firmware > Static Node ID](px4_cannode_fw.md#static-node-id) for more information.
|
||||
- [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM): Enable CAN bus termination on the last node in the bus.
|
||||
|
||||
## Device Specific Setup
|
||||
|
||||
Most DroneCAN nodes require no further setup, unless specifically noted in their device-specific documentation.
|
||||
|
||||
@@ -20,6 +20,26 @@ make ark_can-flow_default
|
||||
|
||||
This will create an output in **build/ark_can-flow_default** named **XX-X.X.XXXXXXXX.uavcan.bin**. Follow the instructions at [DroneCAN firmware update](index.md#firmware-update) to flash the firmware.
|
||||
|
||||
## 설정
|
||||
|
||||
### Static Node ID
|
||||
|
||||
By default, DroneCAN devices use [Dynamic Node Allocation (DNA)](index.md#node-id-allocation) to automatically obtain a unique node ID from the flight controller.
|
||||
However, you can configure a static node ID using the [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter.
|
||||
|
||||
To configure a static node ID:
|
||||
|
||||
1. Set [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) to a value between 1-127 using [QGroundControl](index.md#qgc-cannode-parameter-configuration)
|
||||
2. Reboot the device
|
||||
|
||||
To return to dynamic allocation, set `CANNODE_NODE_ID` back to 0.
|
||||
Note that when switching back to dynamic allocation, the flight controller will typically continue to allocate the same node ID that was previously used (this is normal DNA behavior).
|
||||
|
||||
:::warning
|
||||
When using static node IDs, you must ensure that each device on the CAN bus has a unique node ID.
|
||||
Configuring two devices with the same ID will cause communication conflicts.
|
||||
:::
|
||||
|
||||
## 개발자 정보
|
||||
|
||||
This section has information that is relevant to developers who want to add support for new DroneCAN hardware to the PX4 Autopilot.
|
||||
|
||||
@@ -43,9 +43,8 @@ The horizontal position of the vehicle can move due to wind (or pre-existing mom
|
||||
|
||||
The mode is affected by the following parameters:
|
||||
|
||||
| 매개변수 | 설명 |
|
||||
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
|
||||
| <a id="MPC_Z_VEL_MAX_UP"></a>[MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | 최대 수직 상승 속도. 기본값: 3 m/s. |
|
||||
| <a id="MPC_Z_VEL_MAX_DN"></a>[MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | 최대 수직 하강 속도. 기본값: 1 m/s. |
|
||||
| <a id="RCX_DZ"></a>`RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. |
|
||||
| <a id="MPC_xxx"></a>`MPC_XXXX` | 대부분의 MPC_xxx 매개 변수는이 모드에서 비행 동작에 어느정도 영향을 미칩니다 . For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. |
|
||||
| 매개변수 | 설명 |
|
||||
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="MPC_Z_VEL_MAX_UP"></a>[MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | 최대 수직 상승 속도. 기본값: 3 m/s. |
|
||||
| <a id="MPC_Z_VEL_MAX_DN"></a>[MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | 최대 수직 하강 속도. 기본값: 1 m/s. |
|
||||
| <a id="MPC_xxx"></a>`MPC_XXXX` | 대부분의 MPC_xxx 매개 변수는이 모드에서 비행 동작에 어느정도 영향을 미칩니다 . For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. |
|
||||
|
||||
@@ -67,7 +67,6 @@ All the parameters in the [Multicopter Position Control](../advanced_config/para
|
||||
| <a id="MPC_Z_VEL_MAX_DN"></a>[MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | 최대 수직 하강 속도. 기본값: 1 m/s. |
|
||||
| <a id="MPC_LAND_ALT1"></a>[MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | Altitude for triggering first phase of slow landing. Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). Default 10m. |
|
||||
| <a id="MPC_LAND_ALT2"></a>[MPC_LAND_ALT2](../advanced_config/parameter_reference.md#MPC_LAND_ALT2) | Altitude for second phase of slow landing. Below this altitude descending velocity gets limited to [`MPC_LAND_SPEED`](#MPC_LAND_SPEED). Value needs to be lower than "MPC_LAND_ALT1". Default 5m. |
|
||||
| <a id="RCX_DZ"></a>`RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. |
|
||||
| <a id="MPC_xxx"></a>`MPC_XXXX` | 대부분의 MPC_xxx 매개 변수는이 모드에서 비행 동작에 어느정도 영향을 미칩니다 . For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. |
|
||||
| <a id="MPC_POS_MODE"></a>[MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Stick input to movement translation strategy. From PX4 v1.12 the default (`Acceleration based`) is that stick position controls acceleration (in a similar way to a car accelerator pedal). Other options allow stick deflection to directly control speed over ground, with and without smoothing and acceleration limits. |
|
||||
| <a id="MPC_ACC_HOR_MAX"></a>[MPC_ACC_HOR_MAX](../advanced_config/parameter_reference.md#MPC_ACC_HOR_MAX) | Maximum horizontal acceleration. |
|
||||
|
||||
@@ -123,35 +123,35 @@ This should be set by default, but if not, follow the [MAVLink2 configuration in
|
||||
RTK GPS 연결은 기본적으로 플러그앤플레이입니다.
|
||||
|
||||
1. Start _QGroundControl_ and attach the base RTK GPS via USB to the ground station.
|
||||
장치가 자동으로 인식됩니다.
|
||||
장치가 자동으로 인식됩니다.
|
||||
|
||||
2. Start the vehicle and make sure it is connected to _QGroundControl_.
|
||||
|
||||
:::tip
|
||||
_QGroundControl_ displays an RTK GPS status icon in the top icon bar while an RTK GPS device is connected (in addition to the normal GPS status icon).
|
||||
RTK가 설정되는 동안 아이콘은 빨간색으로 표시되고, RTK GPS가 활성화되면 흰색으로 바뀝니다.
|
||||
아이콘을 클릭하여 현재 상태와 RTK 정확도를 확인할 수 있습니다.
|
||||
:::tip
|
||||
_QGroundControl_ displays an RTK GPS status icon in the top icon bar while an RTK GPS device is connected (in addition to the normal GPS status icon).
|
||||
RTK가 설정되는 동안 아이콘은 빨간색으로 표시되고, RTK GPS가 활성화되면 흰색으로 바뀝니다.
|
||||
아이콘을 클릭하여 현재 상태와 RTK 정확도를 확인할 수 있습니다.
|
||||
|
||||
:::
|
||||
|
||||
3. _QGroundControl_ then starts the RTK setup process (known as "Survey-In").
|
||||
|
||||
Survey-In은 기지국의 정확한 위치 추정치를 획득을 위한 시작 절차입니다.
|
||||
The process typically takes several minutes (it ends after reaching the minimum time and accuracy specified in the [RTK settings](#rtk-gps-settings)).
|
||||
Survey-In은 기지국의 정확한 위치 추정치를 획득을 위한 시작 절차입니다.
|
||||
The process typically takes several minutes (it ends after reaching the minimum time and accuracy specified in the [RTK settings](#rtk-gps-settings)).
|
||||
|
||||
RTK GPS 상태 아이콘을 클릭하여 진행 상황을 추적할 수 있습니다.
|
||||
RTK GPS 상태 아이콘을 클릭하여 진행 상황을 추적할 수 있습니다.
|
||||
|
||||

|
||||

|
||||
|
||||
4. Survey-in이 완료되면 :
|
||||
- The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle:
|
||||
- The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle:
|
||||
|
||||

|
||||

|
||||
|
||||
- 기체의 GPS가 RTK 모드로 전환됩니다.
|
||||
The new mode is displayed in the _normal_ GPS status icon (`3D RTK GPS Lock`):
|
||||
- 기체의 GPS가 RTK 모드로 전환됩니다.
|
||||
The new mode is displayed in the _normal_ GPS status icon (`3D RTK GPS Lock`):
|
||||
|
||||

|
||||

|
||||
|
||||
### GPS를 Yaw/Heading 소스로 설정
|
||||
|
||||
@@ -206,7 +206,7 @@ MAVLink2 프로토콜은 낮은 대역폭 채널을 보다 효율적으로 사
|
||||
MAVLink2가 사용되는 지 확인하려면 :
|
||||
|
||||
- Update the telemetry module firmware to the latest version (see [QGroundControl > Setup > Firmware](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/firmware.html)).
|
||||
- Set [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html))
|
||||
- Ensure [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) is set to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html))
|
||||
|
||||
#### 튜닝
|
||||
|
||||
|
||||
+12
-2
@@ -1,3 +1,8 @@
|
||||
<script setup>
|
||||
import { useData } from 'vitepress'
|
||||
const { site } = useData();
|
||||
</script>
|
||||
|
||||
<div style="float:right; padding:10px; margin-right:20px;"><a href="https://px4.io/"><img src="../assets/site/logo_pro_small.png" title="PX4 Logo" width="180px" /></a></div>
|
||||
|
||||
# PX4 Autopilot 사용자 안내서
|
||||
@@ -9,17 +14,22 @@ PX4 is the _Professional Autopilot_.
|
||||
세계 각국에서 활동중인 여러 단체들의 지원을 받을 수 있습니다. PX4는 레이싱 드론, 운송용 드론, 자동차와 선박 등의 다양한 운송체에 적용하여 사용할 수 있습니다.
|
||||
|
||||
:::tip
|
||||
This guide contains everything you need to assemble, configure, and safely fly a PX4-based vehicle. 이 프로젝트에 기여하시려면, Check out the [Development](development/development.md) section.
|
||||
|
||||
This guide contains everything you need to assemble, configure, and safely fly a PX4-based vehicle.
|
||||
이 프로젝트에 기여하시려면, Check out the [Development](development/development.md) section.
|
||||
:::
|
||||
|
||||
<div v-if="site.title == 'PX4 Guide (main)'">
|
||||
|
||||
:::warning
|
||||
|
||||
This guide is for the _development_ version of PX4 (`main` branch).
|
||||
Use the **Version** selector to find the current _stable_ version.
|
||||
|
||||
Documented changes since the stable release are captured in the evolving [release note](releases/main.md).
|
||||
:::
|
||||
|
||||
</div>
|
||||
|
||||
## 시작하기
|
||||
|
||||
[Basic Concepts](getting_started/px4_basic_concepts.md) should be read by all users!
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
|
||||
:::
|
||||
|
||||
The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default).
|
||||
The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) and/or [zenoh](../modules/modules_driver.md#zenoh) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default).
|
||||
|
||||
This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on.
|
||||
|
||||
|
||||
@@ -0,0 +1,201 @@
|
||||
# Zenoh (PX4 ROS 2 rmw_zenoh)
|
||||
|
||||
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
|
||||
|
||||
:::warning
|
||||
실험
|
||||
At the time of writing, PX4 Zenoh-pico is experimental, and hence subject to change.
|
||||
:::
|
||||
|
||||
PX4 supports Zenoh as an alternative mechanism (to DDS) for bridging uORB topics to [ROS 2](../ros2/user_guide.md) (via the ROS 2 [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh) middleware).
|
||||
This allows uORB messages to be published and subscribed on a companion computer as though they were ROS 2 topics.
|
||||
It provides a fast and lightweight way to connect PX4 to ROS 2, making it easier for applications to access vehicle telemetry and send control commands.
|
||||
|
||||
The following guide describes the architecture and various options for setting up the Zenoh client and router.
|
||||
In particular, it covers the options that are most important to PX4 users exploring Zenoh as an alternative communication layer for ROS 2.
|
||||
|
||||
## 아키텍쳐
|
||||
|
||||
The Zenoh-based middleware consists of a client running on PX4 and a Zenoh router running on the companion computer, with bi-directional data exchange between them over a UART, TCP, UDP, or multicast-UDP link.
|
||||
The router acts as a broker and discovery service, enabling PX4 to publish and subscribe to topics in the global Zenoh data space.
|
||||
This allows seamless integration with ROS 2 nodes using [`rmw_zenoh`](https://github.com/ros2/rmw_zenoh), and supports flexible deployment across distributed systems.
|
||||
|
||||

|
||||
|
||||
The client is the _PX4 Zenoh-Pico Node_ referred to above, which is implemented in the [PX4 `zenoh` module](../modules/modules_driver.md#zenoh).
|
||||
This is based on Zenoh-Pico, a minimalistic version of [Eclipse Zenoh](https://zenoh.io/) (a data-centric protocol designed for real-time, distributed, and resource-constrained environments).
|
||||
|
||||
The router suggested above is [zenohd](https://github.com/eclipse-zenoh/zenoh/tree/main/zenohd).
|
||||
|
||||
:::info
|
||||
UART is supported by Zenoh but has not yet implemented in the PX4 Zenoh-Pico node.
|
||||
:::
|
||||
|
||||
## ROS 2 Zenoh Bring-up on Linux Companion
|
||||
|
||||
In order for PX4 uORB topics to be shared with ROS 2 applications, you will need the PX4 Zenoh-Pico Node client running on your FMU, connected to a Zenoh router running on the companion computer (or elsewhere in the network).
|
||||
|
||||
First select Zenoh as the ROS 2 transport by setting the `RMW_IMPLEMENTATION` environment variable as shown:
|
||||
|
||||
```sh
|
||||
export RMW_IMPLEMENTATION=rmw_zenoh_cpp
|
||||
```
|
||||
|
||||
Then start the Zenoh router using the command:
|
||||
|
||||
```sh
|
||||
ros2 run rmw_zenoh_cpp rmw_zenohd
|
||||
```
|
||||
|
||||
For more information about the Zenoh Router see the [rmw_zenoh](https://github.com/ros2/rmw_zenoh?tab=readme-ov-file#start-the-zenoh-router) documentation.
|
||||
|
||||
## PX4 Zenoh-Pico Node Setup
|
||||
|
||||
### PX4 Firmware
|
||||
|
||||
Before setting up the Zenoh communication, first make sure that your firmware contains the driver that implements the [`zenoh` driver](../modules/modules_driver.md#zenoh), which provides the implementation of the _PX4 Zenoh-Pico Node_.
|
||||
|
||||
You can check if the module is present on your board by searching for the key `CONFIG_MODULES_ZENOH=y` in your board's `default.px4board` KConfig file.
|
||||
For example, you can see that the module is present in `px4_fmu-v6xrt` build targets from [/boards/px4/fmu-v6xrt/default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6xrt/default.px4board#L91).
|
||||
|
||||
If `CONFIG_MODULES_ZENOH=y` is not preset you can add this key to your board configuration and rebuild.
|
||||
Note that due to flash constraints you may need to remove other components in order to include the module (such as the [`uxrce_dds_client` module](../modules/modules_system.md#uxrce-dds-client), which you will not need if you are using Zenoh).
|
||||
|
||||
The table below shows some of the PX4 targets that include Zenoh by default.
|
||||
|
||||
| PX4 Target | 참고 |
|
||||
| ---------------------- | -------------------------------------------------------------------------------------------------------------- |
|
||||
| `px4_fmu-v6xrt` | For [FMUv6X-RT](../flight_controller/nxp_mr_vmu_rt1176.md) (reference platform for testing) |
|
||||
| `nxp_tropic-community` | |
|
||||
| `nxp_mr-tropic` | |
|
||||
| `nxp_mr-canhubk344` | |
|
||||
| `px4_sitl_zenoh` | Zenoh-enabled simulation build |
|
||||
| `px4_fmu-v6x_zenoh` | Zenoh-enabled firmware for FMUv6X |
|
||||
|
||||
Zenoh is not included in the default `px4_fmu-` targets for any firmware other than `px4_fmu-v6xrt` (`px4_sitl_zenoh` and `px4_fmu-v6x_zenoh` [are build variants](../dev_setup/building_px4.md#px4-make-build-targets)).
|
||||
|
||||
:::tip
|
||||
You can check if Zenoh is present at runtime by using QGroundControl to [find the parameter](../advanced_config/parameters.md#finding-a-parameter) [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE).
|
||||
If present, the module is installed.
|
||||
:::
|
||||
|
||||
### Enable Zenoh on PX4 Startup
|
||||
|
||||
Set the [ZENOH_ENABLE](../advanced_config/parameter_reference.md#ZENOH_ENABLE) parameter to `1` to enable Zenoh on PX4 startup.
|
||||
|
||||
### Configure Zenoh Network
|
||||
|
||||
Set up PX4 to connect to the companion computer running `zenohd`.
|
||||
|
||||
PX4's default IP address of the Zenoh daemon host is `10.41.10.1`.
|
||||
If you're using a different IP for the Zenoh daemon, run the following command (replacing the address) in a PX4 shell and then reboot:
|
||||
|
||||
```sh
|
||||
zenoh config net client tcp/10.41.10.1:7447#iface=eth0
|
||||
```
|
||||
|
||||
Note that for the simulation target with Zeroh (`px4_sitl_zenoh`) you won't need to make any changes because the default IP address of the Zenoh daemon is set to `localhost`.
|
||||
|
||||
:::warning
|
||||
Any changes to the network configuration require a PX4 system reboot to take effect.
|
||||
:::
|
||||
|
||||
:::tip
|
||||
See [PX4 Ethernet Setup](../advanced_config/ethernet_setup.md) for more information about Ethernet configuration.
|
||||
:::
|
||||
|
||||
### PX4 Zenoh-pico Node configuration
|
||||
|
||||
The **default configuration** is auto-generated from the [dds_topics.yaml](../middleware/dds_topics.md) file in the PX4 repository.
|
||||
This file specifies which uORB message definitions are to be published/subscribed by ROS 2 applications, and hence (indirectly) which topics are compiled into the zenoh module.
|
||||
|
||||
To inspect the current Zenoh configuration:
|
||||
|
||||
```sh
|
||||
zenoh config
|
||||
```
|
||||
|
||||
The PX4 Zenoh-pico node stores its configuration on the **SD card** under the `zenoh` folder.
|
||||
This folder contains three key files:
|
||||
|
||||
- **`net.txt`** – Defines the **Zenoh network configuration**.
|
||||
- **`pub.csv`** – Maps **uORB topics to ROS2 topics** (used for publishing).
|
||||
- **`sub.csv`** – Maps **ROS2 topics to uORB topics** (used for subscribing).
|
||||
|
||||
### 4. Modifying Topic Mappings
|
||||
|
||||
Zenoh topic mappings define how data flows between PX4's internal uORB topics and external ROS2 topics via Zenoh.
|
||||
These mappings are stored in `pub.csv` and `sub.csv` on the SD card, and can be modified at runtime using the `zenoh config` CLI tool.
|
||||
|
||||
:::warning
|
||||
Any changes to the topic mappings require a PX4 system reboot to take effect.
|
||||
:::
|
||||
|
||||
There are two types of mappings you can modify:
|
||||
|
||||
- **Publisher mappings**: Forward data from a uORB topic to a Zenoh topic.
|
||||
- **Subscriber mappings**: Receive data from a Zenoh topic and publish it to a uORB topic.
|
||||
|
||||
The main operations and their commands are:
|
||||
|
||||
- Publish a uORB topic to a Zenoh topic:
|
||||
|
||||
```sh
|
||||
zenoh config add publisher <zenoh_topic> <uorb_topic> [uorb_instance]
|
||||
```
|
||||
|
||||
- Subscribe to a Zenoh topic and forward it to a uORB topic:
|
||||
|
||||
```sh
|
||||
zenoh config add subscriber <zenoh_topic> <uorb_topic> [uorb_instance]
|
||||
```
|
||||
|
||||
- Remove existing mappings:
|
||||
|
||||
```sh
|
||||
zenoh config delete publisher <zenoh_topic>
|
||||
zenoh config delete subscriber <zenoh_topic>
|
||||
```
|
||||
|
||||
After modifying the mappings, reboot PX4 to apply the changes.
|
||||
The updated configuration will be loaded from the SD card during startup.
|
||||
|
||||
## Communicating with PX4 from ROS 2 via Zenoh
|
||||
|
||||
Once your PX4 FMU is publishing data into ROS 2, you can inspect the available topics and their contents using standard ROS 2 CLI tools:
|
||||
|
||||
```sh
|
||||
ros2 topic list
|
||||
```
|
||||
|
||||
Check topic type and publishers/subscribers:
|
||||
|
||||
```sh
|
||||
ros2 topic info -v /fmu/out/vehicle_status
|
||||
Type: px4_msgs/msg/VehicleStatus
|
||||
|
||||
Publisher count: 1
|
||||
|
||||
Node name: px4_aabbcc00000000000000000000000000
|
||||
Node namespace: /
|
||||
Topic type: px4_msgs/msg/VehicleStatus
|
||||
Topic type hash: RIHS01_828bddbb7d4c2aa6ad93757955f6893be1ec5d8f11885ec7715bcdd76b5226c9
|
||||
Endpoint type: PUBLISHER
|
||||
GID: 82.99.74.2c.b6.7d.93.44.91.4d.fe.14.93.58.40.16
|
||||
QoS profile:
|
||||
Reliability: RELIABLE
|
||||
History (Depth): KEEP_LAST (7)
|
||||
Durability: VOLATILE
|
||||
Lifespan: Infinite
|
||||
Deadline: Infinite
|
||||
Liveliness: AUTOMATIC
|
||||
Liveliness lease duration: Infinite
|
||||
|
||||
Subscription count: 0
|
||||
```
|
||||
|
||||
### PX4 ROS 2 Interface with Zenoh
|
||||
|
||||
The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) works out of the box with Zenoh as a transport backend.
|
||||
This means you can publish and subscribe to PX4 topics over Zenoh without changing your ROS 2 nodes or dealing with DDS configuration.
|
||||
For setup details and supported message types, refer to the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md).
|
||||
@@ -104,7 +104,7 @@ Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4
|
||||
|
||||
### 설명
|
||||
|
||||
I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20.
|
||||
I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20, SF30/d.
|
||||
|
||||
Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html
|
||||
|
||||
|
||||
@@ -1,29 +1,39 @@
|
||||
# AirspeedValidated (UORB message)
|
||||
|
||||
Validated airspeed
|
||||
|
||||
Provides information about airspeed (indicated, true, calibrated) and the source of the data.
|
||||
Used by controllers, estimators and for airspeed reporting to operator.
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg)
|
||||
|
||||
```c
|
||||
# Validated airspeed
|
||||
#
|
||||
# Provides information about airspeed (indicated, true, calibrated) and the source of the data.
|
||||
# Used by controllers, estimators and for airspeed reporting to operator.
|
||||
|
||||
|
||||
uint32 MESSAGE_VERSION = 1
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
float32 indicated_airspeed_m_s # [m/s] Indicated airspeed (IAS), set to NAN if invalid
|
||||
float32 calibrated_airspeed_m_s # [m/s] Calibrated airspeed (CAS), set to NAN if invalid
|
||||
float32 true_airspeed_m_s # [m/s] True airspeed (TAS), set to NAN if invalid
|
||||
float32 indicated_airspeed_m_s # [m/s] [@invalid NaN] Indicated airspeed (IAS)
|
||||
float32 calibrated_airspeed_m_s # [m/s] [@invalid NaN] Calibrated airspeed (CAS)
|
||||
float32 true_airspeed_m_s # [m/s] [@invalid NaN] True airspeed (TAS)
|
||||
|
||||
int8 airspeed_source # Source of currently published airspeed values
|
||||
int8 DISABLED = -1
|
||||
int8 GROUND_MINUS_WIND = 0
|
||||
int8 SENSOR_1 = 1
|
||||
int8 SENSOR_2 = 2
|
||||
int8 SENSOR_3 = 3
|
||||
int8 SYNTHETIC = 4
|
||||
int8 airspeed_source # [@enum SOURCE] Source of currently published airspeed values
|
||||
int8 SOURCE_DISABLED = -1 # Disabled
|
||||
int8 SOURCE_GROUND_MINUS_WIND = 0 # Ground speed minus wind
|
||||
int8 SOURCE_SENSOR_1 = 1 # Sensor 1
|
||||
int8 SOURCE_SENSOR_2 = 2 # Sensor 2
|
||||
int8 SOURCE_SENSOR_3 = 3 # Sensor 3
|
||||
int8 SOURCE_SYNTHETIC = 4 # Synthetic airspeed
|
||||
|
||||
# debug states
|
||||
float32 calibrated_ground_minus_wind_m_s # CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid
|
||||
float32 calibraded_airspeed_synth_m_s # synthetic airspeed in m/s, set to NAN if invalid
|
||||
float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s]
|
||||
float32 throttle_filtered # filtered fixed-wing throttle [-]
|
||||
float32 pitch_filtered # filtered pitch [rad]
|
||||
float32 calibrated_ground_minus_wind_m_s # [m/s] [@invalid NaN] CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption
|
||||
float32 calibraded_airspeed_synth_m_s # [m/s] [@invalid NaN] Synthetic airspeed
|
||||
float32 airspeed_derivative_filtered # [m/s^2] Filtered indicated airspeed derivative
|
||||
float32 throttle_filtered # [-] Filtered fixed-wing throttle
|
||||
float32 pitch_filtered # [rad] Filtered pitch
|
||||
|
||||
```
|
||||
|
||||
@@ -1,42 +1,59 @@
|
||||
# AutotuneAttitudeControlStatus (UORB message)
|
||||
|
||||
Autotune attitude control status
|
||||
|
||||
This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune,
|
||||
and is subscribed to by the respective attitude controllers to command rate setpoints.
|
||||
|
||||
The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging.
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AutotuneAttitudeControlStatus.msg)
|
||||
|
||||
```c
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
# Autotune attitude control status
|
||||
#
|
||||
# This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune,
|
||||
# and is subscribed to by the respective attitude controllers to command rate setpoints.
|
||||
#
|
||||
# The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging.
|
||||
|
||||
float32[5] coeff # coefficients of the identified discrete-time model
|
||||
float32[5] coeff_var # coefficients' variance of the identified discrete-time model
|
||||
float32 fitness # fitness of the parameter estimate
|
||||
float32 innov
|
||||
float32 dt_model
|
||||
uint64 timestamp # [us] Time since system start
|
||||
|
||||
float32 kc
|
||||
float32 ki
|
||||
float32 kd
|
||||
float32 kff
|
||||
float32 att_p
|
||||
float32[5] coeff # [-] Coefficients of the identified discrete-time model
|
||||
float32[5] coeff_var # [-] Coefficients' variance of the identified discrete-time model
|
||||
float32 fitness # [-] Fitness of the parameter estimate
|
||||
float32 innov # [rad/s] Innovation (residual error between model and measured output)
|
||||
float32 dt_model # [s] Model sample time used for identification
|
||||
|
||||
float32[3] rate_sp
|
||||
|
||||
float32 u_filt
|
||||
float32 y_filt
|
||||
float32 kc # [-] Proportional rate-loop gain (ideal form)
|
||||
float32 ki # [-] Integral rate-loop gain (ideal form)
|
||||
float32 kd # [-] Derivative rate-loop gain (ideal form)
|
||||
float32 kff # [-] Feedforward rate-loop gain
|
||||
float32 att_p # [-] Proportional attitude gain
|
||||
|
||||
uint8 STATE_IDLE = 0
|
||||
uint8 STATE_INIT = 1
|
||||
uint8 STATE_ROLL = 2
|
||||
uint8 STATE_ROLL_PAUSE = 3
|
||||
uint8 STATE_PITCH = 4
|
||||
uint8 STATE_PITCH_PAUSE = 5
|
||||
uint8 STATE_YAW = 6
|
||||
uint8 STATE_YAW_PAUSE = 7
|
||||
uint8 STATE_VERIFICATION = 8
|
||||
uint8 STATE_APPLY = 9
|
||||
uint8 STATE_TEST = 10
|
||||
uint8 STATE_COMPLETE = 11
|
||||
uint8 STATE_FAIL = 12
|
||||
uint8 STATE_WAIT_FOR_DISARM = 13
|
||||
float32[3] rate_sp # [rad/s] Rate setpoint commanded to the attitude controller.
|
||||
|
||||
uint8 state
|
||||
float32 u_filt # [-] Filtered input signal (normalized torque setpoint) used in system identification.
|
||||
float32 y_filt # [rad/s] Filtered output signal (angular velocity) used in system identification.
|
||||
|
||||
uint8 state # [@enum STATE] Current state of the autotune procedure.
|
||||
uint8 STATE_IDLE = 0 # Idle (not running)
|
||||
uint8 STATE_INIT = 1 # Initialize filters and setup
|
||||
uint8 STATE_ROLL_AMPLITUDE_DETECTION = 2 # FW only: determine required excitation amplitude (roll)
|
||||
uint8 STATE_ROLL = 3 # Roll-axis excitation and model identification
|
||||
uint8 STATE_ROLL_PAUSE = 4 # Pause to return to level flight
|
||||
uint8 STATE_PITCH_AMPLITUDE_DETECTION = 5 # FW only: determine required excitation amplitude (pitch)
|
||||
uint8 STATE_PITCH = 6 # Pitch-axis excitation and model identification
|
||||
uint8 STATE_PITCH_PAUSE = 7 # Pause to return to level flight
|
||||
uint8 STATE_YAW_AMPLITUDE_DETECTION = 8 # FW only: determine required excitation amplitude (yaw)
|
||||
uint8 STATE_YAW = 9 # Yaw-axis excitation and model identification
|
||||
uint8 STATE_YAW_PAUSE = 10 # Pause to return to level flight
|
||||
uint8 STATE_VERIFICATION = 11 # Verify model and candidate gains
|
||||
uint8 STATE_APPLY = 12 # Apply gains
|
||||
uint8 STATE_TEST = 13 # Test gains in closed-loop
|
||||
uint8 STATE_COMPLETE = 14 # Tuning completed successfully
|
||||
uint8 STATE_FAIL = 15 # Tuning failed (model invalid or controller unstable)
|
||||
uint8 STATE_WAIT_FOR_DISARM = 16 # Waiting for disarm before finalizing
|
||||
|
||||
```
|
||||
|
||||
@@ -24,5 +24,6 @@ int8[16] actuator_saturation # Indicates actuator saturation status.
|
||||
# Note 2: an actuator with limited dynamics can be indicated as upper-saturated even if it as not reached its maximum value.
|
||||
|
||||
uint16 handled_motor_failure_mask # Bitmask of failed motors that were removed from the allocation / effectiveness matrix. Not necessarily identical to the report from FailureDetector
|
||||
uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection
|
||||
|
||||
```
|
||||
|
||||
@@ -54,8 +54,9 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein
|
||||
bool cs_constant_pos # 42 - true if the vehicle is at a constant position
|
||||
bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used
|
||||
bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended
|
||||
bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used
|
||||
bool cs_gnss_fault # 45 - true if GNSS true if GNSS measurements (lat, lon, vel) have been declared faulty
|
||||
bool cs_yaw_manual # 46 - true if yaw has been set manually
|
||||
bool cs_gnss_hgt_fault # 47 - true if GNSS true if GNSS measurements (alt) have been declared faulty
|
||||
|
||||
# fault status
|
||||
uint32 fault_status_changes # number of filter fault status (fs) changes
|
||||
|
||||
@@ -17,5 +17,6 @@ bool fd_motor
|
||||
|
||||
float32 imbalanced_prop_metric # Metric of the imbalanced propeller check (low-passed)
|
||||
uint16 motor_failure_mask # Bit-mask with motor indices, indicating critical motor failures
|
||||
uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection
|
||||
|
||||
```
|
||||
|
||||
@@ -14,6 +14,9 @@ uint16 DEVICE_FLAGS_NEUTRAL = 2
|
||||
uint16 DEVICE_FLAGS_ROLL_LOCK = 4
|
||||
uint16 DEVICE_FLAGS_PITCH_LOCK = 8
|
||||
uint16 DEVICE_FLAGS_YAW_LOCK = 16
|
||||
uint16 DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32
|
||||
uint16 DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64
|
||||
|
||||
|
||||
float32[4] q
|
||||
float32 angular_velocity_x
|
||||
|
||||
@@ -0,0 +1,19 @@
|
||||
# SensorGnssStatus (UORB message)
|
||||
|
||||
Gnss quality indicators
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGnssStatus.msg)
|
||||
|
||||
```c
|
||||
# Gnss quality indicators
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint32 device_id # unique device ID for the sensor that does not change between power cycles
|
||||
|
||||
bool quality_available # Set to true if quality indicators are available
|
||||
uint8 quality_corrections # Corrections quality from 0 to 10, or 255 if not available
|
||||
uint8 quality_receiver # Overall receiver operating status from 0 to 10, or 255 if not available
|
||||
uint8 quality_gnss_signals # Quality of GNSS signals from 0 to 10, or 255 if not available
|
||||
uint8 quality_post_processing # Expected post processing quality from 0 to 10, or 255 if not available
|
||||
|
||||
```
|
||||
@@ -38,18 +38,26 @@ float32 vdop # Vertical dilution of precision
|
||||
int32 noise_per_ms # GPS noise per millisecond
|
||||
uint16 automatic_gain_control # Automatic gain control monitor
|
||||
|
||||
uint8 JAMMING_STATE_UNKNOWN = 0
|
||||
uint8 JAMMING_STATE_OK = 1
|
||||
uint8 JAMMING_STATE_WARNING = 2
|
||||
uint8 JAMMING_STATE_CRITICAL = 3
|
||||
uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical
|
||||
int32 jamming_indicator # indicates jamming is occurring
|
||||
uint8 JAMMING_STATE_UNKNOWN = 0 #default
|
||||
uint8 JAMMING_STATE_OK = 1
|
||||
uint8 JAMMING_STATE_MITIGATED = 2
|
||||
uint8 JAMMING_STATE_DETECTED = 3
|
||||
uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected
|
||||
int32 jamming_indicator # indicates jamming is occurring
|
||||
|
||||
uint8 SPOOFING_STATE_UNKNOWN = 0
|
||||
uint8 SPOOFING_STATE_NONE = 1
|
||||
uint8 SPOOFING_STATE_INDICATED = 2
|
||||
uint8 SPOOFING_STATE_MULTIPLE = 3
|
||||
uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical
|
||||
uint8 SPOOFING_STATE_UNKNOWN = 0 #default
|
||||
uint8 SPOOFING_STATE_OK = 1
|
||||
uint8 SPOOFING_STATE_MITIGATED = 2
|
||||
uint8 SPOOFING_STATE_DETECTED = 3
|
||||
uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected
|
||||
|
||||
# Combined authentication state (e.g. Galileo OSNMA)
|
||||
uint8 AUTHENTICATION_STATE_UNKNOWN = 0 #default
|
||||
uint8 AUTHENTICATION_STATE_INITIALIZING = 1
|
||||
uint8 AUTHENTICATION_STATE_ERROR = 2
|
||||
uint8 AUTHENTICATION_STATE_OK = 3
|
||||
uint8 AUTHENTICATION_STATE_DISABLED = 4
|
||||
uint8 authentication_state # GPS signal authentication state
|
||||
|
||||
float32 vel_m_s # GPS ground speed, (metres/sec)
|
||||
float32 vel_n_m_s # GPS North velocity, (metres/sec)
|
||||
@@ -63,6 +71,16 @@ uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp whi
|
||||
|
||||
uint8 satellites_used # Number of satellites used
|
||||
|
||||
uint32 SYSTEM_ERROR_OK = 0 #default
|
||||
uint32 SYSTEM_ERROR_INCOMING_CORRECTIONS = 1
|
||||
uint32 SYSTEM_ERROR_CONFIGURATION = 2
|
||||
uint32 SYSTEM_ERROR_SOFTWARE = 4
|
||||
uint32 SYSTEM_ERROR_ANTENNA = 8
|
||||
uint32 SYSTEM_ERROR_EVENT_CONGESTION = 16
|
||||
uint32 SYSTEM_ERROR_CPU_OVERLOAD = 32
|
||||
uint32 SYSTEM_ERROR_OUTPUT_CONGESTION = 64
|
||||
uint32 system_error # General errors with the connected GPS receiver
|
||||
|
||||
float32 heading # heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI])
|
||||
float32 heading_offset # heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI])
|
||||
float32 heading_accuracy # heading accuracy (rad, [0, 2PI])
|
||||
|
||||
@@ -1,41 +1,44 @@
|
||||
# VehicleOdometry (UORB message)
|
||||
|
||||
Vehicle odometry data. Fits ROS REP 147 for aerial vehicles
|
||||
Vehicle odometry data
|
||||
|
||||
Fits ROS REP 147 for aerial vehicles
|
||||
|
||||
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleOdometry.msg)
|
||||
|
||||
```c
|
||||
# Vehicle odometry data. Fits ROS REP 147 for aerial vehicles
|
||||
# Vehicle odometry data
|
||||
#
|
||||
# Fits ROS REP 147 for aerial vehicles
|
||||
|
||||
uint32 MESSAGE_VERSION = 0
|
||||
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
uint64 timestamp_sample
|
||||
uint64 timestamp # [us] Time since system start
|
||||
uint64 timestamp_sample # [us] Timestamp sample
|
||||
|
||||
uint8 POSE_FRAME_UNKNOWN = 0
|
||||
uint8 POSE_FRAME_NED = 1 # NED earth-fixed frame
|
||||
uint8 POSE_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference
|
||||
uint8 pose_frame # Position and orientation frame of reference
|
||||
uint8 pose_frame # [@enum POSE_FRAME] Position and orientation frame of reference
|
||||
uint8 POSE_FRAME_UNKNOWN = 0 # Unknown frame
|
||||
uint8 POSE_FRAME_NED = 1 # North-East-Down (NED) navigation frame. Aligned with True North.
|
||||
uint8 POSE_FRAME_FRD = 2 # Forward-Right-Down (FRD) frame. Constant arbitrary heading offset from True North. Z is down.
|
||||
|
||||
float32[3] position # Position in meters. Frame of reference defined by local_frame. NaN if invalid/unknown
|
||||
float32[4] q # Quaternion rotation from FRD body frame to reference frame. First value NaN if invalid/unknown
|
||||
float32[3] position # [m] [@frame local frame] [@invalid NaN If invalid/unknown] Position. Origin is position of GC at startup.
|
||||
float32[4] q # [-] [@invalid NaN First value if invalid/unknown] Attitude (expressed as a quaternion) relative to pose reference frame at current location. Follows the Hamiltonian convention (w, x, y, z, right-handed, passive rotations from body to world)
|
||||
|
||||
uint8 VELOCITY_FRAME_UNKNOWN = 0
|
||||
uint8 VELOCITY_FRAME_NED = 1 # NED earth-fixed frame
|
||||
uint8 VELOCITY_FRAME_FRD = 2 # FRD world-fixed frame, arbitrary heading reference
|
||||
uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame
|
||||
uint8 velocity_frame # Reference frame of the velocity data
|
||||
uint8 velocity_frame # [@enum VELOCITY_FRAME] Reference frame of the velocity data
|
||||
uint8 VELOCITY_FRAME_UNKNOWN = 0 # Unknown frame
|
||||
uint8 VELOCITY_FRAME_NED = 1 # NED navigation frame at current position.
|
||||
uint8 VELOCITY_FRAME_FRD = 2 # FRD navigation frame at current position. Constant arbitrary heading offset from True North. Z is down.
|
||||
uint8 VELOCITY_FRAME_BODY_FRD = 3 # FRD body-fixed frame
|
||||
|
||||
float32[3] velocity # Velocity in meters/sec. Frame of reference defined by velocity_frame variable. NaN if invalid/unknown
|
||||
float32[3] velocity # [m/s] [@frame @velocity_frame] [@invalid NaN If invalid/unknown] Velocity.
|
||||
float32[3] angular_velocity # [rad/s] [@frame @VELOCITY_FRAME_BODY_FRD] [@invalid NaN If invalid/unknown] Angular velocity in body-fixed frame
|
||||
|
||||
float32[3] angular_velocity # Angular velocity in body-fixed frame (rad/s). NaN if invalid/unknown
|
||||
float32[3] position_variance # [m^2] Variance of position error
|
||||
float32[3] orientation_variance # [rad^2] Variance of orientation/attitude error (expressed in body frame)
|
||||
float32[3] velocity_variance # [m^2/s^2] Variance of velocity error
|
||||
|
||||
float32[3] position_variance
|
||||
float32[3] orientation_variance
|
||||
float32[3] velocity_variance
|
||||
|
||||
uint8 reset_counter
|
||||
int8 quality
|
||||
uint8 reset_counter # [-] Reset counter. Counts reset events on attitude, velocity and position.
|
||||
int8 quality # [-] [@invalid 0] Quality. Unused.
|
||||
|
||||
# TOPICS vehicle_odometry vehicle_mocap_odometry vehicle_visual_odometry
|
||||
# TOPICS estimator_odometry
|
||||
|
||||
@@ -15,7 +15,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
|
||||
|
||||
- [ActuatorMotors](ActuatorMotors.md) — Motor control message
|
||||
- [ActuatorServos](ActuatorServos.md) — Servo control message
|
||||
- [AirspeedValidated](AirspeedValidated.md)
|
||||
- [AirspeedValidated](AirspeedValidated.md) — Validated airspeed
|
||||
- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply
|
||||
- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request
|
||||
- [BatteryStatus](BatteryStatus.md) — Battery status
|
||||
@@ -70,7 +70,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
|
||||
- [VehicleLandDetected](VehicleLandDetected.md)
|
||||
- [VehicleLocalPosition](VehicleLocalPosition.md) — Fused local position in NED.
|
||||
The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
|
||||
- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data. Fits ROS REP 147 for aerial vehicles
|
||||
- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data
|
||||
- [VehicleRatesSetpoint](VehicleRatesSetpoint.md)
|
||||
- [VehicleStatus](VehicleStatus.md) — Encodes the system state of the vehicle published by commander
|
||||
- [VtolVehicleStatus](VtolVehicleStatus.md) — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE
|
||||
@@ -87,7 +87,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
|
||||
- [AdcReport](AdcReport.md)
|
||||
- [Airspeed](Airspeed.md) — Airspeed data from sensors
|
||||
- [AirspeedWind](AirspeedWind.md) — Wind estimate (from airspeed_selector)
|
||||
- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md)
|
||||
- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) — Autotune attitude control status
|
||||
- [BatteryInfo](BatteryInfo.md) — Battery information
|
||||
- [ButtonEvent](ButtonEvent.md)
|
||||
- [CameraCapture](CameraCapture.md)
|
||||
@@ -246,6 +246,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
|
||||
change with board revisions and sensor updates.
|
||||
- [SensorCorrection](SensorCorrection.md) — Sensor corrections in SI-unit form for the voted sensor
|
||||
- [SensorGnssRelative](SensorGnssRelative.md) — GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station.
|
||||
- [SensorGnssStatus](SensorGnssStatus.md) — Gnss quality indicators
|
||||
- [SensorGps](SensorGps.md) — GPS position in WGS84 coordinates.
|
||||
the field 'timestamp' is for the position & velocity (microseconds)
|
||||
- [SensorGyro](SensorGyro.md)
|
||||
|
||||
@@ -36,7 +36,7 @@ There are some benefits and drawbacks to using ROS-based missions, which are pro
|
||||
|
||||
- QGroundControl currently does not display the mission or progress during execution, and cannot upload or download a mission.
|
||||
Therefore you will need another mechanism to provide a mission, such as from a web server, a custom GCS, or by generating it directly inside the application.
|
||||
- The current implementation only supports multicopters (it uses the [GotoSetpointType](../ros2/px4_ros2_control_interface.md#go-to-setpoint-gotosetpointtype), which only works for multicopters, and VTOL in MC mode).
|
||||
- The current implementation only supports multicopters (it uses the [GotoSetpointType](../ros2/px4_ros2_control_interface.md#go-to-setpoint-multicoptergotosetpointtype), which only works for multicopters, and VTOL in MC mode).
|
||||
It is designed to be extendable to any other vehicle type.
|
||||
|
||||
## 개요
|
||||
|
||||
@@ -9,6 +9,7 @@ However PX4 can also use some INS devices as either sources of raw data, or as a
|
||||
INS systems that can be used as a replacement for EKF2 in PX4:
|
||||
|
||||
- [InertialLabs](../sensor/inertiallabs.md)
|
||||
- [MicroStrain](../sensor/microstrain.md): Includes VRU, AHRS, INS, and GNSS/INS devices.
|
||||
- [SBG Systems](../sensor/sbgecom.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data.
|
||||
- [VectorNav](../sensor/vectornav.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data.
|
||||
|
||||
|
||||
@@ -0,0 +1,219 @@
|
||||
# MicroStrain (INS, IMU, VRU, AHRS)
|
||||
|
||||
MicroStrain by HBK provides high-performance inertial sensors engineered for reliability and precision in challenging environments.
|
||||
Widely used across industries like aerospace, robotics, industrial automation, and research, MicroStrain sensors are optimized for real-time, accurate motion tracking and orientation data.
|
||||
|
||||

|
||||
|
||||
The driver currently supports the following hardware:
|
||||
|
||||
- [`MicroStrain CV7-AR`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/vertical-reference-units--vru-/3dm-cv7-ar): Inertial Measurement Unit (IMU) and Vertical Reference Unit (VRU)
|
||||
- [`MicroStrain CV7-AHRS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/attitude-and-heading-reference-systems--ahrs-/3dm-cv7-ahrs): Inertial Measurement Unit (IMU) and Attitude Heading Reference System (AHRS)
|
||||
- [`MicroStrain CV7-INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS).
|
||||
- [`MicroStrain CV7-GNSS/INS`](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-gnss-ins): Inertial Measurement Unit (IMU) and Inertial Navigation System (INS) combined with dual multiband (GNSS) receivers.
|
||||
|
||||
PX4 can use these sensors to provide raw IMU data for EKF2 or to replace EKF2 as an external INS.
|
||||
For more information, including user manuals and datasheets, please refer to the sensors product page.
|
||||
|
||||
## 구매처
|
||||
|
||||
MicroStrain sensors can be purchased through HBK's official [MicroStrain product page](https://www.hbkworld.com/en/products/transducers/inertial-sensors) or through authorized distributors globally.
|
||||
For large orders, custom requirements, or technical inquiries, reach out directly to [sales](https://www.hbkworld.com/en/contact-us/contact-sales-microstrain)
|
||||
|
||||
## 하드웨어 설정
|
||||
|
||||
### 배선
|
||||
|
||||
Connect the main UART port of the MicroStrain sensor to any unused serial port on the flight controller.
|
||||
This port needs to be specified while starting the device.
|
||||
|
||||
### 장착
|
||||
|
||||
The MicroStrain sensor can be mounted in any orientation.
|
||||
The default coordinate system uses X for the front, Y for the right, and Z for down, with directions marked on the device.
|
||||
|
||||
## 펌웨어 설정
|
||||
|
||||
### PX4 설정
|
||||
|
||||
To use the MicroStrain driver:
|
||||
|
||||
1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_MICROSTRAIN` or `CONFIG_COMMON_INS`.
|
||||
|
||||
2. Configure the driver mode by setting [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE)
|
||||
|
||||
- To use the MicroStrain sensor to provide raw IMU data to EKF2
|
||||
|
||||
1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 0
|
||||
2. Update the [EKF2_MULTI_IMU](../advanced_config/parameter_reference.md#EKF2_MULTI_IMU) parameter to account for the added MicroStrain sensor.
|
||||
3. Enable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 1
|
||||
4. To prioritize MicroStrain sensor output, adjust the priority level of individual sensors from 0-100 using the following parameters:
|
||||
|
||||
- [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO)
|
||||
- [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO)
|
||||
- [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO)
|
||||
- [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO)
|
||||
|
||||
where `n` corresponds to the index of the corresponding sensor.
|
||||
|
||||
::: tip
|
||||
Sensors can be identified by their device id, which can be found by checking the parameters:
|
||||
|
||||
- [CAL_ACCn_ID](../advanced_config/parameter_reference.md#CAL_ACC0_ID)
|
||||
- [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID)
|
||||
- [CAL_MAGn_ID](../advanced_config/parameter_reference.md#CAL_MAG0_ID)
|
||||
- [CAL_BAROn_ID](../advanced_config/parameter_reference.md#CAL_BARO0_ID)
|
||||
|
||||
|
||||
:::
|
||||
|
||||
- To use the MicroStrain sensor as an external INS
|
||||
1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 1
|
||||
2. Disable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 0
|
||||
|
||||
3. Reboot and start the driver
|
||||
- `microstrain start -d <port>`
|
||||
- To start the driver automatically when the flight controller powers on, set [SENS_MS_CFG](../advanced_config/parameter_reference.md#SENS_MS_CFG) to the sensor’s connected port.
|
||||
|
||||
## MicroStrain Configuration
|
||||
|
||||
1. Rates:
|
||||
|
||||
- By default, accel and gyro data are published at 500 Hz, magnetometer at 50 Hz, and barometric pressure at 50 Hz.
|
||||
This can be changed by adjusting the following parameters:
|
||||
|
||||
- [MS_IMU_RATE_HZ](../advanced_config/parameter_reference.md#MS_IMU_RATE_HZ)
|
||||
- [MS_MAG_RATE_HZ](../advanced_config/parameter_reference.md#MS_MAG_RATE_HZ)
|
||||
- [MS_BARO_RATE_HZ](../advanced_config/parameter_reference.md#MS_BARO_RATE_HZ)
|
||||
|
||||
- Global position, local position, attitude and odometry will be published at 250 Hz by default.
|
||||
This can be configured via:
|
||||
|
||||
- [MS_FILT_RATE_HZ](../advanced_config/parameter_reference.md#MS_FILT_RATE_HZ)
|
||||
|
||||
- For the CV7-GNSS/INS, the GNSS receiver 1 and 2 will publish data at 5Hz by default.
|
||||
This can be changed using:
|
||||
|
||||
- [MS_GNSS_RATE_HZ](../advanced_config/parameter_reference.md#MS_GNSS_RATE_HZ)
|
||||
|
||||
- The driver will automatically configure data outputs based on the specific sensor model and available data streams.
|
||||
|
||||
- The driver is scheduled to run at twice the fastest configured data rate.
|
||||
|
||||
2. Aiding measurements:
|
||||
|
||||
- If supported, GNSS position and velocity aiding are always enabled.
|
||||
|
||||
- Internal/external magnetometer and heading aiding, as well as optical flow aiding, are disabled by default. They can be enabled using the following parameters:
|
||||
|
||||
- [MS_INT_MAG_EN](../advanced_config/parameter_reference.md#MS_INT_MAG_EN)
|
||||
- [MS_INT_HEAD_EN](../advanced_config/parameter_reference.md#MS_INT_HEAD_EN)
|
||||
- [MS_EXT_HEAD_EN](../advanced_config/parameter_reference.md#MS_EXT_HEAD_EN)
|
||||
- [MS_EXT_MAG_EN](../advanced_config/parameter_reference.md#MS_EXT_MAG_EN)
|
||||
- [MS_OPT_FLOW_EN](../advanced_config/parameter_reference.md#MS_OPT_FLOW_EN)
|
||||
|
||||
- The aiding frames for external sources can be configured using the following parameters:
|
||||
|
||||
- [MS_EHEAD_YAW](../advanced_config/parameter_reference.md#MS_EHEAD_YAW)
|
||||
- [MS_EMAG_ROLL](../advanced_config/parameter_reference.md#MS_EMAG_ROLL)
|
||||
- [MS_EMAG_PTCH](../advanced_config/parameter_reference.md#MS_EMAG_PTCH)
|
||||
- [MS_EMAG_YAW](../advanced_config/parameter_reference.md#MS_EMAG_YAW)
|
||||
- [MS_OFLW_OFF_X](../advanced_config/parameter_reference.md#MS_OFLW_OFF_X)
|
||||
- [MS_OFLW_OFF_Y](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Y)
|
||||
- [MS_OFLW_OFF_Z](../advanced_config/parameter_reference.md#MS_OFLW_OFF_Z)
|
||||
- [SENS_FLOW_ROT](../advanced_config/parameter_reference.md#SENS_FLOW_ROT)
|
||||
|
||||
- The uncertainty for optical flow and external magnetometer aiding must be specified using the following parameters:
|
||||
|
||||
- [MS_EMAG_UNCERT](../advanced_config/parameter_reference.md#MS_EMAG_UNCERT)
|
||||
- [MS_OFLW_UNCERT](../advanced_config/parameter_reference.md#MS_OFLW_UNCERT)
|
||||
|
||||
::: tip
|
||||
|
||||
1. When optical flow aiding is enabled, the sensor uses the `vehicle_optical_flow_vel` output from the flight controller as a body-frame velocity aiding measurement.
|
||||
2. If the MicroStrain sensor does not support these aiding sources but they are enabled, sensor initialization will fail.
|
||||
|
||||
|
||||
:::
|
||||
|
||||
3. Initial heading alignment:
|
||||
|
||||
- Initial heading alignment is set to kinematic by default. This can be changed by adjusting
|
||||
|
||||
- [MS_ALIGNMENT](../advanced_config/parameter_reference.md#MS_ALIGNMENT)
|
||||
|
||||
4. GNSS Aiding Source Control (GNSS/INS only)
|
||||
|
||||
- The Source of the GNSS aiding data can be configured using:
|
||||
|
||||
- [MS_GNSS_AID_SRC](../advanced_config/parameter_reference.md#MS_GNSS_AID_SRC)
|
||||
|
||||
5. Sensor to vehicle transform:
|
||||
|
||||
- If the sensor is mounted in an orientation different from the vehicle frame. A sensor to vehicle transform can be enabled using
|
||||
|
||||
- [MS_SVT_EN](../advanced_config/parameter_reference.md#MS_SVT_EN)
|
||||
|
||||
- The transform is defined using the following parameters
|
||||
|
||||
- [MS_SENSOR_ROLL](../advanced_config/parameter_reference.md#MS_SENSOR_ROLL)
|
||||
- [MS_SENSOR_PTCH](../advanced_config/parameter_reference.md#MS_SENSOR_PTCH)
|
||||
- [MS_SENSOR_YAW](../advanced_config/parameter_reference.md#MS_SENSOR_YAW)
|
||||
|
||||
6. IMU ranges:
|
||||
|
||||
- The accelerometer and gyroscope ranges on the device are configurable using:
|
||||
|
||||
- [MS_ACCEL_RANGE](../advanced_config/parameter_reference.md#MS_ACCEL_RANGE)
|
||||
- [MS_GYRO_RANGE](../advanced_config/parameter_reference.md#MS_GYRO_RANGE)
|
||||
|
||||
::: tip
|
||||
Available range settings depend on the specific [sensor](https://www.hbkworld.com/en/products/transducers/inertial-sensors) and can be found in the corresponding user manual.
|
||||
By default, the ranges are not changed.
|
||||
|
||||
|
||||
:::
|
||||
|
||||
7. GNSS Lever arm offsets:
|
||||
|
||||
- The lever arm offset for the external GNSS receiver can be configured using:
|
||||
|
||||
- [MS_GNSS_OFF1_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_X)
|
||||
- [MS_GNSS_OFF1_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Y)
|
||||
- [MS_GNSS_OFF1_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Z)
|
||||
|
||||
- For dual-antenna configurations, the second GNSS receiver’s offset is configured using:
|
||||
|
||||
- [MS_GNSS_OFF2_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_X)
|
||||
- [MS_GNSS_OFF2_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Y)
|
||||
- [MS_GNSS_OFF2_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Z)
|
||||
|
||||
## Published Data
|
||||
|
||||
The MicroStrain driver continuously publishes sensor data to the following uORB topics:
|
||||
|
||||
- [sensor_accel](../msg_docs/SensorAccel.md)
|
||||
- [sensor_gyro](../msg_docs/SensorGyro.md)
|
||||
- [sensor_mag](../msg_docs/SensorMag.md)
|
||||
- [sensor_baro](../msg_docs/SensorBaro.md)
|
||||
|
||||
For GNSS/INS devices, GPS data is also published to:
|
||||
|
||||
- [sensor_gps](../msg_docs/SensorGps.md)
|
||||
|
||||
If used as an external INS replacing EKF2, it publishes:
|
||||
|
||||
- [vehicle_global_position](../msg_docs/VehicleGlobalPosition.md)
|
||||
- [vehicle_local_position](../msg_docs/VehicleLocalPosition.md)
|
||||
- [vehicle_attitude](../msg_docs/VehicleAttitude.md)
|
||||
- [vehicle_odometry](../msg_docs/VehicleOdometry.md)
|
||||
|
||||
otherwise the same data is published to the following topics
|
||||
|
||||
- `external_ins_global_position`
|
||||
- `external_ins_attitude`
|
||||
- `external_ins_local_position`
|
||||
|
||||
:::tip
|
||||
Published topics can be viewed using the `listener` command.
|
||||
:::
|
||||
@@ -286,6 +286,7 @@
|
||||
- [CubePilot Here+ (Discontined)](gps_compass/rtk_gps_hex_hereplus.md)
|
||||
- [INS (Інерціальна навігація/GNSS)](sensor/inertial_navigation_systems.md)
|
||||
- [InertialLabs](sensor/inertiallabs.md)
|
||||
- [MicroStrain](sensor/microstrain.md)
|
||||
- [sbgECom](sensor/sbgecom.md)
|
||||
- [VectorNav](sensor/vectornav.md)
|
||||
- [Optical Flow](sensor/optical_flow.md)
|
||||
@@ -701,6 +702,7 @@
|
||||
- [SensorCombined](msg_docs/SensorCombined.md)
|
||||
- [SensorCorrection](msg_docs/SensorCorrection.md)
|
||||
- [SensorGnssRelative](msg_docs/SensorGnssRelative.md)
|
||||
- [SensorGnssStatus](msg_docs/SensorGnssStatus.md)
|
||||
- [SensorGps](msg_docs/SensorGps.md)
|
||||
- [SensorGyro](msg_docs/SensorGyro.md)
|
||||
- [SensorGyroFft](msg_docs/SensorGyroFft.md)
|
||||
@@ -762,6 +764,7 @@
|
||||
- [Standard Modes Protocol](mavlink/standard_modes.md)
|
||||
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](middleware/uxrce_dds.md)
|
||||
- [UORB Bridged to ROS 2](middleware/dds_topics.md)
|
||||
- [Zenoh (PX4 ROS 2)](middleware/zenoh.md)
|
||||
- [Модулі & Команди](modules/modules_main.md)
|
||||
- [Автоматичне підлаштування](modules/modules_autotune.md)
|
||||
- [Команди](modules/modules_command.md)
|
||||
|
||||
@@ -615,6 +615,10 @@ div.frame_variant td, div.frame_variant th {
|
||||
<td><a href="https://www.axialadventure.com/product/1-10-scx10-ii-trail-honcho-4wd-rock-crawler-brushed-rtr/AXID9059.html">Axial SCX10 2 Trail Honcho</a></td>
|
||||
<td>Підтримувач: John Doe <john@example.com><p><code>SYS_AUTOSTART</code> = 51001</p></td>
|
||||
</tr>
|
||||
<tr id="rover_rover_nxp_b3rb_rover_ackermann">
|
||||
<td>NXP B3RB Rover Ackermann</td>
|
||||
<td>Підтримувач: John Doe <john@example.com><p><code>SYS_AUTOSTART</code> = 51002</p></td>
|
||||
</tr>
|
||||
<tr id="rover_rover_generic_rover_mecanum">
|
||||
<td>Generic Rover Mecanum</td>
|
||||
<td>Підтримувач: John Doe <john@example.com><p><code>SYS_AUTOSTART</code> = 52000</p></td>
|
||||
|
||||
@@ -274,12 +274,12 @@ The relevant parameters are listed in the table below.
|
||||
|
||||
## Виявлення відмов
|
||||
|
||||
Детектор відмов дозволяє автомобілю вжити захисних заходів, якщо він несподівано перевертається, або якщо йому повідомлено зовнішньою системою виявлення відмов.
|
||||
The failure detector allows a vehicle to take protective actions if it unexpectedly flips, detects a motor failure, or if it is notified by an external failure detection system.
|
||||
|
||||
During **flight**, the failure detector can be used to trigger [flight termination](../advanced_config/flight_termination.md) if failure conditions are met, which may then launch a [parachute](../peripherals/parachute.md) or perform some other action.
|
||||
|
||||
:::info
|
||||
Failure detection during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)).
|
||||
Acting on a detected failure during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)).
|
||||
:::
|
||||
|
||||
During **takeoff** the failure detector [attitude trigger](#attitude-trigger) invokes the [disarm action](#act_disarm) if the vehicle flips (disarm kills the motors but, unlike flight termination, will not launch a parachute or perform other failure actions).
|
||||
@@ -301,6 +301,26 @@ The failure detector is active in all vehicle types and modes, except for those
|
||||
| <a id="FD_FAIL_P_TTRI"></a>[FD_FAIL_P_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_P_TTRI) | Time to exceed [FD_FAIL_P](#FD_FAIL_P) for failure detection (default 0.3s). |
|
||||
| <a id="FD_FAIL_R_TTRI"></a>[FD_FAIL_R_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_R_TTRI) | Time to exceed [FD_FAIL_R](#FD_FAIL_R) for failure detection (default 0.3s). |
|
||||
|
||||
### Motor Failure Trigger
|
||||
|
||||
The failure detector can be configured to detect a motor failure while armed (and trigger an associated action) in the following conditions:
|
||||
|
||||
- A 300 ms timeout occurs in telemetry from an ESC that was previously available.
|
||||
- The input current in the telemetry of an ESC which was previously positive gets too low for more than [`FD_ACT_MOT_TOUT`](FD_ACT_MOT_TOUT) ms.
|
||||
The "too low" condition is defined by:
|
||||
|
||||
```text
|
||||
{esc current} < {parameter FD_ACT_MOT_C2T} * {motor command between 0 and 1}
|
||||
```
|
||||
|
||||
| Параметр | Опис |
|
||||
| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="FD_ACT_EN"></a>[FD_ACT_EN](../advanced_config/parameter_reference.md#FD_ACT_EN) | Enable/disable the motor failure trigger completely. |
|
||||
| <a id="FD_ACT_MOT_THR"></a>[FD_ACT_MOT_THR](../advanced_config/parameter_reference.md#FD_ACT_MOT_THR) | Minimum normalized [0,1] motor command below which motor under current is ignored. |
|
||||
| <a id="FD_ACT_MOT_C2T"></a>[FD_ACT_MOT_C2T](../advanced_config/parameter_reference.md#FD_ACT_MOT_C2T) | Scale between normalized [0,1] motor command and expected minimally reported currrent when the rotor is healthy. |
|
||||
| <a id="FD_ACT_MOT_TOUT"></a>[FD_ACT_MOT_TOUT](../advanced_config/parameter_reference.md#FD_ACT_MOT_TOUT) | Time in miliseconds for which the under current detection condition needs to stay true. |
|
||||
| <a id="CA_FAILURE_MODE"></a>[CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) | Configure to not only warn about a motor failure but remove the first motor that detects a failure from the allocation effectiveness which turns off the motor and tries to operate the vehicle without it until disarming the next time. |
|
||||
|
||||
### Зовнішня автоматична система тригерування (ATS)
|
||||
|
||||
The [failure detector](#failure-detector), if [enabled](#CBRK_FLIGHTTERM), can also be triggered by an external ATS system.
|
||||
|
||||
@@ -19,7 +19,7 @@ Failure injection still in development.
|
||||
|
||||
## Команда системи збою
|
||||
|
||||
Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 console/shell, specifying both the target and type of the failure.
|
||||
Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 [console/shell](../debug/consoles.md) (such as the [QGC MAVLink Console](../debug/mavlink_shell.md#qgroundcontrol-mavlink-console) or SITL _pxh shell_), specifying both the target and type of the failure.
|
||||
|
||||
### Синтаксис
|
||||
|
||||
@@ -61,11 +61,18 @@ failure <component> <failure_type> [-i <instance_number>]
|
||||
- _instance number_ (optional): Instance number of affected sensor.
|
||||
0 (за замовчуванням) вказує на всі сенсори вказаного типу.
|
||||
|
||||
### Example
|
||||
## MAVSDK відлагоджувальний плагін
|
||||
|
||||
The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures.
|
||||
It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)).
|
||||
|
||||
API плагіна - це пряме відображення команди збою, показаної вище, з деякими додатковими сигналами про помилки, пов'язані з підключенням.
|
||||
|
||||
## Example: RC signal
|
||||
|
||||
Щоб симулювати втрату сигналу RC без вимкнення вашого пульта керування RC:
|
||||
|
||||
1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). And specifically to turn off motors also [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE).
|
||||
1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter.
|
||||
2. Enter the following commands on the MAVLink console or SITL _pxh shell_:
|
||||
|
||||
```sh
|
||||
@@ -76,9 +83,18 @@ failure <component> <failure_type> [-i <instance_number>]
|
||||
failure rc_signal ok
|
||||
```
|
||||
|
||||
## MAVSDK відлагоджувальний плагін
|
||||
## Example: Motor
|
||||
|
||||
The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures.
|
||||
It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)).
|
||||
To stop a motor mid-flight without the system anticipating it or excluding it from allocation effectiveness:
|
||||
|
||||
API плагіна - це пряме відображення команди збою, показаної вище, з деякими додатковими сигналами про помилки, пов'язані з підключенням.
|
||||
1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter.
|
||||
2. Enable [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) parameter to allow turning off motors.
|
||||
3. Enter the following commands on the MAVLink console or SITL _pxh shell_:
|
||||
|
||||
```sh
|
||||
# Turn off first motor
|
||||
failure motor off -i 1
|
||||
|
||||
# Turn it back on
|
||||
failure motor ok -i 1
|
||||
```
|
||||
|
||||
@@ -160,7 +160,7 @@ If you have concerns about a particular card you can run the above test and repo
|
||||
|
||||
- If log streaming does not start, make sure the `logger` is running (see above), and inspect the console output while starting.
|
||||
- Якщо це все ще не працює, переконайтеся, що використовується MAVLink 2.
|
||||
Enforce it by setting `MAV_PROTO_VER` to 2.
|
||||
`MAV_PROTO_VER` needs to be set to 2.
|
||||
- Log streaming uses a maximum of 70% of the configured MAVLink rate (`-r` parameter).
|
||||
Якщо потрібно більше, повідомлення видаляються.
|
||||
The currently used percentage can be inspected with `mavlink status` (1.8% is used in this example):
|
||||
|
||||
@@ -83,9 +83,10 @@ This is done using the the parameters named like `UAVCAN_SUB_*` in the parameter
|
||||
|
||||
На ARK CANnode вам може знадобитися налаштувати наступні параметри:
|
||||
|
||||
| Параметр | Опис |
|
||||
| -------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------- |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. |
|
||||
| Параметр | Опис |
|
||||
| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. |
|
||||
|
||||
## Значення LED індикаторів
|
||||
|
||||
|
||||
@@ -109,9 +109,10 @@ When optical flow is the only source of horizontal position/velocity, then lower
|
||||
|
||||
On the ARK Flow, you may need to configure the following parameters:
|
||||
|
||||
| Параметр | Опис |
|
||||
| -------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------- |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. |
|
||||
| Параметр | Опис |
|
||||
| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. |
|
||||
|
||||
## Значення LED індикаторів
|
||||
|
||||
|
||||
@@ -104,9 +104,10 @@ Set the following parameters in _QGroundControl_:
|
||||
|
||||
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK Flow MR itself:
|
||||
|
||||
| Параметр | Опис |
|
||||
| -------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------- |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. |
|
||||
| Параметр | Опис |
|
||||
| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. |
|
||||
|
||||
## Значення LED індикаторів
|
||||
|
||||
|
||||
@@ -91,9 +91,17 @@ DroneCAN configuration in PX4 is explained in more detail in [DroneCAN > Enablin
|
||||
|
||||
- Enable GPS yaw fusion by setting bit 3 of [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL) to true.
|
||||
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
|
||||
- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` if this is that last node on the CAN bus.
|
||||
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK GPS from the vehicles centre of gravity.
|
||||
|
||||
### ARK GPS Configuration
|
||||
|
||||
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK GPS itself:
|
||||
|
||||
| Параметр | Опис |
|
||||
| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. Set to `1` if this is the last node on the CAN bus. |
|
||||
|
||||
## Значення LED індикаторів
|
||||
|
||||
Ви побачите зелені, сині та червоні світлодіоди на ARK GPS під час прошивки, а також мигаючий зелений світлодіод, якщо все працює належним чином.
|
||||
|
||||
@@ -85,7 +85,15 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if
|
||||
- Enable GPS blending to ensure the heading is always published by setting [SENS_GPS_MASK](../advanced_config/parameter_reference.md#SENS_GPS_MASK) to 7 (all three bits checked).
|
||||
- Enable [UAVCAN_SUB_GPS](../advanced_config/parameter_reference.md#UAVCAN_SUB_GPS), [UAVCAN_SUB_MAG](../advanced_config/parameter_reference.md#UAVCAN_SUB_MAG), and [UAVCAN_SUB_BARO](../advanced_config/parameter_reference.md#UAVCAN_SUB_BARO).
|
||||
- The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity.
|
||||
- Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus.
|
||||
|
||||
### ARK RTK GPS Configuration
|
||||
|
||||
You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS itself:
|
||||
|
||||
| Параметр | Опис |
|
||||
| -------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
||||
| <a id="CANNODE_NODE_ID"></a>[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. |
|
||||
| <a id="CANNODE_TERM"></a>[CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | Вбудована завершення шини CAN. Set to `1` if this is the last node on the CAN bus. |
|
||||
|
||||
### Setting Up Rover and Fixed Base
|
||||
|
||||
|
||||
@@ -102,6 +102,10 @@ If you wish to disable the DNA completely, set `UAVCAN_ENABLE` to `1` and manual
|
||||
:::info
|
||||
The PX4 node ID can be configured using the [UAVCAN_NODE_ID](../advanced_config/parameter_reference.md#UAVCAN_NODE_ID) parameter.
|
||||
Параметр за замовчуванням встановлено на 1.
|
||||
|
||||
Devices running the [PX4 DroneCAN firmware](px4_cannode_fw.md) (such as [ARK CANnode](ark_cannode.md)) can use the
|
||||
[CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter to set a static node ID.
|
||||
Set it to 0 (default) for dynamic allocation, or to a value between 1-127 to use a specific static node ID.
|
||||
:::
|
||||
|
||||
:::warning
|
||||
@@ -288,6 +292,11 @@ For example, the screenshot below shows the parameters for a CAN GPS with node i
|
||||
|
||||

|
||||
|
||||
Common CANNODE parameters that you can configure include:
|
||||
|
||||
- [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID): Set a static node ID (1-127) or use 0 for dynamic allocation. See [PX4 DroneCAN Firmware > Static Node ID](px4_cannode_fw.md#static-node-id) for more information.
|
||||
- [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM): Enable CAN bus termination on the last node in the bus.
|
||||
|
||||
## Налаштування пристрою
|
||||
|
||||
Більшість вузлів DroneCAN не потребують додаткової настройки, якщо це не вказано у їх документації, специфічній для пристрою.
|
||||
|
||||
@@ -20,6 +20,26 @@ make ark_can-flow_default
|
||||
|
||||
This will create an output in **build/ark_can-flow_default** named **XX-X.X.XXXXXXXX.uavcan.bin**. Follow the instructions at [DroneCAN firmware update](index.md#firmware-update) to flash the firmware.
|
||||
|
||||
## Налаштування
|
||||
|
||||
### Static Node ID
|
||||
|
||||
By default, DroneCAN devices use [Dynamic Node Allocation (DNA)](index.md#node-id-allocation) to automatically obtain a unique node ID from the flight controller.
|
||||
However, you can configure a static node ID using the [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) parameter.
|
||||
|
||||
To configure a static node ID:
|
||||
|
||||
1. Set [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) to a value between 1-127 using [QGroundControl](index.md#qgc-cannode-parameter-configuration)
|
||||
2. Reboot the device
|
||||
|
||||
To return to dynamic allocation, set `CANNODE_NODE_ID` back to 0.
|
||||
Note that when switching back to dynamic allocation, the flight controller will typically continue to allocate the same node ID that was previously used (this is normal DNA behavior).
|
||||
|
||||
:::warning
|
||||
When using static node IDs, you must ensure that each device on the CAN bus has a unique node ID.
|
||||
Configuring two devices with the same ID will cause communication conflicts.
|
||||
:::
|
||||
|
||||
## Інформація для розробників
|
||||
|
||||
Цей розділ містить інформацію, яка є актуальною для розробників, які хочуть додати підтримку нового апаратного забезпечення DroneCAN до автопілота PX4.
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user