APX4 3.1.0

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

What's new

General

  • Battery: add automatic internal resistance estimation. This feature is enabled by default and constantly estimates the internal resistance of the connected battery, which in turn is used to improve the battery state of charge (SOC) estimate.

  • Add a mechanism to capture parameter versioning, which can be used to specify in an airframe configuration file whether all PX4 parameters should be reset and reloaded from the airframe configuration file. To use, increase the new parameter SYS_PARAM_VER by 1.

  • Add check for high RAM usage (parameter: COM_RAM_MAX).

  • Navigator: add terrain collision avoidance during descents in Mission and RTL modes using the distance sensor information (parameter: NAV_MIN_GND_DIST).

  • Add maximum height above ground (HAGL) check to all navigator modes to stay in range of a downward looking sensor when operating GNSS-denied. When using a downward looking sensor for navigation (e.g.: optical flow), the EKF sends a height above ground limit that the vehicle shouldn't exceed to avoid a loss of navigation. If a failsafe condition triggers a mode that cannot be executed due to HAGL restrictions, then the system applies the next possible mode (e.g. instead of RTL it would trigger a Land).

  • Commander: Always allow the selection of Land mode. If this mode cannot be executed (e.g. because position estimation is not good) then the controller falls back to Descent mode (descend without lateral position hold).

  • Support receiving the AUX fields of the Manual Control MAVLink message.

Sensors / State estimation

  • Add terrain state to EKF2 which allows to simultaneously use optical flow and distance sensor for altitude, terrain height and velocity estimation.

  • Add support for Septentrio GNSS receiver.

  • EKF2: don't fuse optical flow samples when the current distance to the ground is larger than the reported maximum flow sensor distance.

  • Add spoofing check to the GNSS health checks (system reports spoofing if detected by GNSS driver).

  • Add ability to initialize the wind estimation pre-flight.

  • Preflight checks: extend COM_ARM_WO_GPS with option to disable warning as well

  • Add range blockage detection to catch wrong measurements due to rain or fog (parameter: EKF2_RNG_FOG).

  • Add support for MAVLink message MAV_CMD_EXTERNAL_POSITION_ESTIMATE when in GNSS-denied operation. This message is sent by AMC after the operator manually updates the vehicle's location on the map. Before takeoff it is used to also initialize the vehicle's absolute altitude (to compensate for measurement offset of the barometer).

Copter / VTOL (hover)

  • Landing: limit maximum nudging speed based on distance sensor. Below 50cm no horizontal speed allowed, above allow per meter altitude 0.5m/s more speed.

  • Add "fixed yaw" option to MPC_YAW_MODE .

  • MC position controller: new velocity low pass and notch filter (optional, disabled by default).

  • Smoother landing when triggering a Land while having a high ground speed.

  • Cone RTL: never climb more than to RTL_RETURN_ALT (also applies to VTOL in hover).

