* feat(crsf_rc): add CRSF receiver bind command
Add ability to initiate CRSF receiver binding from QGroundControl or
the NSH console. When MAV_CMD_START_RX_PAIR is received with
RC_TYPE_CRSF, the driver sends the CRSF bind command frame over UART.
Binding is rejected when armed or on singlewire configurations.
Also adds RC_TYPE and RC_SUB_TYPE constants to VehicleCommand.msg and
replaces magic numbers in DsmRc and RCInput drivers.
Based on PX4/PX4-Autopilot#23294.
* style(crsf_rc): use C++ style comment
* style(crsf_rc): zero-init vcmd, remove noisy comments, drop unused enum value
* fix(rc): check write return value in BindCRSF, guard Spektrum bind against invalid sub-type
* fix(rc): warn and deny invalid Spektrum bind sub-type
Previously, an unrecognized param2 sub-type would silently leave
dsm_bind_pulses at 0 and return the generic UNSUPPORTED ACK. Add an
explicit else-branch that logs a PX4_WARN and returns DENIED so users
get clear feedback in QGC.
Set CONFIG_STM32H7_DTCMEXCLUDE=y on the four STM32H7 ARK boards
(fmu-v6x, fmu-v6s, fpv, pi6x) so DTCM is no longer part of the kernel
heap. Stacks and dynamic buffers can otherwise land in DTCM, which AHB
DMA masters (SDMMC IDMA, MDMA, BDMA, DMA1/2) cannot access, causing file
operations to fail with EIO/ETIMEDOUT.
Refs PX4/PX4-Autopilot#27242.
An empty mission is the normal "no mission loaded" state, not a rejected
mission. check_mission_valid() runs in the background whenever its trigger
conditions change, so logging this as a critical mavlink/event spammed
QGC even when the pilot was not in mission mode and had no mission on
board. The commander already surfaces auto_mission_missing through the
arming checks when mission mode is actually requested.
The committed ark_fmu-v6s_bootloader.bin was built before BOARD_TYPE was
set to 61 in src/hw_config.h, so it advertises board id 57 (the v6x id)
to px_uploader. Uploading any v6s firmware then fails with:
Board mismatch: No suitable firmware for board 57 (available: [61])
Rebuild the bootloader from the current source so the binary reports
board id 61 and matches firmware.prototype.
* chore(boards): copy ark/fmu-v6x to ark/fmu-v6s
Verbatim copy of ark/fmu-v6x board support to ark/fmu-v6s to
establish a baseline. Functional changes will follow in the next commit.
* feat(boards): add ark/fmu-v6s board support
Low-cost variant of ARK V6X with:
- STM32H743IIK6 MCU (no hardware crypto)
- Single IIM-42653 IMU on SPI1 (SPI2/SPI3 removed)
- IIS2MDC magnetometer on I2C4
- BMP390 barometer on I2C4
- Single sensor power rail
Board ID 61, USB PID 0x003C.
* feat(px4_uploader): add ARK FMU v6s USB ID to the uploader
* refactor: rename SENS_IMU_TEMP to HEATER1_TEMP in rc.board_defaults
* refactor: remove unused ADC channel definitions in board_config.h
* refactor: update ADC channel definitions and remove unused sensor power control
* arkv6s sensor roations
* Add support for Murata SCH16T IMU in default.px4board configuration
* Update bootloader binary for FMU v6s
* Update boards/ark/fmu-v6s/src/hw_config.h
Co-authored-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com>
* Update boards/ark/fmu-v6s/src/hw_config.h
Co-authored-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com>
* fix(ark/fmu-v6s): enable CONFIG_CRYPTO for encrypted_logs build
CONFIG_CRYPTO_RANDOM_POOL was set without its parent CONFIG_CRYPTO,
so it was silently dropped and px4_get_secure_random was compiled out,
breaking the ark_fmu-v6s_encrypted_logs link.
---------
Co-authored-by: alexklimaj <alex@arkelectron.com>
Co-authored-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com>
I2CBusIterator::external() was returning px4_i2c_bus_external(_bus),
where _bus is the constructor filter argument (the user's -b value,
which defaults to -1 when no bus is specified). When a driver was
started with -I and no -b (e.g. iis2mdc -I start, bmp388 -I start),
_bus stayed -1, px4_i2c_bus_external(-1) fell through to its "not
found" fallback that returns true, and the boot log printed
"on I2C bus 4 (external)" for sensors sitting on an internal bus.
Pass bus().bus instead so the result reflects the bus the iterator
is currently positioned on. This mirrors SPIBusIterator::external()
and restores the pre-8080ca966a8 semantics.
Device::external() (the override used by sensors status and
calibration) already used the device id's bus number, so only the
boot-time print was wrong.
Signed-off-by: Jacob Dahl <dahl.jakejacob@gmail.com>
Coverage overlaps with mavsdk_tests on iris (mission + offboard
posctl); MAVROS plugin behavior belongs to the MAVROS project.
Drops the workflow, .test launchers, rostest_px4_run.sh, and the
integrationtests/ python helpers.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
* docs(releases): draft v1.17.0 release notes
Drafts the v1.17.0 release notes based on commits in the
release/1.16..release/1.17 diff, with every PR citation verified as an
ancestor of release/1.17 and not shared with release/1.16.
Major Changes leads with the experimental MC Neural Network Control
mode and the on-device TFLM integration, the new Altitude Cruise mode
for multicopters, FW Takeoff improvements, FW and Rover ROS 2 Control
Interface setpoints, and the in-tree Zenoh middleware maturing toward
rmw_zenoh compatibility.
Hardware Support is reorganized into four sub-groups: New Flight
Controllers, New Build Targets for Existing Hardware, New CAN
Peripherals & Vehicle Platforms, and Existing Boards: Improvements.
The Simulation section is split into Gazebo and SIH sub-groups. The
ROS 2 / DDS section is split into uXRCE-DDS and Zenoh.
Posted on main as a draft to give docs maintainers visibility and
collect review feedback. Backport strategy to release/1.17 (alpha/beta
banner variant vs the stable banner variant on main) is a follow-up
discussion.
Also fixes a long-anchor scroll-restoration bug in
px4_ros2_control_interface.md by giving the FwLateralLongitudinal
heading an explicit short anchor (#fw-lateral-longitudinal-setpoint),
and updates the corresponding link in releases/main.md.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
* docs(releases): address review on v1.17.0 notes
- Cross-link Altitude Cruise in the intro paragraph.
- Reframe MC Neural Network Control as an experimental test path
rather than first-class on-device inference; move it to the bottom
of Major Changes.
- Drop the redundant "opt-in" wording from the Zenoh Major Changes
bullet.
- Rewrite Upgrade Guide as a true upgrade procedure (actionable
numbered steps with what to do and why) following the v1.14 release
notes pattern instead of a flat parameter-delta list.
- Add the missing PR reference for the extended MISSION_CURRENT entry
(#25034, populating the MAVLink mavlink/mavlink#1869 fields).
- Dedupe Safety / Commander against Common: failsafe takeover,
Offboard-to-Position-without-RC, and motor-failure timeout checks
are now listed only once in Common.
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
---------
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Restart the Micro-XRCE-DDS Agent before each integration test so DDS
graph state from a previous PX4 instance does not leak into the next
test.
The MicroXRCEAgent is started once per session, but PX4 reboots between
tests. The Agent retains writer entries from the previous PX4, so when
the new PX4 reconnects, count_publishers() in px4-ros2-interface-lib's
waitForFMU returns >0 immediately against a stale entry. Phase 1
(discovery) returns instantly, then Phase 2 (heartbeat) times out
waiting for a message on a subscription matched to a dead writer.
This is why ModesTest.denyArming (first test) passes while every later
ModesTest fails with "timeout while waiting for FMU heartbeat".
Adds an optional pre_test_hook on test_runner.Tester so ROS-specific
lifecycle stays out of the shared test_runner. The workflow stops
starting the Agent externally; ros_test_runner.py owns the lifecycle.
Refs #27328
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
* feat(gpsRedundancyCheck): add GPS redundancy failsafe with divergence check
- Monitors GPS count and triggers configurable failsafe (COM_GPS_LOSS_ACT) when count drops below SYS_HAS_NUM_GPS
- Tracks online (present+fresh) and fixed (3D fix) receivers separately; emits "receiver offline" vs "receiver lost fix"
- Detects position divergence between two receivers against combined RMS eph uncertainty plus lever-arm separation
- Pre-arm warns immediately; in-flight requires 2s sustained divergence to suppress multipath false alarms
- Adds GpsRedundancyCheckTest functional test suite
New parameters: SYS_HAS_NUM_GPS, COM_GPS_LOSS_ACT
* feat(sensor_gps_sim): publish second GPS instance using SENS_GPS1 lever arm params
When SENS_GPS1_OFFX or SENS_GPS1_OFFY is non-zero, publish a second sensor_gps instance offset by those values from the vehicle position.
fix(sensor_gps_sim): give second instance distinct device_id
Both simulated GPS instances previously shared the same device_id (address 0x00). This prevented testing the device-ID matching path in SITL since both slots would match the same receiver.
* refactor(gpsRedundancyCheck): address code review feedback
* refactor(gpsRedundancyCheck): address code review feedback
* docs: add GNSS check failsafe documentation
Update safety.md and releases/main.md to document the new GNSS check
failsafe (SYS_HAS_NUM_GNSS, COM_GPS_LOSS_ACT) introduced in PX4.
* docs(update): Subedit to taste
* refactor(gps): move GNSS redundancy detection into sensors module
Add GnssRedundancyStatus topic and GnssRedundancyMonitor in
vehicle_gps_position. Commander's gpsRedundancyCheck becomes a thin
consumer of the new topic. Detection lives with blending/fallback in
one module.
Also rename COM_GPS_LOSS_ACT -> COM_GNSS_LSS_ACT.
* docs(safety): clarify GNSS failsafe wording and rename COM_GNSS_LSS_ACT
* refactor(failsafe): consistent default case as fallback for existing option
* Rename COM_GNSS_LSS_ACT -> COM_GNSSLOSS_ACT
for readability
* fix(gnssRedundancyCheck): move logic back into the commander checks and various improvement suggestions
- Rename to GNSS instead of gps
- Use hysteresis
- Small logic refactorings
- Adapt unit tests to different interface
- User reporting on which GPS is offline or doesn't have a fix
* docs(gnssRedundancyCheck): simplify explanations
* refactor(gnssRedundancyCheck): update year numbers in copyright
---------
Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
Co-authored-by: Matthias Grob <maetugr@gmail.com>
* fix(navigator): guard terrain altitude check for position mission items
updateAltToAvoidTerrainCollisionAndRepublishTriplet() calls
get_absolute_altitude_for_item() on the current mission item without first
checking whether the item contains a position.
For non-position mission items, the altitude field has no setpoint meaning.
Using it in the terrain descent condition can make the check operate on an
invalid mission-item altitude.
Add the same item_contains_position() guard used by other mission altitude
handling paths before reading the mission item altitude.
* navigator: remove redundant mission item checks
Remove checks already covered by item_contains_position() and update the
terrain avoidance comment to match the current condition.
* SITL: mavlink bind to a specific interface using an environment variable PX4_NET_INTERFACE
Fixes issue #26384
* document the usage of PX4_NET_INTERFACE
* Improved Docs:
- Added new Environment Configuration subsection at the end of SITL Simulation
- Removed the old Bind MAVLink to Specific Network Interface subsection (content consolidated into the new section)
---------
Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
* EKF2: guard EV position bias updates on active fusion
Horizontal position resets were updating the external vision position bias
estimator even when EV position fusion was not active.
This is the same bug pattern as #27094. In resetAltitudeTo(), the height bias
estimators are only shifted when the corresponding height source is currently
being fused, for example _ev_hgt_b_est is updated only when
_control_status.flags.ev_hgt is true. That guard prevents an inactive EV height
bias estimator from being modified by an EKF state reset.
The horizontal reset paths did not have the equivalent guard. Both
resetHorizontalPositionTo() and resetLatLonTo() unconditionally applied
delta_horz_pos to _ev_pos_b_est. However, controlEvPosFusion() treats
_control_status.flags.ev_pos as the active EV position fusion state, and the
position observation is later computed as:
measurement - _ev_pos_b_est.getBias()
This means a horizontal position reset from another source could shift the EV
position bias estimator while EV position fusion was inactive. When EV position
fusion later resumed, the stale shifted bias could be used in the EV observation
path and produce incorrect innovations.
Only update _ev_pos_b_est during horizontal resets when EV position fusion is
currently active, matching the guarded resetAltitudeTo() behavior fixed by
* Update src/modules/ekf2/EKF/position_fusion.cpp
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
---------
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
AirspeedSource::SYNTHETIC is declared after SENSOR_3, so its integer value is
4 while _airspeed_validator only has MAX_NUM_AIRSPEED_SENSORS entries, with
valid indices 0..2.
select_airspeed_and_publish() only checked whether _prev_airspeed_src was less
than SENSOR_1 before indexing:
_airspeed_validator[prev_airspeed_index - 1]
When _prev_airspeed_src is SYNTHETIC, prev_airspeed_index is 4 and this becomes
_airspeed_validator[3], which is out of bounds. Treat sources above SENSOR_3 as
non-sensor sources so only SENSOR_1..SENSOR_3 can index the validator array.
This fixes the same class of bug as #27232. The external position
reset-by-fusion path explicitly intends to strongly correct correlated
states, including heading, as documented by the existing comment next to
the artificial Kalman gain increase.
However, when VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE is handled in
EKF2::Run(), it runs before _ekf.update(), so heading_observable can
still reflect the previous controlFusionModes() result. If it is false,
clearInhibitedStateKalmanGains() inhibits the intended heading
correction.
Set heading_observable before the external position fusion so the reset
can preserve the documented correction of correlated states. The normal
EKF update path recomputes the flag afterwards.