Three issues caused the monthly audit to report already-resolved submodules:
1. The audit workflow grepped for "NOASSERTION" anywhere in the output,
matching the Detected column even when the Final column had a valid
override (e.g. libtomcrypt detected as NOASSERTION but overridden to
Unlicense). Changed to grep for "<-- UNRESOLVED" marker instead.
2. Submodules with an explicit NOASSERTION override in license-overrides.yaml
(like libfc-sensor-api, which is proprietary) were still counted as
failures. Now treated as "acknowledged" since someone intentionally
added the override entry.
3. Added missing BSD-3-Clause override for sitl_gazebo-classic (PX4 org
project with no LICENSE file in repo).
Fixes#26932
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Add MAVLink stream that maps EstimatorFusionControl uORB message to
ESTIMATOR_SENSOR_FUSION_STATUS, exposing per-sensor intended/active
bitmasks to the GCS.
Split FusionSensor into available (CTRL param != disabled) and enabled
(runtime-toggleable). intended() = enabled && available. EKF core aid
sources now set available themselves and use intended() or _params
directly for CTRL-level checks. Remove drag/imu from FusionControl,
add aspd/rngbcn. Add AGP sourceFusingBitmask() for active-status.
* ci(claude): add review-pr skill for domain-aware PR reviews
Add a Claude Code skill that reviews pull requests with checks
tailored to the domains touched (estimation, control, drivers,
simulation, system, CI/build, messages, board additions).
Built from analysis of 800+ PR reviews across 8 PX4 maintainers.
Includes merge strategy recommendation, interactive dialog for
submitting reviews, and human-sounding PR comment formatting.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
* ci(copilot): add domain-scoped review instructions for GitHub Copilot
Add .github/instructions/ files that give GitHub Copilot PR reviews
the same domain-aware context as the Claude Code review-pr skill.
Each file is scoped via applyTo to the relevant source paths:
core review, estimation, control, drivers/CAN, simulation, system,
CI/build, messages/protocol, and board additions.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
* fix(claude): address Copilot review feedback
- Fix step reference in review-pr skill (step 8 -> step 9)
- Capitalize CMake consistently in skill and Copilot instructions
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
---------
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Several helper scripts assumes bash is available at /bin/bash. That breaks on systems
such as NixOS, where bash is resolved from PATH instead of a fixed /bin location and
causes failures like `bad interpreter` during `make format`, e.g., on my host machine:
```sh
$ make format
/PX4-Autopilot/Tools/astyle/check_code_style.sh: /PX4-Autopilot/Tools/astyle/fix_code_style.sh: /bin/bash: bad interpreter: No such file or directory
```
This change switches these entrypoints to `#!/usr/bin/env bash` so they locate bash properly.
No functional changes intended.
Signed-off-by: Onur Özkan <work@onurozkan.dev>
Disable EKF2 fusion features with no corresponding hardware:
- px4_fmu-v2: optical flow, range finder (~17 KB saved)
- mamba-f405-mk2: optical flow, range finder, external vision,
aux global position, aux velocity, baro compensation,
drag fusion (~42 KB saved)
Before this change, filtered test runs still built every gtest target
because `test_results` depended on all unit and functional gtest targets.
This updates both `px4_add_unit_gtest()` and `px4_add_functional_gtest()`
to use the filtered dependency helper so filtered runs only build the
selected targets.
Signed-off-by: Onur Özkan <work@onurozkan.dev>
The MPL3115A2 ADC conversion at OSR 2 (ratio 4) takes ~18ms. The
driver polls until the conversion completes, so the read time is at
the end of the integration window. Correct timestamp_sample to the
midpoint by subtracting CONVERSION_TIME / 2.
The LPS25H one-shot measurement is integrated over a ~40ms window
(at 25Hz-equivalent internal averaging). The read time corresponds to
the end of the integration window. Correct timestamp_sample to the
midpoint by subtracting CONVERSION_INTERVAL / 2.
The LPS22HB one-shot measurement is integrated over a ~40ms window
(at 25Hz-equivalent internal averaging). The read time corresponds to
the end of the integration window. Correct timestamp_sample to the
midpoint by subtracting CONVERSION_INTERVAL / 2.
Same fix as MS5611: the MS5837 ADC conversion at OSR 1024 takes
~2.28ms, but the data is read after a 10ms scheduling delay. Correct
timestamp_sample by subtracting (CONVERSION_INTERVAL - CONVERSION_TIME/2)
from the read time.
The MS5611 ADC conversion at OSR 1024 takes ~2.28ms, but the data is
read after a 10ms scheduling delay. The current code timestamps the
read time, which is ~8.9ms after the true integration midpoint.
Correct timestamp_sample by subtracting the full offset
(CONVERSION_INTERVAL - CONVERSION_TIME/2) from the read time.
The BMP581 pressure measurement is integrated over a configurable
window (~23ms at 32x pressure / 2x temperature oversampling). The
read time corresponds to the end of the integration window, introducing
a systematic timing bias. Correct timestamp_sample to the midpoint by
subtracting measurement_time / 2.
The BMP280 pressure measurement is integrated over _measure_interval
(~43ms at 16x pressure / 2x temperature oversampling). The read time
corresponds to the end of the integration window, introducing a
systematic timing bias. Correct timestamp_sample to the midpoint by
subtracting measurement_time / 2.