Skip to content

Conversation

@bresch
Copy link
Member

@bresch bresch commented Jan 6, 2026

Solved Problem

Fixedwings can often have a valid local position without a global origin when flying with an airspeed sensor. This lets the user fly in manual position mode, but should also allow autonomous circular landings. The latter is currently not working as no position setpoint is specified by Navigator.

Solution

When not specified by navigator, the center of the landing orbit is set to the current position when landing is triggered.

Changelog Entry

For release notes:

Fixedwing: Fix circular landing when global origin is not set
New parameter: -
Documentation: -

Test coverage

tested in SITL https://logs.px4.io/plot_app?log=21e5d5d0-cd1a-4f4a-b726-fef6727fad43

image

-->

When not specified by navigator, the center of the landing orbit is set
to the current position when landing is triggered.
@bresch bresch requested a review from sfuhrer January 6, 2026 19:08
@bresch bresch self-assigned this Jan 6, 2026
@github-actions
Copy link

github-actions bot commented Jan 6, 2026

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 136 byte (0.01 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%    +136  +0.0%    +136    .text
   +56%     +56   +56%     +56    FixedWingModeManager::getMaxRollAngleNearGround()
  +3.7%     +44  +3.7%     +44    FixedWingModeManager::control_auto_landing_circular()
  +0.9%     +20  +0.9%     +20    FixedWingModeManager::FixedWingModeManager()
  +4.6%     +20  +4.6%     +20    FixedWingModeManager::set_control_mode_current()
   +17%     +14   +17%     +14    FixedWingModeManager::reset_landing_state()
  +0.0%      +8  +0.0%      +8    [section .text]
  +0.3%      +4  +0.3%      +4    FixedWingModeManager::control_auto_landing_straight()
  +3.4%      +2  +3.4%      +2    FixedWingModeManager::vehicle_control_mode_poll()
 -15.4%     -32 -15.4%     -32    FixedWingModeManager::control_backtransition_line_follow()
+0.0%     +55  [ = ]       0    .debug_abbrev
+0.0%      +8  [ = ]       0    .debug_aranges
+0.0%     +16  [ = ]       0    .debug_frame
+0.0% +1.05Ki  [ = ]       0    .debug_info
+0.0%    +379  [ = ]       0    .debug_line
  [DEL]      -2  [ = ]       0    [Unmapped]
  +0.0%    +381  [ = ]       0    [section .debug_line]
+0.0%    +927  [ = ]       0    .debug_loclists
+0.0%     +44  [ = ]       0    .debug_rnglists
+0.0%      +1  [ = ]       0    .debug_str
+0.0%     +16  [ = ]       0    .symtab
  +100%     +32  [ = ]       0    FixedWingModeManager::reset_landing_state()
 -50.0%     -16  [ = ]       0    FixedWingModeManager::vehicle_control_mode_poll()
   +67%     +32  [ = ]       0    __nxsched_remove_blocked_veneer
 -40.0%     -32  [ = ]       0    __nxsem_trywait_veneer
-1.4%    -136  [ = ]       0    [Unmapped]
+0.0% +2.46Ki  +0.0%    +136    TOTAL

px4_fmu-v6x [Total VM Diff: 128 byte (0.01 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%    +128  +0.0%    +128    .text
   +56%     +56   +56%     +56    FixedWingModeManager::getMaxRollAngleNearGround()
  +3.7%     +44  +3.7%     +44    FixedWingModeManager::control_auto_landing_circular()
  +0.9%     +20  +0.9%     +20    FixedWingModeManager::FixedWingModeManager()
  +4.6%     +20  +4.6%     +20    FixedWingModeManager::set_control_mode_current()
   +17%     +14   +17%     +14    FixedWingModeManager::reset_landing_state()
  +0.3%      +4  +0.3%      +4    FixedWingModeManager::control_auto_landing_straight()
  +3.4%      +2  +3.4%      +2    FixedWingModeManager::vehicle_control_mode_poll()
 -15.4%     -32 -15.4%     -32    FixedWingModeManager::control_backtransition_line_follow()
+0.0%     +55  [ = ]       0    .debug_abbrev
+0.0%      +8  [ = ]       0    .debug_aranges
+0.0%     +16  [ = ]       0    .debug_frame
+0.0% +1.05Ki  [ = ]       0    .debug_info
+0.0%    +379  [ = ]       0    .debug_line
  [DEL]      -2  [ = ]       0    [Unmapped]
  +0.0%    +381  [ = ]       0    [section .debug_line]
+0.0%    +917  [ = ]       0    .debug_loclists
+0.0%     +46  [ = ]       0    .debug_rnglists
  [NEW]      +2  [ = ]       0    [Unmapped]
  +0.0%     +44  [ = ]       0    [section .debug_rnglists]
+0.0%      +1  [ = ]       0    .debug_str
+0.0%     +16  [ = ]       0    .symtab
  +100%     +32  [ = ]       0    FixedWingModeManager::reset_landing_state()
 -50.0%     -16  [ = ]       0    FixedWingModeManager::vehicle_control_mode_poll()
-1.6%    -128  [ = ]       0    [Unmapped]
+0.0% +2.46Ki  +0.0%    +128    TOTAL

Updated: 2026-01-07T15:18:37

const bool abort_on_terrain_timeout = checkLandingAbortBitMask(_param_fw_lnd_abort.get(),
position_controller_landing_status_s::TERRAIN_TIMEOUT);
const float terrain_alt = getLandingTerrainAltitudeEstimate(now, pos_sp_curr.alt, false, abort_on_terrain_timeout);
const float land_point_alt = _position_setpoint_current_valid ? pos_sp_curr.alt : 0.f;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should we instead of 0 AMSL init the land alt to something surely never reached, even with an baro offset? So e.g. -1000? Or even better, we init with NAN and only do anything (=trigger flaring) with that terrain alt if actually derived from a distance sensor measurement.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Right, I changed it to let the NAN propagate and handle it properly here: https://github.com/PX4/PX4-Autopilot/pull/26223/changes#diff-0e624ccf7b4ffa7466c2bef13a4a129ea57adf4581ce1593102dedd1d8dd4826R2328-R2331 (otherwise the roll was constrained to 0).

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

A couple of lines below:
if ((_current_altitude < terrain_alt + flare_rel_alt)
Did you double check that _current_altitude < NaN is always false? By the cpp definition I found it should be.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, it is, I checked in sim.

Copy link
Contributor

@sfuhrer sfuhrer left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Neat, thanks!

@bresch bresch merged commit c71e2d4 into main Jan 8, 2026
72 of 73 checks passed
@bresch bresch deleted the pr-fw_land_no_gpos branch January 8, 2026 13:44
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants