APX4 3.3.5

Please use Auterion Mission Control 1.37 or newer with this version of APX4.

What's New

General

  • Remote control driver overhaul

  • Do not publish any MAVLink standard mode to work around an incompatibility of MAVLink mode enumeration. This enables backwards compatibility of this APX4 version with older Auterion Mission Control versions. Side effect: for fixed-wing flight, the manual GPS-assistend flight mode is labelled as "Position" instead of "Cruise" again on AMC. Mode enumeration compatibility with AMC 1.36, AMC 1.37, AMC 1.38

  • Automatically disable all internal magnetometers just after calibration if an external one is available. Removes false magnetometer warnings, and prevents poor fallback on internal magnetometer behavior during flight.

  • Add message translation node for ROS. This ensures that ROS 2 applications that were compiled with different versions of PX4 messages can interwork with newer version of PX4, and vice versa.

  • Add RC termination switch. Compared to the kill switch termination is irreversible, keeps on logging, outputs potentially customized failsafe instead of disarmed values on all outputs and triggers any type of parachute.

  • Add COM_MODE_ARM_CHK parameter to allow mode registration while armed. Brings convenience for developers during simulation.

  • Add support for Skynode N.

  • Add optical flow sensor check to ensure it's present if the vehicle requires so.

  • Add MAVLink stream mode LOW_BANDWIDTH with reduced message rates for long-range low-bandwidth radio links.

  • Add return to land type RTL_TYPE option to automatically either continue the mission until the planned landing or reverse the mission path depending on whichever is closer in terms of mission items.

  • Add parameter COM_DLL_EXCEPT to specify the flight modes in which datalink loss is ignored and the corresponding failsafe action is not triggered.

  • Allow a mission item to execute a MAV_CMD_COMPONENT_ARM_DISARM command to disarm the vehicle if it detected to be landed.

  • Introduce the by default enabled SYS_HF_MAV parameter, which allows the latest hardfault log to be streamed over MAVlink instead of just saved to the SD card, which might get inaccessible.

  • Introduce battery_info uORB message for static data (serial number) compatible with UAVCAN, MAVLink and drivers.

  • Introduce the MAV_S_MODE parameter, similar to MAV_1_MODE, to configure the mode of the MAVLink instance used by PX4 for communication with AuterionOS.

  • Introduce a COM_RCL_EXCEPT option to suppress failsafe activation on manual control loss in external modes. Be careful because this also applies to those that require stick input.

  • Add a COM_RC_IN_MODE option to prioritize RC or MAVLink joystick and immediately switch to the prioritized source when it becomes available.

  • Add a parameter SDLOG_BACKEND to disable logging onto the SD card independently of log streaming to AuterionOS and Auterion Suite. This allows for encrypted streaming of sensitive log data without storing it unencrypted on the autopilot SD card.

  • Add "secure mode" using the parameter: COM_SEC_MODE_EN.In secure mode the vehicle will delete information relating to the ground station position after landing. It consists of:

    • Deleting prior home position

    • Deleting the mission

    • Deleting land approaches

    • Resetting local position origin

    • Disabling the serial console

Sensors / State Estimation

  • Run simplified GNSS checks after initial fix. Reduces the chance for unnecessary rejection of GNSS sensors in air, while keeping the preflight checks tight.

  • Add fallback method in the barometer-sensor-selection, based on the estimator-status of the baro-fusion. This will make the estimator switch to a second barometer when the primary one is faulty.

  • Barometer offset calibration based on GNSS height.

  • Add support for Septentrio GPS.

  • Battery module: report temperature.

  • Add UAVCAN node accelerometer and gyroscope publishers: CANNODE_PUB_IMU, UAVCAN_SUB_IMU

  • Add ASPD_FALLBACK to select synthetic airspeed options as fallback for no remaining valid airspeed sensor.

  • Adjust home position altitude after GNSS altitude correction in flight. Fixes vehicle not slowing down during landing, or slowing down too early.

  • Add GPS_CFG_WIPE option to wipe U-blox GPS flash. This change ensures a clean and consistent configuration by wiping the FLASH on boot, preventing issues from leftover settings.

  • GNSS reset improvements. This allows for avoiding position resets during crude GNSS spoofing. See param EKF2_GPS_MODE.

  • Auxiliary global position (AGP) reset improvements. This allows us to avoid position resets during faulty AGP position measurements. See EKF2_AGP_MODE.