Fixed-wing / VTOL (cruise)

  • TECS: allow for faster descend up to maximum airspeed it some threshold above current altitude setpoint. Use pitch control loop to control max airspeed while giving minimal throttle. Disabled by default, set FW_T_F_ALT_ERR to configure altitude error threshold and enable it.

  • Airspeed validator: added new check to catch sensor blockages due to rain faster. The check is called "First principle check" as it compares the rate of change of the airspeed data with the given pitch and throttle and flags it invalid if it is physically unfeasible. Disabled by default, can be enabled in ASPD_DO_CHECKS (requires good TECS tuning to function correctly).

  • Support tighter altitude tracking during low-height flight. If distance to ground (as measured by the distance sensor) is falling below some threshold, reduce the altitude loop time constant and by that make altitude tracking tighter. Disabled by default, set threshold in FW_T_THR_LOW_HGT.

  • Catapult/hand-launch: Constant position aiding while in the pre-launch state to stay in position controlled mode even when experiencing high vibration levels or when drone is moved (assume position doesn't change).

What improved

General

  • MAVLink: support new message BATTERY_INFO, drop support for outdated SMART_BATTERY_INFO.

  • Commander: improve failsafe messaging (change strings) and raise manual control lost event Manual control lost only as Info.

  • px4iofirmware: simplify lockdown logic to fix IO PWM outputting unexpected signal when switching to SIH without re-powering.

  • Battery state of charge estimation: weigh voltage based estimate more compared to integrated-current one when battery volltage is low to reduce likelihood of completely depleting battery if capacity is set wrongly.

  • Mission feasibility checks: only require both or neither of a Takeoff and Landing while landed.

  • MAVLink: fill SYS_STATUS flags for horizontal position and attitude estimate.

  • MAVLink: High latency link improvements.

    • Improve handling of high latency link lost/regained

    • Don't send events over Iridium.

    • Update logic for detecting if the modem is not responsive.

    • Add parameter MAV_${i}_HL_FREQ.

  • RTL: fix RTL_TYPE=2 with existing landing: continue mission if RTL is triggered while in Mission.

  • RTL: fix RTL_TYPE=2 without existing landing: start from previous waypoint if RTL is triggered while in Mission.

  • Battery status: remove some unnecessary fields.

  • Commander: Termination mode: do not switch out of mode on disarm and prevent user switching out of it.

  • Commander: allow external modes more time for initial response to reduce likelihood of false-positive pre-flight failure.

  • Battery checks: fix auto-disarm during spoolup time.

  • Battery checks: fix that the battery checks are getting skipped when CBRK_SUPPLY_CHK is set.

  • Mission: replay the gimbal and trigger cached items only upon reaching resume waypoint.

  • Commander: only add string "autopilot disengaged" to failsafe notifactions when the failsafe causes the controller to switch out of a position-controlled auto flight mode.

  • Mission: First waypoint distance check only generates a warning, but mission can still be executed. Further, the check is always done against Home (instead of against current position if in-air).

  • Commander: do not allow to clear Land failsafe action automatically, only clear on disarm or manual mode change.

Sensors / State estimation

  • EKF2: do not continuously use mag declination fusion when GNSS fusion is active. This prevents over-constraining the heading from mag fusion. An incorrect mag yaw rotation can be absorbed as a declination error.

  • Optical flow: various improvements for it in EKF2, especially:

    • Can now run before takeoff (useful for bench testing).

    • Better performance during distance sensor outages.

    • Allow selection gyro compensation source (parameter: EKF2_OF_GYR_SRC).

    • Better velocity estimation reset when coming in range of optical flow sensor.

  • Power monitor selector: remove unnecessary INA226_SHUNT value reset.

  • Baro static pressure compensation tuning: remove dependency to baro bias.

  • EKF2: Change from magnetometer heading to magnetometer 3D fusion to improve accuracy and prevent the EKF from being too certain about its heading before takeoff.

  • Magnetometer declination fusion rework: improve heading estimate when using GNSS and poor mag calibration.

  • Commander: make sure to count all valid mags in preflight check to fix false pre-flight failure due to counted mag number not equal to SYS_HAS_MAG.

  • EKF2: more conservative clipping checks for bad_acc_clipping fault status.

  • EKF2: do EV (external vision) fusion in body frame to improve fusion results.

  • EKF2: fix GNSS vertical speed drift preflight check.

  • Enable all GNSS checks (param EKF2_GPS_CHECK) by default.

  • EKF2/Commander: simplify preflight checks. Instead of using separate innovation thresholds to trigger flags, simply flag if active source exceeds half the filtered innovation gate.

  • EKF2: fix offset from height reference after resets.

    • fixes: When several height sensors are failing at the same time, the EKF resets to the first available measurement. If the height is reset to a secondary height source, this leads to a bias buildup of the height reference.

  • Battery estimation: only allow to reset state of charge filter with valid voltage measurement to avoid battery failsafes due to voltage measurement outliers.

  • Distance sensor health check: do not raise a sensor failure if the SXX_MODE is set to 2 and we are in a flight phase that disables the distance sensor.

Copter / VTOL (hover)

  • Improve 3D waypoint following in steep terrain by fixing offtrack logic that caused it to change altitude unexpectedly

  • Improve behavior in Mission landings by not yawing if not required by the landing point

  • Motion planning: fix angle wrapping in heading smoothing.

Fixed-wing / VTOL (cruise)

  • Battery estimation: make flight time remaining estimation dependent on level flight (only estimate flight time remaining if in level flight).

  • Tiltrotor VTOL: disable MC yaw actuation fade out during front transition blending to have better control over vehicle yaw.

  • Navigator: fix RTL during hovering phase of VTOL Takeoff mode not working.

  • VTOL front transition lateral guidance: improve robustness against high cross wind by tracking a line from current position into direction of the transition.

  • FW Takeoff: catapult/hand-launch: do not cut throttle if not landed.

  • FW Takeoff: catapult/hand-launch: enable also without launch detection.

  • TECS: check if integrator update is finite prior applying (fix NaN).

  • Quadchute: Fixed sign for handling altitude resets.

  • VTOL Standard: fix transition pusher motor slew rate.

  • Battery Estimation: reset current filter when transitioning to FW.

  • VTOL tailsitter: fix motor spikes on VTOL state transitions.

  • Airspeed validator: remove extra delay of innovation trigger and reduce default of ASPD_FS_T_STOP to 1s.

  • Airspeed validator: only input local position estimate if coming from a GNSS sensor, to fix false positive airspeed failure detections due to inaccurate local position estimates from alternate sources.

  • Mission: skip a VTOL Ttakoff mission item if already in air.

  • Manual Position flight mode for FW vehicles: fix GNSS denied operation (handle estimator position resets cleanly).

  • Navigator: make sure VTOL transitions in Descend mode are always triggered (fixes: no transition to hover if Descend is triggered from another manual mode).

Peripherals

  • Gimabl: fix gimbal driver for mavlink gimbal v2 input and AUX outputs.

  • Gimbal: fix auto RC and MAVLink mode.

Parameter Changes Compared to APX4 3.0.8

Removed Parameters

Parameter Name
Affecting
Reason

BATx_V_LOAD_DROP

All

Not deemed needed anymore as most drones have current sensing which provides a better way of correcting the voltage drop due to load.

BAT_N_CELLS BAT_V_CHARGED BAT_V_EMPTY BAT_V_LOAD_DROP

All

Remove deprecated BAT_ params (replaced by BAT1_, BAT2_).

COM_ARM_EKF_HGT COM_ARM_EKF_POS COM_ARM_EKF_VEL COM_ARM_EKF_YAW

All

Simplify navigation filter preflight checks, now base it purely on reported test ratios (half the limit).

GPS_PITCH_OFFSET

All

Not deemed needed.

RC_MAP_ACRO_SW RC_MAP_MAN_SW RC_MAP_POSCTL_SW RC_MAP_RATT_SW RC_MAP_STAB_SW

All

Purge deprecated RC switch parameters that are no longer used to map RC switches to flight modes.

EKF2_TERR_MASK

MC, VTOL

Rework of terrain state handling in EKF2 doesn't require this parameter anymore.

New Parameters

Parameter Name
Affecting
About

ASPD_FP_T_WINDOW

FW, VTOL

First principle airspeed check time window

COM_RAM_MAX

All

Maximum allowed RAM usage to pass checks

DSHOT_BIDIR_EN

All

Enable bidirectional DShot

EKF2_DELAY_MAX

All

Maximum delay of all the aiding sensors

EKF2_OF_GYR_SRC

All

Optical flow angular rate compensation source

EKF2_LOG_VERBOSE

All

Verbose logging of EKF2

EKF2_RNG_FOG

All

Maximum distance at which the range finder could detect being stuck with

FW_AT_SYSID_F0 FW_AT_SYSID_F1 FW_AT_SYSID_TIME FW_AT_SYSID_TYPE

FW, VTOL

Signal generator for fixed-wing system ID / auto-tune.

FW_T_F_ALT_ERR

FW, VTOL

Fixed-wing fast decent: Altitude error to enable it.

FW_T_THR_LOW_HGT

FW, VTOL

Low-height (distance to ground) threshold for tighter altitude tracking

MPC_ACC_DECOUPLE

MC

Acceleration to tilt coupling. Enables to decouple tilt from vertical acceleration.

MPC_VEL_LP MPC_VEL_NF_BW MPC_VEL_NF_FRQ

MC, VTOL

mc_pos_control: new low pass (MPC_VEL_LP) and notch filter (MPC_VEL_NF_FRQ/MPC_VEL_NF_BW)

NAV_MIN_GND_DIST

FW, VTOL

Terrain collision prevention by enforcing a minimal distance to ground during descends in Mission and RTL modes.

SYS_PARAM_VER

All

Parameter to capture parameter versioning, which is used to reset and reload parameters.

SYS_USB_AUTO USB_MAV_MODE

All

[mavlink] Parameter to always start on USB

MAV_${i}_HL_FREQ:

All

Configures the frequency of HIGH_LATENCY2 stream for instance ${i}

Features with Renamed Parameters

Old Parameter
New Parameter
Related Feature
Auto translation

SYS_MC_EST_GROUP

EKF2_EN LPE_EN ATT_EN

Estimator type selection.

Yes

Parameters with Changed Defaults

Parameter name
Old value
New value
About

ASPD_FS_T_STOP

2

1

Faster airspeed failure (e.g. blockage) detection

BATx_R_INTERNAL

0.005

-1

Automatic battery resistance estimation when value is negative

COM_FLT_TIME_MAX

3540

-1

Flight time restriction disabled by default

COM_WIND_MAX

12

-1

Wind restriction disabled by default

EKF2_DECL_TYPE

7

3

ekf2: do not continuously use mag decl fusion when GNSS fusion is active

EKF2_EV_CTRL

15

0

External vision input fusion by default disabled

EKF2_GPS_CHECK

255

1023

Enable all GNSS checks by default

EKF2_OF_CTRL

0

1

Enable optical flow aiding by default

FW_T_SPD_STD

0.2

0.07

TECS: reduce default to reduce airspeed measurement delay

INA226_SHUNT

0.0008

0.0005

More appropriate shunt value

MIS_DIST_1WP

900

10000

Larger default is more appropriate for most applications.

Last updated