COM_RC_STICK_OV is now a velocity threshold (1/s) instead of a deflection percentage.
Default 3.0, range [1.0, 10.0]. A stick held statically cannot trigger override.
Mention PWM, OneShot, DShot, and Bidirectional DShot in the long
description so users can discover the parameter by searching for
keywords like "bidirectional" or "dshot" in QGC.
* feat(drivers): add ST LSM6DSV16X IMU driver
Add a new SPI driver for the ST LSM6DSV16X 6-axis IMU with FIFO-based
accel, gyro, and temperature acquisition.
The driver supports continuous FIFO mode with tagged sample parsing,
DRDY interrupt triggering via FIFO threshold, and dynamic watermark
configuration based on the selected sample rate. It also falls back to
scheduled polling when a GPIO interrupt is not available.
To improve robustness, the driver periodically validates critical
register settings and limits FIFO draining per cycle.
Tested on Pixhawk6C with ground testing and flight validation.
* feat(boards/px4_fmu-v6c): add LSM6DSV16X support for Pixhawk6C
Enable the ST LSM6DSV16X as an alternative probe-based IMU on
Pixhawk6C.
The sensor is configured on SPI1 with chip-select PC13 and shares the
same CS and DRDY lines as the ICM42688P across all supported hardware
revisions. Board startup first probes the ICM42688P and then the
LSM6DSV16X, so only the IMU populated on a given board is started.
This change enables the LSM6DSV16X driver in the board configuration,
registers the device type in `spi.cpp`, and adds board sensor probing
for the new IMU.
Use rotation `-R 26` (`ROTATION_PITCH_180_YAW_90`) to match the sensor
orientation on the Pixhawk6C PCB.
* fix(drivers/lsm6dsv): address review comments
- add missing #include <cstddef> for size_t
- check FIFO status transfer() return value
- fix FIFO word count to sample period conversion (DIFF_FIFO reports
words, not sample periods; each sample period is 2 words)
- fix drv_sensor.h macro alignment (spaces to tab)
* drv_sensor: move LSM6DSV devtype into IMU range
* fmu-v6c: use quiet LSM6DSV fallback probe
* fix(uxrce_dds_client): fix session reconnection after agent restart
When the Micro XRCE-DDS Agent is restarted (e.g. via systemd or
Docker), the PX4 client stays "Running, disconnected" forever and
never re-establishes the session. Three bugs prevented reconnection:
1. session.on_pong_flag was never reset after being checked. Once set
to 1 by the first successful pong, it stayed 1 forever, causing
checkConnectivity() to believe pings were still succeeding even
after the agent was gone. Fixed by resetting to 0 after reading.
2. _subs->reset() was never called during session teardown. Stale
uORB file descriptors from the previous session persisted across
reconnection attempts, causing the new session's publishers to
malfunction. Fixed by calling _subs->reset() in deleteSession().
3. _connected was not explicitly reset in deleteSession(). While the
outer loop checked this flag, explicitly clearing it ensures clean
state for the next reconnection attempt.
Closes#26022
Signed-off-by: Pavel Guzenfeld <pavelgu@gmail.com>
* fix(uxrce_dds_client): clear fds[].events in reset() for reconnection
Without clearing events, init() skips orb_subscribe() on reconnect
because the POLLIN guard (fds[idx].events == 0) is never true again.
This causes all fds to remain at -1, px4_poll() returns 0, TX rate
stays zero, and the client enters a disconnect/reconnect loop.
Reported-by: sansha (tested on Pixhawk 6X with serial transport)
* ci: re-trigger SITL tests (flaky offboard test)
* docs(uxrce_dds_client): explain why reset() clears fds[].events
---------
Signed-off-by: Pavel Guzenfeld <pavelgu@gmail.com>
Once a serial telem channel hit 10 consecutive timeouts it was added
to a skip mask and never polled again. Channels that came online late
(e.g. ESC power-cycled after the autopilot boots) stayed permanently
offline, and with both serial and bdshot enabled the motor was
reported offline overall because the combined health check requires
both sources.
Periodically clear the skip mask while disarmed so recovered channels
get another chance. If still broken they are re-skipped after the
normal timeout threshold. Disarmed-only to avoid timeout blips on
healthy channels during flight.
The airframe 10043 (make px4_sitl sihsim_standard_vtol) currently does
not have enough forward thrust to reach VT_ARSP_TRANS (10) or
VT_ARSP_BLEND (8), so we get front transition timeout.
By bisecting, we find that #26720 breaks it. The PR introduces a new
dynamic prop model, which is now used in the airframes 1101, 1102, 1103,
and 1105 (new addition), but not 10043.
The PR also removes a previous magic number that gave the standard VTOL
pusher twice the max thrust of the hover motors (2 * 2N = 4N). It
introduces a separate SIH_F_T_MAX, but by default it is 2N, causing the
weak pusher for 10043.
Fix by using the new dynamic propeller model by default, with the same
params that #26720 introduces for airframe 1103 (It would also suffice
to only set SIH_F_T_MAX=6, but now that we have the nicer model let's
use it).
Note that 10041 (sihsim_airplane) is not broken by #26720 in this way,
as it already has SIH_T_MAX of 6N.
MODULES_TEMPERATURE_COMPENSATION defaults to n in Kconfig, so explicit
=n and "is not set" entries are unnecessary.
Signed-off-by: Jacob Dahl <dahl.jakejacob@gmail.com>
These are generic flight controller boards (not drone-specific
products), so they should not come with a pre-selected airframe like
every other PX4 board. Drop the SYS_AUTOSTART default, matching the
convention used across the rest of the tree.
Drone-specific products (bitcraze/crazyflie, atl/mantis-edu) retain
their default airframe.
* forwarding offboard setpoints in modes using the external mode registration
* requesting offboard setpoint in RAPTOR
* adding old message versions
* bumping vehicle status
* adding message translations
* updating reference to versioned old message on previous translations
Detects when a rotary-wing vehicle drops more than FD_ALT_LOSS metres
below a NED-z reference while altitude control is active,
and immediately triggers flight termination (parachute deployment).
Detection (FailureDetector):
- FD_ALT_LOSS: drop threshold in metres (0 = disabled, default)
- FD_ALT_LOSS_T: hysteresis time
- Guards: rotary-wing only, altitude control active, z_valid, setpoint
fresh (<1 s). Manual, Acro and FW/VTOL-FW modes are excluded.
- Ratcheting reference: initialises to lpos.z on first sample below
setpoint, preventing false triggers on new waypoints
Failsafe action (commander):
- New fd_alt_loss flag in FailsafeFlags.msg
- COM_ALT_LOSS_ACT: -1=Disabled (default), 0=Terminate
- Terminate fires immediately, cannot be overridden, and never clears
until disarm (parachute deployment is irreversible)
* fix(mavlink): align signing with MAVLink spec and fix performance regression
Remove the non-standard MAV_SIGN_CFG parameter and align the signing
implementation with the MAVLink specification.
Key changes:
- Remove MAV_SIGN_CFG parameter that conflicted with GCS implementations
- Only enable signing when a valid key is present on the SD card
- Accept SETUP_SIGNING on any link, not just USB
- Reject SETUP_SIGNING while the vehicle is armed
- Allow disabling signing via signed all-zero key SETUP_SIGNING message
- Propagate key changes to all mavlink instances
- Zero CPU/bandwidth overhead when signing is not active
Fixes#26893
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
* Signing minor subedit
---------
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
Co-authored-by: Jacob Dahl <dahl.jakejacob@gmail.com>
* refactor: make timer_io_channels[].timer_channel 0-indexed
timer_channel was 1-indexed (1-4) to mirror STM32 hardware naming
(TIM_CH1-CH4), but this was purely cosmetic — the ccr_offset field
already handles register mapping. Every consumer did timer_channel - 1
to get a 0-based index, creating underflow bugs when the guard was
missing (e.g. dshot.c capture_complete_callback,
output_channel_from_timer_channel, up_bdshot_get_erpm).
Changes:
- STM32: Timer::Channel enum starts at 0, initIOTimerChannel assigns
directly, removed all timer_channel - 1 in dshot.c and io_timer.c
- NXP (kinetis, s32k1xx, s32k3xx): removed the + 1 in
initIOTimerChannel, removed timer_channel - 1 in io_timer.c,
led_pwm.cpp, and input_capture.c
- RPI: Channel enum starts at 0, removed timer_channel - 1 in
io_timer.c
- Validity checks updated from timer_channel <= 0 || >= 5 to
timer_channel >= 4
Closes#26747
Signed-off-by: Pavel Guzenfeld <pavelgu@gmail.com>
* fix: complete 0-indexed timer_channel migration across all platforms
Address review feedback for incomplete migration:
1. STM32H7 io_timer_hw_description.h: update standalone
initIOTimerChannel() to assign timer_channel from enum
(0-based) instead of hardcoded 1/2/3/4
2. Switch case labels: update all switch(timer_channel) blocks
from 1/2/3/4 to 0/1/2/3 in:
- stm32_common: input_capture.c (4 blocks), led_pwm.cpp (3),
io_timer.c DMA base register switch
- kinetis: input_capture.c (2 filter blocks)
- s32k1xx: input_capture.c (2 filter blocks)
- spix_sync.c (ark/fpv + ark/pi6x, 3 blocks each)
3. Sentinel checks: replace timer_channel != 0 / == 0 (which
now conflicts with valid channel 0) with gpio_out-based
checks in:
- io_timer_validate_channel_index() across all 5 platforms
- led_pwm_channel_init() and led_pwm_servo_get() in all
led_pwm.cpp variants (STM32 + 4 NXP)
- spix_sync_channel_init() and spix_sync_servo_get()
Tested: px4_fmu-v6x_default (H7) build OK, px4_sitl_default
build OK, 154/154 unit tests pass, ASan build clean.
* fix: update NXP board led_pwm_channels to 0-indexed timer_channel
These 4 board files manually specify led_pwm_channels[] with
1-indexed timer_channel values. Since the platform code no longer
subtracts 1, decrement all values to match the new 0-indexed
convention.
* fix: correct FTM CH3 filter mask in kinetis and s32k1xx input capture
Case 3 in up_input_capture_set_filter() was using CH2FVAL_MASK/SHIFT
instead of CH3FVAL_MASK/SHIFT due to a copy-paste error, causing
channel 3 filter writes to modify channel 2's filter register instead.
---------
Signed-off-by: Pavel Guzenfeld <pavelgu@gmail.com>
Co-authored-by: Jacob Dahl <dahl.jakejacob@gmail.com>
* refactor(battery_simulator): remove SIM_BAT_ENABLE
disable instead with SIM_BAT_DRAIN <= 0
* fix(battery_simulator): disable battery sim only if SIM_BAT_DRAIN strictly < 0
* fix(battery_simulator): disable if 0, adjust limit to 0
* fix(battery_simulator): remove constraining again
now that SIM_BAT_DRAIN=0 means the module is not started we are safe
from division by zero again (param compare has a tolerance of 1e-7)
* fix(battery_simulator): constrain param to min of 1
to avoid division by zero.
This reverts commit 6380c4fdee.
* fix(battery_simulator): remove arbitrary param max
* fix(battery_simulator): reword long param description
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
* fix(battery_simulator): reword short param description
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
---------
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>