Daniel Agar
6 years ago
committed by
GitHub
3 changed files with 455 additions and 0 deletions
@ -0,0 +1,129 @@ |
|||||||
|
|
||||||
|
px4_add_board( |
||||||
|
PLATFORM nuttx |
||||||
|
VENDOR px4 |
||||||
|
MODEL fmu-v5 |
||||||
|
LABEL irqmonitor |
||||||
|
TOOLCHAIN arm-none-eabi |
||||||
|
ARCHITECTURE cortex-m7 |
||||||
|
ROMFSROOT px4fmu_common |
||||||
|
IO px4_io-v2_default |
||||||
|
TESTING |
||||||
|
UAVCAN_INTERFACES 2 |
||||||
|
|
||||||
|
SERIAL_PORTS |
||||||
|
GPS1:/dev/ttyS0 |
||||||
|
TEL1:/dev/ttyS1 |
||||||
|
TEL2:/dev/ttyS2 |
||||||
|
TEL4:/dev/ttyS3 |
||||||
|
|
||||||
|
DRIVERS |
||||||
|
barometer # all available barometer drivers |
||||||
|
batt_smbus |
||||||
|
camera_capture |
||||||
|
camera_trigger |
||||||
|
differential_pressure # all available differential pressure drivers |
||||||
|
distance_sensor # all available distance sensor drivers |
||||||
|
gps |
||||||
|
#heater |
||||||
|
imu/adis16448 |
||||||
|
imu/adis16497 |
||||||
|
#imu # all available imu drivers |
||||||
|
imu/bmi055 |
||||||
|
imu/mpu6000 |
||||||
|
imu/mpu9250 |
||||||
|
irlock |
||||||
|
lights/blinkm |
||||||
|
lights/oreoled |
||||||
|
lights/pca8574 |
||||||
|
lights/rgbled |
||||||
|
lights/rgbled_ncp5623c |
||||||
|
lights/rgbled_pwm |
||||||
|
magnetometer # all available magnetometer drivers |
||||||
|
#md25 |
||||||
|
mkblctrl |
||||||
|
optical_flow # all available optical flow drivers |
||||||
|
pca9685 |
||||||
|
power_monitor/ina226 |
||||||
|
#protocol_splitter |
||||||
|
pwm_input |
||||||
|
pwm_out_sim |
||||||
|
px4fmu |
||||||
|
px4io |
||||||
|
rc_input |
||||||
|
roboclaw |
||||||
|
stm32 |
||||||
|
stm32/adc |
||||||
|
stm32/tone_alarm |
||||||
|
tap_esc |
||||||
|
telemetry # all available telemetry drivers |
||||||
|
test_ppm |
||||||
|
tone_alarm |
||||||
|
uavcan |
||||||
|
|
||||||
|
MODULES |
||||||
|
attitude_estimator_q |
||||||
|
camera_feedback |
||||||
|
commander |
||||||
|
dataman |
||||||
|
ekf2 |
||||||
|
events |
||||||
|
fw_att_control |
||||||
|
fw_pos_control_l1 |
||||||
|
rover_pos_control |
||||||
|
land_detector |
||||||
|
landing_target_estimator |
||||||
|
load_mon |
||||||
|
local_position_estimator |
||||||
|
logger |
||||||
|
mavlink |
||||||
|
mc_att_control |
||||||
|
mc_pos_control |
||||||
|
navigator |
||||||
|
sensors |
||||||
|
sih |
||||||
|
vmount |
||||||
|
vtol_att_control |
||||||
|
airspeed_selector |
||||||
|
|
||||||
|
SYSTEMCMDS |
||||||
|
bl_update |
||||||
|
config |
||||||
|
dmesg |
||||||
|
dumpfile |
||||||
|
esc_calib |
||||||
|
hardfault_log |
||||||
|
i2cdetect |
||||||
|
led_control |
||||||
|
mixer |
||||||
|
motor_ramp |
||||||
|
motor_test |
||||||
|
mtd |
||||||
|
nshterm |
||||||
|
param |
||||||
|
perf |
||||||
|
pwm |
||||||
|
reboot |
||||||
|
reflect |
||||||
|
sd_bench |
||||||
|
shutdown |
||||||
|
tests # tests and test runner |
||||||
|
top |
||||||
|
topic_listener |
||||||
|
tune_control |
||||||
|
usb_connected |
||||||
|
ver |
||||||
|
|
||||||
|
EXAMPLES |
||||||
|
bottle_drop # OBC challenge |
||||||
|
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control |
||||||
|
hello |
||||||
|
hwtest # Hardware test |
||||||
|
#matlab_csv_serial |
||||||
|
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html |
||||||
|
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html |
||||||
|
rover_steering_control # Rover example app |
||||||
|
segway |
||||||
|
uuv_example_app |
||||||
|
|
||||||
|
) |
@ -0,0 +1,253 @@ |
|||||||
|
# |
||||||
|
# This file is autogenerated: PLEASE DO NOT EDIT IT. |
||||||
|
# |
||||||
|
# You can use "make menuconfig" to make any modifications to the installed .config file. |
||||||
|
# You can then do "make savedefconfig" to generate a new defconfig file that includes your |
||||||
|
# modifications. |
||||||
|
# |
||||||
|
# CONFIG_DISABLE_OS_API is not set |
||||||
|
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set |
||||||
|
# CONFIG_MMCSD_HAVE_CARDDETECT is not set |
||||||
|
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set |
||||||
|
# CONFIG_MMCSD_MMCSUPPORT is not set |
||||||
|
# CONFIG_MMCSD_SPI is not set |
||||||
|
# CONFIG_NSH_DISABLEBG is not set |
||||||
|
# CONFIG_NSH_DISABLESCRIPT is not set |
||||||
|
# CONFIG_NSH_DISABLE_DF is not set |
||||||
|
# CONFIG_NSH_DISABLE_EXEC is not set |
||||||
|
# CONFIG_NSH_DISABLE_EXIT is not set |
||||||
|
# CONFIG_NSH_DISABLE_GET is not set |
||||||
|
# CONFIG_NSH_DISABLE_ITEF is not set |
||||||
|
# CONFIG_NSH_DISABLE_LOOPS is not set |
||||||
|
# CONFIG_NSH_DISABLE_SEMICOLON is not set |
||||||
|
# CONFIG_NSH_DISABLE_TIME is not set |
||||||
|
CONFIG_ARCH="arm" |
||||||
|
CONFIG_ARCH_BOARD_CUSTOM_DIR="../nuttx-config" |
||||||
|
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" |
||||||
|
CONFIG_ARCH_CHIP_STM32F765II=y |
||||||
|
CONFIG_ARCH_CHIP_STM32F7=y |
||||||
|
CONFIG_ARCH_INTERRUPTSTACK=512 |
||||||
|
CONFIG_ARCH_MATH_H=y |
||||||
|
CONFIG_ARCH_STACKDUMP=y |
||||||
|
CONFIG_ARMV7M_BASEPRI_WAR=y |
||||||
|
CONFIG_ARMV7M_DCACHE=y |
||||||
|
CONFIG_ARMV7M_DTCM=y |
||||||
|
CONFIG_ARMV7M_ICACHE=y |
||||||
|
CONFIG_ARMV7M_MEMCPY=y |
||||||
|
CONFIG_ARMV7M_USEBASEPRI=y |
||||||
|
CONFIG_BOARDCTL_RESET=y |
||||||
|
CONFIG_BOARD_CRASHDUMP=y |
||||||
|
CONFIG_BOARD_LOOPSPERMSEC=22114 |
||||||
|
CONFIG_BOARD_RESET_ON_ASSERT=2 |
||||||
|
CONFIG_BUILTIN=y |
||||||
|
CONFIG_C99_BOOL8=y |
||||||
|
CONFIG_CDCACM=y |
||||||
|
CONFIG_CDCACM_PRODUCTID=0x0032 |
||||||
|
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v5.x" |
||||||
|
CONFIG_CDCACM_RXBUFSIZE=600 |
||||||
|
CONFIG_CDCACM_TXBUFSIZE=12000 |
||||||
|
CONFIG_CDCACM_VENDORID=0x26ac |
||||||
|
CONFIG_CDCACM_VENDORSTR="3D Robotics" |
||||||
|
CONFIG_CLOCK_MONOTONIC=y |
||||||
|
CONFIG_DEBUG_FULLOPT=y |
||||||
|
CONFIG_DEBUG_HARDFAULT_ALERT=y |
||||||
|
CONFIG_DEBUG_SYMBOLS=y |
||||||
|
CONFIG_DEFAULT_SMALL=y |
||||||
|
CONFIG_DEV_FIFO_SIZE=0 |
||||||
|
CONFIG_DEV_PIPE_MAXSIZE=1024 |
||||||
|
CONFIG_DEV_PIPE_SIZE=70 |
||||||
|
CONFIG_FAT_DMAMEMORY=y |
||||||
|
CONFIG_FAT_LCNAMES=y |
||||||
|
CONFIG_FAT_LFN=y |
||||||
|
CONFIG_FAT_LFN_ALIAS_HASH=y |
||||||
|
CONFIG_FDCLONE_STDIO=y |
||||||
|
CONFIG_FS_BINFS=y |
||||||
|
CONFIG_FS_CROMFS=y |
||||||
|
CONFIG_FS_FAT=y |
||||||
|
CONFIG_FS_FATTIME=y |
||||||
|
CONFIG_FS_PROCFS=y |
||||||
|
CONFIG_FS_PROCFS_EXCLUDE_BLOCKS=y |
||||||
|
CONFIG_FS_PROCFS_EXCLUDE_MOUNT=y |
||||||
|
CONFIG_FS_PROCFS_EXCLUDE_MOUNTS=y |
||||||
|
CONFIG_FS_PROCFS_EXCLUDE_PARTITIONS=y |
||||||
|
CONFIG_FS_PROCFS_EXCLUDE_USAGE=y |
||||||
|
CONFIG_FS_PROCFS_REGISTER=y |
||||||
|
CONFIG_FS_ROMFS=y |
||||||
|
CONFIG_GRAN=y |
||||||
|
CONFIG_GRAN_INTR=y |
||||||
|
CONFIG_HAVE_CXX=y |
||||||
|
CONFIG_HAVE_CXXINITIALIZE=y |
||||||
|
CONFIG_I2C=y |
||||||
|
CONFIG_I2C_RESET=y |
||||||
|
CONFIG_IDLETHREAD_STACKSIZE=750 |
||||||
|
CONFIG_LIBC_FLOATINGPOINT=y |
||||||
|
CONFIG_LIBC_LONG_LONG=y |
||||||
|
CONFIG_LIBC_STRERROR=y |
||||||
|
CONFIG_MAX_TASKS=64 |
||||||
|
CONFIG_MAX_WDOGPARMS=2 |
||||||
|
CONFIG_MEMSET_64BIT=y |
||||||
|
CONFIG_MEMSET_OPTSPEED=y |
||||||
|
CONFIG_MMCSD=y |
||||||
|
CONFIG_MMCSD_MULTIBLOCK_DISABLE=y |
||||||
|
CONFIG_MMCSD_SDIO=y |
||||||
|
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y |
||||||
|
CONFIG_MM_REGIONS=3 |
||||||
|
CONFIG_MTD=y |
||||||
|
CONFIG_MTD_BYTE_WRITE=y |
||||||
|
CONFIG_MTD_PARTITION=y |
||||||
|
CONFIG_MTD_RAMTRON=y |
||||||
|
CONFIG_NFILE_DESCRIPTORS=20 |
||||||
|
CONFIG_NFILE_STREAMS=8 |
||||||
|
CONFIG_NSH_ARCHINIT=y |
||||||
|
CONFIG_NSH_ARCHROMFS=y |
||||||
|
CONFIG_NSH_ARGCAT=y |
||||||
|
CONFIG_NSH_BUILTIN_APPS=y |
||||||
|
CONFIG_NSH_CMDPARMS=y |
||||||
|
CONFIG_NSH_CROMFSETC=y |
||||||
|
CONFIG_NSH_DISABLE_IFCONFIG=y |
||||||
|
CONFIG_NSH_DISABLE_IFUPDOWN=y |
||||||
|
CONFIG_NSH_DISABLE_MB=y |
||||||
|
CONFIG_NSH_DISABLE_MH=y |
||||||
|
CONFIG_NSH_DISABLE_TELNETD=y |
||||||
|
CONFIG_NSH_LINELEN=128 |
||||||
|
CONFIG_NSH_MAXARGUMENTS=12 |
||||||
|
CONFIG_NSH_NESTDEPTH=8 |
||||||
|
CONFIG_NSH_QUOTE=y |
||||||
|
CONFIG_NSH_ROMFSETC=y |
||||||
|
CONFIG_NSH_ROMFSSECTSIZE=128 |
||||||
|
CONFIG_NSH_STRERROR=y |
||||||
|
CONFIG_NSH_VARS=y |
||||||
|
CONFIG_NXFONTS_DISABLE_16BPP=y |
||||||
|
CONFIG_NXFONTS_DISABLE_1BPP=y |
||||||
|
CONFIG_NXFONTS_DISABLE_24BPP=y |
||||||
|
CONFIG_NXFONTS_DISABLE_2BPP=y |
||||||
|
CONFIG_NXFONTS_DISABLE_32BPP=y |
||||||
|
CONFIG_NXFONTS_DISABLE_4BPP=y |
||||||
|
CONFIG_NXFONTS_DISABLE_8BPP=y |
||||||
|
CONFIG_PIPES=y |
||||||
|
CONFIG_PREALLOC_MQ_MSGS=4 |
||||||
|
CONFIG_PREALLOC_TIMERS=50 |
||||||
|
CONFIG_PREALLOC_WDOGS=50 |
||||||
|
CONFIG_PRIORITY_INHERITANCE=y |
||||||
|
CONFIG_PTHREAD_MUTEX_ROBUST=y |
||||||
|
CONFIG_PTHREAD_STACK_MIN=512 |
||||||
|
CONFIG_RAMTRON_SETSPEED=y |
||||||
|
CONFIG_RAMTRON_WRITEWAIT=y |
||||||
|
CONFIG_RAM_SIZE=245760 |
||||||
|
CONFIG_RAM_START=0x20010000 |
||||||
|
CONFIG_RAW_BINARY=y |
||||||
|
CONFIG_RTC_DATETIME=y |
||||||
|
CONFIG_SCHED_ATEXIT=y |
||||||
|
CONFIG_SCHED_HPWORK=y |
||||||
|
CONFIG_SCHED_HPWORKPRIORITY=249 |
||||||
|
CONFIG_SCHED_HPWORKSTACKSIZE=1280 |
||||||
|
CONFIG_SCHED_INSTRUMENTATION=y |
||||||
|
CONFIG_SCHED_IRQMONITOR=y |
||||||
|
CONFIG_SCHED_LPWORK=y |
||||||
|
CONFIG_SCHED_LPWORKPRIORITY=50 |
||||||
|
CONFIG_SCHED_LPWORKSTACKSIZE=1536 |
||||||
|
CONFIG_SCHED_WAITPID=y |
||||||
|
CONFIG_SDCLONE_DISABLE=y |
||||||
|
CONFIG_SDMMC1_SDIO_MODE=y |
||||||
|
CONFIG_SEM_NNESTPRIO=8 |
||||||
|
CONFIG_SEM_PREALLOCHOLDERS=0 |
||||||
|
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y |
||||||
|
CONFIG_SERIAL_TERMIOS=y |
||||||
|
CONFIG_SIG_DEFAULT=y |
||||||
|
CONFIG_SIG_SIGALRM_ACTION=y |
||||||
|
CONFIG_SIG_SIGUSR1_ACTION=y |
||||||
|
CONFIG_SIG_SIGUSR2_ACTION=y |
||||||
|
CONFIG_SIG_SIGWORK=4 |
||||||
|
CONFIG_STACK_COLORATION=y |
||||||
|
CONFIG_START_DAY=30 |
||||||
|
CONFIG_START_MONTH=11 |
||||||
|
CONFIG_STDIO_BUFFER_SIZE=32 |
||||||
|
CONFIG_STM32F7_ADC1=y |
||||||
|
CONFIG_STM32F7_BBSRAM=y |
||||||
|
CONFIG_STM32F7_BBSRAM_FILES=5 |
||||||
|
CONFIG_STM32F7_BKPSRAM=y |
||||||
|
CONFIG_STM32F7_DMA1=y |
||||||
|
CONFIG_STM32F7_DMA2=y |
||||||
|
CONFIG_STM32F7_DMACAPABLE=y |
||||||
|
CONFIG_STM32F7_FLOWCONTROL_BROKEN=y |
||||||
|
CONFIG_STM32F7_I2C1=y |
||||||
|
CONFIG_STM32F7_I2C2=y |
||||||
|
CONFIG_STM32F7_I2C3=y |
||||||
|
CONFIG_STM32F7_I2C4=y |
||||||
|
CONFIG_STM32F7_I2C_DYNTIMEO=y |
||||||
|
CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10 |
||||||
|
CONFIG_STM32F7_OTGFS=y |
||||||
|
CONFIG_STM32F7_PWR=y |
||||||
|
CONFIG_STM32F7_RTC=y |
||||||
|
CONFIG_STM32F7_RTC_HSECLOCK=y |
||||||
|
CONFIG_STM32F7_RTC_MAGIC_REG=1 |
||||||
|
CONFIG_STM32F7_SAVE_CRASHDUMP=y |
||||||
|
CONFIG_STM32F7_SDMMC1=y |
||||||
|
CONFIG_STM32F7_SDMMC_DMA=y |
||||||
|
CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y |
||||||
|
CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y |
||||||
|
CONFIG_STM32F7_SPI1=y |
||||||
|
CONFIG_STM32F7_SPI2=y |
||||||
|
CONFIG_STM32F7_SPI4=y |
||||||
|
CONFIG_STM32F7_SPI5=y |
||||||
|
CONFIG_STM32F7_SPI6=y |
||||||
|
CONFIG_STM32F7_TIM10=y |
||||||
|
CONFIG_STM32F7_TIM11=y |
||||||
|
CONFIG_STM32F7_TIM1=y |
||||||
|
CONFIG_STM32F7_TIM3=y |
||||||
|
CONFIG_STM32F7_TIM4=y |
||||||
|
CONFIG_STM32F7_TIM9=y |
||||||
|
CONFIG_STM32F7_UART4=y |
||||||
|
CONFIG_STM32F7_UART7=y |
||||||
|
CONFIG_STM32F7_UART8=y |
||||||
|
CONFIG_STM32F7_USART1=y |
||||||
|
CONFIG_STM32F7_USART2=y |
||||||
|
CONFIG_STM32F7_USART3=y |
||||||
|
CONFIG_STM32F7_USART6=y |
||||||
|
CONFIG_STM32F7_USART_BREAKS=y |
||||||
|
CONFIG_STM32F7_USART_INVERT=y |
||||||
|
CONFIG_STM32F7_USART_SINGLEWIRE=y |
||||||
|
CONFIG_STM32F7_USART_SWAP=y |
||||||
|
CONFIG_STM32F7_WWDG=y |
||||||
|
CONFIG_SYSTEM_CDCACM=y |
||||||
|
CONFIG_SYSTEM_NSH=y |
||||||
|
CONFIG_TASK_NAME_SIZE=24 |
||||||
|
CONFIG_TIME_EXTENDED=y |
||||||
|
CONFIG_UART4_BAUD=57600 |
||||||
|
CONFIG_UART4_RXBUFSIZE=600 |
||||||
|
CONFIG_UART4_RXDMA=y |
||||||
|
CONFIG_UART4_TXBUFSIZE=1500 |
||||||
|
CONFIG_UART7_BAUD=57600 |
||||||
|
CONFIG_UART7_RXBUFSIZE=600 |
||||||
|
CONFIG_UART7_SERIAL_CONSOLE=y |
||||||
|
CONFIG_UART7_TXBUFSIZE=1500 |
||||||
|
CONFIG_UART8_BAUD=57600 |
||||||
|
CONFIG_UART8_RXBUFSIZE=600 |
||||||
|
CONFIG_UART8_RXDMA=y |
||||||
|
CONFIG_UART8_TXBUFSIZE=1500 |
||||||
|
CONFIG_USART1_BAUD=57600 |
||||||
|
CONFIG_USART1_RXBUFSIZE=600 |
||||||
|
CONFIG_USART1_RXDMA=y |
||||||
|
CONFIG_USART1_TXBUFSIZE=1500 |
||||||
|
CONFIG_USART2_BAUD=57600 |
||||||
|
CONFIG_USART2_IFLOWCONTROL=y |
||||||
|
CONFIG_USART2_OFLOWCONTROL=y |
||||||
|
CONFIG_USART2_RXBUFSIZE=600 |
||||||
|
CONFIG_USART2_RXDMA=y |
||||||
|
CONFIG_USART2_TXBUFSIZE=1500 |
||||||
|
CONFIG_USART3_BAUD=57600 |
||||||
|
CONFIG_USART3_IFLOWCONTROL=y |
||||||
|
CONFIG_USART3_OFLOWCONTROL=y |
||||||
|
CONFIG_USART3_RXBUFSIZE=600 |
||||||
|
CONFIG_USART3_RXDMA=y |
||||||
|
CONFIG_USART3_TXBUFSIZE=3000 |
||||||
|
CONFIG_USART6_BAUD=57600 |
||||||
|
CONFIG_USART6_RXBUFSIZE=600 |
||||||
|
CONFIG_USART6_RXDMA=y |
||||||
|
CONFIG_USART6_TXBUFSIZE=1500 |
||||||
|
CONFIG_USBDEV=y |
||||||
|
CONFIG_USBDEV_BUSPOWERED=y |
||||||
|
CONFIG_USBDEV_MAXPOWER=500 |
||||||
|
CONFIG_USEC_PER_TICK=1000 |
||||||
|
CONFIG_USERMAIN_STACKSIZE=2624 |
||||||
|
CONFIG_USER_ENTRYPOINT="nsh_main" |
Loading…
Reference in new issue