Compare commits

...

14 Commits

Author SHA1 Message Date
JacobCrabill 8e01fe661a fixup! Update submodule nuttx 2022-03-18 10:56:44 -07:00
JacobCrabill 64863fe54e uavcan_v1: Add Publishers dir to includes 2022-03-18 09:03:48 -07:00
JacobCrabill 73b1de85cb uavcan_v1: SocketCAN set 'can_fd' based on CONFIG 2022-03-18 09:03:06 -07:00
JacobCrabill fd3662097f fixup! Update submodule nuttx 2022-03-18 09:02:00 -07:00
JacobCrabill 76da12fce3 uavcan_v1: Immediate transmit() from Publishers
Add 'do_transmit()' to UavcanNode
Add 'transmit()' to Publisher base class to call do_transmit()
Call transmit() after canardTxPush from Publishers
2022-03-17 17:01:54 -07:00
JacobCrabill 9531900afa mro/ctrl-zero-h7-oem: Start adding socketcan support 2022-03-16 10:21:10 -07:00
JacobCrabill 25271a3f04 fixup! Update submodule nuttx 2022-03-16 10:20:29 -07:00
JacobCrabill 4048ac57bf fixup! Update submodule nuttx 2022-03-15 18:53:13 -07:00
JacobCrabill 399ab35a4f fixup! HACK: Disable SO_TIMESTAMP in uavcan_v1 temporarily while bringing up H7 SocketCAN driver 2022-03-15 18:52:00 -07:00
JacobCrabill f4f8eee02d cubeorange: Add TX_DEADLINE support 2022-03-15 18:24:03 -07:00
JacobCrabill dec15b4fa9 Update submodule nuttx 2022-03-15 18:23:22 -07:00
JacobCrabill 7db8d3ad78 HACK: Disable SO_TIMESTAMP in uavcan_v1 temporarily while bringing up H7 SocketCAN driver 2022-03-15 17:45:34 -07:00
JacobCrabill 7e34806046 mavlink: Replace CONFIG_NET with CONFIG_NET_UDP
Allows use of SocketCAN w/o also enabling UDP support in NuttX
2022-03-15 17:22:27 -07:00
JacobCrabill 9f18ef6688 Orange Cube: Add socketcan target 2022-03-15 17:11:42 -07:00
17 changed files with 608 additions and 14 deletions
+2 -2
View File
@@ -24,8 +24,8 @@
branch = master
[submodule "platforms/nuttx/NuttX/nuttx"]
path = platforms/nuttx/NuttX/nuttx
url = https://github.com/PX4/NuttX.git
branch = px4_firmware_nuttx-10.1.0+
url = https://github.com/JacobCrabill/incubator-nuttx.git
branch = dev-h7-socketcan
[submodule "platforms/nuttx/NuttX/apps"]
path = platforms/nuttx/NuttX/apps
url = https://github.com/PX4/NuttX-apps.git
@@ -0,0 +1,245 @@
#
# 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_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_NET_CAN_CANFD is not set
# CONFIG_NET_ETHERNET is not set
# CONFIG_NET_IPv4 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_MKFATFS is not set
# CONFIG_NSH_DISABLE_REBOOT is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_SHUTDOWN is not set
# CONFIG_NSH_DISABLE_TIME is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/cubepilot/cubeorange/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743ZI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=512
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_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=79954
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CANUTILS_CANDUMP=y
CONFIG_CANUTILS_CANSEND=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x1016
CONFIG_CDCACM_PRODUCTSTR="CubeOrange"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x2DAE
CONFIG_CDCACM_VENDORSTR="CubePilot"
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXAMPLES_CALIB_UDELAY=y
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_REGIONS=4
CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_PROGMEM=y
CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
CONFIG_NET=y
CONFIG_NETDEV_CAN_BITRATE_IOCTL=y
CONFIG_NETDEV_IFINDEX=y
CONFIG_NETDEV_PHY_IOCTL=y
CONFIG_NET_CAN=y
CONFIG_NET_CAN_RAW_TX_DEADLINE=y
CONFIG_NET_CAN_SOCK_OPTS=y
CONFIG_NET_TIMESTAMP=y
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_TELNETD=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_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_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=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=256
CONFIG_STM32H7_ADC1=y
CONFIG_STM32H7_ADC3=y
CONFIG_STM32H7_BBSRAM=y
CONFIG_STM32H7_BBSRAM_FILES=5
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_FDCAN1=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C2=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_HSECLOCK=y
CONFIG_STM32H7_RTC_MAGIC_REG=1
CONFIG_STM32H7_SAVE_CRASHDUMP=y
CONFIG_STM32H7_SDMMC1=y
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_SPI4_DMA=y
CONFIG_STM32H7_SPI4_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_USART6=y
CONFIG_STM32H7_USART_BREAKS=y
CONFIG_STM32H7_USART_INVERT=y
CONFIG_STM32H7_USART_SINGLEWIRE=y
CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
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_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y
@@ -0,0 +1,22 @@
CONFIG_DRIVERS_ADC_ADS1115=n
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_RPM=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
CONFIG_UAVCAN_V1_ESC_CONTROLLER=y
CONFIG_UAVCAN_V1_ESC_SUBSCRIBER=y
CONFIG_UAVCAN_V1_GNSS_PUBLISHER=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_0=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_1=y
CONFIG_UAVCAN_V1_READINESS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER=y
@@ -0,0 +1,249 @@
#
# 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_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_NET_CAN_CANFD is not set
# CONFIG_NET_ETHERNET is not set
# CONFIG_NET_IPv4 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_MKFATFS is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_TIME is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/mro/ctrl-zero-h7-oem/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743II=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=512
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_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x1024
CONFIG_CDCACM_PRODUCTSTR="mRoControlZeroH7 OEM"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x26ac
CONFIG_CDCACM_VENDORSTR="mRo"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_MEMFAULT=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_DISABLE_MQUEUE=y
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_REGIONS=4
CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_PROGMEM=y
CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
CONFIG_NET=y
CONFIG_NETDEV_CAN_BITRATE_IOCTL=y
CONFIG_NETDEV_IFINDEX=y
CONFIG_NETDEV_PHY_IOCTL=y
CONFIG_NET_CAN=y
CONFIG_NET_CAN_RAW_TX_DEADLINE=y
CONFIG_NET_CAN_SOCK_OPTS=y
CONFIG_NET_TIMESTAMP=y
CONFIG_NSH_ARCHINIT=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_TELNETD=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_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_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=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=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_FDCAN1=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C3=y
CONFIG_STM32H7_I2C4=y
CONFIG_STM32H7_I2C_DYNTIMEO=y
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_RTC=y
CONFIG_STM32H7_RTC_HSECLOCK=y
CONFIG_STM32H7_RTC_MAGIC_REG=1
CONFIG_STM32H7_SAVE_CRASHDUMP=y
CONFIG_STM32H7_SDMMC1=y
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI5=y
CONFIG_STM32H7_SPI5_DMA=y
CONFIG_STM32H7_SPI5_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM2=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_TIM8=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_USART6=y
CONFIG_STM32H7_USART_BREAKS=y
CONFIG_STM32H7_USART_INVERT=y
CONFIG_STM32H7_USART_SINGLEWIRE=y
CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_SERIAL_CONSOLE=y
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
@@ -0,0 +1,13 @@
CONFIG_DRIVERS_UAVCAN=n
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
CONFIG_UAVCAN_V1_CLIENT=y
CONFIG_UAVCAN_V1_ESC_CONTROLLER=y
CONFIG_UAVCAN_V1_ESC_SUBSCRIBER=y
CONFIG_UAVCAN_V1_GNSS_PUBLISHER=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_0=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_1=y
CONFIG_UAVCAN_V1_READINESS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER=y
+2
View File
@@ -112,6 +112,7 @@ px4_add_module(
INCLUDES
${LIBCANARD_DIR}/libcanard/
${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated
${CMAKE_CURRENT_SOURCE_DIR}/Publishers
SRCS
PublicationManager.cpp
PublicationManager.hpp
@@ -124,6 +125,7 @@ px4_add_module(
Publishers/uORB/uorb_publisher.cpp
Subscribers/uORB/uorb_subscriber.cpp
${SRCS}
Publishers/Publisher.cpp
o1heap/o1heap.c
o1heap/o1heap.h
${LIBCANARD_DIR}/libcanard/canard.c
+4 -1
View File
@@ -56,8 +56,11 @@ int CanardSocketCAN::init()
struct ifreq ifr;
//FIXME HOTFIX to make this code compile
#ifdef CONFIG_NET_CAN_CANFD
bool can_fd = 1;
#else
bool can_fd = 0;
#endif
_can_fd = can_fd;
/* open socket */
@@ -45,7 +45,9 @@
#include <reg/drone/physics/kinematics/geodetic/Point_0_1.h>
#include <reg/drone/service/gnss/DilutionOfPrecision_0_1.h>
#include "../Publisher.hpp"
class UavcanNode;
#include "Publisher.hpp"
class UavcanGnssPublisher : public UavcanPublisher
{
@@ -124,6 +126,8 @@ public:
// set the data ready in the buffer and chop if needed
++_transfer_id_2; // The transfer-ID shall be incremented after every transmission on this subject.
result = canardTxPush(&_canard_instance, &transfer2);
transmit();
}
}
};
@@ -95,6 +95,8 @@ public:
// set the data ready in the buffer and chop if needed
++_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
result = canardTxPush(&_canard_instance, &transfer);
transmit();
}
}
};
@@ -0,0 +1,49 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file Publisher.cpp
*
* Defines basic functionality of UAVCAN v1 publisher class
*
* @author Jacob Crabill <jacob@flyvoly.com>
*/
#include "Publisher.hpp"
#include "../Uavcan.hpp"
void UavcanPublisher::transmit()
{
UavcanNode::do_transmit();
}
@@ -142,4 +142,6 @@ protected:
CanardTransferID _transfer_id {0};
UavcanPublisher *_next_pub {nullptr};
void transmit();
};
@@ -81,6 +81,7 @@ public:
// set the data ready in the buffer and chop if needed
++_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
canardTxPush(&_canard_instance, &transfer);
transmit();
}
};
+2
View File
@@ -140,6 +140,8 @@ public:
static UavcanNode *instance() { return _instance; }
static void do_transmit() { if (_instance) _instance->transmit(); };
/* The bit rate that can be passed back to the bootloader */
int32_t active_bitrate{0};
+6 -6
View File
@@ -765,12 +765,12 @@ void Mavlink::send_finish()
else if (get_protocol() == Protocol::UDP) {
# if defined(CONFIG_NET)
# if defined(CONFIG_NET_UDP)
if (_src_addr_initialized) {
# endif // CONFIG_NET
ret = sendto(_socket_fd, _buf, _buf_fill, 0, (struct sockaddr *)&_src_addr, sizeof(_src_addr));
# if defined(CONFIG_NET)
# if defined(CONFIG_NET_UDP)
}
# endif // CONFIG_NET
@@ -1849,7 +1849,7 @@ Mavlink::task_main(int argc, char *argv[])
bool err_flag = false;
int myoptind = 1;
const char *myoptarg = nullptr;
#if defined(CONFIG_NET) || defined(__PX4_POSIX)
#if defined(CONFIG_NET_UDP) || defined(__PX4_POSIX)
int temp_int_arg;
#endif
@@ -3270,7 +3270,7 @@ $ mavlink stream -u 14556 -s HIGHRES_IMU -r 50
PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS1", "<file:dev>", "Select Serial Device", true);
PRINT_MODULE_USAGE_PARAM_INT('b', 57600, 9600, 3000000, "Baudrate (can also be p:<param_name>)", true);
PRINT_MODULE_USAGE_PARAM_INT('r', 0, 10, 10000000, "Maximum sending data rate in B/s (if 0, use baudrate / 20)", true);
#if defined(CONFIG_NET) || defined(__PX4_POSIX)
#if defined(CONFIG_NET_UDP) || defined(__PX4_POSIX)
PRINT_MODULE_USAGE_PARAM_FLAG('p', "Enable Broadcast", true);
PRINT_MODULE_USAGE_PARAM_INT('u', 14556, 0, 65536, "Select UDP Network Port (local)", true);
PRINT_MODULE_USAGE_PARAM_INT('o', 14550, 0, 65536, "Select UDP Network Port (remote)", true);
@@ -3291,7 +3291,7 @@ $ mavlink stream -u 14556 -s HIGHRES_IMU -r 50
PRINT_MODULE_USAGE_COMMAND_DESCR("stop-all", "Stop all instances");
PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop a running instance");
#if defined(CONFIG_NET) || defined(__PX4_POSIX)
#if defined(CONFIG_NET_UDP) || defined(__PX4_POSIX)
PRINT_MODULE_USAGE_PARAM_INT('u', -1, 0, 65536, "Select Mavlink instance via local Network Port", true);
#endif
PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "<file:dev>", "Select Mavlink instance via Serial Device", true);
@@ -3301,7 +3301,7 @@ $ mavlink stream -u 14556 -s HIGHRES_IMU -r 50
PRINT_MODULE_USAGE_ARG("streams", "Print all enabled streams", true);
PRINT_MODULE_USAGE_COMMAND_DESCR("stream", "Configure the sending rate of a stream for a running instance");
#if defined(CONFIG_NET) || defined(__PX4_POSIX)
#if defined(CONFIG_NET_UDP) || defined(__PX4_POSIX)
PRINT_MODULE_USAGE_PARAM_INT('u', -1, 0, 65536, "Select Mavlink instance via local Network Port", true);
#endif
PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "<file:dev>", "Select Mavlink instance via Serial Device", true);
+2 -2
View File
@@ -53,7 +53,7 @@
#include <sys/socket.h>
#endif
#if defined(CONFIG_NET) || !defined(__PX4_NUTTX)
#if defined(CONFIG_NET_UDP) || !defined(__PX4_NUTTX)
#include <net/if.h>
#include <netinet/in.h>
#endif
@@ -90,7 +90,7 @@
#define HASH_PARAM "_HASH_CHECK"
#if defined(CONFIG_NET) || defined(__PX4_POSIX)
#if defined(CONFIG_NET_UDP) || defined(__PX4_POSIX)
# define MAVLINK_UDP
# define DEFAULT_REMOTE_PORT_UDP 14550 ///< GCS port per MAVLink spec
#endif // CONFIG_NET || __PX4_POSIX
+1 -1
View File
@@ -3091,7 +3091,7 @@ MavlinkReceiver::run()
#if defined(__PX4_POSIX)
/* 1500 is the Wifi MTU, so we make sure to fit a full packet */
uint8_t buf[1600 * 5];
#elif defined(CONFIG_NET)
#elif defined(CONFIG_NET_UDP)
/* 1500 is the Wifi MTU, so we make sure to fit a full packet */
uint8_t buf[1000];
#else