Links
Comment on page

APX4 2.4.1

Compatibility

Please ensure to use Auterion Mission Control v1.13 or newer:

What’s new

Powered-by-Auterion:

  • VTOL
    • Simplified UX for quick takeoff and landing using Safe Areas
    • Introduce automatic Eco and Dash mode switching for situational adaptation of energy conservation vs. setpoint tracking
    • Simplified preflight check mechanism
  • Online airspeed scale estimation

Powered-by-upstream-PX4:

  • All the new features made available in upstream PX4 v1.11 release.

What improved

Powered-by-Auterion:

VTOL

  • Transition logic improvements to allow earlier alignment of heading with transition direction
  • Overhaul of (setpoint) constraints for safe back transitions across various conditions
  • Improve computation of height rate setpoint in TECS. Introduced parameters for target climb-and sinkrates
  • Tiltrotor: Add quadchute when transition times out similar as in standard VTOL
  • Use temperature data from differential pressure sensor to calculate air density
  • Tiltrotor: add hover tilt offset to pusher assist tilt
  • FW Position Controller: Add ability to climb fast/slow
  • Add transition timeout mechanism as fallback
  • Make sure (erroneous) mavlink VTOL takeoff can only be executed on VTOL vehicle type
  • replace ASPD_STALL by FW_AIRSPD_STAL and introduce sanity checks
  • FW Position control: add roll slewrate also in manual Position flight mode

Other

  • Overhaul of geofence handling
  • microRTPS support to allow parallel mavlink and RTPS communication
  • gimbal: support for v1 gimbals while using v2 protocol between AMC and vehicle
  • mavlink: 14S battery support
  • Allow yawing nudging during yaw and allow nudging from beginning of decent
  • Add wind speed warning when vehicle reaches wind limits
  • Airspeed validator: extend check for constant value to hover flight
  • Better RC loss failsafe configuration options for BVLOS (ability to disable RC loss reaction)
  • Send parachute command on termination
  • Param whitelist (restricted build) option for production builds
  • DShot: timeout if commands are not processed
  • Differential Pressure Sensors: switch to explicitly enable sensors with new params
  • Consumption based RTL: make margin configurable
  • Making "airspeed sensor failure detected" warning more understandable
  • Fallback logic from gps heading in case gps heading fails
  • Mavlink: increase MAX_REMOTE_COMPONENTS to 12
  • Airspeed Selection: make message to user more clear
  • Add vehicle_odometry and vehicle_trajectory_bezier logging for obstacle avoidance and VIO debug and inspection
  • sdp6x driver: remove inversion of differential pressure

Powered by community:

  • Add ability to set GPIO to pull down
  • Proper cleanup of mavlink instance on exit
  • All the improvements made available in upstream PX4 v1.11 release.

Bug fixes

The following bugs have been fixed:

Fixed-by-Auterion:

VTOL

  • Fix cases where state machine did not transition to MC mode
  • Fix issue where the wind estimate was off on tail-sitters type aircraft
  • Fix: Orbits aren't joint tangentially
  • Enable different pitch sp offset in hover for landing: Fixes an issue where the vehicle has issues descending when landing in high wind.
  • Fix: RC lost failsafe action broken when happening during GPS lost failsafe
  • Fix: Failsafe interrupting VTOL Takeoff
  • Fix: Flight Time Estimator RTL Interferes With Active Landing : enforce landing at home only if VTOL in hover and not on mission landing
  • Fix TECS airspeed filtering to use raw inertial acceleration & Log more airspeed filter states
  • Fix: Tiltrotor Throttle setpoint wrong during stabilized transition
  • Fix control surface check for non-tilt rotor vehicles

Rover

  • Allow arming a rover with the throttle stick in the middle
  • Rover: Correct throttle scale

Estimation

  • Fix: yaw gyro bias oscillation on ground
  • Fix: autotuning failing on some quadplane setups
  • Fix: autotuning: parameter not applied correctly
  • Fix: land detection when drone is moving after landing in Position mode
  • Fix: wrong flight time estimates when on ground
  • Fix mag-less in air yaw alignment
  • Fix: Mag bias estimator does not work after disarm
  • Fix missing hysteresis for hover thrust estimator
  • Fix: quaternion- Z accel bias coupling (leads to EKF covariance prediction stability improvements)
  • Fix: User override not working during GPS lost failsafe landing
  • Fix: Triggering RTL from fast manual descent resulted in commanded descent instead of climb in RTL
  • Fix: Datalink failsafe: drone does not disarm
  • Fix instance where vertical geofence was breachable
  • Fix: Cruise speed is not re-used if mission is paused and resumed
  • Fix: Rejected mission can be executed
  • Fix: invalid setpoints during switch from stab to alt
  • Fix: Nudging: Yaw action stops descend
  • Fix: Com loss leads to pos control and switching to altitude control
  • Fix: possibility erroneous position setpoint when changing altitude during fixed wing position control mode
  • Fix: Mission not advancing if next waypoint within loiter radius of current loiter waypoint
  • Fix: ROI as part of mission not working
  • Consumption based RTL: Ignore RTL estimate if RTL is not configured as failsafe action

Other

  • sdp3x: fix situation when wire/contact gets disconnected SDP3X sensor was not able to reconfigure.
  • Disable iridium driver per default
  • mavlink: fix runaway case during mission upload
  • MAVLink forwarding improvements / fix incorrect rejection of forwarded alien commands
  • Fix: FTP usage during FMU configuration update results on timeouts or "protocol errors" (mavlink receiver improvements)
  • Set UART4//dev/ttyS3 as UART for Pixhawk Payload bus
  • logger: remove unused topics, move some to debug profile
  • Fix: operator spammed by ADSB messages
  • Fix pwm default failsafe values (PWM_AUX_DISx to use common default value)
  • Fix: correctly route custom actions to mission computer
  • Fix: GPS heading and timeout for uBlox ZED-F9P
  • Fix instances of missed mavlink log messages
  • Fix: hardfault on mavlink stop-all shell command

Fixed by community:

  • Fix memory corruption when work queue is being deleted
  • NuttX Fix for DATA timeout (SD logging stops after short period of time)
  • only play safety change tunes if initialized
  • Report vehicle termination correctly over MAVLink
  • Fix instance where PWM param update was interfering with VTOL flight modes
  • Fix: SITL jMAVsim oscillates in pitch
  • All the bug fixes made available in upstream PX4 v1.11 release.
Last modified 8mo ago