- Added offset to Posix hrt time to account for synchronization with Qurt hrt time
- Added new Kconfig to configure synchronization of HRT timestamps on VOXL2
- Moved voxl2 libfc sensor library submodule from muorb module to boards directory
- Added check to make sure hrt_elapsed_time can never be negative
The voxl2 has a split architecture. PX4 runs on a posix platform and a Qurt platform. The two communicate uorb topics back and forth with the muorb module. But each has it's own parameters database and they need to stay in sync with each other. This PR adds support to keep the 2 parameter databases in sync. The main parameters database running on Linux has file system support while the Qurt one does not. The Linux side is considered the primary and the Qurt side is considered the remote.
Previously uORB queue size was an awkward mix of runtime configurable (at advertise or IOCTL before allocate), but effectively static with all queue size settings (outside of test code) actually coming from the topic declaration (presently ORB_QUEUE_LENGTH in the .msg). This change finally resolves the inconsistency making the queue size fully static.
Additionally there were some corner cases that the muorb and orb communicator implementation were not correctly handling. This PR provides fixes for those issues. Also correctly sets remote queue lengths now based on the topic definitions.
* Made setting of uORB topic queue size in based on topic definition only
* Fixes to the ModalAI muorb implementation
* Removed libfc sensor from format checks
* msg/TransponderReport.msg ORB_QUEUE_LENGTH 8->16 (was set to higher in AdsbConflict.h
---------
Co-authored-by: Eric Katzfey <eric.katzfey@modalai.com>
Co-authored-by: Daniel Agar <daniel@agar.ca>
The ADC peripheral can only support up to
50MHz on rev V silicon and 36MHz on Y silicon.
The existing driver always used no prescaler
and kept boost setting at 0.
A board can optionaly define RC_SERIAL_SWAP_USING_SINGLEWIRE
If the board is wired board with TX to the input (Swapped) and
the SoC does not support U[S]ART level RX-TX swapping to allow
useing onewire to do the swap if and only if:
RC_SERIAL_SWAP_USING_SINGLEWIRE is defined
RC_SERIAL_SWAP_RXTX is defined
TIOCSSWAP is defined and retuns !OK
TIOCSSINGLEWIRE is defined
nxp/rt117x:Fix Pin IRQ
nxp/rt117x:Support 4 i2c busses
nxp/rt117x:Add px4io_serial support
nxp/imxrt:Expand ToneAlarmInterface to GPT 3 & 4
px4_fmu-6xrt:Using imxrt_flexspi_nor_octal
px4_fmu-6xrt:Entry is start
px4_fmu-6xrt:Add Proper MTD
px4_fmu-6xrt:Set I2C Buses
px4_fmu-6xrt:Proper SPI usage
px4_fmu-6xrt:Adjust memory Map to use the 2 MB
px4_fmu-6xrt:Bring in ROMAPI
px4_fmu-6xrt:Push FLASH to 200Mhz
px4_fmu-6xrt:Use BOARD_I2C_LATEINIT
px4_fmu-6xrt:Clock Config remove unused devices
px4_fmu-6xrt:Remove EVK SDRAM IO
px4_fmu-6xrt:Enable SE550 using HW_VER_REV_DRIVE
px4_fmu-6xrt:Use MTD to mount FRAM on Flex SPI
px4_fmu-6xrt:Manifest
px4_fmu-6xrt:Restore board_peripheral_reset
px4_fmu-6xrt:Set I2C buss Interna/Externa and startup
nxp/rt117x:Set 6 I2C busses
px4_fmu-6xrt:Correct Clock Sources and Freqency Settings
px4_fmu-6xrt:Correct ADC Settings
px4_fmu-6xrt:Tune FlexSPI config and sync header with debug variant Linker prep for rodata ahb partitioning
px4_fmu-6xrt:FlexSPI prefetch partition split .text and .rodata
Current config
1KB Prefetch .rodata
3KB Prefetch .text
px4_fmu-6xrt:Run imxrt_flash_setup_prefetch_partition from ram with barriers
px4_fmu-6xrt:Use All OCTL setting from FLASH g_flash_config SANS lookupTable
px4_fmu-6xrt:Octal spi boot/debug problem bypass
px4_fmu-6xrt:Add PWM test
px4_fmu-6xrt:Fix clockconfig and USB vbus sense
px4_fmu-6xrt: Use TCM
px4_fmu-6xrt: Ethernet bringup
imxrt: use unique_id register for board_identity
px4_fmu-6xrt: update ITCM mapping, todo proper trap on pc hitting 0x0
px4_fmu-6xrt:correct rotation icm42688p onboard imu
rt117x: Add SSARC HP RAM driver for memory dumps
px4_fmu-6xrt: Enable hardfault_log
px4_fmu-6xrt: Enable DMA pool
px4_fmu-6xrt: fix uart mapping
px4_fmu-6xrt: enable SocketCAN & DroneCAN
px4_fmu-6xrt:Command line history TAB completion
px4_fmu-6xrt:Fix pinning duplication
px4_fmu-6xrt:Support conditional PHY address based on selected PHY
px4_fmu-6xrt:Add Pull Downs on CTS, use GPIO for RTS
px4_fmu-6xrt:Set TelemN TX Slew rate and Drive Strenth to max
px4_fmu-6xrt::Set TELEM Buffers add HW HS
px4_fmu-6xrt:Turn off DMA poll
px4_fmu-6xrt:RC_SERIAL_PORT needed to be px4io to disable rc_input using TELEM2!
px4_fmu-6xrt: bootloader (#22228)
* imxrt:Add bootloader support
* bootloader:imxrt clear BOOT_RTC_SIGNATURE
* px4_fmu-6xrt:Add bootloader
* px4_fmu-6xrt:bootloader removed ADC
* px4_fmu-6xrt:bootloader base bootloader script off of script.ld
* px4_fmu-6xrt:add _bootdelay_signature & change entry from 0x30000000 to 0x30040000
* px4_fmu-6xrt:hw_config Bootloader has to have 12 bytes
px4_fmu-6xrt:Default to use LAN8742A PHY
px4_fmu-v6xrt:VID Set to Drone Code
board_reset:Enable ability to write RTC GP regs
px4_fmu-6xrt:Fix CMP0079 error
rt117x:micro_hal Add a PX4_MAKE_GPIO_PULLED_INPUT
px4_fmu-v6xrt:Set CTS High before VDD_5V applided to ports to avoid radios fro entering bootloaders
fmu-v6xrt: increase 5v down time
fmu-v6xrt:Ready for Release DEBUGASSERTS off and Console 57600,
Bootloder updated.
imxrt:board_hw_rev_ver Rework for 3.893V Ref
px4_fmu-v6xrt:Move ADC to Port3
imxrt:117x Reuse all but io_timer_hw_description and imxrt_pinirq.c
imxrt:ADC & LPADC bifurcation and restructuring
imxrt:hrt support Up to GPT6
nxp/rt117x:adc Corrected
The UART7 TXDMA services TELEM1 with flow control. If CTS is high, the
transmitting thread will wait on a semaphore, which may block other
threads from acquiring necessary resources to make progress, for
example, preventing MAVLINK instances from transmitting.
This change in NuttX makes the TXDMA acquire the semaphore in a
non-blocking way, preventing this issue.
Reduces flash usage by ~16KB.
- compress formats at build-time into a single string with all formats
- then at runtime iteratively decompress using
https://github.com/atomicobject/heatshrink