Copter / VTOL (Hover)

  • Introduce helicopter main rotor RPM sensing and control.

  • Add yaw torque low pass filter to filter out amplified high-frequency torque setpoint. Reduce the inertia wheel effect by low-passing the yaw torque setpoint. This allows higher yaw rate gains and reduces vibrations. New param: MC_YAW_TQ_CUTOFF

  • To reduce latency between yaw stick input and live video in position slow mode, yaw stick input is applied to the gimbal setpoint directly and the vehicle will follow the gimbal's orientation.

Fixed-wing / VTOL plane (Cruise)

VTOL

Rover

  • Various improvements, please have a look at the rover guide.

What Improved

General

  • rpm_capture: add rpm capture driver, publishing to the rpm topic.

  • Don't accept out of range MAVLink joystick input. Fixes: support for 3-axis joystick.

  • PWM ESC protocol robustification on autopilot soft reboot.

  • DDS robustness improvements.

  • Handle mode change rejection the same for RC and MAVLink.

  • Fix parachute trigger. Ensure only the force_failsafe flag is set, without lockdown, so that the parachute can still be triggered.

  • On mission resume immediately apply speed change.

  • Increase the maximal number of mission items for Skynode X and S.

  • Do not start Mavlink on external UART ports by default.

  • Don't reset home position if landed during a (uncompleted) mission.

  • Fix ADSB heading angle obtained from driver which was in some cases off by 180°

  • Never clear link loss failsafe automatically, also not when the failsafe is Hold.

  • Make failsafe handling more robust:

    • do not trigger obsolete failsafe when deactivating failsafe deferring

    • set failsafe action state immediately after failsafe update

    • only clear hold delay when failsafes are being deferred

  • Only trigger MAVLink parachute on termination.

  • Delay the neutral gimbal command during flight mode transitions to ensure proper command sequencing and execution.

Multicopter/VTOL in Hover

  • Handle EKF position reset properly in Position mode.

  • Smoother yaw by limiting the angular acceleration.

    • Also used in Orbit to avoid steps during the initial circle approach.

  • Fix to not amend NAN (disarmed) output values with non-zero THR_MDL_FAC.

  • Address corner case for altitude setpoint jumps when moving vertically with terrain distance lock. Fixes: unexpected altitude change when varying throttle stick input while vertically descending in Position mode.

  • Altitude hold with distance sensor: Only lock distance once vertical speed is low. Fixes: The drone stopping its vertical motion first and then descending again to the distance-lock height.

  • RTL fast reverse: enable precision landing. Precision landing is only initiated if RTL_PLD_MD is enabled, including in reverse mission RTL. Fixes: precision landing was always triggered in RTL direct mode, regardless of settings.

  • Use valid hover throttle estimate for center stick position in Stabilized mode.

  • Remove limiting of nudging speed based on distance sensor.

  • Improve behavior of nudging during autonomous landing.

  • Fix reverse mission RTL's unsteady landing due to wrong waypoint type assigned for landing.

  • Use PX4 default ublox GNSS dynamic model (<2g) also for multirotors (previously <1g). Fixes estimation issues when doing erratic high thrust maneuvers.

  • Lower default roll and pitch attitude gains from 6.5 to 4. Fixes default tuning for >450mm size vehicles.

  • Collision Prevention Scale obstacle distance with vehicle attitude for varying sensor orientations.

  • FlightTaskOrbit: replace hardcoded 10m/s maximum speed with multicopter speed configuration.

  • Fix race condition on trajectory setpoint when entering a failsafe event, resulting in a twitch.

Fixed-wing/VTOL in fixed-wing

  • Fix wheel controller

  • Do not use an invalid groundspeed for land detection. Fixes: Invalid speed estimation used for "takeoff detected".

  • FW land detector: Introduce max rotational speed condition (new param: LNDFW_ROT_MAX).

  • Remove EKF2_GPS_CHECK custom FW setting.

  • Scale static trim offsets with airspeed. Fixes: Trim is constant for the whole airspeed range, and does not create higher torque when flying faster.

  • FW land detector: only force to landed if launch detection is not yet triggered. Fixes: Vehicle staying "landed" during the whole launch sequence.

  • Autotune: Fix failure and abort on first try.

  • Enable yaw rate controller when feeding in yaw rate setpoints outside of manual control. Fixes: Enabling FW_ACRO_YAW_EN was previously required to have yaw rate control while being in an external flight mode.

  • Fixed altitude hold for auto fixed-bank loiter after a loss of navigation before descending.

