mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-18 16:01:28 +08:00
Compare commits
16 Commits
v1.15.2
...
release/1.
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
85df8c2281 | ||
|
|
d66956a682 | ||
|
|
d9c5acb669 | ||
|
|
a7659ddf12 | ||
|
|
99c40407ff | ||
|
|
03b4ad46e8 | ||
|
|
51000107a9 | ||
|
|
dba5383e99 | ||
|
|
ca611f1580 | ||
|
|
faa7bb91d0 | ||
|
|
8017135965 | ||
|
|
eb76cc6001 | ||
|
|
15dd55e86a | ||
|
|
4798b6b631 | ||
|
|
b8e7237317 | ||
|
|
510d6a1f70 |
@ -46,6 +46,8 @@ pipeline {
|
||||
"ark_cannode_default",
|
||||
"ark_fmu-v6x_bootloader",
|
||||
"ark_fmu-v6x_default",
|
||||
"ark_fpv_bootloader",
|
||||
"ark_fpv_default",
|
||||
"ark_pi6x_bootloader",
|
||||
"ark_pi6x_default",
|
||||
"atl_mantis-edu_default",
|
||||
|
||||
10
.vscode/cmake-variants.yaml
vendored
10
.vscode/cmake-variants.yaml
vendored
@ -181,6 +181,16 @@ CONFIG:
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: ark_fmu-v6x_default
|
||||
ark_fpv_bootloader:
|
||||
short: ark_fpv_bootloader
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: ark_fpv_bootloader
|
||||
ark_fpv_default:
|
||||
short: ark_fpv_default
|
||||
buildType: MinSizeRel
|
||||
settings:
|
||||
CONFIG: ark_fpv_default
|
||||
ark_pi6x_bootloader:
|
||||
short: ark_pi6x_bootloader
|
||||
buildType: MinSizeRel
|
||||
|
||||
1
Makefile
1
Makefile
@ -325,6 +325,7 @@ px4io_update:
|
||||
|
||||
bootloaders_update: \
|
||||
ark_fmu-v6x_bootloader \
|
||||
ark_fpv_bootloader \
|
||||
ark_pi6x_bootloader \
|
||||
cuav_nora_bootloader \
|
||||
cuav_x7pro_bootloader \
|
||||
|
||||
@ -198,6 +198,13 @@ then
|
||||
spl06 -X -a 0x77 start
|
||||
fi
|
||||
|
||||
# SPA06 sensor external I2C
|
||||
if param compare -s SENS_EN_SPA06 1
|
||||
then
|
||||
spa06 -X start
|
||||
spa06 -X -a 0x77 start
|
||||
fi
|
||||
|
||||
# PCF8583 counter (RPM sensor)
|
||||
if param compare -s SENS_EN_PCF8583 1
|
||||
then
|
||||
|
||||
3
boards/ark/fpv/bootloader.px4board
Normal file
3
boards/ark/fpv/bootloader.px4board
Normal file
@ -0,0 +1,3 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_ROMFSROOT=""
|
||||
83
boards/ark/fpv/default.px4board
Normal file
83
boards/ark/fpv/default.px4board
Normal file
@ -0,0 +1,83 @@
|
||||
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
|
||||
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
|
||||
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_HEATER=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y
|
||||
CONFIG_DRIVERS_IMU_MURATA_SCH16T=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||
CONFIG_MODULES_DATAMAN=y
|
||||
CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_ESC_BATTERY=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=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_NUM_MISSION_ITMES_SUPPORTED=1000
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_SENSORS=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_HARDFAULT_LOG=y
|
||||
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_MTD=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_PERF=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_SD_BENCH=y
|
||||
CONFIG_SYSTEMCMDS_SD_STRESS=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
|
||||
BIN
boards/ark/fpv/extras/ark_fpv_bootloader.bin
Executable file
BIN
boards/ark/fpv/extras/ark_fpv_bootloader.bin
Executable file
Binary file not shown.
13
boards/ark/fpv/firmware.prototype
Normal file
13
boards/ark/fpv/firmware.prototype
Normal file
@ -0,0 +1,13 @@
|
||||
{
|
||||
"board_id": 59,
|
||||
"magic": "ARKFPVFWv1",
|
||||
"description": "Firmware for the ARKFPV board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "ARKFPV",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 1835008,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
34
boards/ark/fpv/init/rc.board_defaults
Normal file
34
boards/ark/fpv/init/rc.board_defaults
Normal file
@ -0,0 +1,34 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board specific defaults
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
# transision from params file to flash-based params (2022-08)
|
||||
if [ -f $PARAM_FILE ]
|
||||
then
|
||||
param load $PARAM_FILE
|
||||
param save
|
||||
# create a backup
|
||||
mv $PARAM_FILE ${PARAM_FILE}.bak
|
||||
reboot
|
||||
fi
|
||||
|
||||
# TODO: Tune the following parameters
|
||||
param set-default SENS_EN_THERMAL 1
|
||||
param set-default SENS_IMU_TEMP 10.0
|
||||
#param set-default SENS_IMU_TEMP_FF 0.0
|
||||
#param set-default SENS_IMU_TEMP_I 0.025
|
||||
#param set-default SENS_IMU_TEMP_P 1.0
|
||||
|
||||
if ver hwtypecmp ARKFPV000
|
||||
then
|
||||
param set-default SENS_TEMP_ID 3014666
|
||||
fi
|
||||
|
||||
param set-default BAT1_V_DIV 21.0
|
||||
|
||||
param set-default IMU_GYRO_DNF_EN 3
|
||||
|
||||
# Single IMU
|
||||
param set-default EKF2_MULTI_IMU 0
|
||||
param set-default SENS_IMU_MODE 1
|
||||
18
boards/ark/fpv/init/rc.board_sensors
Normal file
18
boards/ark/fpv/init/rc.board_sensors
Normal file
@ -0,0 +1,18 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# ARKFPV specific board sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
board_adc start
|
||||
|
||||
if ver hwtypecmp ARKFPV000
|
||||
then
|
||||
# Internal SPI bus IIM42653
|
||||
iim42653 -R 14 -s -b 1 start
|
||||
fi
|
||||
|
||||
# Internal magnetometer on I2C
|
||||
iis2mdc -R 0 -I -b 4 start
|
||||
|
||||
# Internal Baro on I2C
|
||||
bmp388 -I -b 2 start
|
||||
17
boards/ark/fpv/nuttx-config/Kconfig
Normal file
17
boards/ark/fpv/nuttx-config/Kconfig
Normal file
@ -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.
|
||||
95
boards/ark/fpv/nuttx-config/bootloader/defconfig
Normal file
95
boards/ark/fpv/nuttx-config/bootloader/defconfig
Normal file
@ -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/ark/fpv/nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="ark"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H743II=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=0x003B
|
||||
CONFIG_CDCACM_PRODUCTSTR="ARK BL FPV.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x3185
|
||||
CONFIG_CDCACM_VENDORSTR="ARK"
|
||||
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_UART7=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_UART7_RXBUFSIZE=512
|
||||
CONFIG_UART7_RXDMA=y
|
||||
CONFIG_UART7_TXBUFSIZE=512
|
||||
CONFIG_UART7_TXDMA=y
|
||||
CONFIG_USBDEV=y
|
||||
CONFIG_USBDEV_BUSPOWERED=y
|
||||
CONFIG_USBDEV_MAXPOWER=500
|
||||
CONFIG_USEC_PER_TICK=1000
|
||||
507
boards/ark/fpv/nuttx-config/include/board.h
Normal file
507
boards/ark/fpv/nuttx-config/include/board.h
Normal file
@ -0,0 +1,507 @@
|
||||
/************************************************************************************
|
||||
* nuttx-configs/px4_fmu-v6x/include/board.h
|
||||
*
|
||||
* Copyright (C) 2016-2024 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) * 40 = 640 MHz
|
||||
*
|
||||
* PLL1P = PLL1_VCO/2 = 640 MHz / 2 = 320 MHz
|
||||
* PLL1Q = PLL1_VCO/4 = 640 MHz / 4 = 160 MHz
|
||||
* PLL1R = PLL1_VCO/8 = 640 MHz / 8 = 80 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(40)
|
||||
#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) * 40)
|
||||
#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 = 160
|
||||
*/
|
||||
|
||||
#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 (80 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 (80 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 (80 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 (80 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
|
||||
|
||||
/* 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 ARKV6X 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_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 */
|
||||
// GPIO_UART5_RTS No remap /* PC8 */
|
||||
//#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 /* PF8 */
|
||||
#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */
|
||||
|
||||
|
||||
/* CAN
|
||||
*
|
||||
* CAN1 is routed to transceiver.
|
||||
*/
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
|
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
|
||||
|
||||
/* SPI
|
||||
* SPI1 is sensors1
|
||||
* SPI2 is sensors2
|
||||
* SPI3 is sensors3
|
||||
* SPI4 is Not Used
|
||||
* SPI5 is Not Used
|
||||
* 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_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_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 */
|
||||
|
||||
/* 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_PORTH|GPIO_PIN6) /* PH6 AUX7 */
|
||||
# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */
|
||||
|
||||
# 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 */
|
||||
108
boards/ark/fpv/nuttx-config/include/board_dma_map.h
Normal file
108
boards/ark/fpv/nuttx-config/include/board_dma_map.h
Normal file
@ -0,0 +1,108 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned
|
||||
// V
|
||||
|
||||
// Timer 4 Channel 1 /* DMA1:29 TIM4CH1 */
|
||||
|
||||
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 IIM-42653 */
|
||||
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 IIM-42653 */
|
||||
|
||||
//#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_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */
|
||||
//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */
|
||||
|
||||
// Timer 8 Channel 1 /* DMA1:47 TIM8CH1 */
|
||||
// Timer 8 Channel 2 /* DMA1:48 TIM8CH2 */
|
||||
// Timer 8 Channel 3 /* DMA1:49 TIM8CH3 */
|
||||
// Timer 8 Channel 4 /* DMA1:50 TIM8CH4 */
|
||||
|
||||
// Timer 5 Channel 1 /* DMA1:55 TIM5CH1 */
|
||||
// Timer 5 Channel 2 /* DMA1:56 TIM5CH2 */
|
||||
// Timer 5 Channel 3 /* DMA1:57 TIM5CH3 */
|
||||
// Timer 5 Channel 4 /* DMA1:58 TIM5CH4 */
|
||||
|
||||
// #define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 UART4 */
|
||||
// #define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 UART4 */
|
||||
|
||||
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 RC */
|
||||
// #define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 RC */
|
||||
|
||||
// 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
|
||||
|
||||
// Timer 4 Channel 1 /* DMA2:29 TIM4CH1 */
|
||||
|
||||
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* 3 DMA2:43 TELEM3 */
|
||||
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* 4 DMA2:44 TELEM3 */
|
||||
|
||||
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */
|
||||
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */
|
||||
|
||||
// Timer 8 Channel 1 /* DMA2:47 TIM8CH1 */
|
||||
// Timer 8 Channel 2 /* DMA2:48 TIM8CH2 */
|
||||
// Timer 8 Channel 3 /* DMA2:49 TIM8CH3 */
|
||||
// Timer 8 Channel 4 /* DMA2:50 TIM8CH4 */
|
||||
|
||||
// Timer 5 Channel 1 /* DMA2:55 TIM5CH1 */
|
||||
// Timer 5 Channel 2 /* DMA2:56 TIM5CH2 */
|
||||
// Timer 5 Channel 3 /* DMA2:57 TIM5CH3 */
|
||||
// Timer 5 Channel 4 /* DMA2:58 TIM5CH4 */
|
||||
|
||||
//#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_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 */
|
||||
|
||||
// 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 */
|
||||
279
boards/ark/fpv/nuttx-config/nsh/defconfig
Normal file
279
boards/ark/fpv/nuttx-config/nsh/defconfig
Normal file
@ -0,0 +1,279 @@
|
||||
#
|
||||
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||
#
|
||||
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||
# modifications.
|
||||
#
|
||||
# CONFIG_DISABLE_ENVIRON is not set
|
||||
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||
# CONFIG_DISABLE_PTHREAD is not set
|
||||
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||
# CONFIG_MMCSD_SPI is not set
|
||||
# CONFIG_NSH_DISABLEBG is not set
|
||||
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||
# CONFIG_NSH_DISABLE_CAT is not set
|
||||
# CONFIG_NSH_DISABLE_CD is not set
|
||||
# CONFIG_NSH_DISABLE_CP is not set
|
||||
# CONFIG_NSH_DISABLE_DATE is not set
|
||||
# CONFIG_NSH_DISABLE_DF is not set
|
||||
# CONFIG_NSH_DISABLE_ECHO is not set
|
||||
# CONFIG_NSH_DISABLE_ENV is not set
|
||||
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||
# CONFIG_NSH_DISABLE_EXPORT is not set
|
||||
# CONFIG_NSH_DISABLE_FREE is not set
|
||||
# CONFIG_NSH_DISABLE_GET is not set
|
||||
# CONFIG_NSH_DISABLE_HELP is not set
|
||||
# CONFIG_NSH_DISABLE_IFCONFIG is not set
|
||||
# CONFIG_NSH_DISABLE_IFUPDOWN is not set
|
||||
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||
# CONFIG_NSH_DISABLE_KILL is not set
|
||||
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||
# CONFIG_NSH_DISABLE_LS is not set
|
||||
# CONFIG_NSH_DISABLE_MKDIR is not set
|
||||
# CONFIG_NSH_DISABLE_MKFATFS is not set
|
||||
# CONFIG_NSH_DISABLE_MOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_MV is not set
|
||||
# CONFIG_NSH_DISABLE_PS is not set
|
||||
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
|
||||
# CONFIG_NSH_DISABLE_PWD is not set
|
||||
# CONFIG_NSH_DISABLE_RM is not set
|
||||
# CONFIG_NSH_DISABLE_RMDIR is not set
|
||||
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||
# CONFIG_NSH_DISABLE_SET is not set
|
||||
# CONFIG_NSH_DISABLE_SLEEP is not set
|
||||
# CONFIG_NSH_DISABLE_SOURCE is not set
|
||||
# CONFIG_NSH_DISABLE_TELNETD is not set
|
||||
# CONFIG_NSH_DISABLE_TEST is not set
|
||||
# CONFIG_NSH_DISABLE_TIME is not set
|
||||
# CONFIG_NSH_DISABLE_UMOUNT is not set
|
||||
# CONFIG_NSH_DISABLE_UNSET is not set
|
||||
# CONFIG_NSH_DISABLE_USLEEP is not set
|
||||
CONFIG_ARCH="arm"
|
||||
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/fpv/nuttx-config"
|
||||
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||
CONFIG_ARCH_BOARD_CUSTOM_NAME="ark"
|
||||
CONFIG_ARCH_CHIP="stm32h7"
|
||||
CONFIG_ARCH_CHIP_STM32H743II=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=0x003B
|
||||
CONFIG_CDCACM_PRODUCTSTR="ARK FPV.x"
|
||||
CONFIG_CDCACM_RXBUFSIZE=600
|
||||
CONFIG_CDCACM_TXBUFSIZE=12000
|
||||
CONFIG_CDCACM_VENDORID=0x3185
|
||||
CONFIG_CDCACM_VENDORSTR="ARK"
|
||||
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_EXPERIMENTAL=y
|
||||
CONFIG_FAT_DMAMEMORY=y
|
||||
CONFIG_FAT_LCNAMES=y
|
||||
CONFIG_FAT_LFN=y
|
||||
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||
CONFIG_FDCLONE_STDIO=y
|
||||
CONFIG_FS_BINFS=y
|
||||
CONFIG_FS_CROMFS=y
|
||||
CONFIG_FS_FAT=y
|
||||
CONFIG_FS_FATTIME=y
|
||||
CONFIG_FS_PROCFS=y
|
||||
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
|
||||
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||
CONFIG_FS_PROCFS_REGISTER=y
|
||||
CONFIG_FS_ROMFS=y
|
||||
CONFIG_GRAN=y
|
||||
CONFIG_GRAN_INTR=y
|
||||
CONFIG_HAVE_CXX=y
|
||||
CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=750
|
||||
CONFIG_INIT_ENTRYPOINT="nsh_main"
|
||||
CONFIG_INIT_STACKSIZE=3194
|
||||
CONFIG_LIBC_FLOATINGPOINT=y
|
||||
CONFIG_LIBC_LONG_LONG=y
|
||||
CONFIG_LIBC_MAX_EXITFUNS=1
|
||||
CONFIG_LIBC_STRERROR=y
|
||||
CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_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_NSH_ARCHINIT=y
|
||||
CONFIG_NSH_ARGCAT=y
|
||||
CONFIG_NSH_BUILTIN_APPS=y
|
||||
CONFIG_NSH_CMDPARMS=y
|
||||
CONFIG_NSH_CROMFSETC=y
|
||||
CONFIG_NSH_LINELEN=128
|
||||
CONFIG_NSH_MAXARGUMENTS=15
|
||||
CONFIG_NSH_NESTDEPTH=8
|
||||
CONFIG_NSH_QUOTE=y
|
||||
CONFIG_NSH_ROMFSETC=y
|
||||
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||
CONFIG_NSH_STRERROR=y
|
||||
CONFIG_NSH_VARS=y
|
||||
CONFIG_OTG_ID_GPIO_DISABLE=y
|
||||
CONFIG_PIPES=y
|
||||
CONFIG_PREALLOC_TIMERS=50
|
||||
CONFIG_PRIORITY_INHERITANCE=y
|
||||
CONFIG_PTHREAD_MUTEX_ROBUST=y
|
||||
CONFIG_PTHREAD_STACK_MIN=512
|
||||
CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5
|
||||
CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5
|
||||
CONFIG_RAMTRON_SETSPEED=y
|
||||
CONFIG_RAM_SIZE=245760
|
||||
CONFIG_RAM_START=0x20010000
|
||||
CONFIG_RAW_BINARY=y
|
||||
CONFIG_READLINE_CMD_HISTORY=y
|
||||
CONFIG_READLINE_TABCOMPLETION=y
|
||||
CONFIG_RTC_DATETIME=y
|
||||
CONFIG_SCHED_HPWORK=y
|
||||
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||
CONFIG_SCHED_INSTRUMENTATION=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
|
||||
CONFIG_SCHED_LPWORK=y
|
||||
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||
CONFIG_SCHED_LPWORKSTACKSIZE=1632
|
||||
CONFIG_SCHED_WAITPID=y
|
||||
CONFIG_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_FLASH_OVERRIDE_I=y
|
||||
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
|
||||
CONFIG_STM32H7_I2C1=y
|
||||
CONFIG_STM32H7_I2C2=y
|
||||
CONFIG_STM32H7_I2C4=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO=y
|
||||
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_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_SPI6=y
|
||||
CONFIG_STM32H7_SPI6_DMA=y
|
||||
CONFIG_STM32H7_SPI6_DMA_BUFFER=1024
|
||||
CONFIG_STM32H7_TIM1=y
|
||||
CONFIG_STM32H7_TIM2=y
|
||||
CONFIG_STM32H7_TIM3=y
|
||||
CONFIG_STM32H7_TIM4=y
|
||||
CONFIG_STM32H7_TIM5=y
|
||||
CONFIG_STM32H7_TIM8=y
|
||||
CONFIG_STM32H7_TIM12=y
|
||||
CONFIG_STM32H7_UART4=y
|
||||
CONFIG_STM32H7_UART5=y
|
||||
CONFIG_STM32H7_UART7=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_NSH=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_RXBUFSIZE=600
|
||||
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_USART1_BAUD=57600
|
||||
CONFIG_USART1_RXDMA=y
|
||||
CONFIG_USART1_TXDMA=y
|
||||
CONFIG_USART1_RXBUFSIZE=600
|
||||
CONFIG_USART1_TXBUFSIZE=1500
|
||||
CONFIG_USART2_BAUD=57600
|
||||
CONFIG_USART2_RXDMA=y
|
||||
CONFIG_USART2_TXDMA=y
|
||||
CONFIG_USART2_RXBUFSIZE=600
|
||||
CONFIG_USART2_TXBUFSIZE=1500
|
||||
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_RXDMA=y
|
||||
CONFIG_USART6_RXBUFSIZE=600
|
||||
CONFIG_USART6_TXBUFSIZE=1500
|
||||
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
|
||||
215
boards/ark/fpv/nuttx-config/scripts/bootloader_script.ld
Normal file
215
boards/ark/fpv/nuttx-config/scripts/bootloader_script.ld
Normal file
@ -0,0 +1,215 @@
|
||||
/****************************************************************************
|
||||
* scripts/script.ld
|
||||
*
|
||||
* Copyright (C) 2016, 2024 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 ARKV6X uses an STM32H743II 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 ARKV6X 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) }
|
||||
}
|
||||
229
boards/ark/fpv/nuttx-config/scripts/script.ld
Normal file
229
boards/ark/fpv/nuttx-config/scripts/script.ld
Normal file
@ -0,0 +1,229 @@
|
||||
/****************************************************************************
|
||||
* scripts/script.ld
|
||||
*
|
||||
* Copyright (C) 2016, 2024 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 ARKV6X uses an STM32H743II 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 ARKV6X 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 = 1792K /* params in last sector */
|
||||
|
||||
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) }
|
||||
}
|
||||
77
boards/ark/fpv/src/CMakeLists.txt
Normal file
77
boards/ark/fpv/src/CMakeLists.txt
Normal file
@ -0,0 +1,77 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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
|
||||
spix_sync.c
|
||||
spix_sync.h
|
||||
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()
|
||||
397
boards/ark/fpv/src/board_config.h
Normal file
397
boards/ark/fpv/src/board_config.h
Normal file
@ -0,0 +1,397 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016-2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file board_config.h
|
||||
*
|
||||
* ARK FPV 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
|
||||
|
||||
/* Configuration ************************************************************************************/
|
||||
|
||||
# define BOARD_HAS_USB_VALID 1
|
||||
# define BOARD_HAS_NBAT_V 1
|
||||
# define BOARD_HAS_NBAT_I 1
|
||||
|
||||
/* 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
|
||||
|
||||
/* SPI */
|
||||
|
||||
#define SPI6_nRESET_EXTERNAL1 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN10)
|
||||
#define SPI6_RESET(on_true) px4_arch_gpiowrite(SPI6_nRESET_EXTERNAL1, !(on_true))
|
||||
|
||||
/* I2C busses */
|
||||
|
||||
/* Devices on the onboard buses.
|
||||
*
|
||||
* Note that these are unshifted addresses.
|
||||
*/
|
||||
#define PX4_I2C_OBDEV_SE050 0x48
|
||||
|
||||
/*
|
||||
* 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 /* PB0 */ ADC1_CH(9)
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL /* PC2 */ ADC3_CH(12)
|
||||
#define ADC_SCALED_12V_CHANNEL /* PA4 */ ADC1_CH(18)
|
||||
#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL /* PA0 */ ADC1_CH(16)
|
||||
#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5)
|
||||
#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_SENSORS_CHANNEL) | \
|
||||
(1 << ADC_SCALED_V5_CHANNEL) | \
|
||||
(1 << ADC_SCALED_12V_CHANNEL))
|
||||
|
||||
|
||||
#define BOARD_BATTERY1_V_DIV (21.0f) // (20k + 1k) / 1k = 21
|
||||
|
||||
#define ADC_SCALED_PAYLOAD_SENSE ADC_SCALED_12V_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 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 HW_INFO_INIT_PREFIX "ARKFPV"
|
||||
|
||||
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2
|
||||
// Base/FMUM
|
||||
#define ARKFPV_0 HW_FMUM_ID(0x0) // ARKFPV, Sensor Set Rev 0
|
||||
#define ARKFPV_1 HW_FMUM_ID(0x1) // ARKFPV, Sensor Set Rev 1
|
||||
|
||||
#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
|
||||
|
||||
#define GPIO_FMU_CH1 /* PI0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTI|GPIO_PIN0)
|
||||
#define GPIO_FMU_CH2 /* PH12 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN12)
|
||||
#define GPIO_FMU_CH3 /* PH11 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN11)
|
||||
#define GPIO_FMU_CH4 /* PH10 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN10)
|
||||
#define GPIO_FMU_CH5 /* PI5 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTI|GPIO_PIN5)
|
||||
#define GPIO_FMU_CH6 /* PI6 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTI|GPIO_PIN6)
|
||||
#define GPIO_FMU_CH7 /* PI7 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTI|GPIO_PIN7)
|
||||
#define GPIO_FMU_CH8 /* PI2 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTI|GPIO_PIN2)
|
||||
#define GPIO_FMU_CH9 /* PD12 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTD|GPIO_PIN12)
|
||||
|
||||
#define GPIO_SPIX_SYNC /* PE9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTE|GPIO_PIN9)
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
|
||||
#define GPIO_VDD_5V_PGOOD /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13)
|
||||
#define GPIO_VDD_12V_PGOOD /* PE15 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN15)
|
||||
#define GPIO_5V_ON_BATTERY /* PG1 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTG|GPIO_PIN1)
|
||||
#define GPIO_VDD_12V_EN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN4)
|
||||
|
||||
#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
|
||||
|
||||
|
||||
#define BOARD_NUMBER_BRICKS 1
|
||||
|
||||
/* Define True logic Power Control in arch agnostic form */
|
||||
|
||||
#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true))
|
||||
#define PAYLOAD_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_12V_EN, (on_true))
|
||||
|
||||
/* 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)
|
||||
|
||||
#define FLASH_BASED_PARAMS
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 3 /* use timer3 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
|
||||
/* RC Serial port */
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS4"
|
||||
|
||||
/* 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
|
||||
|
||||
#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))
|
||||
|
||||
/* ARKFPV never powers off the Servo rail */
|
||||
|
||||
#define BOARD_ADC_SERVO_VALID (1)
|
||||
|
||||
#define BOARD_ADC_BRICK_VALID (px4_arch_gpioread(GPIO_VDD_5V_PGOOD))
|
||||
#define BOARD_GPIO_PAYOLOAD_V_VALID (px4_arch_gpioread(GPIO_VDD_12V_PGOOD))
|
||||
|
||||
/* 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_HEATER_OUTPUT, \
|
||||
GPIO_VDD_5V_PGOOD, \
|
||||
GPIO_VDD_12V_PGOOD, \
|
||||
GPIO_VDD_12V_EN, \
|
||||
GPIO_5V_ON_BATTERY, \
|
||||
GPIO_VDD_3V3_SD_CARD_EN, \
|
||||
GPIO_nARMED_INIT, \
|
||||
SPI6_nRESET_EXTERNAL1, \
|
||||
GPIO_FMU_CH1, \
|
||||
GPIO_FMU_CH2, \
|
||||
GPIO_FMU_CH3, \
|
||||
GPIO_FMU_CH4, \
|
||||
GPIO_FMU_CH5, \
|
||||
GPIO_FMU_CH6, \
|
||||
GPIO_FMU_CH7, \
|
||||
GPIO_FMU_CH8, \
|
||||
GPIO_FMU_CH9, \
|
||||
GPIO_SPIX_SYNC \
|
||||
}
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
#define BOARD_NUM_IO_TIMERS 3
|
||||
#define BOARD_SPIX_SYNC_FREQ 32000
|
||||
|
||||
__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
|
||||
85
boards/ark/fpv/src/bootloader_main.c
Normal file
85
boards/ark/fpv/src/bootloader_main.c
Normal file
@ -0,0 +1,85 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 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 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/gpio.h>
|
||||
#include <px4_platform_common/init.h>
|
||||
|
||||
extern int sercon_main(int c, char **argv);
|
||||
|
||||
__EXPORT void board_on_reset(int status) {}
|
||||
|
||||
__EXPORT void stm32_boardinitialize(void)
|
||||
{
|
||||
/* configure pins */
|
||||
const uint32_t list[] = PX4_GPIO_INIT_LIST;
|
||||
|
||||
for (size_t gpio = 0; gpio < arraySize(list); gpio++) {
|
||||
if (list[gpio] != 0) {
|
||||
px4_arch_configgpio(list[gpio]);
|
||||
}
|
||||
}
|
||||
|
||||
/* configure USB interfaces */
|
||||
stm32_usbinitialize();
|
||||
}
|
||||
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
void board_late_initialize(void)
|
||||
{
|
||||
sercon_main(0, NULL);
|
||||
}
|
||||
|
||||
extern void sys_tick_handler(void);
|
||||
void board_timerhook(void)
|
||||
{
|
||||
sys_tick_handler();
|
||||
}
|
||||
140
boards/ark/fpv/src/can.c
Normal file
140
boards/ark/fpv/src/can.c
Normal file
@ -0,0 +1,140 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file can.c
|
||||
*
|
||||
* Board-specific CAN functions.
|
||||
*/
|
||||
|
||||
#if !defined(CONFIG_CAN)
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
|
||||
__EXPORT
|
||||
uint16_t board_get_can_interfaces(void)
|
||||
{
|
||||
uint16_t enabled_interfaces = 0x3;
|
||||
|
||||
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 */
|
||||
129
boards/ark/fpv/src/hw_config.h
Normal file
129
boards/ark/fpv/src/hw_config.h
Normal file
@ -0,0 +1,129 @@
|
||||
/*
|
||||
* 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/ttyS6,921600"
|
||||
#define BOOT_DELAY_ADDRESS 0x000001a0
|
||||
#define BOARD_TYPE 59
|
||||
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
|
||||
#define BOARD_FLASH_SECTORS (14)
|
||||
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)
|
||||
#define APP_RESERVATION_SIZE (1 * 128 * 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_ */
|
||||
40
boards/ark/fpv/src/i2c.cpp
Normal file
40
boards/ark/fpv/src/i2c.cpp
Normal file
@ -0,0 +1,40 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 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/i2c_hw_description.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusExternal(1),
|
||||
initI2CBusInternal(2),
|
||||
initI2CBusInternal(4),
|
||||
};
|
||||
299
boards/ark/fpv/src/init.c
Normal file
299
boards/ark/fpv/src/init.c
Normal file
@ -0,0 +1,299 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
*
|
||||
* ARKFMU-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 "spix_sync.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>
|
||||
|
||||
# if defined(FLASH_BASED_PARAMS)
|
||||
# include <parameters/flashparams/flashfs.h>
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* 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 */
|
||||
|
||||
PAYLOAD_POWER_EN(false);
|
||||
board_control_spi_sensors_power(false, 0xffff);
|
||||
SPI6_RESET(true);
|
||||
|
||||
/* 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);
|
||||
PAYLOAD_POWER_EN(true);
|
||||
|
||||
/* Release SPI6 Reset */
|
||||
SPI6_RESET(false);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_on_reset
|
||||
*
|
||||
* Description:
|
||||
* Optionally provided function called on entry to board_system_reset
|
||||
* It should perform any house keeping prior to the rest.
|
||||
*
|
||||
* status - 1 if resetting to boot loader
|
||||
* 0 if just resetting
|
||||
*
|
||||
************************************************************************************/
|
||||
__EXPORT void board_on_reset(int status)
|
||||
{
|
||||
for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) {
|
||||
px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i)));
|
||||
}
|
||||
|
||||
if (status >= 0) {
|
||||
up_mdelay(6);
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the initialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void
|
||||
stm32_boardinitialize(void)
|
||||
{
|
||||
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();
|
||||
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* 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)
|
||||
{
|
||||
/* Power on Interfaces */
|
||||
PAYLOAD_POWER_EN(true);
|
||||
|
||||
SPI6_RESET(false);
|
||||
|
||||
/* Need hrt running before using the ADC */
|
||||
|
||||
px4_platform_init();
|
||||
|
||||
// Use the default HW_VER_REV(0x0,0x0) for Ramtron
|
||||
|
||||
stm32_spiinitialize();
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
static sector_descriptor_t params_sector_map[] = {
|
||||
{15, 128 * 1024, 0x081E0000},
|
||||
{0, 0, 0},
|
||||
};
|
||||
|
||||
/* Initialize the flashfs layer to use heap allocated memory */
|
||||
int result = parameter_flashfs_init(params_sector_map, NULL, 0);
|
||||
|
||||
if (result != OK) {
|
||||
syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
|
||||
led_on(LED_AMBER);
|
||||
}
|
||||
|
||||
#endif // FLASH_BASED_PARAMS
|
||||
|
||||
/* Configure the HW based on the manifest */
|
||||
|
||||
px4_platform_configure();
|
||||
|
||||
if (OK == board_determine_hw_info()) {
|
||||
syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(),
|
||||
board_get_hw_type_name());
|
||||
|
||||
} else {
|
||||
syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n");
|
||||
}
|
||||
|
||||
/* 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 */
|
||||
|
||||
/* Configure the SPIX_SYNC output */
|
||||
spix_sync_servo_init(BOARD_SPIX_SYNC_FREQ);
|
||||
spix_sync_servo_set(0, 150);
|
||||
|
||||
return OK;
|
||||
}
|
||||
234
boards/ark/fpv/src/led.c
Normal file
234
boards/ark/fpv/src/led.c
Normal file
@ -0,0 +1,234 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file led.c
|
||||
*
|
||||
* ARKFMU 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
|
||||
};
|
||||
|
||||
#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 */
|
||||
55
boards/ark/fpv/src/mtd.cpp
Normal file
55
boards/ark/fpv/src/mtd.cpp
Normal file
@ -0,0 +1,55 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <px4_platform_common/px4_manifest.h>
|
||||
|
||||
static const px4_mft_entry_s mft_mft = {
|
||||
.type = MFT,
|
||||
.pmft = (void *) system_query_manifest,
|
||||
};
|
||||
|
||||
static const px4_mft_s mft = {
|
||||
.nmft = 1,
|
||||
.mfts = {
|
||||
&mft_mft,
|
||||
}
|
||||
};
|
||||
|
||||
const px4_mft_s *board_get_manifest(void)
|
||||
{
|
||||
return &mft;
|
||||
}
|
||||
177
boards/ark/fpv/src/sdio.c
Normal file
177
boards/ark/fpv/src/sdio.c
Normal file
@ -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 */
|
||||
57
boards/ark/fpv/src/spi.cpp
Normal file
57
boards/ark/fpv/src/spi.cpp
Normal file
@ -0,0 +1,57 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_arch/spi_hw_description.h>
|
||||
#include <drivers/drv_sensor.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
|
||||
constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = {
|
||||
initSPIFmumID(ARKFPV_0, {
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
|
||||
}, {GPIO::PortI, GPIO::Pin11}),
|
||||
initSPIBusExternal(SPI::Bus::SPI6, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11})
|
||||
}),
|
||||
}),
|
||||
initSPIFmumID(ARKFPV_1, { // Placeholder
|
||||
initSPIBus(SPI::Bus::SPI1, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}),
|
||||
}, {GPIO::PortI, GPIO::Pin11}),
|
||||
initSPIBusExternal(SPI::Bus::SPI6, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11})
|
||||
}),
|
||||
}),
|
||||
};
|
||||
|
||||
static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw);
|
||||
309
boards/ark/fpv/src/spix_sync.c
Normal file
309
boards/ark/fpv/src/spix_sync.c
Normal file
@ -0,0 +1,309 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2023 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 Airmind 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 spix_sync.c
|
||||
*
|
||||
*
|
||||
*/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <ctype.h>
|
||||
|
||||
|
||||
#include <perf/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
#include <px4_arch/io_timer.h>
|
||||
|
||||
#include "spix_sync.h"
|
||||
|
||||
#define REG(_tmr, _reg) (*(volatile uint32_t *)(spix_sync_timers[_tmr].base + _reg))
|
||||
|
||||
#define rCR1(_tmr) REG(_tmr, STM32_GTIM_CR1_OFFSET)
|
||||
#define rCR2(_tmr) REG(_tmr, STM32_GTIM_CR2_OFFSET)
|
||||
#define rSMCR(_tmr) REG(_tmr, STM32_GTIM_SMCR_OFFSET)
|
||||
#define rDIER(_tmr) REG(_tmr, STM32_GTIM_DIER_OFFSET)
|
||||
#define rSR(_tmr) REG(_tmr, STM32_GTIM_SR_OFFSET)
|
||||
#define rEGR(_tmr) REG(_tmr, STM32_GTIM_EGR_OFFSET)
|
||||
#define rCCMR1(_tmr) REG(_tmr, STM32_GTIM_CCMR1_OFFSET)
|
||||
#define rCCMR2(_tmr) REG(_tmr, STM32_GTIM_CCMR2_OFFSET)
|
||||
#define rCCER(_tmr) REG(_tmr, STM32_GTIM_CCER_OFFSET)
|
||||
#define rCNT(_tmr) REG(_tmr, STM32_GTIM_CNT_OFFSET)
|
||||
#define rPSC(_tmr) REG(_tmr, STM32_GTIM_PSC_OFFSET)
|
||||
#define rARR(_tmr) REG(_tmr, STM32_GTIM_ARR_OFFSET)
|
||||
#define rCCR1(_tmr) REG(_tmr, STM32_GTIM_CCR1_OFFSET)
|
||||
#define rCCR2(_tmr) REG(_tmr, STM32_GTIM_CCR2_OFFSET)
|
||||
#define rCCR3(_tmr) REG(_tmr, STM32_GTIM_CCR3_OFFSET)
|
||||
#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET)
|
||||
#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET)
|
||||
#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
|
||||
#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET)
|
||||
|
||||
#define BOARD_SPIX_SYNC_PWM_FREQ 1024000
|
||||
|
||||
unsigned
|
||||
spix_sync_timer_get_period(unsigned timer)
|
||||
{
|
||||
return (rARR(timer));
|
||||
}
|
||||
|
||||
static void spix_sync_timer_init_timer(unsigned timer, unsigned rate)
|
||||
{
|
||||
if (spix_sync_timers[timer].base) {
|
||||
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
|
||||
/* enable the timer clock before we try to talk to it */
|
||||
|
||||
modifyreg32(spix_sync_timers[timer].clock_register, 0, spix_sync_timers[timer].clock_bit);
|
||||
|
||||
/* disable and configure the timer */
|
||||
rCR1(timer) = 0;
|
||||
rCR2(timer) = 0;
|
||||
rSMCR(timer) = 0;
|
||||
rDIER(timer) = 0;
|
||||
rCCER(timer) = 0;
|
||||
rCCMR1(timer) = 0;
|
||||
rCCMR2(timer) = 0;
|
||||
rCCR1(timer) = 0;
|
||||
rCCR2(timer) = 0;
|
||||
rCCR3(timer) = 0;
|
||||
rCCR4(timer) = 0;
|
||||
rCCER(timer) = 0;
|
||||
rDCR(timer) = 0;
|
||||
|
||||
if ((spix_sync_timers[timer].base == STM32_TIM1_BASE) || (spix_sync_timers[timer].base == STM32_TIM8_BASE)) {
|
||||
|
||||
/* master output enable = on */
|
||||
|
||||
rBDTR(timer) = ATIM_BDTR_MOE;
|
||||
}
|
||||
|
||||
/* If the timer clock source provided as clock_freq is the STM32_APBx_TIMx_CLKIN
|
||||
* then configure the timer to free-run at 1MHz.
|
||||
* Otherwise, other frequencies are attainable by adjusting .clock_freq accordingly.
|
||||
*/
|
||||
|
||||
rPSC(timer) = (spix_sync_timers[timer].clock_freq / BOARD_SPIX_SYNC_PWM_FREQ) - 1;
|
||||
|
||||
/* configure the timer to update at the desired rate */
|
||||
|
||||
rARR(timer) = (BOARD_SPIX_SYNC_PWM_FREQ / rate) - 1;
|
||||
|
||||
/* generate an update event; reloads the counter and all registers */
|
||||
rEGR(timer) = GTIM_EGR_UG;
|
||||
|
||||
px4_leave_critical_section(flags);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void spix_sync_channel_init(unsigned channel)
|
||||
{
|
||||
/* Only initialize used channels */
|
||||
|
||||
if (spix_sync_channels[channel].timer_channel) {
|
||||
|
||||
unsigned timer = spix_sync_channels[channel].timer_index;
|
||||
|
||||
/* configure the GPIO first */
|
||||
px4_arch_configgpio(spix_sync_channels[channel].gpio_out);
|
||||
|
||||
uint16_t polarity = spix_sync_channels[channel].masks;
|
||||
|
||||
/* configure the channel */
|
||||
switch (spix_sync_channels[channel].timer_channel) {
|
||||
case 1:
|
||||
rCCMR1(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR1_OC1M_SHIFT) | GTIM_CCMR1_OC1PE;
|
||||
rCCER(timer) |= polarity | GTIM_CCER_CC1E;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
rCCMR1(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR1_OC2M_SHIFT) | GTIM_CCMR1_OC2PE;
|
||||
rCCER(timer) |= polarity | GTIM_CCER_CC2E;
|
||||
break;
|
||||
|
||||
case 3:
|
||||
rCCMR2(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR2_OC3M_SHIFT) | GTIM_CCMR2_OC3PE;
|
||||
rCCER(timer) |= polarity | GTIM_CCER_CC3E;
|
||||
break;
|
||||
|
||||
case 4:
|
||||
rCCMR2(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR2_OC4M_SHIFT) | GTIM_CCMR2_OC4PE;
|
||||
rCCER(timer) |= polarity | GTIM_CCER_CC4E;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
spix_sync_servo_set(unsigned channel, uint8_t cvalue)
|
||||
{
|
||||
if (channel >= arraySize(spix_sync_channels)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
unsigned timer = spix_sync_channels[channel].timer_index;
|
||||
|
||||
/* test timer for validity */
|
||||
if ((spix_sync_timers[timer].base == 0) ||
|
||||
(spix_sync_channels[channel].gpio_out == 0)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
unsigned period = spix_sync_timer_get_period(timer);
|
||||
|
||||
unsigned value = (unsigned)cvalue * period / 255;
|
||||
|
||||
/* configure the channel */
|
||||
if (value > 0) {
|
||||
value--;
|
||||
}
|
||||
|
||||
|
||||
switch (spix_sync_channels[channel].timer_channel) {
|
||||
case 1:
|
||||
rCCR1(timer) = value;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
rCCR2(timer) = value;
|
||||
break;
|
||||
|
||||
case 3:
|
||||
rCCR3(timer) = value;
|
||||
break;
|
||||
|
||||
case 4:
|
||||
rCCR4(timer) = value;
|
||||
break;
|
||||
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
unsigned spix_sync_servo_get(unsigned channel)
|
||||
{
|
||||
if (channel >= 3) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
unsigned timer = spix_sync_channels[channel].timer_index;
|
||||
uint16_t value = 0;
|
||||
|
||||
/* test timer for validity */
|
||||
if ((spix_sync_timers[timer].base == 0) ||
|
||||
(spix_sync_channels[channel].timer_channel == 0)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* configure the channel */
|
||||
switch (spix_sync_channels[channel].timer_channel) {
|
||||
case 1:
|
||||
value = rCCR1(timer);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
value = rCCR2(timer);
|
||||
break;
|
||||
|
||||
case 3:
|
||||
value = rCCR3(timer);
|
||||
break;
|
||||
|
||||
case 4:
|
||||
value = rCCR4(timer);
|
||||
break;
|
||||
}
|
||||
|
||||
unsigned period = spix_sync_timer_get_period(timer);
|
||||
return ((value + 1) * 255 / period);
|
||||
}
|
||||
|
||||
int spix_sync_servo_init(unsigned rate)
|
||||
{
|
||||
/* do basic timer initialisation first */
|
||||
for (unsigned i = 0; i < arraySize(spix_sync_timers); i++) {
|
||||
spix_sync_timer_init_timer(i, rate);
|
||||
}
|
||||
|
||||
/* now init channels */
|
||||
for (unsigned i = 0; i < arraySize(spix_sync_channels); i++) {
|
||||
spix_sync_channel_init(i);
|
||||
}
|
||||
|
||||
spix_sync_servo_arm(true);
|
||||
return OK;
|
||||
}
|
||||
|
||||
void
|
||||
spix_sync_servo_deinit(void)
|
||||
{
|
||||
/* disable the timers */
|
||||
spix_sync_servo_arm(false);
|
||||
}
|
||||
void
|
||||
spix_sync_servo_arm(bool armed)
|
||||
{
|
||||
/* iterate timers and arm/disarm appropriately */
|
||||
for (unsigned i = 0; i < arraySize(spix_sync_timers); i++) {
|
||||
if (spix_sync_timers[i].base != 0) {
|
||||
if (armed) {
|
||||
/* force an update to preload all registers */
|
||||
rEGR(i) = GTIM_EGR_UG;
|
||||
|
||||
/* arm requires the timer be enabled */
|
||||
rCR1(i) |= GTIM_CR1_CEN | GTIM_CR1_ARPE;
|
||||
|
||||
} else {
|
||||
rCR1(i) = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
42
boards/ark/fpv/src/spix_sync.h
Normal file
42
boards/ark/fpv/src/spix_sync.h
Normal file
@ -0,0 +1,42 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2023 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
__BEGIN_DECLS
|
||||
void spix_sync_channel_init(unsigned channel);
|
||||
int spix_sync_servo_set(unsigned channel, uint8_t value);
|
||||
unsigned spix_sync_servo_get(unsigned channel);
|
||||
int spix_sync_servo_init(unsigned rate);
|
||||
void spix_sync_servo_deinit(void);
|
||||
void spix_sync_servo_arm(bool armed);
|
||||
unsigned spix_sync_timer_get_period(unsigned timer);
|
||||
__END_DECLS
|
||||
86
boards/ark/fpv/src/timer_config.cpp
Normal file
86
boards/ark/fpv/src/timer_config.cpp
Normal file
@ -0,0 +1,86 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
*
|
||||
* TIM8_CH1 T FMU_CH5
|
||||
* TIM8_CH2 T FMU_CH6
|
||||
* TIM8_CH3 T FMU_CH7
|
||||
* TIM8_CH4 T FMU_CH8
|
||||
*
|
||||
* TIM4_CH1 T FMU_CH9
|
||||
*
|
||||
* TIM1_CH1 T SPIX_SYNC > Pulse or GPIO strobe
|
||||
*
|
||||
* TIM2_CH3 T HEATER > PWM OUT or GPIO
|
||||
*
|
||||
* TIM3_CH1 T HRT_TIMER
|
||||
*
|
||||
*/
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOTimer(Timer::Timer5, DMA{DMA::Index1}),
|
||||
initIOTimer(Timer::Timer8, DMA{DMA::Index1}),
|
||||
initIOTimer(Timer::Timer4, DMA{DMA::Index1}),
|
||||
};
|
||||
|
||||
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::Timer8, Timer::Channel1}, {GPIO::PortI, GPIO::Pin5}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer8, Timer::Channel2}, {GPIO::PortI, GPIO::Pin6}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer8, Timer::Channel3}, {GPIO::PortI, GPIO::Pin7}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer8, Timer::Channel4}, {GPIO::PortI, GPIO::Pin2}),
|
||||
initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel1}, {GPIO::PortD, GPIO::Pin12}),
|
||||
};
|
||||
|
||||
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||
initIOTimerChannelMapping(io_timers, timer_io_channels);
|
||||
|
||||
|
||||
constexpr io_timers_t spix_sync_timers[MAX_SPIX_SYNC_TIMERS] = {
|
||||
initIOTimer(Timer::Timer1),
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t spix_sync_channels[MAX_SPIX_SYNC_TIMERS] = {
|
||||
initIOTimerChannel(spix_sync_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}),
|
||||
};
|
||||
105
boards/ark/fpv/src/usb.c
Normal file
105
boards/ark/fpv/src/usb.c
Normal file
@ -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 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 ARKFMU 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);
|
||||
}
|
||||
@ -11,4 +11,7 @@ then
|
||||
icm42688p -R 6 -s start
|
||||
fi
|
||||
|
||||
bmp280 -X start
|
||||
if ! bmp280 -X start
|
||||
then
|
||||
spa06 -X start
|
||||
fi
|
||||
|
||||
@ -196,7 +196,7 @@ CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y
|
||||
CONFIG_STM32H7_RTC_HSECLOCK=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SDMMC1=y
|
||||
|
||||
@ -9,4 +9,7 @@ then
|
||||
icm42688p -R 0 -s start
|
||||
fi
|
||||
|
||||
bmp280 -X start
|
||||
if ! bmp280 -X start
|
||||
then
|
||||
spa06 -X start
|
||||
fi
|
||||
|
||||
@ -195,7 +195,7 @@ CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y
|
||||
CONFIG_STM32_RTC_HSECLOCK=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SDMMC1=y
|
||||
|
||||
@ -9,4 +9,7 @@ then
|
||||
icm42688p -R 0 -s start
|
||||
fi
|
||||
|
||||
bmp280 -X start
|
||||
if ! bmp280 -X start
|
||||
then
|
||||
spa06 -X start
|
||||
fi
|
||||
|
||||
@ -195,7 +195,7 @@ CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
|
||||
CONFIG_STM32H7_OTGFS=y
|
||||
CONFIG_STM32H7_PROGMEM=y
|
||||
CONFIG_STM32H7_RTC=y
|
||||
CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y
|
||||
CONFIG_STM32H7_RTC_HSECLOCK=y
|
||||
CONFIG_STM32H7_RTC_MAGIC_REG=1
|
||||
CONFIG_STM32H7_SAVE_CRASHDUMP=y
|
||||
CONFIG_STM32H7_SDMMC1=y
|
||||
|
||||
@ -29,6 +29,8 @@ uint8 transition_switch # VTOL transition switch: _HOVER, FORWARD_FLIGH
|
||||
uint8 photo_switch # Photo trigger switch
|
||||
uint8 video_switch # Photo trigger switch
|
||||
|
||||
uint8 payload_power_switch # Payload power switch
|
||||
|
||||
uint8 engage_main_motor_switch # Engage the main motor (for helicopters)
|
||||
|
||||
uint32 switch_changes # number of switch changes
|
||||
|
||||
@ -28,13 +28,14 @@ uint8 FUNCTION_FLTBTN_SLOT_4 = 24
|
||||
uint8 FUNCTION_FLTBTN_SLOT_5 = 25
|
||||
uint8 FUNCTION_FLTBTN_SLOT_6 = 26
|
||||
uint8 FUNCTION_ENGAGE_MAIN_MOTOR = 27
|
||||
uint8 FUNCTION_PAYLOAD_POWER = 28
|
||||
|
||||
uint8 FUNCTION_FLTBTN_SLOT_COUNT = 6
|
||||
|
||||
uint64 timestamp_last_valid # Timestamp of last valid RC signal
|
||||
float32[18] channels # Scaled to -1..1 (throttle: 0..1)
|
||||
uint8 channel_count # Number of valid channels
|
||||
int8[28] function # Functions mapping
|
||||
int8[29] function # Functions mapping
|
||||
uint8 rssi # Receive signal strength index
|
||||
bool signal_lost # Control signal lost, should be checked together with topic timeout
|
||||
uint32 frame_drop_count # Number of dropped frames
|
||||
|
||||
@ -1,5 +1,6 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
float32 voltage5v_v # peripheral 5V rail voltage
|
||||
float32 voltage_payload_v # payload rail voltage
|
||||
float32[4] sensors3v3 # Sensors 3V3 rail voltage
|
||||
uint8 sensors3v3_valid # Sensors 3V3 rail voltage was read (bitfield).
|
||||
uint8 usb_connected # USB is connected when 1
|
||||
@ -10,6 +11,7 @@ uint8 periph_5v_oc # peripheral overcurrent when 1
|
||||
uint8 hipower_5v_oc # high power peripheral overcurrent when 1
|
||||
uint8 comp_5v_valid # 5V to companion valid
|
||||
uint8 can1_gps1_5v_valid # 5V for CAN1/GPS1 valid
|
||||
uint8 payload_v_valid # payload rail voltage is valid
|
||||
|
||||
uint8 BRICK1_VALID_SHIFTS=0
|
||||
uint8 BRICK1_VALID_MASK=1
|
||||
|
||||
@ -106,6 +106,13 @@
|
||||
#define ADC_V5_SCALE (2.0f) // The scale factor defined by HW's resistive divider (Rt+Rb)/ Rb
|
||||
#endif
|
||||
|
||||
#if !defined(ADC_PAYLOAD_V_FULL_SCALE)
|
||||
#define ADC_PAYLOAD_V_FULL_SCALE (25.3f) // Payload volt Rail full scale voltage
|
||||
#endif
|
||||
#if !defined(ADC_PAYLOAD_SCALE)
|
||||
#define ADC_PAYLOAD_SCALE (7.667f) // The scale factor defined by HW's resistive divider (Rt+Rb)/ Rb
|
||||
#endif
|
||||
|
||||
#if !defined(ADC_3V3_V_FULL_SCALE)
|
||||
#define ADC_3V3_V_FULL_SCALE (3.6f) // 3.3V volt Rail full scale voltage
|
||||
#endif
|
||||
|
||||
@ -41,12 +41,14 @@ set(serial_ports)
|
||||
if(${CMAKE_HOST_SYSTEM_NAME} STREQUAL "Linux")
|
||||
|
||||
set(px4_usb_path "${vendorstr_underscore}_${productstr_underscore}")
|
||||
set(px4_bl_usb_path "${vendorstr_underscore}_BL")
|
||||
|
||||
list(APPEND serial_ports
|
||||
# NuttX vendor + product string
|
||||
/dev/serial/by-id/*-${px4_usb_path}*
|
||||
|
||||
# Bootloader
|
||||
/dev/serial/by-id/*_${px4_bl_usb_path}*
|
||||
/dev/serial/by-id/*PX4_BL* # typical bootloader USB device string
|
||||
/dev/serial/by-id/*BL_FMU*
|
||||
|
||||
|
||||
@ -95,7 +95,7 @@ struct boardinfo board_info = {
|
||||
.board_type = BOARD_TYPE,
|
||||
.board_rev = 0,
|
||||
.fw_size = 0,
|
||||
.systick_mhz = 480,
|
||||
.systick_mhz = STM32_CPUCLK_FREQUENCY / 1000000,
|
||||
};
|
||||
|
||||
static void board_init(void);
|
||||
|
||||
@ -204,6 +204,9 @@ void ADC::update_system_power(hrt_abstime now)
|
||||
# if defined(ADC_SCALED_V5_SENSE) && defined(ADC_SCALED_V3V3_SENSORS_SENSE)
|
||||
cnt += ADC_SCALED_V3V3_SENSORS_COUNT;
|
||||
# endif
|
||||
# if defined(ADC_SCALED_PAYLOAD_SENSE)
|
||||
cnt++;
|
||||
# endif
|
||||
|
||||
for (unsigned i = 0; i < _channel_count; i++) {
|
||||
# if defined(ADC_SCALED_V5_SENSE)
|
||||
@ -234,6 +237,16 @@ void ADC::update_system_power(hrt_abstime now)
|
||||
}
|
||||
|
||||
# endif
|
||||
# if defined(ADC_SCALED_PAYLOAD_SENSE)
|
||||
|
||||
if (_samples[i].am_channel == ADC_SCALED_PAYLOAD_SENSE) {
|
||||
system_power.voltage_payload_v = _samples[i].am_data * ((ADC_PAYLOAD_V_FULL_SCALE / 3.3f) *
|
||||
(px4_arch_adc_reference_v() /
|
||||
px4_arch_adc_dn_fullcount()));
|
||||
cnt--;
|
||||
}
|
||||
|
||||
# endif
|
||||
|
||||
if (cnt == 0) {
|
||||
break;
|
||||
@ -285,6 +298,9 @@ void ADC::update_system_power(hrt_abstime now)
|
||||
#ifdef BOARD_GPIO_VDD_5V_CAN1_GPS1_VALID
|
||||
system_power.can1_gps1_5v_valid = read_gpio_value(_5v_can1_gps1_valid_fd);
|
||||
#endif
|
||||
#ifdef BOARD_GPIO_PAYOLOAD_V_VALID
|
||||
system_power.payload_v_valid = BOARD_GPIO_PAYOLOAD_V_VALID;
|
||||
#endif
|
||||
|
||||
system_power.timestamp = hrt_absolute_time();
|
||||
_to_system_power.publish(system_power);
|
||||
|
||||
@ -10,6 +10,7 @@ menu "barometer"
|
||||
select DRIVERS_BAROMETER_MS5611
|
||||
select DRIVERS_BAROMETER_MAIERTEK_MPC2520
|
||||
select DRIVERS_BAROMETER_GOERTEK_SPL06
|
||||
select DRIVERS_BAROMETER_GOERTEK_SPA06
|
||||
select DRIVERS_BAROMETER_INVENSENSE_ICP101XX
|
||||
select DRIVERS_BAROMETER_INVENSENSE_ICP201XX
|
||||
---help---
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2022 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2022-2024 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@ -32,3 +32,4 @@
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(spl06)
|
||||
add_subdirectory(spa06)
|
||||
|
||||
45
src/drivers/barometer/goertek/spa06/CMakeLists.txt
Normal file
45
src/drivers/barometer/goertek/spa06/CMakeLists.txt
Normal file
@ -0,0 +1,45 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2024 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
px4_add_module(
|
||||
MODULE drivers__barometer__spa06
|
||||
MAIN spa06
|
||||
SRCS
|
||||
SPA06.cpp
|
||||
SPA06.hpp
|
||||
SPA06_I2C.cpp
|
||||
SPA06_SPI.cpp
|
||||
spa06_main.cpp
|
||||
DEPENDS
|
||||
px4_work_queue
|
||||
)
|
||||
5
src/drivers/barometer/goertek/spa06/Kconfig
Normal file
5
src/drivers/barometer/goertek/spa06/Kconfig
Normal file
@ -0,0 +1,5 @@
|
||||
menuconfig DRIVERS_BAROMETER_GOERTEK_SPA06
|
||||
bool "spa06"
|
||||
default n
|
||||
---help---
|
||||
Enable support for spa06
|
||||
259
src/drivers/barometer/goertek/spa06/SPA06.cpp
Normal file
259
src/drivers/barometer/goertek/spa06/SPA06.cpp
Normal file
@ -0,0 +1,259 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include "SPA06.hpp"
|
||||
|
||||
SPA06::SPA06(const I2CSPIDriverConfig &config, spa06::ISPA06 *interface) :
|
||||
I2CSPIDriver(config),
|
||||
_interface(interface),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": sample")),
|
||||
_measure_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": measure")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms errors"))
|
||||
{
|
||||
}
|
||||
|
||||
SPA06::~SPA06()
|
||||
{
|
||||
// free perf counters
|
||||
perf_free(_sample_perf);
|
||||
perf_free(_measure_perf);
|
||||
perf_free(_comms_errors);
|
||||
|
||||
delete _interface;
|
||||
}
|
||||
|
||||
/*
|
||||
float
|
||||
SPA06::scale_factor(int oversampling_rate)
|
||||
{
|
||||
float k;
|
||||
|
||||
switch (oversampling_rate) {
|
||||
case 1:
|
||||
k = 524288.0f;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
k = 1572864.0f;
|
||||
break;
|
||||
|
||||
case 4:
|
||||
k = 3670016.0f;
|
||||
break;
|
||||
|
||||
case 8:
|
||||
k = 7864320.0f;
|
||||
break;
|
||||
|
||||
case 16:
|
||||
k = 253952.0f;
|
||||
break;
|
||||
|
||||
case 32:
|
||||
k = 516096.0f;
|
||||
break;
|
||||
|
||||
case 64:
|
||||
k = 1040384.0f;
|
||||
break;
|
||||
|
||||
case 128:
|
||||
k = 2088960.0f;
|
||||
break;
|
||||
|
||||
default:
|
||||
k = 0;
|
||||
break;
|
||||
}
|
||||
|
||||
return k;
|
||||
}
|
||||
*/
|
||||
|
||||
int
|
||||
SPA06::calibrate()
|
||||
{
|
||||
uint8_t buf[21];
|
||||
|
||||
_interface->read(SPA06_ADDR_CAL, buf, sizeof(buf));
|
||||
|
||||
_cal.c0 = (uint16_t)(buf[0]) << 4 | (uint16_t)(buf[1]) >> 4;
|
||||
// If value is negative, we need to fill the missing bits.
|
||||
_cal.c0 = (_cal.c0 & 1 << 11) ? (0xf000 | _cal.c0) : _cal.c0;
|
||||
|
||||
_cal.c1 = (uint16_t)(buf[1] & 0x0F) << 8 | buf[2];
|
||||
_cal.c1 = (_cal.c1 & 1 << 11) ? (0xf000 | _cal.c1) : _cal.c1;
|
||||
|
||||
_cal.c00 = (uint32_t)(buf[3]) << 12 | (uint32_t)(buf[4]) << 4 | (buf[5]) >> 4;
|
||||
_cal.c00 = (_cal.c00 & 1 << 19) ? (0xfff00000 | _cal.c00) : _cal.c00;
|
||||
|
||||
_cal.c10 = (uint32_t)(buf[5] & 0x0F) << 16 | (uint32_t)(buf[6]) << 8 | buf[7];
|
||||
_cal.c10 = (_cal.c10 & 1 << 19) ? (0xfff00000 | _cal.c10) : _cal.c10;
|
||||
|
||||
_cal.c01 = (uint16_t)(buf[8]) << 8 | buf[9];
|
||||
|
||||
_cal.c11 = (uint16_t)(buf[10]) << 8 | buf[11];
|
||||
|
||||
_cal.c20 = (uint16_t)(buf[12]) << 8 | buf[13];
|
||||
|
||||
_cal.c21 = (uint16_t)(buf[14]) << 8 | buf[15];
|
||||
|
||||
_cal.c30 = (uint16_t)(buf[16]) << 8 | buf[17];
|
||||
|
||||
_cal.c31 = (uint16_t)(buf[18]) << 4 | (uint16_t)(buf[19] & 0xF0) >> 4;
|
||||
_cal.c31 = (_cal.c31 & 1 << 11) ? (0xf000 | _cal.c31) : _cal.c31;
|
||||
|
||||
_cal.c40 = (uint16_t)(buf[19] & 0x0F) << 8 | buf[20];
|
||||
_cal.c40 = (_cal.c40 & 1 << 11) ? (0xf000 | _cal.c40) : _cal.c40;
|
||||
|
||||
PX4_DEBUG("c0:%d\nc1:%d\nc00:%ld\nc10:%ld\nc01:%d\nc11:%d\nc20:%d\nc21:%d\nc30:%d\nc31:%d\nc40:%d\n",
|
||||
_cal.c0, _cal.c1,
|
||||
_cal.c00, _cal.c10,
|
||||
_cal.c01, _cal.c11, _cal.c20, _cal.c21, _cal.c30, _cal.c31, _cal.c40);
|
||||
|
||||
return OK;
|
||||
}
|
||||
int
|
||||
SPA06::init()
|
||||
{
|
||||
int8_t tries = 5;
|
||||
// reset sensor
|
||||
_interface->set_reg(SPA06_VALUE_RESET, SPA06_ADDR_RESET);
|
||||
usleep(10000);
|
||||
|
||||
// check id
|
||||
if (_interface->get_reg(SPA06_ADDR_ID) != SPA06_VALUE_ID) {
|
||||
PX4_DEBUG("id of your baro is not: 0x%02x", SPA06_VALUE_ID);
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
while (tries--) {
|
||||
uint8_t meas_cfg = _interface->get_reg(SPA06_ADDR_MEAS_CFG);
|
||||
|
||||
if (meas_cfg & (1 << 7) && meas_cfg & (1 << 6)) {
|
||||
break;
|
||||
}
|
||||
|
||||
usleep(10000);
|
||||
}
|
||||
|
||||
if (tries < 0) {
|
||||
PX4_DEBUG("spa06 sensor or coef not ready");
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
// get calibration and pre process them
|
||||
calibrate();
|
||||
|
||||
// set config, recommended settings
|
||||
_interface->set_reg(_curr_prs_cfg, SPA06_ADDR_PRS_CFG);
|
||||
kp = 253952.0f; // refer to scale_factor()
|
||||
_interface->set_reg(_curr_tmp_cfg, SPA06_ADDR_TMP_CFG);
|
||||
kt = 524288.0f;
|
||||
|
||||
// Enable FIFO
|
||||
_interface->set_reg(1 << 2, SPA06_ADDR_CFG_REG);
|
||||
// Continuous pressure and temperature mesasurement.
|
||||
_interface->set_reg(7, SPA06_ADDR_MEAS_CFG);
|
||||
|
||||
Start();
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
void
|
||||
SPA06::Start()
|
||||
{
|
||||
// schedule a cycle to start things
|
||||
ScheduleNow();
|
||||
}
|
||||
|
||||
void
|
||||
SPA06::RunImpl()
|
||||
{
|
||||
collect();
|
||||
|
||||
ScheduleDelayed(_measure_interval);
|
||||
}
|
||||
int
|
||||
SPA06::collect()
|
||||
{
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
// this should be fairly close to the end of the conversion, so the best approximation of the time
|
||||
const hrt_abstime timestamp_sample = hrt_absolute_time();
|
||||
|
||||
if (_interface->read(SPA06_ADDR_DATA, (uint8_t *)&_data, sizeof(_data)) != OK) {
|
||||
perf_count(_comms_errors);
|
||||
perf_cancel(_sample_perf);
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
int32_t temp_raw = (uint32_t)_data.t_msb << 16 | (uint32_t)_data.t_lsb << 8 | (uint32_t)_data.t_xlsb;
|
||||
temp_raw = (temp_raw & 1 << 23) ? (0xff000000 | temp_raw) : temp_raw;
|
||||
|
||||
int32_t press_raw = (uint32_t)_data.p_msb << 16 | (uint32_t) _data.p_lsb << 8 | (uint32_t) _data.p_xlsb;
|
||||
press_raw = (press_raw & 1 << 23) ? (0xff000000 | press_raw) : press_raw;
|
||||
|
||||
// calculate
|
||||
float ftsc = (float)temp_raw / kt;
|
||||
float fpsc = (float)press_raw / kp;
|
||||
float qua2 = (float)_cal.c10 + fpsc * ((float)_cal.c20 + fpsc * ((float)_cal.c30) + fpsc * (float)_cal.c40);
|
||||
float qua3 = ftsc * fpsc * ((float)_cal.c11 + fpsc * ((float)_cal.c21) + fpsc * (float)_cal.c31);
|
||||
|
||||
float fp = (float)_cal.c00 + fpsc * qua2 + ftsc * (float)_cal.c01 + qua3;
|
||||
float temperature = (float)_cal.c0 * 0.5f + (float)_cal.c1 * ftsc;
|
||||
|
||||
|
||||
sensor_baro_s sensor_baro{};
|
||||
sensor_baro.timestamp_sample = timestamp_sample;
|
||||
sensor_baro.device_id = _interface->get_device_id();
|
||||
sensor_baro.pressure = fp;
|
||||
sensor_baro.temperature = temperature;
|
||||
sensor_baro.error_count = perf_event_count(_comms_errors);
|
||||
sensor_baro.timestamp = hrt_absolute_time();
|
||||
_sensor_baro_pub.publish(sensor_baro);
|
||||
|
||||
perf_end(_sample_perf);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
void
|
||||
SPA06::print_status()
|
||||
{
|
||||
I2CSPIDriverBase::print_status();
|
||||
perf_print_counter(_sample_perf);
|
||||
perf_print_counter(_measure_perf);
|
||||
perf_print_counter(_comms_errors);
|
||||
}
|
||||
117
src/drivers/barometer/goertek/spa06/SPA06.hpp
Normal file
117
src/drivers/barometer/goertek/spa06/SPA06.hpp
Normal file
@ -0,0 +1,117 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "spa06.h"
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <uORB/PublicationMulti.hpp>
|
||||
#include <uORB/topics/sensor_baro.h>
|
||||
|
||||
class SPA06 : public I2CSPIDriver<SPA06>
|
||||
{
|
||||
public:
|
||||
SPA06(const I2CSPIDriverConfig &config, spa06::ISPA06 *interface);
|
||||
virtual ~SPA06();
|
||||
|
||||
static I2CSPIDriverBase *instantiate(const I2CSPIDriverConfig &config, int runtime_instance);
|
||||
static void print_usage();
|
||||
|
||||
int init();
|
||||
void print_status();
|
||||
|
||||
void RunImpl();
|
||||
private:
|
||||
void Start();
|
||||
// float scale_factor(int oversampling_rate);
|
||||
|
||||
int collect(); //get results and publish
|
||||
int calibrate();
|
||||
|
||||
uORB::PublicationMulti<sensor_baro_s> _sensor_baro_pub{ORB_ID(sensor_baro)};
|
||||
|
||||
spa06::ISPA06 *_interface;
|
||||
spa06::data_s _data;
|
||||
spa06::calibration_s _cal{};
|
||||
|
||||
// set config, recommended settings
|
||||
//
|
||||
// oversampling rate : single | 2 | 4 | 8 | 16 | 32 | 64 | 128
|
||||
// scale factor(KP/KT): 524288 | 1572864 | 3670016 | 7864320 | 253952 | 516096 | 1040384 | 2088960
|
||||
|
||||
// configuration of pressure measurement rate (PM_RATE) and resolution (PM_PRC)
|
||||
//
|
||||
// PM_RATE[7:4] : 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15
|
||||
// measurement rate: 1 | 2 | 4 | 8 | 16 | 32 | 64 | 128 | 25/16 | 25/8 | 25/4 | 25/2 | 25 | 50 | 100 | 200
|
||||
// note: applicable for measurements in background mode only
|
||||
//
|
||||
// PM_PRC[3:0] : 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7
|
||||
// oversampling (times): single | 2 | 4 | 8 | 16 | 32 | 64 | 128
|
||||
// measurement time(ms): 3.6 | 5.2 | 8.4 | 14.8 | 27.6 | 53.2 | 104.4 | 206.8
|
||||
// precision(PaRMS) : 5.0 | | 2.5 | | 1.2 | 0.9 | 0.5 |
|
||||
// note: use in combination with a bit shift when the oversampling rate is > 8 times. see CFG_REG(0x19) register
|
||||
//
|
||||
// -> 32 measurements per second, 16 oversampling
|
||||
static constexpr uint8_t _curr_prs_cfg{5 << 4 | 4};
|
||||
|
||||
// configuration of temperature measurment rate (TMP_RATE) and resolution (TMP_PRC)
|
||||
//
|
||||
// temperature measurement: internal sensor (in ASIC) | external sensor (in pressure sensor MEMS element)
|
||||
// PM_RATE[7:4] : 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15
|
||||
// measurement rate: 1 | 2 | 4 | 8 | 16 | 32 | 64 | 128 | 25/16 | 25/8 | 25/4 | 25/2 | 25 | 50 | 100 | 200
|
||||
// note: applicable for measurements in background mode only
|
||||
//
|
||||
// TMP_PRC[2:0] : 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7
|
||||
// oversampling (times): single | 2 | 4 | 8 | 16 | 32 | 64 | 128
|
||||
// note: single(default) measurement time 3.6ms, other settings are optional, and may not be relevant
|
||||
// note: use in combination with a bit shift when the oversampling rate is > 8 times. see CFG_REG(0x19) register
|
||||
|
||||
// -> 32 measurements per second, single oversampling
|
||||
static constexpr uint8_t _curr_tmp_cfg{5 << 4 | 0};
|
||||
|
||||
bool _collect_phase{false};
|
||||
float kp;
|
||||
float kt;
|
||||
|
||||
perf_counter_t _sample_perf;
|
||||
perf_counter_t _measure_perf;
|
||||
perf_counter_t _comms_errors;
|
||||
|
||||
static constexpr uint32_t _sample_rate{32};
|
||||
static constexpr uint32_t _measure_interval{1000000 / _sample_rate};
|
||||
};
|
||||
102
src/drivers/barometer/goertek/spa06/SPA06_I2C.cpp
Normal file
102
src/drivers/barometer/goertek/spa06/SPA06_I2C.cpp
Normal file
@ -0,0 +1,102 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file SPA06_I2C.cpp
|
||||
*
|
||||
* SPI interface for Goertek SPA06
|
||||
*/
|
||||
|
||||
#include "spa06.h"
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
class SPA06_I2C: public device::I2C, public spa06::ISPA06
|
||||
{
|
||||
public:
|
||||
SPA06_I2C(uint8_t bus, uint32_t device, int bus_frequency);
|
||||
virtual ~SPA06_I2C() override = default;
|
||||
|
||||
int init() override { return I2C::init(); }
|
||||
|
||||
uint8_t get_reg(uint8_t addr) override;
|
||||
int set_reg(uint8_t value, uint8_t addr) override;
|
||||
|
||||
int read(uint8_t addr, uint8_t *buf, uint8_t len) override;
|
||||
//spa06::data_s *get_data(uint8_t addr) override;
|
||||
//spa06::calibration_s *get_calibration(uint8_t addr) override;
|
||||
|
||||
uint32_t get_device_id() const override { return device::I2C::get_device_id(); }
|
||||
|
||||
uint8_t get_device_address() const override { return device::I2C::get_device_address(); }
|
||||
private:
|
||||
spa06::calibration_s _cal{};
|
||||
spa06::data_s _data{};
|
||||
};
|
||||
|
||||
spa06::ISPA06 *spa06_i2c_interface(uint8_t busnum, uint32_t device, int bus_frequency)
|
||||
{
|
||||
return new SPA06_I2C(busnum, device, bus_frequency);
|
||||
}
|
||||
|
||||
SPA06_I2C::SPA06_I2C(uint8_t bus, uint32_t device, int bus_frequency) :
|
||||
I2C(DRV_BARO_DEVTYPE_SPA06, MODULE_NAME, bus, device, bus_frequency)
|
||||
{
|
||||
}
|
||||
|
||||
uint8_t
|
||||
SPA06_I2C::get_reg(uint8_t addr)
|
||||
{
|
||||
uint8_t cmd[2] = { (uint8_t)(addr), 0};
|
||||
transfer(&cmd[0], 1, &cmd[1], 1);
|
||||
|
||||
return cmd[1];
|
||||
}
|
||||
|
||||
int
|
||||
SPA06_I2C::set_reg(uint8_t value, uint8_t addr)
|
||||
{
|
||||
uint8_t cmd[2] = { (uint8_t)(addr), value};
|
||||
return transfer(cmd, sizeof(cmd), nullptr, 0);
|
||||
}
|
||||
|
||||
int
|
||||
SPA06_I2C::read(uint8_t addr, uint8_t *buf, uint8_t len)
|
||||
{
|
||||
return transfer(&addr, 1, buf, len);
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
104
src/drivers/barometer/goertek/spa06/SPA06_SPI.cpp
Normal file
104
src/drivers/barometer/goertek/spa06/SPA06_SPI.cpp
Normal file
@ -0,0 +1,104 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file SPA06_SPI.cpp
|
||||
*
|
||||
* SPI interface for Goertek SPA06
|
||||
*/
|
||||
|
||||
#include "spa06.h"
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <drivers/device/spi.h>
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
/* SPI protocol address bits */
|
||||
#define DIR_READ (1<<7) //for set
|
||||
#define DIR_WRITE ~(1<<7) //for clear
|
||||
|
||||
class SPA06_SPI: public device::SPI, public spa06::ISPA06
|
||||
{
|
||||
public:
|
||||
SPA06_SPI(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode);
|
||||
virtual ~SPA06_SPI() override = default;
|
||||
|
||||
int init() override { return SPI::init(); }
|
||||
|
||||
uint8_t get_reg(uint8_t addr) override;
|
||||
int set_reg(uint8_t value, uint8_t addr) override;
|
||||
|
||||
int read(uint8_t addr, uint8_t *buf, uint8_t len) override;
|
||||
|
||||
uint32_t get_device_id() const override { return device::SPI::get_device_id(); }
|
||||
|
||||
uint8_t get_device_address() const override { return device::SPI::get_device_address(); }
|
||||
};
|
||||
|
||||
spa06::ISPA06 *
|
||||
spa06_spi_interface(uint8_t busnum, uint32_t device, int bus_frequency, spi_mode_e spi_mode)
|
||||
{
|
||||
return new SPA06_SPI(busnum, device, bus_frequency, spi_mode);
|
||||
}
|
||||
|
||||
SPA06_SPI::SPA06_SPI(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) :
|
||||
SPI(DRV_BARO_DEVTYPE_SPA06, MODULE_NAME, bus, device, spi_mode, bus_frequency)
|
||||
{
|
||||
}
|
||||
|
||||
uint8_t
|
||||
SPA06_SPI::get_reg(uint8_t addr)
|
||||
{
|
||||
uint8_t cmd[2] = { (uint8_t)(addr | DIR_READ), 0}; // set MSB bit
|
||||
transfer(&cmd[0], &cmd[0], 2);
|
||||
|
||||
return cmd[1];
|
||||
}
|
||||
|
||||
int
|
||||
SPA06_SPI::set_reg(uint8_t value, uint8_t addr)
|
||||
{
|
||||
uint8_t cmd[2] = { (uint8_t)(addr & DIR_WRITE), value}; // clear MSB bit
|
||||
return transfer(&cmd[0], nullptr, 2);
|
||||
}
|
||||
|
||||
int
|
||||
SPA06_SPI::read(uint8_t addr, uint8_t *buf, uint8_t len)
|
||||
{
|
||||
uint8_t tx_buf[len + 1] = {(uint8_t)(addr | DIR_READ)}; // GCC support VLA, let's use it
|
||||
|
||||
return transfer(tx_buf, buf, len);
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
41
src/drivers/barometer/goertek/spa06/parameters.c
Normal file
41
src/drivers/barometer/goertek/spa06/parameters.c
Normal file
@ -0,0 +1,41 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Goertek SPA06 Barometer (external I2C)
|
||||
*
|
||||
* @reboot_required true
|
||||
* @group Sensors
|
||||
* @boolean
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_EN_SPA06, 0);
|
||||
107
src/drivers/barometer/goertek/spa06/spa06.h
Normal file
107
src/drivers/barometer/goertek/spa06/spa06.h
Normal file
@ -0,0 +1,107 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file spa06.h
|
||||
*
|
||||
* Shared defines for the SPA06 driver.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
|
||||
#define SPA06_ADDR_ID 0x0d
|
||||
#define SPA06_ADDR_RESET 0x0c // set to reset
|
||||
#define SPA06_ADDR_CAL 0x10
|
||||
#define SPA06_ADDR_PRS_CFG 0x06
|
||||
#define SPA06_ADDR_TMP_CFG 0x07
|
||||
#define SPA06_ADDR_MEAS_CFG 0x08
|
||||
#define SPA06_ADDR_CFG_REG 0x09
|
||||
#define SPA06_ADDR_DATA 0x00
|
||||
|
||||
|
||||
#define SPA06_VALUE_RESET 9
|
||||
#define SPA06_VALUE_ID 0x11
|
||||
|
||||
namespace spa06
|
||||
{
|
||||
|
||||
#pragma pack(push,1)
|
||||
struct calibration_s {
|
||||
int16_t c0, c1;
|
||||
int32_t c00, c10;
|
||||
int16_t c01, c11, c20, c21, c30, c31, c40;
|
||||
};
|
||||
|
||||
struct data_s {
|
||||
uint8_t p_msb;
|
||||
uint8_t p_lsb;
|
||||
uint8_t p_xlsb;
|
||||
|
||||
uint8_t t_msb;
|
||||
uint8_t t_lsb;
|
||||
uint8_t t_xlsb;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
class ISPA06
|
||||
{
|
||||
public:
|
||||
virtual ~ISPA06() = default;
|
||||
|
||||
virtual int init() = 0;
|
||||
|
||||
// read reg value
|
||||
virtual uint8_t get_reg(uint8_t addr) = 0;
|
||||
|
||||
// write reg value
|
||||
virtual int set_reg(uint8_t value, uint8_t addr) = 0;
|
||||
|
||||
// bulk read of data into buffer, return same pointer
|
||||
virtual int read(uint8_t addr, uint8_t *buf, uint8_t len) = 0;
|
||||
// bulk read of calibration data into buffer, return same pointer
|
||||
|
||||
virtual uint32_t get_device_id() const = 0;
|
||||
|
||||
virtual uint8_t get_device_address() const = 0;
|
||||
};
|
||||
|
||||
} // namespace spa06
|
||||
|
||||
|
||||
#if defined(CONFIG_SPI)
|
||||
extern spa06::ISPA06 *spa06_spi_interface(uint8_t busnum, uint32_t device, int bus_frequency, spi_mode_e spi_mode);
|
||||
#endif // CONFIG_SPI
|
||||
#if defined(CONFIG_I2C)
|
||||
extern spa06::ISPA06 *spa06_i2c_interface(uint8_t busnum, uint32_t device, int bus_frequency);
|
||||
#endif // CONFIG_I2C
|
||||
141
src/drivers/barometer/goertek/spa06/spa06_main.cpp
Normal file
141
src/drivers/barometer/goertek/spa06/spa06_main.cpp
Normal file
@ -0,0 +1,141 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 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_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
|
||||
#include "SPA06.hpp"
|
||||
|
||||
#include <drivers/drv_sensor.h>
|
||||
|
||||
extern "C" { __EXPORT int spa06_main(int argc, char *argv[]); }
|
||||
|
||||
void
|
||||
SPA06::print_usage()
|
||||
{
|
||||
PRINT_MODULE_USAGE_NAME("spa06", "driver");
|
||||
PRINT_MODULE_USAGE_SUBCATEGORY("baro");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
#if defined(CONFIG_I2C)
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, true);
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x76);
|
||||
#else
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true);
|
||||
#endif
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
I2CSPIDriverBase *SPA06::instantiate(const I2CSPIDriverConfig &config, int runtime_instance)
|
||||
{
|
||||
spa06::ISPA06 *interface = nullptr;
|
||||
|
||||
#if defined(CONFIG_I2C)
|
||||
|
||||
if (config.bus_type == BOARD_I2C_BUS) {
|
||||
interface = spa06_i2c_interface(config.bus, config.i2c_address, config.bus_frequency);
|
||||
|
||||
}
|
||||
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
|
||||
if (config.bus_type == BOARD_SPI_BUS) {
|
||||
interface = spa06_spi_interface(config.bus, config.spi_devid, config.bus_frequency, config.spi_mode);
|
||||
}
|
||||
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
if (interface == nullptr) {
|
||||
PX4_ERR("failed creating interface for bus %i", config.bus);
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
if (interface->init() != OK) {
|
||||
delete interface;
|
||||
PX4_DEBUG("no device on bus %i", config.bus);
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
SPA06 *dev = new SPA06(config, interface);
|
||||
|
||||
if (dev == nullptr) {
|
||||
delete interface;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
if (OK != dev->init()) {
|
||||
delete dev;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
return dev;
|
||||
}
|
||||
|
||||
int
|
||||
spa06_main(int argc, char *argv[])
|
||||
{
|
||||
using ThisDriver = SPA06;
|
||||
BusCLIArguments cli{true, true};
|
||||
#if defined(CONFIG_I2C)
|
||||
cli.i2c_address = 0x76;
|
||||
cli.default_i2c_frequency = 100 * 1000;
|
||||
#endif // CONFIG_I2C
|
||||
#if defined(CONFIG_SPI)
|
||||
cli.default_spi_frequency = 10 * 1000 * 1000;
|
||||
#endif // CONFIG_SPI
|
||||
|
||||
const char *verb = cli.parseDefaultArguments(argc, argv);
|
||||
|
||||
if (!verb) {
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_BARO_DEVTYPE_SPA06);
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
return ThisDriver::module_start(cli, iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "stop")) {
|
||||
return ThisDriver::module_stop(iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "status")) {
|
||||
return ThisDriver::module_status(iterator);
|
||||
}
|
||||
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
@ -1,6 +1,6 @@
|
||||
/**************************************************************************
|
||||
*
|
||||
* Copyright (c) 2022-2023 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2022-2024 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -32,24 +32,22 @@
|
||||
****************************************************************************/
|
||||
|
||||
#include "lightware_sf45_serial.hpp"
|
||||
#include "sf45_commands.h"
|
||||
|
||||
#include <inttypes.h>
|
||||
#include <fcntl.h>
|
||||
#include <termios.h>
|
||||
#include <lib/crc/crc.h>
|
||||
#include <lib/mathlib/mathlib.h>
|
||||
|
||||
#include <float.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <matrix/matrix/math.hpp>
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
/* Configuration Constants */
|
||||
#define SF45_MAX_PAYLOAD 256
|
||||
#define SF45_SCALE_FACTOR 0.01f
|
||||
|
||||
SF45LaserSerial::SF45LaserSerial(const char *port, uint8_t rotation) :
|
||||
|
||||
SF45LaserSerial::SF45LaserSerial(const char *port) :
|
||||
ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(port)),
|
||||
_px4_rangefinder(0, rotation),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": com_err"))
|
||||
{
|
||||
@ -68,17 +66,17 @@ SF45LaserSerial::SF45LaserSerial(const char *port, uint8_t rotation) :
|
||||
device_id.devid_s.bus = bus_num;
|
||||
}
|
||||
|
||||
_num_retries = 2;
|
||||
_px4_rangefinder.set_device_id(device_id.devid);
|
||||
_px4_rangefinder.set_device_type(DRV_DIST_DEVTYPE_LIGHTWARE_LASER);
|
||||
|
||||
// populate obstacle map members
|
||||
_obstacle_map_msg.frame = obstacle_distance_s::MAV_FRAME_BODY_FRD;
|
||||
_obstacle_map_msg.increment = 5;
|
||||
_obstacle_map_msg.angle_offset = -2.5;
|
||||
_obstacle_map_msg.min_distance = UINT16_MAX;
|
||||
_obstacle_map_msg.max_distance = 5000;
|
||||
_obstacle_distance.frame = obstacle_distance_s::MAV_FRAME_BODY_FRD;
|
||||
_obstacle_distance.sensor_type = obstacle_distance_s::MAV_DISTANCE_SENSOR_LASER;
|
||||
_obstacle_distance.increment = 5;
|
||||
_obstacle_distance.min_distance = 20;
|
||||
_obstacle_distance.max_distance = 5000;
|
||||
_obstacle_distance.angle_offset = 0;
|
||||
|
||||
for (uint32_t i = 0 ; i < BIN_COUNT; i++) {
|
||||
_obstacle_distance.distances[i] = UINT16_MAX;
|
||||
}
|
||||
}
|
||||
|
||||
SF45LaserSerial::~SF45LaserSerial()
|
||||
@ -91,55 +89,42 @@ SF45LaserSerial::~SF45LaserSerial()
|
||||
|
||||
int SF45LaserSerial::init()
|
||||
{
|
||||
|
||||
param_get(param_find("SF45_UPDATE_CFG"), &_update_rate);
|
||||
param_get(param_find("SF45_ORIENT_CFG"), &_orient_cfg);
|
||||
param_get(param_find("SF45_YAW_CFG"), &_yaw_cfg);
|
||||
|
||||
/* SF45/B (50M) */
|
||||
_px4_rangefinder.set_min_distance(0.2f);
|
||||
_px4_rangefinder.set_max_distance(50.0f);
|
||||
_interval = 10000;
|
||||
|
||||
start();
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
int SF45LaserSerial::measure()
|
||||
{
|
||||
|
||||
int rate = (int)_update_rate;
|
||||
_data_output = 0x101; // raw distance + yaw readings
|
||||
int32_t rate = (int32_t)_update_rate;
|
||||
_data_output = 0x101; // raw distance (first return) + yaw readings
|
||||
_stream_data = 5; // enable constant streaming
|
||||
|
||||
// send some packets so the sensor starts scanning
|
||||
// send packets to the sensor depending on the state
|
||||
switch (_sensor_state) {
|
||||
|
||||
// sensor should now respond
|
||||
case 0:
|
||||
while (_num_retries--) {
|
||||
sf45_send(SF_PRODUCT_NAME, false, &_product_name[0], 0);
|
||||
_sensor_state = 0;
|
||||
}
|
||||
|
||||
_sensor_state = 1;
|
||||
case STATE_UNINIT:
|
||||
// Used to probe if the sensor is alive
|
||||
sf45_send(SF_PRODUCT_NAME, false, &_product_name[0], 0);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
case STATE_ACK_PRODUCT_NAME:
|
||||
// Update rate default to 50 readings/s
|
||||
sf45_send(SF_UPDATE_RATE, true, &rate, sizeof(uint8_t));
|
||||
_sensor_state = 2;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
case STATE_ACK_UPDATE_RATE:
|
||||
// Configure the data that the sensor shall output
|
||||
sf45_send(SF_DISTANCE_OUTPUT, true, &_data_output, sizeof(_data_output));
|
||||
_sensor_state = 3;
|
||||
break;
|
||||
|
||||
case 3:
|
||||
case STATE_ACK_DISTANCE_OUTPUT:
|
||||
// Configure the sensor to automatically output data at the configured update rate
|
||||
sf45_send(SF_STREAM, true, &_stream_data, sizeof(_stream_data));
|
||||
_sensor_state = 4;
|
||||
_sensor_state = STATE_SEND_STREAM;
|
||||
break;
|
||||
|
||||
default:
|
||||
@ -151,104 +136,90 @@ int SF45LaserSerial::measure()
|
||||
|
||||
int SF45LaserSerial::collect()
|
||||
{
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
/* clear buffer if last read was too long ago */
|
||||
int64_t read_elapsed = hrt_elapsed_time(&_last_read);
|
||||
int ret;
|
||||
/* the buffer for read chars is buflen minus null termination */
|
||||
param_get(param_find("SF45_CP_LIMIT"), &_collision_constraint);
|
||||
uint8_t readbuf[SF45_MAX_PAYLOAD];
|
||||
|
||||
float distance_m = -1.0f;
|
||||
|
||||
/* read from the sensor (uart buffer) */
|
||||
const hrt_abstime timestamp_sample = hrt_absolute_time();
|
||||
if (_sensor_state == STATE_UNINIT) {
|
||||
|
||||
if (_sensor_state == 1) {
|
||||
perf_begin(_sample_perf);
|
||||
const int payload_length = 22;
|
||||
|
||||
ret = ::read(_fd, &readbuf[0], 22);
|
||||
sf45_request_handle(ret, readbuf);
|
||||
ScheduleDelayed(_interval * 2);
|
||||
_crc_valid = false;
|
||||
sf45_get_and_handle_request(payload_length, SF_PRODUCT_NAME);
|
||||
|
||||
} else if (_sensor_state == 2) {
|
||||
|
||||
ret = ::read(_fd, &readbuf[0], 7);
|
||||
|
||||
if (readbuf[3] == SF_UPDATE_RATE) {
|
||||
sf45_request_handle(ret, readbuf);
|
||||
ScheduleDelayed(_interval * 5);
|
||||
if (_crc_valid) {
|
||||
_sensor_state = STATE_ACK_PRODUCT_NAME;
|
||||
perf_end(_sample_perf);
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
} else if (_sensor_state == 3) {
|
||||
return -EAGAIN;
|
||||
|
||||
ret = ::read(_fd, &readbuf[0], 8);
|
||||
} else if (_sensor_state == STATE_ACK_PRODUCT_NAME) {
|
||||
|
||||
if (readbuf[3] == SF_DISTANCE_OUTPUT) {
|
||||
sf45_request_handle(ret, readbuf);
|
||||
ScheduleDelayed(_interval * 5);
|
||||
perf_begin(_sample_perf);
|
||||
const int payload_length = 7;
|
||||
|
||||
_crc_valid = false;
|
||||
sf45_get_and_handle_request(payload_length, SF_UPDATE_RATE);
|
||||
|
||||
if (_crc_valid) {
|
||||
_sensor_state = STATE_ACK_UPDATE_RATE;
|
||||
perf_end(_sample_perf);
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
return -EAGAIN;
|
||||
|
||||
} else if (_sensor_state == STATE_ACK_UPDATE_RATE) {
|
||||
|
||||
perf_begin(_sample_perf);
|
||||
const int payload_length = 10;
|
||||
|
||||
_crc_valid = false;
|
||||
sf45_get_and_handle_request(payload_length, SF_DISTANCE_OUTPUT);
|
||||
|
||||
if (_crc_valid) {
|
||||
_sensor_state = STATE_ACK_DISTANCE_OUTPUT;
|
||||
perf_end(_sample_perf);
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
return -EAGAIN;
|
||||
|
||||
} else {
|
||||
|
||||
ret = ::read(_fd, &readbuf[0], 10);
|
||||
uint8_t flags_payload = (readbuf[1] >> 6) | (readbuf[2] << 2);
|
||||
// Stream data from sensor
|
||||
perf_begin(_sample_perf);
|
||||
const int payload_length = 10;
|
||||
|
||||
if (readbuf[3] == SF_DISTANCE_DATA_CM && flags_payload == 5) {
|
||||
_crc_valid = false;
|
||||
sf45_get_and_handle_request(payload_length, SF_DISTANCE_DATA_CM);
|
||||
|
||||
for (uint8_t i = 0; i < ret; ++i) {
|
||||
sf45_request_handle(ret, readbuf);
|
||||
}
|
||||
|
||||
if (_init_complete) {
|
||||
sf45_process_replies(&distance_m);
|
||||
} // end if
|
||||
|
||||
} else {
|
||||
|
||||
ret = ::read(_fd, &readbuf[0], 10);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
if (ret < 0) {
|
||||
PX4_DEBUG("read err: %d", ret);
|
||||
perf_count(_comms_errors);
|
||||
perf_end(_sample_perf);
|
||||
|
||||
/* only throw an error if we time out */
|
||||
if (read_elapsed > (_interval * 2)) {
|
||||
PX4_DEBUG("Timing out...");
|
||||
return ret;
|
||||
|
||||
} else {
|
||||
|
||||
return -EAGAIN;
|
||||
if (_crc_valid) {
|
||||
sf45_process_replies(&distance_m);
|
||||
PX4_DEBUG("val (float): %8.4f, valid: %s", (double)distance_m, ((_crc_valid) ? "OK" : "NO"));
|
||||
perf_end(_sample_perf);
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
} else if (ret == 0) {
|
||||
return -EAGAIN;
|
||||
}
|
||||
|
||||
_last_read = hrt_absolute_time();
|
||||
|
||||
if (!_crc_valid) {
|
||||
return -EAGAIN;
|
||||
}
|
||||
|
||||
PX4_DEBUG("val (float): %8.4f, raw: %s, valid: %s", (double)distance_m, _linebuf, ((_crc_valid) ? "OK" : "NO"));
|
||||
_px4_rangefinder.update(timestamp_sample, distance_m);
|
||||
|
||||
perf_end(_sample_perf);
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
void SF45LaserSerial::start()
|
||||
{
|
||||
/* reset the report ring and state machine */
|
||||
/* reset the sensor state */
|
||||
_sensor_state = STATE_UNINIT;
|
||||
|
||||
/* reset the report ring */
|
||||
_collect_phase = false;
|
||||
|
||||
/* reset the UART receive buffer size */
|
||||
_linebuf_size = 0;
|
||||
|
||||
/* reset the fail counter */
|
||||
_last_received_time = hrt_absolute_time();
|
||||
|
||||
/* schedule a cycle to start things */
|
||||
ScheduleNow();
|
||||
}
|
||||
@ -263,11 +234,10 @@ void SF45LaserSerial::Run()
|
||||
/* fds initialized? */
|
||||
if (_fd < 0) {
|
||||
/* open fd: non-blocking read mode*/
|
||||
|
||||
_fd = ::open(_port, O_RDWR | O_NOCTTY);
|
||||
_fd = ::open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK);
|
||||
|
||||
if (_fd < 0) {
|
||||
PX4_ERR("open failed (%i)", errno);
|
||||
PX4_ERR("serial open failed (%i)", errno);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -278,34 +248,11 @@ void SF45LaserSerial::Run()
|
||||
/* fill the struct for the new configuration */
|
||||
tcgetattr(_fd, &uart_config);
|
||||
|
||||
uart_config.c_cflag = (uart_config.c_cflag & ~CSIZE) | CS8;
|
||||
/* clear ONLCR flag (which appends a CR for every LF) */
|
||||
uart_config.c_oflag &= ~ONLCR;
|
||||
|
||||
uart_config.c_cflag |= (CLOCAL | CREAD);
|
||||
|
||||
// no parity, 1 stop bit, flow control disabled
|
||||
uart_config.c_cflag &= ~(PARENB | PARODD);
|
||||
|
||||
uart_config.c_cflag |= 0;
|
||||
|
||||
uart_config.c_cflag &= ~CSTOPB;
|
||||
|
||||
uart_config.c_cflag &= ~CRTSCTS;
|
||||
|
||||
uart_config.c_iflag &= ~IGNBRK;
|
||||
|
||||
uart_config.c_iflag &= ~ICRNL;
|
||||
|
||||
uart_config.c_iflag &= ~(IXON | IXOFF | IXANY);
|
||||
|
||||
// echo and echo NL off, canonical mode off (raw mode)
|
||||
// extended input processing off, signal chars off
|
||||
uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
|
||||
|
||||
uart_config.c_oflag = 0;
|
||||
|
||||
uart_config.c_cc[VMIN] = 0;
|
||||
|
||||
uart_config.c_cc[VTIME] = 1;
|
||||
/* no parity, one stop bit */
|
||||
uart_config.c_cflag &= ~(CSTOPB | PARENB);
|
||||
|
||||
unsigned speed = B921600;
|
||||
|
||||
@ -321,54 +268,37 @@ void SF45LaserSerial::Run()
|
||||
if ((termios_state = tcsetattr(_fd, TCSANOW, &uart_config)) < 0) {
|
||||
PX4_ERR("baud %d ATTR", termios_state);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (_collect_phase) {
|
||||
|
||||
/* perform collection */
|
||||
int collect_ret = collect();
|
||||
|
||||
if (collect_ret == -EAGAIN) {
|
||||
/* reschedule to grab the missing bits, time to transmit 8 bytes @ 9600 bps */
|
||||
ScheduleDelayed(1042 * 8);
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
if (OK != collect_ret) {
|
||||
/* we know the sensor needs about four seconds to initialize */
|
||||
if (hrt_absolute_time() > 5 * 1000 * 1000LL && _consecutive_fail_count < 5) {
|
||||
PX4_ERR("collection error #%u", _consecutive_fail_count);
|
||||
}
|
||||
|
||||
_consecutive_fail_count++;
|
||||
|
||||
/* restart the measurement state machine */
|
||||
if (hrt_absolute_time() - _last_received_time >= 1_s) {
|
||||
start();
|
||||
return;
|
||||
|
||||
} else {
|
||||
/* apparently success */
|
||||
_consecutive_fail_count = 0;
|
||||
}
|
||||
|
||||
/* next phase is measurement */
|
||||
_collect_phase = false;
|
||||
/* perform collection */
|
||||
if (collect() != PX4_OK && errno != EAGAIN) {
|
||||
PX4_DEBUG("collect error");
|
||||
}
|
||||
|
||||
if (_sensor_state != STATE_SEND_STREAM) {
|
||||
/* next phase is measurement */
|
||||
_collect_phase = false;
|
||||
}
|
||||
|
||||
} else {
|
||||
/* measurement phase */
|
||||
|
||||
if (measure() != PX4_OK) {
|
||||
PX4_DEBUG("measure error");
|
||||
}
|
||||
|
||||
/* next phase is collection */
|
||||
_collect_phase = true;
|
||||
}
|
||||
|
||||
/* measurement phase */
|
||||
|
||||
if (OK != measure()) {
|
||||
PX4_DEBUG("measure error");
|
||||
}
|
||||
|
||||
/* next phase is collection */
|
||||
_collect_phase = true;
|
||||
|
||||
/* schedule a fresh cycle call when the measurement is done */
|
||||
ScheduleDelayed(_interval);
|
||||
|
||||
}
|
||||
|
||||
void SF45LaserSerial::print_info()
|
||||
@ -377,9 +307,8 @@ void SF45LaserSerial::print_info()
|
||||
perf_print_counter(_comms_errors);
|
||||
}
|
||||
|
||||
void SF45LaserSerial::sf45_request_handle(int return_val, uint8_t *input_buf)
|
||||
void SF45LaserSerial::sf45_get_and_handle_request(const int payload_length, const SF_SERIAL_CMD msg_id)
|
||||
{
|
||||
|
||||
// SF45 protocol
|
||||
// Start byte is 0xAA and is the start of packet
|
||||
// Payload length sanity check (0-1023) bytes
|
||||
@ -388,159 +317,175 @@ void SF45LaserSerial::sf45_request_handle(int return_val, uint8_t *input_buf)
|
||||
// ID byte precedes the data in the payload
|
||||
// CRC comprised of 16-bit checksum (not included in checksum calc.)
|
||||
|
||||
uint16_t recv_crc = 0;
|
||||
bool restart_flag = false;
|
||||
int ret;
|
||||
size_t max_read = sizeof(_linebuf) - _linebuf_size;
|
||||
ret = ::read(_fd, &_linebuf[_linebuf_size], max_read);
|
||||
|
||||
while (restart_flag != true) {
|
||||
if (ret < 0 && errno != EAGAIN) {
|
||||
PX4_ERR("ERROR (ack from streaming distance data): %d", ret);
|
||||
_linebuf_size = 0;
|
||||
perf_count(_comms_errors);
|
||||
perf_end(_sample_perf);
|
||||
return;
|
||||
}
|
||||
|
||||
switch (_parsed_state) {
|
||||
case 0: {
|
||||
if (input_buf[0] == 0xAA) {
|
||||
// start of frame is valid, continue
|
||||
_sop_valid = true;
|
||||
_calc_crc = sf45_format_crc(_calc_crc, _start_of_frame);
|
||||
_parsed_state = 1;
|
||||
break;
|
||||
if (ret > 0) {
|
||||
_last_received_time = hrt_absolute_time();
|
||||
_linebuf_size += ret;
|
||||
}
|
||||
|
||||
} else {
|
||||
_sop_valid = false;
|
||||
_crc_valid = false;
|
||||
_parsed_state = 0;
|
||||
restart_flag = true;
|
||||
_calc_crc = 0;
|
||||
PX4_INFO("INFO: start of packet not valid");
|
||||
break;
|
||||
} // end else
|
||||
} // end case 0
|
||||
// Not enough data to parse a complete packet. Gather more data in the next cycle.
|
||||
if (_linebuf_size < payload_length) {
|
||||
return;
|
||||
}
|
||||
|
||||
case 1: {
|
||||
rx_field.flags_lo = input_buf[1];
|
||||
_calc_crc = sf45_format_crc(_calc_crc, rx_field.flags_lo);
|
||||
_parsed_state = 2;
|
||||
break;
|
||||
}
|
||||
int index = 0;
|
||||
|
||||
case 2: {
|
||||
rx_field.flags_hi = input_buf[2];
|
||||
rx_field.data_len = (rx_field.flags_hi << 2) | (rx_field.flags_lo >> 6);
|
||||
_calc_crc = sf45_format_crc(_calc_crc, rx_field.flags_hi);
|
||||
while (index <= _linebuf_size - payload_length && _crc_valid == false) {
|
||||
bool restart_flag = false;
|
||||
|
||||
// Check payload length against known max value
|
||||
if (rx_field.data_len > 17) {
|
||||
PX4_INFO("INFO: payload length invalid, restarting data request");
|
||||
_parsed_state = 0;
|
||||
restart_flag = true;
|
||||
_calc_crc = 0;
|
||||
break;
|
||||
|
||||
} else {
|
||||
_parsed_state = 3;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
case 3: {
|
||||
|
||||
rx_field.msg_id = input_buf[3];
|
||||
|
||||
if (rx_field.msg_id == SF_PRODUCT_NAME || rx_field.msg_id == SF_UPDATE_RATE || rx_field.msg_id == SF_DISTANCE_OUTPUT
|
||||
|| rx_field.msg_id == SF_STREAM || rx_field.msg_id == SF_DISTANCE_DATA_CM) {
|
||||
|
||||
if (rx_field.msg_id == SF_DISTANCE_DATA_CM && rx_field.data_len > 1) {
|
||||
_sensor_ready = true;
|
||||
while (restart_flag != true) {
|
||||
switch (_parsed_state) {
|
||||
case SF45_PARSED_STATE::START: {
|
||||
if (_linebuf[index] == 0xAA) {
|
||||
// start of frame is valid, continue
|
||||
_sop_valid = true;
|
||||
_calc_crc = sf45_format_crc(_calc_crc, _start_of_frame);
|
||||
_parsed_state = SF45_PARSED_STATE::FLG_LOW;
|
||||
break;
|
||||
|
||||
} else {
|
||||
_sensor_ready = false;
|
||||
_sop_valid = false;
|
||||
_crc_valid = false;
|
||||
_parsed_state = SF45_PARSED_STATE::START;
|
||||
restart_flag = true;
|
||||
_calc_crc = 0;
|
||||
PX4_DEBUG("Start of packet not valid: %d", _sensor_state);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
case SF45_PARSED_STATE::FLG_LOW: {
|
||||
rx_field.flags_lo = _linebuf[index + 1];
|
||||
_calc_crc = sf45_format_crc(_calc_crc, rx_field.flags_lo);
|
||||
_parsed_state = SF45_PARSED_STATE::FLG_HIGH;
|
||||
break;
|
||||
}
|
||||
|
||||
case SF45_PARSED_STATE::FLG_HIGH: {
|
||||
rx_field.flags_hi = _linebuf[index + 2];
|
||||
rx_field.data_len = (rx_field.flags_hi << 2) | (rx_field.flags_lo >> 6);
|
||||
_calc_crc = sf45_format_crc(_calc_crc, rx_field.flags_hi);
|
||||
|
||||
// Check payload length against known max value
|
||||
if (rx_field.data_len > 17) {
|
||||
_parsed_state = SF45_PARSED_STATE::START;
|
||||
restart_flag = true;
|
||||
_calc_crc = 0;
|
||||
PX4_DEBUG("Payload length error: %d", _sensor_state);
|
||||
break;
|
||||
|
||||
} else {
|
||||
_parsed_state = SF45_PARSED_STATE::ID;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
case SF45_PARSED_STATE::ID: {
|
||||
rx_field.msg_id = _linebuf[index + 3];
|
||||
|
||||
if (rx_field.msg_id == msg_id) {
|
||||
_calc_crc = sf45_format_crc(_calc_crc, rx_field.msg_id);
|
||||
_parsed_state = SF45_PARSED_STATE::DATA;
|
||||
break;
|
||||
}
|
||||
|
||||
_calc_crc = sf45_format_crc(_calc_crc, rx_field.msg_id);
|
||||
|
||||
_parsed_state = 4;
|
||||
break;
|
||||
// Ignore message ID's that aren't searched
|
||||
else {
|
||||
_parsed_state = SF45_PARSED_STATE::START;
|
||||
_calc_crc = 0;
|
||||
restart_flag = true;
|
||||
PX4_DEBUG("Non needed message ID: %d", _sensor_state);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Ignore message ID's that aren't defined
|
||||
else {
|
||||
_parsed_state = 0;
|
||||
_calc_crc = 0;
|
||||
restart_flag = true;
|
||||
break;
|
||||
case SF45_PARSED_STATE::DATA: {
|
||||
// Process commands with & w/out data bytes
|
||||
if (rx_field.data_len > 1) {
|
||||
for (uint8_t i = 4; i < 3 + rx_field.data_len; ++i) {
|
||||
|
||||
}
|
||||
}
|
||||
rx_field.data[_data_bytes_recv] = _linebuf[index + i];
|
||||
_calc_crc = sf45_format_crc(_calc_crc, rx_field.data[_data_bytes_recv]);
|
||||
_data_bytes_recv = _data_bytes_recv + 1;
|
||||
|
||||
// Data
|
||||
case 4: {
|
||||
// Process commands with & w/out data bytes
|
||||
if (rx_field.data_len > 1) {
|
||||
for (uint8_t i = 4; i < 3 + rx_field.data_len; ++i) {
|
||||
}
|
||||
}
|
||||
|
||||
rx_field.data[_data_bytes_recv] = input_buf[i];
|
||||
_calc_crc = sf45_format_crc(_calc_crc, rx_field.data[_data_bytes_recv]);
|
||||
_data_bytes_recv = _data_bytes_recv + 1;
|
||||
else {
|
||||
|
||||
} // end for
|
||||
} //end if
|
||||
_parsed_state = SF45_PARSED_STATE::CRC_LOW;
|
||||
_data_bytes_recv = 0;
|
||||
_calc_crc = sf45_format_crc(_calc_crc, _data_bytes_recv);
|
||||
}
|
||||
|
||||
else {
|
||||
|
||||
_parsed_state = 5;
|
||||
_parsed_state = SF45_PARSED_STATE::CRC_LOW;
|
||||
_data_bytes_recv = 0;
|
||||
_calc_crc = sf45_format_crc(_calc_crc, _data_bytes_recv);
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
_parsed_state = 5;
|
||||
_data_bytes_recv = 0;
|
||||
break;
|
||||
}
|
||||
case SF45_PARSED_STATE::CRC_LOW: {
|
||||
rx_field.crc[0] = _linebuf[index + 3 + rx_field.data_len];
|
||||
_parsed_state = SF45_PARSED_STATE::CRC_HIGH;
|
||||
break;
|
||||
}
|
||||
|
||||
// CRC low byte
|
||||
case 5: {
|
||||
rx_field.crc[0] = input_buf[3 + rx_field.data_len];
|
||||
_parsed_state = 6;
|
||||
break;
|
||||
}
|
||||
case SF45_PARSED_STATE::CRC_HIGH: {
|
||||
rx_field.crc[1] = _linebuf[index + 4 + rx_field.data_len];
|
||||
uint16_t recv_crc = (rx_field.crc[1] << 8) | rx_field.crc[0];
|
||||
|
||||
// CRC high byte
|
||||
case 6: {
|
||||
rx_field.crc[1] = input_buf[4 + rx_field.data_len];
|
||||
recv_crc = (rx_field.crc[1] << 8) | rx_field.crc[0];
|
||||
|
||||
// Check the received crc bytes from the sf45 against our own CRC calcuation
|
||||
// If it matches, we can check if sensor ready
|
||||
// Only if crc match is valid and sensor ready (transmitting distance data) do we flag _init_complete
|
||||
if (recv_crc == _calc_crc) {
|
||||
_crc_valid = true;
|
||||
|
||||
// Sensor is ready if we read msg ID 44: SF_DISTANCE_DATA_CM
|
||||
if (_sensor_ready) {
|
||||
_init_complete = true;
|
||||
// Check the received crc bytes from the sf45 against our own CRC calcuation
|
||||
// If it matches, we can check if sensor ready
|
||||
// Only if crc match is valid and sensor ready (transmitting distance data) do we flag _init_complete
|
||||
if (recv_crc == _calc_crc) {
|
||||
_crc_valid = true;
|
||||
_parsed_state = SF45_PARSED_STATE::START;
|
||||
_calc_crc = 0;
|
||||
restart_flag = true;
|
||||
break;
|
||||
|
||||
} else {
|
||||
_init_complete = false;
|
||||
|
||||
_crc_valid = false;
|
||||
_parsed_state = SF45_PARSED_STATE::START;
|
||||
_calc_crc = 0;
|
||||
restart_flag = true;
|
||||
perf_count(_comms_errors);
|
||||
PX4_DEBUG("CRC mismatch: %d", _sensor_state);
|
||||
break;
|
||||
}
|
||||
|
||||
_parsed_state = 0;
|
||||
_calc_crc = 0;
|
||||
restart_flag = true;
|
||||
break;
|
||||
|
||||
} else {
|
||||
PX4_INFO("INFO: CRC mismatch");
|
||||
_crc_valid = false;
|
||||
_init_complete = false;
|
||||
_parsed_state = 0;
|
||||
_calc_crc = 0;
|
||||
restart_flag = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
} // end switch
|
||||
} //end while
|
||||
}
|
||||
|
||||
index++;
|
||||
}
|
||||
|
||||
// If we parsed successfully, remove the parsed part from the buffer if it is still large enough
|
||||
if (_crc_valid && index + payload_length < _linebuf_size) {
|
||||
unsigned next_after_index = index + payload_length;
|
||||
memmove(&_linebuf[0], &_linebuf[next_after_index], _linebuf_size - next_after_index);
|
||||
_linebuf_size -= next_after_index;
|
||||
}
|
||||
|
||||
// The buffer is filled. Either we can't keep up with the stream and/or it contains only invalid data. Reset to try again.
|
||||
if ((unsigned)_linebuf_size >= sizeof(_linebuf)) {
|
||||
_linebuf_size = 0;
|
||||
perf_count(_comms_errors);
|
||||
}
|
||||
}
|
||||
|
||||
void SF45LaserSerial::sf45_send(uint8_t msg_id, bool write, int *data, uint8_t data_len)
|
||||
void SF45LaserSerial::sf45_send(uint8_t msg_id, bool write, int32_t *data, uint8_t data_len)
|
||||
{
|
||||
uint16_t crc_val = 0;
|
||||
uint8_t packet_buff[SF45_MAX_PAYLOAD];
|
||||
@ -577,7 +522,7 @@ void SF45LaserSerial::sf45_send(uint8_t msg_id, bool write, int *data, uint8_t d
|
||||
if (msg_id == SF_DISTANCE_OUTPUT) {
|
||||
uint8_t data_convert = data[0] & 0x00FF;
|
||||
// write data bytes to the output buffer
|
||||
packet_buff[data_inc] = data_convert;
|
||||
packet_buff[data_inc] = data_convert;
|
||||
// Add data bytes to crc add function
|
||||
crc_val = sf45_format_crc(crc_val, data_convert);
|
||||
data_inc = data_inc + 1;
|
||||
@ -615,12 +560,11 @@ void SF45LaserSerial::sf45_send(uint8_t msg_id, bool write, int *data, uint8_t d
|
||||
// Add data bytes to crc add function
|
||||
crc_val = sf45_format_crc(crc_val, data[0]);
|
||||
data_inc = data_inc + 1;
|
||||
|
||||
}
|
||||
|
||||
else {
|
||||
// Product Name
|
||||
PX4_INFO("INFO: Product name");
|
||||
PX4_DEBUG("DEBUG: Product name");
|
||||
}
|
||||
|
||||
uint8_t crc_lo = crc_val & 0xFF;
|
||||
@ -635,25 +579,23 @@ void SF45LaserSerial::sf45_send(uint8_t msg_id, bool write, int *data, uint8_t d
|
||||
|
||||
// DEBUG
|
||||
for (uint8_t i = 0; i < packet_len; ++i) {
|
||||
PX4_INFO("INFO: Send byte: %d", packet_buff[i]);
|
||||
PX4_DEBUG("DEBUG: Send byte: %d", packet_buff[i]);
|
||||
}
|
||||
|
||||
ret = ::write(_fd, packet_buff, packet_len);
|
||||
|
||||
if (ret != packet_len) {
|
||||
perf_count(_comms_errors);
|
||||
PX4_DEBUG("write fail %d", ret);
|
||||
//return ret;
|
||||
PX4_ERR("serial write fail %d", ret);
|
||||
// Flush data written, not transmitted
|
||||
tcflush(_fd, TCOFLUSH);
|
||||
}
|
||||
}
|
||||
|
||||
void SF45LaserSerial::sf45_process_replies(float *distance_m)
|
||||
{
|
||||
|
||||
switch (rx_field.msg_id) {
|
||||
case SF_DISTANCE_DATA_CM: {
|
||||
|
||||
uint16_t obstacle_dist_cm = 0;
|
||||
const float raw_distance = (rx_field.data[0] << 0) | (rx_field.data[1] << 8);
|
||||
int16_t raw_yaw = ((rx_field.data[2] << 0) | (rx_field.data[3] << 8));
|
||||
int16_t scaled_yaw = 0;
|
||||
@ -661,63 +603,66 @@ void SF45LaserSerial::sf45_process_replies(float *distance_m)
|
||||
// The sensor scans from 0 to -160, so extract negative angle from int16 and represent as if a float
|
||||
if (raw_yaw > 32000) {
|
||||
raw_yaw = raw_yaw - 65535;
|
||||
|
||||
}
|
||||
|
||||
// The sensor is facing downward, so the sensor is flipped about it's x-axis -inverse of each yaw angle
|
||||
if (_orient_cfg == 1) {
|
||||
if (_orient_cfg == ROTATION_DOWNWARD_FACING) {
|
||||
raw_yaw = raw_yaw * -1;
|
||||
}
|
||||
|
||||
// SF45/B product guide {Data output bit: 8 Description: "Yaw angle [1/100 deg] size: int16}"
|
||||
scaled_yaw = raw_yaw * SF45_SCALE_FACTOR;
|
||||
|
||||
switch (_yaw_cfg) {
|
||||
case 0:
|
||||
case ROTATION_FORWARD_FACING:
|
||||
break;
|
||||
|
||||
case 1:
|
||||
if (raw_yaw > 180) {
|
||||
raw_yaw = raw_yaw - 180;
|
||||
case ROTATION_BACKWARD_FACING:
|
||||
if (scaled_yaw > 180) {
|
||||
scaled_yaw = scaled_yaw - 180;
|
||||
|
||||
} else {
|
||||
raw_yaw = raw_yaw + 180; // rotation facing aft
|
||||
scaled_yaw = scaled_yaw + 180; // rotation facing aft
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case 2:
|
||||
raw_yaw = raw_yaw + 90; // rotation facing right
|
||||
case ROTATION_RIGHT_FACING:
|
||||
scaled_yaw = scaled_yaw + 90; // rotation facing right
|
||||
break;
|
||||
|
||||
case 3:
|
||||
raw_yaw = raw_yaw - 90; // rotation facing left
|
||||
case ROTATION_LEFT_FACING:
|
||||
scaled_yaw = scaled_yaw - 90; // rotation facing left
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
scaled_yaw = raw_yaw * SF45_SCALE_FACTOR;
|
||||
|
||||
// Convert to meters for rangefinder update
|
||||
// Convert to meters for the debug message
|
||||
*distance_m = raw_distance * SF45_SCALE_FACTOR;
|
||||
obstacle_dist_cm = (uint16_t)raw_distance;
|
||||
_current_bin_dist = ((uint16_t)raw_distance < _current_bin_dist) ? (uint16_t)raw_distance : _current_bin_dist;
|
||||
|
||||
uint8_t current_bin = sf45_convert_angle(scaled_yaw);
|
||||
|
||||
// If we have moved to a new bin
|
||||
|
||||
if (current_bin != _previous_bin) {
|
||||
PX4_DEBUG("scaled_yaw: \t %d, \t current_bin: \t %d, \t distance: \t %8.4f\n", scaled_yaw, current_bin,
|
||||
(double)*distance_m);
|
||||
|
||||
// update the current bin to the distance sensor reading
|
||||
// readings in cm
|
||||
_obstacle_map_msg.distances[current_bin] = obstacle_dist_cm;
|
||||
_obstacle_map_msg.timestamp = hrt_absolute_time();
|
||||
if (_current_bin_dist > _obstacle_distance.max_distance) {
|
||||
_current_bin_dist = _obstacle_distance.max_distance + 1; // As per ObstacleDistance.msg definition
|
||||
}
|
||||
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
_handle_missed_bins(current_bin, _previous_bin, _current_bin_dist, now);
|
||||
|
||||
_publish_obstacle_msg(now);
|
||||
|
||||
// reset the values for the next measurement
|
||||
_current_bin_dist = UINT16_MAX;
|
||||
_previous_bin = current_bin;
|
||||
}
|
||||
|
||||
_previous_bin = current_bin;
|
||||
|
||||
_obstacle_distance_pub.publish(_obstacle_map_msg);
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
@ -726,13 +671,67 @@ void SF45LaserSerial::sf45_process_replies(float *distance_m)
|
||||
break;
|
||||
}
|
||||
}
|
||||
void SF45LaserSerial::_publish_obstacle_msg(hrt_abstime now)
|
||||
{
|
||||
// This whole logic is in place because CollisionPrevention, just reads in the last published message on the topic, and not every message,
|
||||
// This can result in messages being misssed if the sensor is publishing at a faster rate than the CollisionPrevention module is reading.
|
||||
for (uint8_t i = 0; i < BIN_COUNT; i++) {
|
||||
if (now - _data_timestamps[i] > SF45_MEAS_TIMEOUT) {
|
||||
// If the data is older than SF45_MEAS_TIMEOUT, we discard the value (UINT16_MAX means no valid data)
|
||||
_obstacle_distance.distances[i] = UINT16_MAX;
|
||||
}
|
||||
}
|
||||
|
||||
_obstacle_distance.timestamp = now;
|
||||
_obstacle_distance_pub.publish(_obstacle_distance);
|
||||
}
|
||||
|
||||
void SF45LaserSerial::_handle_missed_bins(uint8_t current_bin, uint8_t previous_bin, uint16_t measurement,
|
||||
hrt_abstime now)
|
||||
{
|
||||
// if the sensor has its cycle delay configured for a low value like 5, it can happen that not every bin gets a measurement.
|
||||
// in this case we assume the measurement to be valid for all bins between the previous and the current bin.
|
||||
uint8_t start;
|
||||
uint8_t end;
|
||||
|
||||
if (abs(current_bin - previous_bin) > BIN_COUNT / 4) {
|
||||
// wrap-around case is assumed to have happend when the distance between the bins is larger than 1/4 of all Bins
|
||||
// THis is simplyfied as we are not considering the scaning direction
|
||||
start = math::max(previous_bin, current_bin);
|
||||
end = math::min(previous_bin, current_bin);
|
||||
|
||||
} else if (previous_bin < current_bin) { // Scanning clockwise
|
||||
start = previous_bin + 1;
|
||||
end = current_bin;
|
||||
|
||||
} else { // scanning counter-clockwise
|
||||
start = current_bin;
|
||||
end = previous_bin - 1;
|
||||
}
|
||||
|
||||
if (start <= end) {
|
||||
for (uint8_t i = start; i <= end; i++) {
|
||||
_obstacle_distance.distances[i] = measurement;
|
||||
_data_timestamps[i] = now;
|
||||
}
|
||||
|
||||
} else { // wrap-around case
|
||||
for (uint8_t i = start; i < BIN_COUNT; i++) {
|
||||
_obstacle_distance.distances[i] = measurement;
|
||||
_data_timestamps[i] = now;
|
||||
}
|
||||
|
||||
for (uint8_t i = 0; i <= end; i++) {
|
||||
_obstacle_distance.distances[i] = measurement;
|
||||
_data_timestamps[i] = now;
|
||||
}
|
||||
}
|
||||
}
|
||||
uint8_t SF45LaserSerial::sf45_convert_angle(const int16_t yaw)
|
||||
{
|
||||
|
||||
uint8_t mapped_sector = 0;
|
||||
float adjusted_yaw = sf45_wrap_360(yaw - _obstacle_map_msg.angle_offset);
|
||||
mapped_sector = round(adjusted_yaw / _obstacle_map_msg.increment);
|
||||
float adjusted_yaw = sf45_wrap_360(yaw - _obstacle_distance.angle_offset);
|
||||
mapped_sector = round(adjusted_yaw / _obstacle_distance.increment);
|
||||
|
||||
return mapped_sector;
|
||||
}
|
||||
|
||||
@ -50,72 +50,101 @@
|
||||
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/topics/obstacle_distance.h>
|
||||
#include <uORB/topics/distance_sensor.h>
|
||||
|
||||
#include "sf45_commands.h"
|
||||
|
||||
enum SF_SERIAL_STATE {
|
||||
STATE_UNINIT = 0,
|
||||
STATE_ACK_PRODUCT_NAME = 1,
|
||||
STATE_ACK_UPDATE_RATE = 2,
|
||||
STATE_ACK_DISTANCE_OUTPUT = 3,
|
||||
STATE_SEND_STREAM = 4,
|
||||
};
|
||||
|
||||
enum SF45_PARSED_STATE {
|
||||
START = 0,
|
||||
FLG_LOW,
|
||||
FLG_HIGH,
|
||||
ID,
|
||||
DATA,
|
||||
CRC_LOW,
|
||||
CRC_HIGH
|
||||
};
|
||||
|
||||
enum SensorOrientation { // Direction the sensor faces from MAV_SENSOR_ORIENTATION enum
|
||||
ROTATION_FORWARD_FACING = 0, // MAV_SENSOR_ROTATION_NONE
|
||||
ROTATION_RIGHT_FACING = 2, // MAV_SENSOR_ROTATION_YAW_90
|
||||
ROTATION_BACKWARD_FACING = 4, // MAV_SENSOR_ROTATION_YAW_180
|
||||
ROTATION_LEFT_FACING = 6, // MAV_SENSOR_ROTATION_YAW_270
|
||||
ROTATION_UPWARD_FACING = 24, // MAV_SENSOR_ROTATION_PITCH_90
|
||||
ROTATION_DOWNWARD_FACING = 25 // MAV_SENSOR_ROTATION_PITCH_270
|
||||
};
|
||||
|
||||
using namespace time_literals;
|
||||
class SF45LaserSerial : public px4::ScheduledWorkItem
|
||||
{
|
||||
public:
|
||||
SF45LaserSerial(const char *port, uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING);
|
||||
SF45LaserSerial(const char *port);
|
||||
~SF45LaserSerial() override;
|
||||
|
||||
int init();
|
||||
int init();
|
||||
void print_info();
|
||||
void sf45_request_handle(int val, uint8_t *value);
|
||||
void sf45_send(uint8_t msg_id, bool r_w, int *data, uint8_t data_len);
|
||||
uint16_t sf45_format_crc(uint16_t crc, uint8_t data_value);
|
||||
void sf45_process_replies(float *data);
|
||||
uint8_t sf45_convert_angle(const int16_t yaw);
|
||||
float sf45_wrap_360(float f);
|
||||
protected:
|
||||
obstacle_distance_s _obstacle_map_msg{};
|
||||
uORB::Publication<obstacle_distance_s> _obstacle_distance_pub{ORB_ID(obstacle_distance)}; /**< obstacle_distance publication */
|
||||
void sf45_get_and_handle_request(const int payload_length, const SF_SERIAL_CMD msg_id);
|
||||
void sf45_send(uint8_t msg_id, bool r_w, int32_t *data, uint8_t data_len);
|
||||
uint16_t sf45_format_crc(uint16_t crc, uint8_t data_value);
|
||||
void sf45_process_replies(float *data);
|
||||
uint8_t sf45_convert_angle(const int16_t yaw);
|
||||
float sf45_wrap_360(float f);
|
||||
|
||||
private:
|
||||
obstacle_distance_s _obstacle_distance{};
|
||||
uORB::Publication<obstacle_distance_s> _obstacle_distance_pub{ORB_ID(obstacle_distance)}; /**< obstacle_distance publication */
|
||||
static constexpr uint8_t BIN_COUNT = sizeof(obstacle_distance_s::distances) / sizeof(
|
||||
obstacle_distance_s::distances[0]);
|
||||
static constexpr uint64_t SF45_MEAS_TIMEOUT{100_ms};
|
||||
static constexpr float SF45_SCALE_FACTOR = 0.01f;
|
||||
|
||||
void start();
|
||||
void stop();
|
||||
void Run() override;
|
||||
int measure();
|
||||
int collect();
|
||||
bool _crc_valid{false};
|
||||
PX4Rangefinder _px4_rangefinder;
|
||||
bool _crc_valid{false};
|
||||
|
||||
void _handle_missed_bins(uint8_t current_bin, uint8_t previous_bin, uint16_t measurement, hrt_abstime now);
|
||||
void _publish_obstacle_msg(hrt_abstime now);
|
||||
uint64_t _data_timestamps[BIN_COUNT];
|
||||
|
||||
|
||||
char _port[20] {};
|
||||
int _interval{10000};
|
||||
int _interval{2000};
|
||||
bool _collect_phase{false};
|
||||
int _fd{-1};
|
||||
int _linebuf[256] {};
|
||||
unsigned _linebuf_index{0};
|
||||
hrt_abstime _last_read{0};
|
||||
uint8_t _linebuf[SF45_MAX_PAYLOAD] {};
|
||||
int _linebuf_size{0};
|
||||
|
||||
// SF45/B uses a binary protocol to include header,flags
|
||||
// message ID, payload, and checksum
|
||||
bool _is_sf45{false};
|
||||
bool _init_complete{false};
|
||||
bool _sensor_ready{false};
|
||||
uint8_t _sensor_state{0};
|
||||
int _baud_rate{0};
|
||||
int _product_name[16] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
int _stream_data{0};
|
||||
int32_t _update_rate{1};
|
||||
int _data_output{0};
|
||||
const uint8_t _start_of_frame{0xAA};
|
||||
uint16_t _data_bytes_recv{0};
|
||||
uint8_t _parsed_state{0};
|
||||
bool _sop_valid{false};
|
||||
uint16_t _calc_crc{0};
|
||||
uint8_t _num_retries{2};
|
||||
int32_t _yaw_cfg{0};
|
||||
int32_t _orient_cfg{0};
|
||||
int32_t _collision_constraint{0};
|
||||
uint16_t _previous_bin{0};
|
||||
bool _is_sf45{false};
|
||||
SF_SERIAL_STATE _sensor_state{STATE_UNINIT};
|
||||
int _baud_rate{0};
|
||||
int32_t _product_name[16] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
int32_t _stream_data{0};
|
||||
int32_t _update_rate{0};
|
||||
int32_t _data_output{0};
|
||||
const uint8_t _start_of_frame{0xAA};
|
||||
uint16_t _data_bytes_recv{0};
|
||||
uint8_t _parsed_state{0};
|
||||
bool _sop_valid{false};
|
||||
uint16_t _calc_crc{0};
|
||||
int32_t _yaw_cfg{0};
|
||||
int32_t _orient_cfg{0};
|
||||
uint8_t _previous_bin{0};
|
||||
uint16_t _current_bin_dist{UINT16_MAX};
|
||||
|
||||
// end of SF45/B data members
|
||||
|
||||
unsigned _consecutive_fail_count;
|
||||
|
||||
perf_counter_t _sample_perf;
|
||||
perf_counter_t _comms_errors;
|
||||
|
||||
hrt_abstime _last_received_time{0};
|
||||
perf_counter_t _sample_perf;
|
||||
perf_counter_t _comms_errors;
|
||||
};
|
||||
|
||||
@ -41,7 +41,7 @@ namespace lightware_sf45
|
||||
|
||||
SF45LaserSerial *g_dev{nullptr};
|
||||
|
||||
static int start(const char *port, uint8_t rotation)
|
||||
static int start(const char *port)
|
||||
{
|
||||
if (g_dev != nullptr) {
|
||||
PX4_WARN("already started");
|
||||
@ -54,7 +54,7 @@ static int start(const char *port, uint8_t rotation)
|
||||
}
|
||||
|
||||
/* create the driver */
|
||||
g_dev = new SF45LaserSerial(port, rotation);
|
||||
g_dev = new SF45LaserSerial(port);
|
||||
|
||||
if (g_dev == nullptr) {
|
||||
return -1;
|
||||
@ -102,7 +102,6 @@ static int usage()
|
||||
|
||||
Serial bus driver for the Lightware SF45/b Laser rangefinder.
|
||||
|
||||
Setup/usage information: https://docs.px4.io/master/en/sensor/sfxx_lidar.html
|
||||
|
||||
### Examples
|
||||
|
||||
@ -116,7 +115,6 @@ $ lightware_sf45_serial stop
|
||||
PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start driver");
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, nullptr, "Serial device", false);
|
||||
PRINT_MODULE_USAGE_PARAM_INT('R', 25, 0, 25, "Sensor rotation - downward facing by default", false);
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop driver");
|
||||
return PX4_OK;
|
||||
}
|
||||
@ -125,18 +123,13 @@ $ lightware_sf45_serial stop
|
||||
|
||||
extern "C" __EXPORT int lightware_sf45_serial_main(int argc, char *argv[])
|
||||
{
|
||||
uint8_t rotation = distance_sensor_s::ROTATION_FORWARD_FACING;
|
||||
const char *device_path = nullptr;
|
||||
int ch;
|
||||
int myoptind = 1;
|
||||
const char *myoptarg = nullptr;
|
||||
|
||||
while ((ch = px4_getopt(argc, argv, "R:d:", &myoptind, &myoptarg)) != EOF) {
|
||||
while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) {
|
||||
switch (ch) {
|
||||
case 'R':
|
||||
rotation = (uint8_t)atoi(myoptarg);
|
||||
break;
|
||||
|
||||
case 'd':
|
||||
device_path = myoptarg;
|
||||
break;
|
||||
@ -153,7 +146,7 @@ extern "C" __EXPORT int lightware_sf45_serial_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
if (!strcmp(argv[myoptind], "start")) {
|
||||
return lightware_sf45::start(device_path, rotation);
|
||||
return lightware_sf45::start(device_path);
|
||||
|
||||
} else if (!strcmp(argv[myoptind], "stop")) {
|
||||
return lightware_sf45::stop();
|
||||
|
||||
@ -1,10 +1,9 @@
|
||||
module_name: Lightware SF45 Rangefinder (serial)
|
||||
serial_config:
|
||||
- command: lightware_sf45_serial start -R 0 -d ${SERIAL_DEV}
|
||||
- command: lightware_sf45_serial start -d ${SERIAL_DEV}
|
||||
port_config_param:
|
||||
name: SENS_EN_SF45_CFG
|
||||
group: Sensors
|
||||
default: TEL2
|
||||
num_instances: 1
|
||||
supports_networking: false
|
||||
|
||||
@ -32,7 +31,7 @@ parameters:
|
||||
12: 5000hz
|
||||
reboot_required: true
|
||||
num_instances: 1
|
||||
default: 1
|
||||
default: 5
|
||||
|
||||
SF45_ORIENT_CFG:
|
||||
description:
|
||||
@ -41,11 +40,11 @@ parameters:
|
||||
The SF45 mounted facing upward or downward on the frame
|
||||
type: enum
|
||||
values:
|
||||
0: Rotation upward
|
||||
1: Rotation downward
|
||||
24: Rotation upward
|
||||
25: Rotation downward
|
||||
reboot_required: true
|
||||
num_instances: 1
|
||||
default: 0
|
||||
default: 24
|
||||
|
||||
SF45_YAW_CFG:
|
||||
description:
|
||||
@ -55,9 +54,9 @@ parameters:
|
||||
type: enum
|
||||
values:
|
||||
0: Rotation forward
|
||||
1: Rotation backward
|
||||
2: Rotation right
|
||||
3: Rotation left
|
||||
4: Rotation backward
|
||||
6: Rotation left
|
||||
reboot_required: true
|
||||
num_instances: 1
|
||||
default: 0
|
||||
|
||||
@ -239,6 +239,8 @@
|
||||
#define DRV_INS_DEVTYPE_VN300 0xE3
|
||||
#define DRV_DIFF_PRESS_DEVTYPE_ASP5033 0xE4
|
||||
|
||||
#define DRV_BARO_DEVTYPE_SPA06 0xE8
|
||||
|
||||
#define DRV_DEVTYPE_UNUSED 0xff
|
||||
|
||||
#endif /* _DRV_SENSOR_H */
|
||||
#endif /* _DRV_SENSOR_H */
|
||||
@ -1 +1 @@
|
||||
Subproject commit 17c0e2bfad1e544c4b11329c742630a765c7537f
|
||||
Subproject commit ad769ff53d683d06937c92bae58377d65893967b
|
||||
@ -215,9 +215,6 @@ void FixedwingAttitudeControl::Run()
|
||||
_last_run = time_now_us;
|
||||
}
|
||||
|
||||
vehicle_angular_velocity_s angular_velocity{};
|
||||
_vehicle_rates_sub.copy(&angular_velocity);
|
||||
|
||||
if (_vehicle_status.is_vtol_tailsitter) {
|
||||
/* vehicle is a tailsitter, we need to modify the estimated attitude for fw mode
|
||||
*
|
||||
@ -389,10 +386,13 @@ void FixedwingAttitudeControl::Run()
|
||||
wheel_u = _manual_control_setpoint.yaw;
|
||||
|
||||
} else {
|
||||
vehicle_angular_velocity_s angular_velocity{};
|
||||
_vehicle_rates_sub.copy(&angular_velocity);
|
||||
|
||||
// XXX: yaw_sp_move_rate here is an abuse -- used to ferry manual yaw inputs from
|
||||
// position controller during auto modes _manual_control_setpoint.r gets passed
|
||||
// whenever nudging is enabled, otherwise zero
|
||||
const float wheel_controller_output = _wheel_ctrl.control_bodyrate(dt, euler_angles.psi(), _groundspeed,
|
||||
const float wheel_controller_output = _wheel_ctrl.control_bodyrate(dt, angular_velocity.xyz[2], _groundspeed,
|
||||
groundspeed_scale);
|
||||
wheel_u = wheel_control ? wheel_controller_output + _att_sp.yaw_sp_move_rate : 0.f;
|
||||
}
|
||||
|
||||
@ -376,7 +376,9 @@ void LoggedTopics::add_sensor_comparison_topics()
|
||||
void LoggedTopics::add_vision_and_avoidance_topics()
|
||||
{
|
||||
add_topic("collision_constraints");
|
||||
add_topic_multi("distance_sensor");
|
||||
add_topic("obstacle_distance_fused");
|
||||
add_topic("obstacle_distance");
|
||||
add_topic("vehicle_mocap_odometry", 30);
|
||||
add_topic("vehicle_trajectory_waypoint", 200);
|
||||
add_topic("vehicle_trajectory_waypoint_desired", 200);
|
||||
|
||||
@ -271,6 +271,19 @@ void ManualControl::processSwitches(hrt_abstime &now)
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(PAYLOAD_POWER_EN)
|
||||
|
||||
if (switches.payload_power_switch != _previous_switches.payload_power_switch) {
|
||||
if (switches.payload_power_switch == manual_control_switches_s::SWITCH_POS_ON) {
|
||||
PAYLOAD_POWER_EN(true);
|
||||
|
||||
} else if (switches.payload_power_switch == manual_control_switches_s::SWITCH_POS_OFF) {
|
||||
PAYLOAD_POWER_EN(false);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // PAYLOAD_POWER_EN
|
||||
|
||||
} else if (!_armed) {
|
||||
// Directly initialize mode using RC switch but only before arming
|
||||
evaluateModeSlot(switches.mode_slot);
|
||||
|
||||
@ -1762,6 +1762,35 @@ PARAM_DEFINE_INT32(RC_MAP_AUX5, 0);
|
||||
* @value 18 Channel 18
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_AUX6, 0);
|
||||
|
||||
/**
|
||||
* Payload Power Switch RC channel
|
||||
*
|
||||
* @min 0
|
||||
* @max 18
|
||||
* @group Radio Switches
|
||||
* @value 0 Unassigned
|
||||
* @value 1 Channel 1
|
||||
* @value 2 Channel 2
|
||||
* @value 3 Channel 3
|
||||
* @value 4 Channel 4
|
||||
* @value 5 Channel 5
|
||||
* @value 6 Channel 6
|
||||
* @value 7 Channel 7
|
||||
* @value 8 Channel 8
|
||||
* @value 9 Channel 9
|
||||
* @value 10 Channel 10
|
||||
* @value 11 Channel 11
|
||||
* @value 12 Channel 12
|
||||
* @value 13 Channel 13
|
||||
* @value 14 Channel 14
|
||||
* @value 15 Channel 15
|
||||
* @value 16 Channel 16
|
||||
* @value 17 Channel 17
|
||||
* @value 18 Channel 18
|
||||
*/
|
||||
PARAM_DEFINE_INT32(RC_MAP_PAY_SW, 0);
|
||||
|
||||
/**
|
||||
* PARAM1 tuning channel
|
||||
*
|
||||
@ -2029,6 +2058,22 @@ PARAM_DEFINE_FLOAT(RC_GEAR_TH, 0.75f);
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_ENG_MOT_TH, 0.75f);
|
||||
|
||||
/**
|
||||
* Threshold for selecting payload power switch
|
||||
*
|
||||
* 0-1 indicate where in the full channel range the threshold sits
|
||||
* 0 : min
|
||||
* 1 : max
|
||||
* sign indicates polarity of comparison
|
||||
* positive : true when channel>th
|
||||
* negative : true when channel<th
|
||||
*
|
||||
* @min -1
|
||||
* @max 1
|
||||
* @group Radio Switches
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RC_PAYLOAD_TH, 0.75f);
|
||||
|
||||
/**
|
||||
* PWM input channel that provides RSSI.
|
||||
*
|
||||
|
||||
@ -57,6 +57,7 @@ static bool operator ==(const manual_control_switches_s &a, const manual_control
|
||||
a.gear_switch == b.gear_switch &&
|
||||
a.photo_switch == b.photo_switch &&
|
||||
a.video_switch == b.video_switch &&
|
||||
a.payload_power_switch == b.payload_power_switch &&
|
||||
a.engage_main_motor_switch == b.engage_main_motor_switch);
|
||||
}
|
||||
|
||||
@ -254,6 +255,8 @@ void RCUpdate::update_rc_functions()
|
||||
_rc.function[rc_channels_s::FUNCTION_AUX_5] = _param_rc_map_aux5.get() - 1;
|
||||
_rc.function[rc_channels_s::FUNCTION_AUX_6] = _param_rc_map_aux6.get() - 1;
|
||||
|
||||
_rc.function[rc_channels_s::FUNCTION_PAYLOAD_POWER] = _param_rc_map_payload_sw.get() - 1;
|
||||
|
||||
for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
|
||||
_rc.function[rc_channels_s::FUNCTION_PARAM_1 + i] = _parameters.rc_map_param[i] - 1;
|
||||
}
|
||||
@ -651,6 +654,11 @@ void RCUpdate::UpdateManualSwitches(const hrt_abstime ×tamp_sample)
|
||||
switches.video_switch = getRCSwitchOnOffPosition(rc_channels_s::FUNCTION_AUX_4, 0.5f);
|
||||
#endif
|
||||
|
||||
#if defined(PAYLOAD_POWER_EN)
|
||||
switches.payload_power_switch = getRCSwitchOnOffPosition(rc_channels_s::FUNCTION_PAYLOAD_POWER,
|
||||
_param_rc_payload_th.get());
|
||||
#endif
|
||||
|
||||
// last 2 switch updates identical within 1 second (simple protection from bad RC data)
|
||||
if ((switches == _manual_switches_previous)
|
||||
&& (switches.timestamp_sample < _manual_switches_previous.timestamp_sample + VALID_DATA_MIN_INTERVAL_US)) {
|
||||
|
||||
@ -230,6 +230,8 @@ protected:
|
||||
|
||||
(ParamInt<px4::params::RC_FAILS_THR>) _param_rc_fails_thr,
|
||||
|
||||
(ParamInt<px4::params::RC_MAP_PAY_SW>) _param_rc_map_payload_sw,
|
||||
|
||||
(ParamFloat<px4::params::RC_LOITER_TH>) _param_rc_loiter_th,
|
||||
(ParamFloat<px4::params::RC_OFFB_TH>) _param_rc_offb_th,
|
||||
(ParamFloat<px4::params::RC_KILLSWITCH_TH>) _param_rc_killswitch_th,
|
||||
@ -238,6 +240,7 @@ protected:
|
||||
(ParamFloat<px4::params::RC_GEAR_TH>) _param_rc_gear_th,
|
||||
(ParamFloat<px4::params::RC_RETURN_TH>) _param_rc_return_th,
|
||||
(ParamFloat<px4::params::RC_ENG_MOT_TH>) _param_rc_eng_mot_th,
|
||||
(ParamFloat<px4::params::RC_PAYLOAD_TH>) _param_rc_payload_th,
|
||||
|
||||
(ParamInt<px4::params::RC_CHAN_CNT>) _param_rc_chan_cnt
|
||||
)
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user