Sweep at sihsim_quadx (default rate-PID gains, ramp-first sequence)
identified omega_n=50 with a 100 dps FF cap as the best tradeoff:
fastest ramp tracking with no large-step ringing and no wind-up
undershoot on returns. Rewrite the param descriptions accordingly so
QGroundControl tuners see a single-paragraph explanation of each knob.
Signed-off-by: gguidone <gennaroguido2002@gmail.com>
- Remove _komega (written by setRefModelFrequency, never read) and the
unused getRefModelFrequency / getFeedForwardGain accessors.
- Inline the kFFNaturalFreqDefault / kFFGainDefault constants as member
initializers so the defaults live in one place.
- Rename b_neg to b (nothing was negated) and drop comments that
restated the code or carried session-specific debugging anecdotes.
Signed-off-by: gguidone <gennaroguido2002@gmail.com>
The test referenced AttitudeControl::kFFNaturalFreq, which was removed
when MC_REF_W_N was introduced; pin the frequency explicitly in the
fixture so the residual tolerances stay calibrated against a known
omega_n independent of class defaults.
Signed-off-by: gguidone <gennaroguido2002@gmail.com>
The SITL sweep showed that 5 * MC_REF_W_N deg/s is a principled
starting point: it preserves the full FF benefit for ~10 deg steps
while clipping the excess spike on larger steps.
Signed-off-by: gguidone <gennaroguido2002@gmail.com>
The ref-model FF is intended for ramp tracking, where peak omega_ref
equals the ramp rate (~45 dps). On step commands, however, the uncapped
FF can spike well above the rate-loop bandwidth, saturating the rate
controller and winding up its integrator — causing the undershoot seen
after large attitude steps.
MC_REF_FF_MAX (deg/s, default 0 = disabled) clips the per-axis FF
contribution to the rate setpoint before it is added to the P term.
The ramp-tracking benefit is fully preserved because the ramp steady-
state demand never reaches the cap; only the transient step spikes are
attenuated.
Signed-off-by: gguidone <gennaroguido2002@gmail.com>
Replace the hard-coded ref-model coefficients with two runtime parameters
and raise the default bandwidth based on SITL sweep data:
MC_REF_W_N [rad/s, default 100]
Natural frequency of the 2nd-order critically-damped reference model.
Was hardcoded to 10 rad/s, a conservative value pinned by the previous
symplectic-Euler stability bound. The exact-discretisation introduced
in the previous commit lifts that constraint; SITL maneuver sweeps
show omega_n = 100 reduces small-step overshoot to zero, halves the
AUTO_LAND-style snap-back undershoot, and improves ramp tracking
by 2-3x with no measurable downside on the rate-loop side.
MC_REF_FF [0..1, default 1.0]
Magnitude scaling for the angular-velocity feed-forward contribution
to the rate setpoint. 1 = full FF (default, prior PR behaviour),
0 = FF off (attitude P-loop targets q_d directly, legacy behaviour).
Lets operators disable or attenuate the FF on airframes whose rate
loop is not tuned to handle the FF demand, without recompiling.
Signed-off-by: gguidone <gennaroguido2002@gmail.com>
Replace the symplectic-Euler one-step update of the 2nd-order
critically-damped attitude reference model with its closed-form exact
discretisation. The symplectic scheme is conditionally stable
(kFFNaturalFreq*dt < 2): when the setpoint stream pauses across a mode
handoff (e.g. the ~500 ms gap PX4 produces when OFFBOARD hands off to
AUTO_LAND), a single integration step with dt ~= 0.5 s blows up,
producing several thousand dps of peak omega_ref, a multi-radian
single-step rotation of q_ref, and a tens-of-degrees attitude excursion
on the vehicle.
The exact-discrete update integrates the linear ODE analytically and is
unconditionally stable for any dt: large dt collapses to a snap of q_ref
onto q_d with omega_ref ~ 0. Behaviour at nominal control rates is
indistinguishable from the previous scheme.
Verified in SITL across an omega_n sweep 10..200 rad/s: ramp-tracking
lag and steady-state response unchanged, AUTO_LAND spike eliminated.
Adds one expf() and a handful of scalar multiplies per call.
Signed-off-by: gguidone <gennaroguido2002@gmail.com>
Mavlink::request_stop() unconditionally called
_sign_control.write_key_and_timestamp() on every instance shutdown,
which created /fs/microsd/mavlink/mavlink-signing-key.bin filled with a
zero key and zero timestamp on FCs that never enabled signing.
The shutdown write is redundant: every signing state transition
(KEY_ACCEPTED, SIGNING_DISABLED) already persists synchronously inside
check_for_signing() before returning. The in-memory state is always
flushed to disk at the moment it changes.
Aggravated by mavlink_main.cpp:3334 calling request_stop() up to 1000
times in a tight loop while waiting for the thread to exit, plus the
~Mavlink() destructor path. Each call re-truncates and rewrites the
phantom file.
Reported by Jake Dahl on two separate flight controllers running
mainline.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
The PR-time SBOM license check was using `submodules: false`, so when
generate_sbom.py ran the new submodule directory was empty. The script
treats uninitialized submodules as `(not checked out) -> NOASSERTION
(skipped)` rather than a failure, which let PR #27184 (adding
PX4-OpticalFlow as a submodule) pass without ever inspecting the actual
repo for a LICENSE file. The monthly audit then caught it (#27217)
because it uses `submodules: recursive`.
Switch the PR-time job to `submodules: recursive` so license issues
are caught at PR time rather than on the next monthly audit. The job
only runs when .gitmodules, license-overrides.yaml, or
generate_sbom.py change, so the extra clone cost is bounded.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Bumps the submodule pointer to pick up the BSD-3-Clause LICENSE file
added in PX4/PX4-OpticalFlow#20.
Resolves the SBOM audit NOASSERTION finding without needing a manual
override entry in Tools/ci/license-overrides.yaml.
Fixes#27217
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Remove ASPD_SCALE_NSD, ASPD_BETA_NOISE, ASPD_TAS_GATE, ASPD_BETA_GATE as these
are never changed in practice. Keep ASPD_WIND_NSD and ASPD_TAS_NOISE tunable as
they are relevant for high-altitude (wind NSD) and high-speed (TAS noise) use cases.
* feat: add driver for ADS7128 ADC
* style: used make format
* fix: only read 1 byte in adc_get()
* fix: set correct min/max/def value for VRef
* fix: print i2c address in status
* feat: add threshhold to failures before reset
* feat: add failure_threshhold_count
* style: remove unused variable definition from module.yaml
* fix: removed retry logic from poll functions
* fix: decreased sleep time in probe function
* feat: add driver for ADS7128 ADC
* style: used make format
* fix: only read 1 byte in adc_get()
* fix: changed scheduling logic
* fix: ensure no false values are published
* fix: removed unused variable definition
* style: used make format
* fix: removed merge artifact
* fix: removed some merge artifacts
Integrators can declare read-only parameters in a per-board YAML file:
readonly_params.yaml.
There are two ways to define the read-only params:
- "block": default writable, explicitly list params to be locked
- "allow": default readonly, explicitly list params to be writable
Enforcement is activated by `param lock` in rcS after all startup
scripts have run, so board defaults and airframe scripts can still set
params during init.
The feedback via MAVLink uses the new
MAV_PARAM_ERROR_READ_ONLY as part of the PARAM_ERROR message.