APX4 3.0.5
Please use Auterion Mission Control 1.29 or newer with this version of APX4.
Attention: Default disarmed PWM was changed from 900us to 1000us! See PX4 v1.14 release notes.
Major changes
Improved ROS 2 Interface thanks to uXRCE-DDS. This enables the use the Auterion SDK to build advanced flight control capabilities in ROS 2.
Added helicopter support
APX4 is based on the open-source PX4 release v1.14. See here for detailed release notes for 1.14.
Below are the changes made on top of v1.14.
What's new
General
Mission feasibility checks: check if mission items fit to the current vehicle type
Add magnetometer thermal calibration/compensation
Factory calibration: do not store _PRIO parameters
Arming checks: disallow arming via parameter
Commander: add warning for imminent navigation failure
Enable arbitrary Euler angle for magnetometer rotation
Battery preflight check: add new battery threshold for arming (COM_ARM_BAT_MIN)
Add option to configure action when wind limit is exceeded (COM_WIND_MAX_ACT)
Disarm if battery failure is detected during spool-up
Add option to enable stick gesture to "kill" vehicle
Sensors / State estimation
EKF2: new vision attitude error filter
Add magnetometer inclination check
Add auxiliary global position fusion option
Added support to reset vehicle position based on external position. This can be useful in GPS denied conditions where the operator can recognize the current position by looking for landmarks in the video stream.
Add SF30/D Lightware laser distance sensor
Copter
Helicopter: add tail servo support
Coaxial Helicopter Support
Add "Slow Position Mode" feature. This mode is similar to position mode but allows you to change the speed of the drone. This can be very useful during inspections where the operator wants to make very small maneuvers while inspecting an object.
Add option for throw launch
Fixed-wing / VTOL
Tiltrotor VTOL back-transition: expose tilting time as parameter
Added Performance model for fixed-wing to improve controller stability when flying with varying payload weights or in different altitudes
Optionally disable SF1xx sensor in VTOL fixed-wing flight phase
Rover
Add Roboclaw ESC driver
Differential drive for Rover & Gazebo R1 Rover port
What improved
General
Micro-XRCE-DDS-Client improvements
Fix geofence when changing altitude through reposition
Improvement: Default motor PWM limits minimum 1100 maximum 1900
Documentation can be found here
Attention: Default disarmed PWM was changed from 900us to 1000us!
Geofence: Disable pre-emptive geofence predictor by default
GNSS-denied workflow: Allow auto modes with local position estimate if global origin is set manually
Don't allow external reposition commands without a mode switch, and ensure old reposition commands are not erroneously set
Geofence: if armed, do not allow to upload a fence that would trigger a geofence breach immediately
Geofence: do not allow to upload a fence that doesn't include Home (to ensure that RTL to Home is always possible)
Navigator: prevent race condition when receiving multiple commands at once
Sensors / State estimation
Optical flow: general improvements
Yaw estimator improvements
Improve yaw emergency estimator convergence
Yaw estimator: use gyro bias from EKF2 if at rest
Magnetometer preflight check: report strength and inclination values in case of failure
EKF2: improve resilience against incorrect magnetometer data
Robustify range finder kinematic consistency check
Terrain estimator: handle EKF2 height reset
Improve EKF2 stability by switching to an error-state Kalman filter
Sensors: add parameter to silence IMU clipping (SENS_IMU_CLPNOTI)
Multi GNSS fallback improvements
Copter
Respect spool-up time in Stabilized mode and have zero throttle while still landed
Fix helicopter actuator saturation logic
Fix multicopter altitude change sometimes not linear between two waypoints
Fix FlightTaskAuto: harden line following logic (only do line following if previous and current setpoints are not equal).
Yaw handling improvements/simplifications, e.g. remove waypoint yaw acceptance requirement if weather vane is enabled
Beginner/tuning friendly Acro mode defaults
Fixed-wing / VTOL
Replace old implementation of "uncommanded descend quad-chute" (VT_QC_ALT_LOSS and VT_QC_T_ALT_LOSS)
Fixed-wing: Always establish loiter around current position when switching into Hold mode
VTOL: scale transition airspeed threshold with configured vehicle weight and air density
Fixed-wing/VTOL: High wind controller hardening
Rework figure eight joining logic
Add guidance fallback for corner cases without valid wind estimates
Make airspeed sensor configuration easier and consistent with other sensors
VTOL Tailsitter: add automatic pitch ramps in transition also in Stabilized mode
TECS throttle gains renames and defaults reduction
VTOL: treat Descend mode like Land mode for pusher/tilt assist
Fixed wing autotune improvements
Parameter Changes Compared to APX4 2.7
Removed Parameters
CBRK_RATE_CTRL
All
Deemed not necessary anymore.
CBRK_VELPOSERR
All
Deemed not necessary anymore.
COM_ARM_ARSP_EN
VTOL, FW
Deemed not necessary anymore after airspeed preflight check changes.
COM_ARM_WO_OBLOG
All
Allow arming without onboard logger being enabled and in ready state.
COM_OBL_ACT
All
Commander state machine rewrite.
COM_RC_DARM_A_H
All
Disarm gesture rework.
EKF2_REQ_MAG_H
All
Required mag health time rework.
FD_BAT_EN
All
State machine rewrite: now battery health is always checked.
FW_ECO_AD_THRLD, FW_ECO_ALT_ERR_O, FW_ECO_ALT_ERR_U, FW_ECO_ALT_MIN FW_THR_MAX_E FW_T_ALT_TC_E FW_T_CLMB_R_SP_E FW_T_SPDWEIGHT_E
VTOL, FW
Removal of ECO flight mode (deemed not necessary anymore).
FW_L1_DAMPING FW_L1_PERIOD FW_L1_R_SLEW_MAX FW_USE_NPFG
VTOL, FW
Replace L1 guidance with NPFG, deprecate L1.
FW_T_SPD_OMEGA FW_T_TAS_R_TC
VTOL, FW
TECS rework, params not required anymore.
GF_ALTMODE GF_COUNT
All
Remove outdated features during a general geofence rework.
LNDMC_ALT_MAX
MC, VTOL
Not deemed necessary anymore.
MAV_ODOM_LP
All
EKF2: EV overhaul and position fusion
MIS_DIST_WPS
All
Deemed not necessary anymore.
MNT_MAV_SYSID
All
Mavlink System ID of the mount: not needed anymore
PWM_AUX_RATE PWM_MAIN_RATE SYS_CTRL_ALLOC VT_FW_MOT_OFFID VT_IDLE_PWM_MC VT_MC_ON_FMU VT_MOT_ID MOT_ORDERING
All
Deprecated with switch from static mixing to control allocation.
TF_TERRAIN_EN
All
Removed feature (terrain follower in RTL).
VT_B_DEC_FF
VTOL
Not needed functionality, P gain is enough.
VT_B_REV_DEL VT_B_REV_OUT
VTOL
Not needed functionality, not implemented with new control allocation.
RTL_HDG_MD
MC
Deemed not necessary anymore.
SYS_USE_IO
All
Not needed anymore.
New Parameters
CAL_MAGx_ROLL/PITCH/YAW
All
Enable arbitrary Euler angle for Mag rotation.
COM_ARMABLE
All
Disallow arming via a parameter.
COM_ARM_ODID
All
Enable Drone ID system detection and health check
COM_THROW_EN COM_THROW_SPEED
MC
MC throw launch
EKF2_AGP_CTRL, EKF2_AGP_DELAY, EKF2_AGP_GATE, EKF2_AGP_NOISE
All
Aux global position (AGP) sensor aiding.
EKF2_GRAV_NOISE
All
Gravity observation.
EKF2_GYR_B_LIM
All
Gyro bias limit
EKF2_OF_QMIN_GND
All
Optical flow data quality metric threshold.
FW_ACRO_YAW_EN
FW, VTOL
Parameter to enable yaw rate controller in Acro
FW_AT_MAN_AUX
FW, VTOL
Enable/disable auto tuning using an RC AUX input
FW_MAN_YR_MAX
FW, VTOL
FW attitude controller: add option to disable yaw rate input
FW_PR_D, FW_RR_D, FW_YR_D
FW, VTOL
D gains for fixed-wing rate controller.
FW_T_SPD_DEV_STD, FW_T_SPD_PRC_STD, FW_T_SPD_STD
FW, VTOL
TECS rework
IMU_GYRO_DNF_MIN
All
IMU gyro dynamic notch filter minimum frequency
MAN_KILL_GEST_T
ALl
Stick gesture to kill
MPC_YAWRAUTO_ACC
MC
Heading acceleration. Only applies to Goto Setpoints atm.
MPC_LAND_RADIUS
MC, VTOL
Landing nudging radius
RTL_APPR_FORCE
VTOL
RTL force approach landing
SENS_IMU_CLPNOTI
All
IMU notify clipping
UXRCE_DDS_DOM_ID UXRCE_DDS_KEY UXRCE_DDS_PTCFG UXRCE_DDS_SYNCC UXRCE_DDS_SYNCT
All
Micro XRCE-DDS configuration
Features with Renamed Parameters
COM_DR_EPH
COM_POS_LOW_EPH
GNSS-denied navigation (feature has been re-worked)
No
EKF2_HGT_MODE EKF2_BARO_B_EN
EKF2_HGT_REF
EKF2 multiple height sources fusion
No
EKF2_RNG_AID
EKF2_RNG_CTRL
EKF2 multiple height sources fusion
No
EKF2_AID_MASK
EKF2_DRAG_CTRL EKF2_OF_CTRL EKF2_GPS_CTRL EKF2_IMU_CTRL EKF2_EV_CTRL
EKF2 multiple height sources fusion
Yes
FW_DTRIM_P_FLPS FW_DTRIM_P_SPOIL FW_DTRIM_R_FLPS
CA_SV_CS${i}_FLAP CA_SV_CS${i}_SPOIL
Flap & Spoiler Handling rework
No
FW_L1_PERIOD
NPFG_PERIOD
Replacement of L1 by NPFG
No
FW_L1_R_SLEW_MAX
FW_PN_R_SLEW_MAX
Replacement of L1 by NPFG
Yes
POSSLOW_DEF_HVEL
POSSLOW_DEF_VVEL
POSSLOW_DEF_YAWR
POSSLOW_MAP_HVEL
POSSLOW_MAP_VVEL
POSSLOW_MAP_YAWR POSSLOW_MIN_HVEL
POSSLOW_MIN_VVEL
POSSLOW_MIN_YAWR
MC_SLOW_DEF_HVEL MC_SLOW_DEF_VVEL MC_SLOW_DEF_YAWR MC_SLOW_MAP_HVEL MC_SLOW_MAP_VVEL MC_SLOW_MAP_YAWR MC_SLOW_MIN_HVEL MC_SLOW_MIN_VVEL MC_SLOW_MIN_YAWR
Rework of MC slow mode
No
RWTO_L1_PERIOD
RWTO_NPFG_PERIOD
FW runway takeoff
No
VT_FW_DIFTHR_SC
VT_FW_DIFTHR_S_P VT_FW_DIFTHR_S_R VT_FW_DIFTHR_S_Y
VTOL differential thrust in FW
No
VT_PSHER_RMP_DT
VT_PSHER_SLEW
Pusher throttle ramp up slew rate
Yes
VT_QC_HR_ERROR_I
VT_QC_ALT_LOSS
Quad-chute uncommanded descent threshold
Yes
COM_RCL_ACT_T COM_BAT_ACT_T
COM_FAIL_ACT_T
Commander state machine rewrite
No
NAV_FT_ALT_M NAV_FT_DST NAV_FT_FS NAV_FT_RS NAV_MIN_FT_HT
FLW_TGT_ALT_M, FLW_TGT_DST, FLW_TGT_FA, FLW_TGT_HT, FLW_TGT_MAX_VEL, FLW_TGT_RS
Rewrite of flight task follow target
No
COM_PREARM_ODID
COM_ARM_ODID
Open Drone ID
Yes
FW_ARSP_MODE
FW_USE_AIRSPD
Rework airspeed configuration
Yes
CBRK_AIRSPD_CHK
SYS_HAS_NUM_ASPD
Rework airspeed configuration
Yes
FW_T_THR_DAMP
FW_T_THR_DAMPING
TECS rework
No
FW_T_I_GAIN_THR
FW_T_THR_INTEG
TECS rework
No
Parameters with Changed Defaults
COM_ARM_HFLT_CHK
0
1
Enable hardfault log check
COM_ARM_MAG_ANG
45
60
Relax threshold for magnetic field inconsistency between units that will allow arming
COM_LOW_BAT_ACT
0
2
Automatic return/land in battery empty case
COM_RC_STICK_OV
12
30
Increase threshold for stick override
EKF2_EVA_NOISE
0.05
0.1
Increase measurement noise for vision angle observations
EKF2_MAG_YAWLIM
0.25
0.2
Reduce yaw rate threshold for 3D magnetometer fusion
EKF2_WIND_NSD
0.02
0.05
Increase wind process noise
FW_AIRSPD_MAX
20
25
Increase max airspeed limit
FW_WR_IMAX
1
0.4
Reduce max integrator value of wheel controller
GF_PREDICT
1
0
Disable predictive geofence feature
MC_ACRO_EXPO MC_ACRO_EXPO_Y
0.7
0
Disable Acro stick expo
MC_ACRO_P_MAX MC_ACRO_R_MAX
720
100
Reduce max Acro roll/pitching rate
MC_ACRO_SUPEXPO MC_ACRO_SUPEXPOY
0.7
0
Disable Acro stick super expo
MC_ACRO_Y_MAX
540
100
Reduce max Acro yawing rate
MPC_ALT_MODE
0
2
Set default to terrain following
SENS_GPS_MASK
0
7
Use speed, hpos and vpos accuracy for multi GPS blending logic
SENS_MAG_AUTOCAL
0
1
Automatically initialize magnetometer calibration from bias estimate
SENS_MAG_MODE
0
1
Publish primary magnetometer
VT_B_TRANS_DUR
8
10
Increase max VTOL backtransition duration
Last updated