APX4 3.2.10
General Improvements
Boards: Disarm the PWM ESCs after reboot/hardfault/assertion, by pulling the PWM PINs low for 100ms. Fixes: depending on how fast the system reboots, a valid PWM pulse can be created which can cause the motors to spin.
v6s: add
MODULES_SIMULATION_SIMULATOR_SIH
to default build. Fixes: SIH (simulation in hardware) not enabled on Skynode S.Commander: Only set the
force_failsafe
(notlockdown
) flag when in flight termination. Fixes: parachute trigger not working because no actuator output allowed inlockdown
.Commander: Handle mode change rejection the same for mode change coming in through RC and MAVLink. Fixes: mode switch to infeasible Position mode not rejected when triggered by RC button, and instead vehicle fail-safes to Altitude mode.
Commander: Do not allow flight mode to switch to an infeasible mode after a fail-safe event. Fixes: system switching to infeasible mode and instantly fail-safes when mode change requested after another fail-safe event.
Dataman: Disabled the persistent dataman storage on Skynode S as it does not have enough storage (has no SD card). Fixes: Skynode not booting anymore when
SYS_DM_BACKEND
is set todefault (SD card)
on Skynode S.Commander: Separate state tracking for battery_unhealthy fail-safe. Fixes: error
duplicate check for caller_id 74
.Mission: Replay change speed mission items on resume immediately if not going to previous waypoint. Fixes: wrong survey flight speed if operator stopped and resumed mission before reaching the survey.
UXRCE_DDS: Add options to specify additional robustness measurements (
UXRCE_DDS_TX_TO
,UXRCE_DDS_RX_TO
), disabled by default. Fixes: In certain situations the DDS Agent stops sending payload to the DDS client. As the DDS client though still can ping the agent the existing robustness measurements did not trigger a reconnect.MAVLink streaming: Make scaling of throttle field of MANUAL_CONTROL consistent with uORB message. Fixes: Input is processed [0, 1000] -> [-1, 1]. Output is processed [-1, 1] -> [-1000, 1000], which is against MAVLink definition.
Nuttx: Fix potential null pointer access in procfs_opendir, e.g. possible to trigger via MAVLink FTP.
ARK Jetson: Increase TELEM2 RX buffer size for DDS over serial use. Fixes: Not receiving some DDS messages sent by the Jetson on the FMU.
Sensors / State Estimation
Sensors: Automatically disable internal magnetometer if external ones are available. Fixes: Internal magnetometers are almost always highly affected by varying magnetic fields generated by the drone due to their location inside the drone, and should thus not be used for navigation. A fallback to the internal magnetometer can lead to worse performance than not using a magnetometer at all.
GNSS driver: update GPS submodule to include F9P outpute rate fix to improve RTK accuracy.
GNSS driver: Fix GPS RTCM instance selection. Fixes: RTCM injection of data received via MAVLINK.
GNSS Dump timeout increase + GNSS overflow fix. Fixes: GNSS data timeouts with RTK setups.
Integrator: Prevent overflow of dt in integrator class. Fixes: Overflow of dt variable in Integrator class for sensors with low sampling rates.
EKF2: Fix flow derivation for negative HAGL. Fixes: Drone climbs again shortly before touching down when landing with optical flow.
ADS1115 driver: Rework to address stability problems. Fixes: Spamming of console, probing/sensor detection and internal I2C error handling.
Magnetometer calibration: Fix large vehicle magnetometer calibration. Fixes: The heading after a quick magnetometer calibration ("large vehicle mag calibration") is sometimes off by up to 10-15 degrees, but correct after a reboot.
EKF2: improve optical flow stability near the ground. Fixes: Some EKF stability issues were occurring near the ground, where the optical flow measurement is near its singularity point (0 distance).
GPS: Parse RTCM3 and NAV in parallel. Fixes: The NAV + RTCM3 parser can block each other and can cause significant delay until the parser gets in sync again.
Copter / VTOL (Hover)
Flight Task Manual: Reset
dist_to_ground_lock
ifdist_to_bottom
is not valid. Fixes: Vehicle can climb unexpectedly back to previous altitude setpoint in manual Position mode when flying close to maximum range of distance sensor.Multicopter attitude control: Fix yaw jump when switching from stabilized to another mode.
Multicopter position control: Improve behavior of "nudging" during landing. Fixes: Vehicle turns instead of translates in some conditions while nudging the vehicle during the landing.
VTOL: Fix attitude setpoint being overwritten in Stabilized mode transitions. Fixes: Pilot not being able to set roll/pitch setpoints manually during transition.
Multicopter: Avoid double compensation of yaw reset in Stabilized mode. Fixes: Unexpected yaw bahvior when the validity of the heading estimate changes.
Fixed-wing / VTOL Plane (Cruise)
EKF2: Allow sideslip fusion to always start together with airspeed fusion. Fixes: Race conditions causing the wind initialization to fail during the transition to cruise flight as the EKF needs to receive the message before activating the sideslip fusion.
EKF2: Allow airspeed fusion only during front transition and cruise flight. Fixes: Airspeed fusion happening in hover mode (VTOL) when airspeed is high, resulting in toggling between Descend and RTL.
EKF2: Constrain max variance by zero innovation update. Fixes: Estimator instability caused by manual position reset after flying for a prolonged period with wind dead-reckoning.
EKF-AGP: Do not reset to AGP (Auxiliary Global Position) measurement if GNSS fusion is active. Fixes: AGP resetting the position after rejection period, even if GNSS was fused all the time.
VTOL: Reduce schedule frequency by only registering relevant callbacks. Fixes: Specific ESCs lose communication and go to failsafe state when switching from MC -> FW in case of using DSHOT150.
New Parameters
UXRCE_DDS_TX_TO
All
Defines after how many seconds of not receiving RX payload the connection is reset
UXRCE_DDS_RX_TO
All
Defines after how many seconds of not sending TX payload the connection is reset
Last updated