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
Add common functions, implemented for nuttx, and link to architecture specific libraries
Make a separate library to wrap nuttx random number generator as "os_random".
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Using mixers on the IO side had a remote benefit of being able to
override all control surfaces with a radio remote on a fixed wing.
This ended up not being used that much and since the original design
10 years ago (2011) we have been able to convince ourselves that the
overall system stability is at a level where this marginal benefit,
which is not present on multicopters, is not worth the hazzle.
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
Co-authored-by: Daniel Agar <daniel@agar.ca>
This is to avoid potential race conditions during startup.
All startup code runs sequentially atm, so this is just for robustness
for later (e.g. concurrent pwm_out and dshot start).
This allows modules to do a first-come-first-serve pin/timer reservation
on bootup.
E.g. camera trigger reserves any of the pins, and then PWM/DShot output
will just use the rest of the available pins.
When the last WorkItem is deleted, it is removed from a work queue and the
queue is being stopped. But, the queue itself might get deleted in the middle,
in a higher priority thread than where the WorkItem deletion was performed from
If the WorkQueue::Detach accesses the member variables after this, there is memory
corruption
This happens in particular when launching i2c or spi devices in
I2CSPIDriverBase::module_start:
- The "initializer" is deleted when the instance is not found and the iterator
while loop continues.
- The workqueue is deleted in the middle of "initializer" deletion when the
WorkQueueRunner returns.
This prevents deletion of the WorkQueue before the Detach has been finished,
in the specific case that the ::Detach triggers the deletion
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
Reduces CPU load by almost 1.5% @ 2khz on F4 and F7.
This changes the motor ordering on boards where the timer ordering does
not match the order of the timer usage in the channels defintion.
Only omnibus f4sd is affected.
There's an increasing amount of slow logged topics at 1-2Hz, which were all
updated in the same logger iteration, leading to data bursts. For log
streaming this started to exceed uart buffer sizes. By distributing updates
more equal over time those bursts are removed, reducing buffer size
requirements.
Tests showed during steady state a reduction of maximum topic updates per
iteration from 40 down to 17.
Also the SD log buffer fill level is more constant.
This commit adds SITL support for ignition gazebo. Ignition gazebo is a replacement for the "classic" gazebo for future applications.
The simulation can be run as the following
```
make px4_sitl ignition
```
This also simplifies the API a bit, since we anyway have to change the
drivers to pass additional information (the bus device index).
The orientation flag is merged with the rotation.
- sending protocol
- uorb event message & template methods for argument packing
- libevents submodule to send common events and handle json files
- cmake maintains a list of all (PX4) source files for the current build
(PX4 modules + libs), which is used to extract event metadata and
generate a json file
- move systick.c under chip specific sources
- move do_jump into chip specific main.c as arch_do_jump
- wrap flash writes to "arch_flash_write" and implement in chip specific main.c
- add bootloader TOC check
- sync image_toc.h with the version currently in use with old bootloader
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
[BACKPORT] binnfmt:Fix return before close ELF fd
stm32h7: serial: use dma tx semaphore as resource holder
[BACKPORT] stm32h7:Serial Add RX and TX DMA
[BACKPORT] drivers/serial: fix Rx interrupt enable for cdcacm
[BACKPORT] stm32h7:Allow for reuse of the OTG_ID GPIO
[BACKPORT] stm32f7:Allow for reuse of the OTG_ID GPIO
Now sets the GDB serial device to the path of a DroneCode Probe by
default, with option command-line option override.
A few usage instructions added to the top of the file.
nxp_ucans32k146:Relocation for Bootloader
nxp_ucans32k146:can_boot enable CAN
nxp_ucans32k146:Save Space use Non Optimize memcpy
nxp_ucans32k146:Increase to 24K
nxp/ucans32k146:Canbootloader LED Driver
nxp_ucans32k146:Can bootloader shut down CAN
nxp_ucans32k146:Use NVMEEPROM for Paramaters
nxp_ucans32k146:Use bootloader AppDescriptor
px4 mtd:Support onchip emulated eeprom
nxp/s32k14x:board_identity: Return length of mfguid
nxp/s32k14x:CAN driver
nxp/s32k14x:Drver Added ABORT on error
canbootloader:Use N words for first word
canbootloader:Ensure the up_progmem API always defined
- store parameter type and if volatile separately (saves kilobytes of flash)
- use Bitset for tracking active and changed parameters
- use atomic for autosave_enabled flag
- compile at ${MAX_CUSTOM_OPT_LEVEL} (-O2 on non flash constrained boards)
* stm32_common: Add support for STM32F42x/STM32F43x rev. 5/B
According to ST, both 5 and B share the same REV_ID.
Signed-off-by: Alexey Rogachevskiy <sfalexrog@gmail.com>
* stm32_common: Change comment to match code, change enum names to match revisions
When an environment variable "SIGNING_TOOL" is defined, the make will
call this with two filename arguments: <input> and <output>.
The SIGNING_TOOL will read in the binary from input, and append
signature to the output. For example:
SIGNING_TOOL=${PWD}/Tools/cryptotools.py make px4_fmu-v5_default
Will use the example "cryptotools.py" to sign the px4_fmu-v5.bin
Signed-off-by: Jukka Laitinen <jukkax@ssrc.tii.ae>
* drivers/uavcannode: Add a simple parameter server
Added a simple parameter server using the libuavcan ParamServer class.
The parameter server exposes a selection of PX4 parameters via UAVCAN.
Also, Increased the stack size of the uavcan work queue in order to
prevent a stack overflow.
* uavcannode: fetch all active PX4 parameters
Co-authored-by: Kenneth Thompson <ken@flyvoly.com>
- control allocation module with multirotor, VTOL standard, and tiltrotor support
- angular_velocity_controller
- See https://github.com/PX4/PX4-Autopilot/pull/13351 for details
Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
Co-authored-by: Roman Bapst <bapstroman@gmail.com>