APX4 3.2.1
Please use Auterion Mission Control 1.34 or newer with this version of APX4.
What's New
General
Add support for the following rover types: Mecanum, Differential and Ackermann.
Add Skynode S support.
Ellipsoidal navigation. This feature enhances the Navigation Filter (EKF2) to handle long-distance flights where the Earth's curvature becomes significant and cannot be approximated by a tangent plane (> ~100km). Instead of navigating on a tangent-plane set during initialization ("flat Earth model"), this solution introduces a local-navigation frame, oriented in NED (North-East-Down), with its origin located at the vehicle's center of gravity (CG). The local-navigation frame moves with the vehicle, ensuring that the linearization remains valid regardless of the current location or distance from the takeoff point. Internally, inertial navigation, dead-reckoning and absolute position corrections are performed using the ellipsoid model defined by WGS84.
Sensors / State Estimation
Optical flow: add scale factor parameter to correct for sensor scale offset (parameter:
SENS_FLOW_SCALE
. See documentation for more info.Add support for AP Periph (dronecan) dual GPS heading setups, and added parameter for configuration yaw offset (parameter:
EKF2_GPS_YAW_OFF
).Add driver support for Bosch BMM350 magnetometer.
Add driver support for AK09915 magnetometer.
Add driver support for Bosch BMP581 barometer.
Copter / VTOL (Hover)
Enable collision prevention with the default manual position mode flight task, FlightModeManualAcceleration and add various improvements. For details see PX4 user guide.
Fixed-wing / VTOL plane (cruise)
Add position feedback to VTOL backtransition braking controller. This reduces the under-/overshoot of the landing point by including position in the loop controlling the pitch-up for braking.
Add parameter for low position estimation accuracy failsafe and fix reporting (parameter:
COM_POS_LOW_ACT
).Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch.
What Improved
General
MAVLink command acknowledgement fixes. This should prevent some of the warnings regarding acks lost that we sometimes see, e.g. "vehicle_command_ack lost, generation 10 -> 15".
Mission validity checks: make clear that check around
MIS_DIST_1WP
only warns, not invalidates the uploaded mission.Navigator: Fix
RTL_TYPE
2 by reloading mission. Fixes: wrong notification of no valid mission when RTL is triggered with that RTL type setting.Gimbal: Fix degrees/radians mix-up for angular rates setpoint.
Gimbal: Override vehicle attitude sent to gimbals when HIL mode is enabled. The simulated attitude can disturb the gimbal estimator and lead to strange behavior of the gimbal. So, since the hardware is not moving in HIL/SIH, we fake a static attitude towards the gimbal.
Gimbal: stop from spinning when an angular velocity setpoint stream times out. The gimbal would otherwise continue to spin with whatever velocity was commanded before the input connection was lost.
Restrict access on gimbal-specific MAVLink instances. Fixes: Connecting to the payload bus's UART allowed full control over the autopilot, even when the MAVLink instance is configured for a gimbal/(camera) payload.
Mission: Replay cached gimbal items before reaching mission waypoint. Fixes: When flying patterns, photos are sometimes taken while the gimbal is pitching up or down.
Battery: Add parameter to manually set the idle current (
BAT${i}_I_OVERWRITE
) when not armed. Fixes: Certain ESCs current measurements are inaccurate in case of no load.
System Failure Reporting / Handling
Arm authorization: Only run on arming request, fix spamming before companion computer is ready to do checks.
Health and arming checks: Allow arming with a battery SOC below critical threshold by setting
COM_ARM_BAT_MIN
lower thanBAT_CRIT_THR
.Failure detector: Only check for motor failures on indexes that have had non zero current. Fixes: False motor failure detected.
Battery status: Clarify "incompatible voltage" error message.
Change some 'RC' keywords to more appropriate 'manual control' if functionality is also active when flying with joystick over MAVLink.
Health and arming checks: only keep error thresholds (at 4.7V), remove warnings.
MAVLink's SYS_STATUS reporting: fill it correctly to fix unclear reporting of positioning vs. attitude estimation health.
Estimator Check: have low position accuracy warning as health component failure to fix reporting.
Change user facing messages to "Remote ID" instead of "OpenDroneID"
Health and arming checks: Ensure health report is always sent out before a failsafe notification. Fixes: As the failsafe message can reference the health report, the health report needs to be sent out first. This is generally the case, except there is a rate limiter set to 2 seconds. So if the report changes quickly, it is sent out delayed (potentially after the failsafe report).
Health and arming checks: Avoid unsigned timestamp underflow in telemetry timeout. Fixes: ESC telemetry missing preflight checks error.
Health and arming checks: improve messaging for position estimate failure by adding string "Navigation error" before failure message.
EKF2: Fix false pre-flight failure report. Fixes: Filtered innovations and test ratios can be large before the reset and can trigger pre-flight warnings.
EKF2: Send event when yaw gets aligned. Fixes: Magnetic interference pop up not changing when matter resolved.
State Estimation
Yaw emergency estimator: Harden it against GNSS sensor glitches. Fixes that during GNSS glitches the yaw estimator is vulnerable as it would immediately converge to the incorrect GNSS readings.
Distance sensor validity checks: allow invalidating at any vertical speed. Fixes: When the height above ground is low, the drone will usually decelerate and then the check would not run anymore. If the low height above ground estimate is due to bad sensor readings (e.g.: reflections), it will be stuck in that state.
Add validity flags to global position message. The flight mode failsafe logic inside Commander now explicitly relies on the validity state of the global position.
EKF2: consider height covariance for terrain reset to range. Range does not provide a direct terrain observation but a measurement relative to the height state. De-correlating those states during initialization brings false information to the filter about the terrain accuracy.
EKF2: Remove legacy acceleration z bias checks.
Sensors: Allow disabling of uncalibrated barometers via the parameters and thus enable to switch to an alternative sensor.
EKF2: set barometer bias when GNSS is altitude reference but GNSS fusion is disabled. Fixes: large altitude estimation offset due to using uncalibrated barometer measurements.
Sensor Drivers
SF45 rotary lidar driver: fixes to restart the state machine if the sensor does not initialize correctly
Update icm40609d. Adds a fix for ICM40609D interrupt (DRDY) driven mode, and cleanups for FIFO handling.
INA228 / INA238 : Implemented temperature sensor support, published in BatteryStatus.msg
INA220 fix max current param name. Fixes: INA220 max current param names were incorrect and being ignored.
Always start board_adc to solve "system power unavailable" using ADS1115/ADC on v6x.
Copter / VTOL Plane (Hover)
Commander: Require only relaxed local position estimation for LAND flight mode, which e.g. enables to land GNSS-denied with an optical flow sensor only.
Navigator: Do not go to initialization point (0/0) but land at current location if no global position estimate is available.
Multicopter position controller: Reset velocity integrators when not in a position controlled mode. Fixes: In some cases the velocity integrator can be strongly loaded when switching out of position control (e.g.: switch during braking or strong wind). When resuming position control, the drone is disturbed by this preloaded integrator since the conditions changed.
Orbit flight mode: reduce jerk when transitioning into orbit.
Orbit: Add vehicle yaw behavior option (parameter:
MC_ORBIT_YAW_MOD
).Descend mode: Fix functionality without velocity estimation. In that case demand constant acceleration downwards.
Flight Task Auto: Added a turning radius to altitude changes. Fixes: When conducting a survey, the drone tended to slow down and accelerate again when covering large altitude changes with terrain following enabled.
Fixed-wing / VTOL (Cruise)
Fixed-wing position controller: Prevent fixed bank loiter during backtransition when we lose local position.
Remove euler angles from attitude setpoint to have clear interface (quaternion).
Fixed-wing position controller: Allow position control without valid global position. Fixes: The controller only runs when global position is valid, inside though only uses local position.
Remove requirement for valid altitude estimate from Descend mode. Fixes: instead of switching to Descend mode, vehicle goes into termination when local position estimate and height estimate get invalidated at the same time.
Runway takeoff: fix wheel controller.
VTOL (exclusively)
Standard VTOL: Remove scaling of torque setpoint during transition to reduce chance of yaw instability during backtransition.
Land mode for VTOL: Take braking distance into account. Fixes: vehicle overshoots calculated landing point and has to fly backwards to get over it.
Start airspeed fusing for wind estimation already during transition to fixed-wing mode (once airspeed is above
EKF2_ARSP_THR)
. This reduces the risk of a navigation failure in GNSS-denied operation when reaching the height limit of the optical flow sensor.
What Got Removed
External sensors (drivers are still in code base but not built by default)
ADIS16448 SPI external IMU
PAA3905 Optical flow
px4flow Optical flow
Lightware Distance sensor (serial)
TeraRanger Distance sensor (i2c)
VL53L0X Distance sensor
LeddarOne Distance sensor
ThoneFlow-3901U Optical flow sensor
VectorNav (VN-100, VN-200, VN-300) INS
Parameter Changes Compared to APX4 3.1.1
Rover parameters are excluded from this list.
Removed Parameters
FW_SPOILERS_DESC
Fixed-wing
This param was already deprecated
MOT_SLEW_MAX
Multicopter
This param was already deprecated
SENS_EN_ADIS164X SENS_OR_ADIS164X SENS_EN_PAA3905 SENS_EN_PX4FLOW SENS_EN_SF0X SENS_SF0X_CFG SENS_EN_TRANGER SENS_EN_VL53L0X SENS_LEDDAR1_CFG SENS_TFLOW_CFG SENS_VN_CFG VN_MODE
All
Removal of some external sensors to save flash space
New Parameters
BATn_I_OVERWRITE
All
Overwrite value of measured battery current when disarmed
COM_POS_LOW_ACT
FW/VTOL
Low position accuracy failsafe action
EKF2_GPS_YAW_OFF
All
Heading/Yaw offset for dual antenna GPS
MC_ORBIT_YAW_MOD
MC
Yaw behavior during orbit flight
Parameters with Changed Defaults
COM_ARM_BAT_MIN
0
-1
Allow arming with critical battery state. A negative value means BAT_CRIT_THR is the threshold.
Last updated