VTOL only

  • Keep high deceleration when overshooting the transition target.

  • Set altitude acceptance radius to infinity when moving to land point after transition. Fixes: unnecessary climbs in hover mode due to dropping altitude during transition to hover.

  • Remove fixed-wing condition from airspeed and side-slip fusion condition - enables airspeed and side-slip fusion to begin during transition already.

  • Add VTOL takeoff feasibility check.

  • Reduce schedule frequency, which fixes DSHOT150 problems.

Driver/State Estimation

  • BatteryCheck: separate event messages for low, critical and emergency battery states.

  • Improvements on stability and performance of GNSS-denied flying with optical flow.

  • SF45 range sensor driver improvements.

  • Accelerometer calibration respect rotation. Fixes: External IMU calibration.

  • INA238 power module retry if read fails.

  • Fix corner case in preflight failure reporting.

  • Quick calibration now supports mag too.

  • Fix GPS RTCM instance selection.

  • Robustify Ulanding Radar.

  • ADS1115 power module driver improvements.

  • GNSS-denied improvements

    • consider GNSS velocity as horizontal velocity aiding

    • Introduce global_position_relaxed for less accuracy requirements

    • allow manual position reset when horizontal aiding is active

    • reset manual position update through fusion to not require a state reset

  • GPS Dump timeout increase + GPS overflow fix

  • GNSS spoofing warning sensitivity adjustment. Fixes: Remove multiple reporting and oversensitivity.

  • GPS: Parse RTCM3 & NAV in parallel.

  • Publish RTCM stream telemetry also for UAVCAN GNSS receivers. Fixes: Not visible if and at what rate the RTCM injection works on GNSS receivers that are connected via UAVCAN.

  • More accurate unaided yaw calculation.

  • Tilt estimation improvements.

  • Do not let magnewtometer heading and declination update the gyroscope biases.

  • Never skip post-takeoff magnetometer yaw reset.

  • ADIS16507 IMU: enhance driver to handle and recover from all failure modes.

  • INA228/INA238 power module: various improvements.

  • BMP388 barometer: retry initialization to make startup more robust.

  • IIS2MDC magnetometer: Help device detection by retrying probing.

  • Battery-monitoring: allow disabling analog battery monitoring through BAT{i}_V_CHANNEL parameter.

  • Stop GNSS altitude and velocity aiding when gnss_fault is set.

What Got Removed

  • Remove DSHOT 1200

  • Remove LIS2MDL driver from source

  • Wheel controller fixed-wing: remove waypoint tracking, only hold heading.

  • Remove Vtrantech VCM1193L from common magnetometer

  • Remove COM_POS_FS_DELAY

Parameter Changes Compared to APX4 3.2.14

Rover parameters are excluded from this list.

Removed Parameters

Parameter Name
Affecting
Reason

COM_OBS_AVOID

MC

Removed avoidance functionality.

COM_POS_FS_DELAY

All

No deemed needed anymore.

EKF2_RNG_A_IGATE

All

Unused.

GND_SPEED_THR_SC

Rover

Deprecated old rover position controller.

MIS_PD_TO

All

substituted by MIS_COMMAND_TOUT

NPFG_EN_MIN_GSP, NPFG_GSP_MAX_TK, NPFG_TRACK_KEEP, NPFG_WIND_REG

VTOL, FW

Removed alternative guidance laws

RWTO_HDG, RWTO_NPFG_PERIOD

FW

Removed waypoint following while on runway takeoff. Instead always do heading control.

New Parameters

Parameter Name
Affecting
About

COM_DLL_EXCEPT

All

Datalink loss exceptions

COM_DLL_NAV_CTL

VTOL, FW

Reset estimator fusion control settings on link loss. When losing the data link connection to the vehicle, it may be desirable to re-enable or disable specific estimator fusions (GNSS, AGP) such that the vehicle can continue fully autonomously

