the nuttx and posix specific options files since this option cannot be used with
the qurt platform. There are header files in the hexagon sdk that fail this check.
- update all msgs to be directly compatible with ROS2
- microdds_client improvements
- timesync
- reduced code size
- add to most default builds if we can afford it
- lots of other little changes
- purge fastrtps (I tried to save this multiple times, but kept hitting roadblocks)
This removes the odd px4_i2c_bus_external override which was confusing
me and lead to odd and inconsistent results.
The function is now only available with an int as the argument.
- To check stack smashing (buffer overflow)
- To check if the buffer without enough length gets appropriate values
filled
- To check if the format has expected length
- Previously, not having a proper boundary check caused overflows in the
buffer (wrong memory access)
- Moreoever, negative size values getting introduced to snprintf &
strncat were also being truncated to unsigned value, hence causing
overflow, so index check needed to be added before both functions
- Fixed typo in board_common.h
- for convenience merge px4_sitl_ign into px4_sitl_default, but allow simulator_ignition_bridge to quietly skip inclusion if ignition-transport isn't available
- simulator_ignition_bridge only try setting the system clock in
lockstep builds
- this simplifies usage and CI system dependencies
For targets that define the SPI buses via px4_spi_buses_all_hw, a call
to px4_set_spi_buses_from_hw_version() is needed. Otherwise a NULL
de-reference will occur when trying to access px4_spi_buses.
Fixes a system crash in px4_fmu-v5_protected:
up_assert: Assertion failed at file:armv7-m/arm_memfault.c line: 101 task: wq:lp_default
Move logic implemented in the header files to source files, this way
it will be simpler to define which is compiled to kernel space and
which to user space
Also allows to remove some headers that pull in half the universe
from the board definitions (which should just be pin definitions and
no functionality)
- new modules/simulation directory to collect all simulators and related modules
- new Tools/simulation directory to collect and organize scattered simulation submodules, scripts, etc
- simulation module renamed to simulator_mavlink
- sih renamed to simulator_sih (not a great name, but I wanted to be clear it was a simulator)
- ignition_simulator renamed to simulator_ignition_bridge
- large sitl_target.cmake split by simulation option and in some cases pushed to appropriate modules
- sitl targets broken down to what's actually available (eg jmavsim only has 1 model and 1 world)
- new Gazebo consistently referred to as Ignition for now (probably the least confusing thing until we fully drop Gazebo classic support someday)
- much simpler direct interface using Ignition Transport
- in tree models and worlds
- control allocation output configuration, no more magic actuator mapping to mavlink and back
- currently requires no custom Gazebo plugins (keeping things as lightweight and simple as possible)
Co-authored-by: Jaeyoung-Lim <jalim@ethz.ch>
- 4096 of 3 hex digits each for rev and ver is enough.
#defines used in SPI versions do not be long format, use use the macro
- Board provides a prefix and the formatting is sized and built in
- No need for funky board_get_base_eeprom_mtd_manifest interface
Original mft is used where the abstraction is done with the MFT interface
Co-authored-by: David Sidrane <David.Sidrane@Nscdg.com>
* sih: Move sih out of work queue
This reverts commit bb7dd0cf00.
* sih-sim: Enable sih in sitl, together with lockstep
* sih-sim: new files for sih: quadx and airplane
* sih: Added tailsitter for sih-sitl simulation
* sitl_target: Added seperate target loop for sih
* jmavsim_run: Allow jmavsim to run in UDP mode
* lockstep: Post semaphore on last lockstep component removed
* sih-sim: Added display for effectively achieved speed
* sih: increase stack size
* sih-sim: Improved sleep time computation, fixes bug of running too fast
* sitl_target: place omnicopter in alphabethic order
Co-authored-by: romain-chiap <romain.chiap@gmail.com>
Co-authored-by: Matthias Grob <maetugr@gmail.com>
This is needed for DMA capable memory for fat also in the user side;
the file system doesn't seem to work reliably without.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
For protected/kernel builds the cxx static initializations
needs to be done also in kernel side, since px4 creates
c++ objects in kernel
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Implement an interface for protected build to access parameters.
The implementation only does IOCTL calls to the kernel, where the parameters
live.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This adds a nuttx userspace interface for hrt driver, communicating with
the actual px4 hrt driver via BOARDCTL IOCTLs
This is be used when running PX4 in NuttX protected or kernel builds
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Move some logic from Subscriber into uORBManager. This reduces calls from the
modules to the uORB manager, improving performance in protected build.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
* Adds Timer15 to stm32_common, if the timer base is defined
* Adds Timer15 logic for DMA and AltFunc config on stm32h7 boards
* Adds TIM15 BDTR->MOE support in stm32_common timer init
* Adds support for TIM15 pwm channels on Matek H743 Slim
If the hardware support RESET lockout that has nArmed ANDed with VBUS
vbus_sense may drop during a param save which uses
BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE to prevent external resets
while writing the params. If we are not armed and nARMRED is low
we are in such a lock out so ignore changes on VBUS_SENSE during this
time.
It was a mistake to mix these two together, it is simpler to implement the boardctl interface
for the protected build, if the boardctl ioctls are different
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This adds an ioctl interface for NuttX protected build, allowing
system calls from user space to kernel for uORB, HRT and crypto
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
When building uORB for NuttX flat build, or for some other target, everything
works as before.
When building uORB for NuttX protected or kernel build, this does the following:
- The kernel side uORB library reigsters a boardctl handler for calls from userspace
and services the boardctl_ioctls by calling the actual uORB functions
- For user mode binaries, the uORBManager acts as a proxy, making boardctl_ioctl calls to the
kernel side
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This is the case for boards with digital readout, like v5x, but still
enable the battery_status module for external analog driver options.
An alternative would be to not run battery_status depending on config.
SD is on SPI3 - correct pin mapping
Fix DMA Mapping for all SPI and RX DMA on U[S]ART RX
Fix Memory MAP SRAM size
Removed unused GPIO
Used proper I2C definitions
Ensure Watchdog is configured for debugging
Fixed FLASH param definitions
Removed unedded SPI init
matek_gnss-m9n-f4:Correct Board ID and Size
Build order SJF
Added Support for F40x
Split the px4_layer into user and kernel space libraries. Add some stubs for
user-space (e.g. version) where an interface to the kernel needs to be added
Use posix-versions for cpuload.cpp and print_load.cpp for userspace; these link to nuttx internals. This functinality could be built on top of posix (e.g. procfs) interfaces
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Since uORB is split into kernel and userspace parts, it is no longer possible to just
link uORB into px4_platform, which is used in both kernel and user side.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
For NuttX protected or kernel build, the prebuilds can't contain libraries which are
different for kernel and user-space in protected/kerenl builds
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This adds the env option PX4_FUZZ which runs the LLVM libFuzzer which
throws random bytes at mavlink_receiver using MAVLink messages over UDP.
The MAVLink messages that are being sent are valid, so the CRC is
calculated but the payload and msgid, etc. are generally garbage, unless
the fuzzing gets a msgid right by chance.
As I understand it, libFuzzer watches the test coverage and will try to
execute as much of the code as possible.
- Allocate and free the node name in uORBDeviceNode.
- Add protected build support by de-allocating the name with kmm_free, when
running in kernel side. strdup allocates from the kernel heap in NuttX kernel
space.
- Remove the CDev::unregister_driver_and_memory(), it is no longer used
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
In NuttX protected build there are separate work queues in kernel and user sides.
pthreads are only available in user side, so use tasks and kthreads for
memory protected builds.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
- use NuttX gdb script for nxthreads and thread backtrace
- update jlink_gdb_backtrace and jlink_debug_gdb helper targets to use
NuttX gdb script
- Debug/PX4 fix "perf" divide by zero
- Debug/PX4 add "dmesg"
dmesg was locking the console buffer, then writing to stdout (a pipe in
the case of the MAVLink shell).
This might block, waiting for mavlink to read from the pipe. If however
mavlink tries to write to the console at that time, the lock is already
taken.
This patch avoids nested locking by using a separate buffer.
This is more logical place for the "backend" implementation than
directly under platform.
This also allows making other implementations as "real" drivers, as well as proper configuration via Kconfigs
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Don't compare pointers to metadata, but the metadata contents.
In protected/kernel build there are two sets of metadata, on on kernel
side and another in user side. Thus the comparison of pointers would just
always fail. Compare orb_id instead
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Proxy all calls to the DeviceNode through Manager;
- This hides the DeviceNode from publishers and subscribers
- Manager can be made an interface class between user and kernel spaces in protected build
- This doesn't increase code size or harm the performance on flat build
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Make possible to define chip-select pin for internal SPI.
By defining chip-select pin, it's possible to start specific SPI device only.
This allows to have several same type of sensors on the same bus with different orientation.
- cmake NuttX build wrapper compile in place instead of copying source tree to build directory
- slightly faster skipping necessary copying (depending on system)
- allows debugging in place
- easier to work directly in NuttX following official documentation
- simplifies overall build which should make it easier to resolve any remaining NuttX dependency issues in the build system
- the downside is switching back and forth between different builds always require rebuilding NuttX, but I think this is worth the improved developer experience
- also no longer builds px4io and bootloader in every single build, for most users these rarely change and we're wasting a lot of build time
In protected build, this needs to go to user-space initialization as it
calls apps (sercon) and launches mavlink.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
This is already removed from nuttx, and in posix the size of s->last_times
can be just checked with sizeof()
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Add interface functions for fetching latency buckets and counters and use
those in perf_counter.cpp. This cleans up the usage of perf counters, when variables defined in hrt_drv are not referenced directly from perf.
This also enables implementing kernel-userspace interface for those for
nuttx protected/kernel build.
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Using cmake_host_system_information, grabs AVAILABLE_PHYSICAL_MEMORY and adds another job for every 1.5GB of available memory.
This is tested on a single system with 16 logical cores and 16GB RAM (~11.5GB available, reported correctly by cmake).
This fixes the case where oneshot was enabled with multi-instance pwm_out,
triggering oneshot updates too close to each other and as a result could
lead to spinning motors while disarmed.
- no longer start sercon or mavlink usb by default
- on USB connection (VBUS) monitor serial USB at low rate and start Mavlink if there's a HEARTBEAT or nshterm on 3 consecutive carriage returns
- the mavlink USB instance is automatically stopped and serdis executed if USB is disconnected
- skipping Mavlink USB (and sercon) saves a considerable amount of memory on older boards