PX4-Autopilot v1.16.0 Release Notes
StablePX4 v1.16 builds on the momentum of v1.15 with significant new features and expanded hardware support thanks to our community contributions. This release introduces bidirectional DShot support sponsored by ARK, a full rover rework with dedicated firmware builds and modular control modes for Ackermann, differential and mecanum rovers, and a switch to Gazebo Harmonic LTS for more reliable simulation. Developers will benefit from the new ROS 2 Message Translation Node for dynamic message versioning and integrated log encryption that embeds decryption keys directly in logs. We also added fresh sensor drivers and board support across our partner ecosystem alongside dozens of improvements in control, estimation and safety. PX4 v1.16 raises the bar for performance and usability. Upgrade today and let us know your feedback on GitHub.
Read Before Upgrading
Please continue reading for upgrade instructions.
Major Changes
- Bidirectional DShot - [Sponsored by ARK] (PX4-Autopilot#23863)
- Rover support rework
- New dedicated firmware build for rovers (airframe IDs 50000–52000)
- Separate modules for Ackermann, differential and mecanum rovers, each with manual, acro, stabilized, position and auto modes
- Shared pure-pursuit guidance library for all rover modules
- Legacy rover position control module deprecated in favor of the new modules
- Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4.
- ROS 2 Message Translation Node to translate PX4 messages from one definition version to another dynamically. (PX4-Autopilot#24113)
- Log Encryption now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file.
Upgrade Guide
- VOXL 2 boards now explicitly set EKF2_EV_CTRL=15 (it had fallen back to 0 globally), so event-based optical flow keeps running (PX4-Autopilot#24648)
- Ethernet static IP changed from 192.168.0.3 to 10.41.10.2 to avoid common network conflicts (PX4-Autopilot#22517)
- SF45 lidar no longer auto-starts on TELEM2—add serial_port: TELEM2 (or your preferred port) in its module config if you still want it there (PX4-Autopilot#24602)
Other changes
Hardware Support
- [New Hardware] Boards: ARK FPV FC (PX4-Autopilot#23830)
- [New Hardware] board: add cuav 7-nano (PX4-Autopilot#23414)
- [New Hardware] add new board corvon743v1 (PX4-Autopilot#24769)
- [New Hardware] boards: bluerobotics: navigator: Add initial support (PX4-Autopilot#24018)
- [New Hardware] boards: add new board micoair743-v2 (PX4-Autopilot#24147)
- [New Hardware] boards: add new board micoair h743 (PX4-Autopilot#23218)
- [New Hardware] boards: Add FMUv6s target (PX4-Autopilot#24512)
- [New Hardware] manifest: Add Skynode S baseboard (PX4-Autopilot#23927)
- [New Hardware] Add Tropic VMU board support (Baseboard for Teensy 4.1) (PX4-Autopilot#23257)
- [New Hardware] boards: add new board X-MAV AP-H743v2 (PX4-Autopilot#23697)
- [New Hardware] 3DR boards: Support for 3DR Control Zero H7 OEM Rev G (PX4-Autopilot#23551)
- [New Hardware] new board support ZeroOne x6 (PX4-Autopilot#23623)
Common
Optical flow scaling factor - SENS_FLOW_SCALE. (PX4-Autopilot#23936).
Reintroduce optional parameter versioning mechanism for airframe maintainers (PX4-Autopilot#22813)
Battery level estimation improvements. (PX4-Autopilot#23205).
- Voltage-based estimation with load compensation now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage.
- Thrust-based load compensation has been removed (along with the
BATn_V_LOAD_DROP
parameters, wheren
is the battery number).
The Position (GNSS) loss failsafe configurable delay (
COM_POS_FS_DELAY
) has been removed. The failsafe will now trigger 1 second after position has been lost. (PX4-Autopilot#24063).Log Encryption now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file. This makes log decryption much easier, as there is no need to download or identify a separate key file. (PX4-Autopilot#24024).
The generic mission command timeout MIS_COMMAND_TOUT parameter replaces the delivery-specific
MIS_PD_TO
parameter. Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires. This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses. (PX4-Autopilot#23960).[uORB] Introduce a version field for a subset of uORB messages (PX4-Autopilot#23850)
Compass calibration disables internal compasses if an external compass is available. This typically reduces false warnings due to magnetometer inconsistencies. (PX4-Autopilot#24316).
Control
[Sponsored by ARK] Bidirectional DShot (PX4-Autopilot#23863)
Make control allocation and actuator effectiveness a non-module-specific library (PX4-Autopilot#24196)
Spacecraft Build and Bare Control Allocator (PX4-Autopilot#24221)
Configurable multicopter orbit-mode yaw via
MC_ORBIT_YAW_MOD
(PX4-Autopilot#23358)Collision prevention now works in manual (acceleration-based) flight mode (
MPC_POS_MODE
) (PX4-Autopilot#23507)
Estimation
EKF2: ellipsoidal earth navigation (PX4-Autopilot#23854)
EKF2: Terrain state (PX4-Autopilot#23263)
ekf2: add mag type init (PX4-Autopilot#23185)
ekf2: Optical flow enabled by default (PX4-Autopilot#23436)
Position-loss failsafe delay removed; triggers 1 s after loss (see Common)
Sensors
Implemented AUAV absolute/differential pressure sensor support (PX4-Autopilot#23656)
Implemented temperature sensor support for INA228 / INA238 (PX4-Autopilot#23639)
Add Ublox ZED-F9P-15B (PX4-Autopilot#22744)
Mag cal: automatically disable internal mags if external ones are available (PX4-Autopilot#24316)
BMP581: Add Bosch BMP581 barometer (PX4-Autopilot#23064)
Murata SCH16T IMU driver (PX4-Autopilot#22914)
ST IIS2MDC Magnetometer driver (PX4-Autopilot#23023)
Include distance sensor in dds topics (PX4-Autopilot#24121)
drivers: magnetometer: mmc5983ma: Add SPI support (PX4-Autopilot#23925)
drivers/magnetometer/ak09916: Add support to AK09915 (PX4-Autopilot#23909)
Add Bosch BMM350 magnetometer (PX4-Autopilot#23362)
Compass calibration now disables internal compass when external unit present, reducing false warnings (PX4-Autopilot#24316)
Simulation
- SIH:
- The SIH on SITL custom takeoff location in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7. (PX4-Autopilot#23363).
- SIH now supports the standard VTOL airframe (PX4-Autopilot#24175).
- Gazebo:
- Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4. The default installer scripts (used for CI) and documentation have been updated. This is required because Garden end-of-life is Nov 2024. (PX4-Autopilot#23603)
- New vehicle model
x500_lidar_2d
— x500 Quadrotor with 2D Lidar. (PX4-Autopilot#22418, PX4-gazebo-models#41). - New vehicle model
x500_lidar_front
— X500 Quadrotor with 1D LIDAR (Front-facing). (PX4-Autopilot#23879, PX4-gazebo-models#62). - New vehicle model
x500_lidar_down
— X500 Quadrotor with 1D LIDAR (Down-facing). (PX4-Autopilot#23879, PX4-gazebo-models#62). - New vehicle model
r1_rover
— Aion Robotics R1 Rover (PX4-Autopilot#22402 and PX4-gazebo-models#21). - New vehicle model
rover_ackermann
— Ackermann Rover (PX4-Autopilot#23383 and PX4-gazebo-models#46). - New vehicle model
x500_gimbal
— Quadrotor(x500) with gimbal (Front-facing) in Gazebo (PX4-Autopilot#23382 and PX4-gazebo-models#47 and PX4-gazebo-models#70). - New vehicle model
quadtailsitter
— Quad Tailsitter VTOL (PX4-Autopilot#23943 and PX4-gazebo-models#65). - New vehicle model
tiltrotor
— Tiltrotor VTOL (PX4-Autopilot#24028 and PX4-gazebo-models#66). - Faster than Real-time Simulation (PX4-Autopilot#24421, PX4-Autopilot#23783)
- PX4-Autopilot#24471: Gazebo: Moving platform
uXRCE-DDS / ROS2
- PX4-Autopilot#24113: Experimental ROS 2 Message Translation Node to translate PX4 messages from one definition version to another dynamically
- dds_topics: add vtol_vehicle_status (PX4-Autopilot#24582)
- dds_topics: add home_position (PX4-Autopilot#24583)
MAVLink
- mavlink_ftp: handle relative paths correctly. (PX4-Autopilot#22980)
- Parameter to always start mavlink stream via USB. (PX4-Autopilot#22234)
- Refactor: MAVLink message handling in one function, reference instead of pointer to main instance (PX4-Autopilo#23219)
- mavlink log handler rewrite for improved effeciency (PX4-Autopilo#23219)
Multi-Rotor
[Multirotor] add yaw torque low pass filter (PX4-Autopilot#24173)
Add gz model for quadtailsitter (PX4-Autopilot#23943)
Allow system-default multicopter orbit mode yaw behaviour to be configured, using the parameter MC_ORBIT_YAW_MOD (PX4-Autopilot#23358)
Adapted the Collision Prevention implementation to work in the default manual flight mode (Acceleration Based) MPC_POS_MODE. (PX4-Autopilot#23507)
VTOL
- vtol_type: Added position feedback to VTOL backward transition. (PX4-Autopilo#23731)
- dds_topics: add vtol_vehicle_status. (PX4-Autopilo#24582)
- vtol: reduce schedule frequency, which causes DSHOT150 problems. (PX4-Autopilo#24727)
Fixed-wing
- Fixedwing: fix wheel controller (PX4-Autopilot#24167)
- FixedWing: allow position control without valid global position (PX4-Autopilot#23520)
- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. PX4-Autopilot#23460
Rover
This release contains a major rework for the rover support in PX4:
- Complete restructure of the rover related documentation.
- New firmware build specifically for rovers.
- New module dedicated to Ackermann rovers:
- The module currently supports manual mode, acro mode, stabilized mode, position mode and auto modes.
- New module dedicated to differential rovers:
- The module currently supports manual mode, acro mode, stabilized mode, position mode and auto modes.
- New module dedicated to mecanum rovers:
- The module currently supports manual mode, acro mode, stabilized mode, position mode and auto modes.
- Added rover-specific firmware build (
50000–52000
) for Ackermann, differential and mecanum rovers - Restructure of the rover airframe numbering convention (PX4-Autopilot#23506). This also introduces several new rover airframes:
- Generic Differential Rover
50000
. - Generic Ackermann Rover
51000
. - Axial SCX10 2 Trail Honcho
51001
. - Generic Mecanum Rover
52000
.
- Generic Differential Rover
- Library for the pure pursuit guidance algorithm that is shared by all the rover modules.
- Simulation for differential-steering and Ackermann rovers in gazebo (for release notes see
r1_rover
androver_ackermann
in simulation). - Deprecation of the
rover position control
module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules.
Infrastructure
- standard_modes: add vehicle-type specific standard modes. (PX4-Autopilot#24011)
- ci: build all upload to releases. (PX4-Autopilot#24020)
- ci: px4-dev container. (PX4-Autopilot#24002)
- ci: workflow for ubuntu 24.04. (PX4-Autopilot#23937)
- ci: add test for Ubuntu 22.04. (PX4-Autopilot#23869)
- ci: try runs-on Dronecode Infra (AWS). (PX4-Autopilot#23574)
- ci: replace build workflows. (PX4-Autopilot#23550)