COM_MODE_ARM_CHK

All

Allow external mode registration while armed

COM_SEC_MODE_EN

All

In secure mode the vehicle will delete information relating to the GCS position after landing.

EKF2_AGP_MODE

All

Auxiliary global position (AGP) sensor aiding

EKF2_GPS_MODE

All

Fusion reset mode. Automatic: reset on fusion timeout if no other source of position is available. Dead-reckoning: reset on fusion timeout if no source of velocity is available

FW_AIRSPD_FLP_SC

FW

Airspeed scale with full flaps

GPS_CFG_WIPE

All

Wipes the flash config of UBX modules

MC_SLOW_MAP_PTCH

MC

RC_MAP_AUX{N} to allow for gimbal pitch rate control in position slow mode

MC_YAW_TQ_CUTOFF

MC

Low pass filter cutoff frequency for yaw torque setpoint

MIS_COMMAND_TOUT

All

Timeout to allow the payload to execute the mission command.

RC_MAP_TERM_SW

All

Termination switch channel.

RC_PAYLOAD_MIDTH

All

Make payload power switch an optional 3-way switch.

SDLOG_BACKEND

All

Logging bBackend (integer bitmask). Allows to disable logging on SD card.

SENS_BAR_AUTOCAL

All

Barometer auto calibration

SYS_HAS_NUM_OF

All

Number of optical flow sensors required to be available

CA_HELI_RPM_I, CA_HELI_RPM_P, CA_HELI_RPM_SP

Helicopter

Helicopter RPM controller.

CA_MAX_SVO_THROW

Helicopter

Throw angle of swashplate servo at maximum commands for linearization.

ICE_ON_SOURCE, ICE_CHOKE_ST_DUR, ICE_STRT_DUR, ICE_MIN_RUN_RPM, ICE_STRT_ATTEMPT, ICE_RUN_FAULT_D, ICE_STRT_THR, ICE_STOP_CHOKE, ICE_THR_SLEW, ICE_IGN_DELAY

FW

Add support for internal combustion engine.

LNDFW_ROT_MAX

FW

Fixed-wing land detector: max rotational speed. Only used if neither airspeed nor groundspeed can be used for landing detection.

MAV_S_MODE

All

MAVLink Mode for SOM to FMU communication channel

BMM350_AVG, BMM350_DRIVE, BMM350_ODR

All

BMM350 magnetometer support.

SENS_DPRES_REV

FW, VTOL

Reverse differential pressure sensor readings.

SENS_EN_AUAVX

FW, VTOL

Amphenol AUAV differential / absolute pressure sensor.

RC_DSM_PRT_CFG, RC_GHST_PRT_CFG, RC_SBUS_PRT_CFG

All

New standalone RC input driver.

RPM_CAP_ENABLE, RPM_PULS_PER_REV

All

PM capture enable.

UAVCAN_ESC_IFACE

All

Which CAN interfaces to output ESC messages on

Renamed Parameters

Old Name
New Name
About

ASPD_FALLBACK_GW

ASPD_FALLBACK

Controls the failback behavior in case of detected airspeed failure

Parameters with Changed Defaults

Parameter Name
Old Value
New Value
About

COM_FLTT_LOW_ACT

3

0

Disable "flight time low" failsafe action by default.

EKF2_RNG_FOG

1

3

Reduce likelihood for false-positive range sensor blockage detection.

ASPD_WERR_THR

0.55

2

Use the wind speed estimate up to higher inaccuracy for ground-minus-wind airspeed estimate

IMU_DGYRO_CUTOFF

30

20

More appropriate for most vehicles.

MPC_YAWRAUTO_ACC

60

20

adjust yaw acceleration and maximum rate for exclusive use with HeadingSmoothing

MPC_YAWRAUTO_MAX

45

60

adjust yaw acceleration and maximum rate for exclusive use with HeadingSmoothing

MC_PITCH_P, MC_ROLL_P

6.5

4

More appropriate default gains for most vehicles. 6.5 is only appropriate for smaller vehicles.

Parameters with Changed Interpretation

Parameter Name
Old Interpretation
New Interpretation
About

COM_POS_FS_EPH

Threshold for triggering navigation failure for all vehicle types.

Only used for multicopters and VTOLs in hover mode.

Last updated