Skip to content

feat(rtl): type prioritize home#26968

Open
anilkir wants to merge 10 commits intoPX4:mainfrom
anilkir:feat/rtl-type-prioritize-home
Open

feat(rtl): type prioritize home#26968
anilkir wants to merge 10 commits intoPX4:mainfrom
anilkir:feat/rtl-type-prioritize-home

Conversation

@anilkir
Copy link
Copy Markdown
Contributor

@anilkir anilkir commented Apr 3, 2026

Solved Problem

There are real-life scenarios where an RTL to home position may be preferable to an RTL to a rally point. The idea is to introduce a layer of prioritization where a return to home point is prioritized over a return to one of the rally points as long as it is reachable in the remaining flight time.

Currently, PX4 does not support a hybrid RTL strategy that prioritizes returning to home while falling back to rally points based on actual remaining flight time.

Solution

Adds RTL_TYPE 6: a new RTL type that selects the return destination based on battery time remaining. If the estimated flight time to home is within the battery's time_remaining_s, home is chosen. Otherwise, the closest rally point is selected as the fallback destination. If an RTL is triggered when time_remaining_s is NaN, then the closest of home or rally points is selected (identical to RTL_TYPE=0 behavior).

This RTL type is particularly useful for long-range operations where rally points are pre-positioned as intermediate safe landing zones, but home is always preferred when battery permits.

Assumptions:

  1. If all safe points are out of reach, the RTL estimate check will trigger a failsafe, so it's not necessary to handle that situation here
  2. If for some reason in a non-SITL scenario the time_remaining_s is NaN and the RTL estimate check is not able to trigger an RTL when the closest safe point is farther than the remaining flight time, we will rely on the CRITICAL and EMERGENCY battery level threshold failsafes with potentially

Key changes:
Added RTL_TYPE 6 case to the RTL module's destination selection logic
Reuses existing rally point and home reachability infrastructure
Uses battery_status.time_remaining_s to evaluate home reachability at the time of RTL trigger

Changelog Entry

For release notes:

Feature: Added RTL_TYPE 6 - home-preferred RTL with battery-based reachability check and rally point fallback
New parameter value: RTL_TYPE = 6

Test coverage

  • RTL triggered when home is within reach with no rally points defined (SITL)
    • Expected: vehicle returns home
    • Result: ✅
  • RTL triggered when home is within reach and is the closest of safe points (SITL)
    • Expected: vehicle returns home
    • Result: ✅
  • RTL triggered when home is within reach but is not the closest of safe point (SITL)
    • Expected: vehicle still returns home despite closer rally point
    • Result: ✅
  • RTL triggered when home is out of reach and is not the closest safe point (SITL)
    • Expected: closest rally point selected
    • Result: ✅
  • RTL triggered by BAT_CRIT_THR flag when all safe points are out of reach (SITL)
    • Not tested due to assumption (1)
  • RTL triggered when time_remaining_s field has a NaN and home is the closest of safe points (SITL)
    • Expected: falls back to distance-based selection from all safe points, home chosen
    • Result: ✅
  • RTL triggered when time_remaining_s field has a NaN but home is not the closest of safe points (SITL)
    • Expected: falls back to distance-based selection from all safe points, closest rally point chosen
    • Result: ✅

Video showing preference of home position within reach over a closer rally point:

home_preferred_comp.mp4

@dakejahl dakejahl requested review from MaEtUgR, dakejahl and sfuhrer April 4, 2026 00:04
dakejahl
dakejahl previously approved these changes Apr 4, 2026
Copy link
Copy Markdown
Contributor

@dakejahl dakejahl left a comment

Choose a reason for hiding this comment

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

It makes sense to me and seems like a good feature. On a side note, we need to start adding CI SITL tests for all of these behaviors.

@anilkir
Copy link
Copy Markdown
Contributor Author

anilkir commented Apr 6, 2026

It makes sense to me and seems like a good feature. On a side note, we need to start adding CI SITL tests for all of these behaviors.

@dakejahl thanks for the feedback. I pushed a test_multicopter_rtl.cpp test file with 3 of the tests I performed covering the time_remaining_s = NaN fallback path (default SITL behavior). The rest of the tests with battery reachability path are not covered by SITL tests because controlling finite time_remaining_s in SITL without modifying production code is not straightforward and no existing test pattern as far as I can see supports it.

@anilkir anilkir force-pushed the feat/rtl-type-prioritize-home branch 2 times, most recently from a1dbebc to 7a96a6e Compare April 6, 2026 20:39
@mrpollo mrpollo changed the title Feat/rtl type prioritize home feat(rtl): type prioritize home Apr 7, 2026
@dakejahl
Copy link
Copy Markdown
Contributor

dakejahl commented Apr 8, 2026

time_remaining_s should be availabe in simulation. Either in Gazebo or SIH. Could you check? If so, it would be great to have a CI test for this. Soon our CI SITL tests will move to SIH which should allow us to run many more SITL tests for much wider coverage.

@hamishwillee
Copy link
Copy Markdown
Contributor

Remember to do docs for this when it goes in, and also update the release note in https://docs.px4.io/main/en/releases/main

@github-actions
Copy link
Copy Markdown

github-actions Bot commented Apr 9, 2026

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 424 byte (0.02 %)]
    FILE SIZE        VM SIZE    
 --------------  -------------- 
  +0.0%    +424  +0.0%    +424    .text
     +38%    +164   +38%    +164    RTL::setRtlTypeAndDestination()
    +0.0%     +76  +0.0%     +76    g_cromfs_image
    +8.3%     +56  +8.3%     +56    RTL::RTL()
    +1.8%     +32  +1.8%     +32    Navigator::Navigator()
    +4.7%     +16  +4.7%     +16    RTL::findClosestSafePoint()
    +7.5%     +12  +7.5%     +12    RTL::on_activation()
    +8.1%     +12  +8.1%     +12    RTL::on_inactive()
    +0.0%     +12  +0.0%     +12    [section .text]
    +5.0%      +8  +5.0%      +8    MissionBlock::setLoiterFromLastLink()
    +0.2%      +8  +0.2%      +8    Navigator::run()
    +5.4%      +8  +5.4%      +8    RTL::~RTL()
    +3.8%      +4  +3.8%      +4    Mission::handleVtolTransition()
    +1.0%      +4  +1.0%      +4    MissionBlock::mission_item_to_position_setpoint()
     +14%      +4   +14%      +4    Navigator::activate_set_gimbal_neutral_timer()
   +10.0%      +4 +10.0%      +4    Navigator::reset_triplets()
    +9.5%      +4  +9.5%      +4    RtlDirect::parameters_update()
     +44%      +4   +44%      +4    g_nullstring
    +0.8%      +2  +0.8%      +2    Navigator::updateParamsImpl()
   -93.8%      +2 -93.8%      +2    [1 Others]
    -4.5%      -4  -4.5%      -4    FlightTask
    -0.4%      -4  -0.4%      -4    Navigator::geofence_breach_check()
  +0.0%     +63  [ = ]       0    .debug_abbrev
  +0.0%      +4  [ = ]       0    .debug_frame
  +0.0% +3.95Ki  [ = ]       0    .debug_info
  +0.0%    +392  [ = ]       0    .debug_line
     +67%      +2  [ = ]       0    [Unmapped]
    +0.0%    +390  [ = ]       0    [section .debug_line]
  +0.0%    +488  [ = ]       0    .debug_loclists
  +0.0%     +16  [ = ]       0    .debug_rnglists
  +0.0%     +64  [ = ]       0    .debug_str
   +45% +3.59Ki  [ = ]       0    [Unmapped]
  +0.0% +8.96Ki  +0.0%    +424    TOTAL

px4_fmu-v6x [Total VM Diff: 376 byte (0.02 %)]
    FILE SIZE        VM SIZE    
 --------------  -------------- 
  +0.0%    +376  +0.0%    +376    .text
     +38%    +164   +38%    +164    RTL::setRtlTypeAndDestination()
    +8.3%     +56  +8.3%     +56    RTL::RTL()
    +0.0%     +40  +0.0%     +40    g_cromfs_image
    +1.8%     +32  +1.8%     +32    Navigator::Navigator()
    +4.7%     +16  +4.7%     +16    RTL::findClosestSafePoint()
    +7.5%     +12  +7.5%     +12    RTL::on_activation()
    +8.1%     +12  +8.1%     +12    RTL::on_inactive()
    +5.0%      +8  +5.0%      +8    MissionBlock::setLoiterFromLastLink()
    +0.2%      +8  +0.2%      +8    Navigator::run()
    +5.4%      +8  +5.4%      +8    RTL::~RTL()
    +3.8%      +4  +3.8%      +4    Mission::handleVtolTransition()
    +1.0%      +4  +1.0%      +4    MissionBlock::mission_item_to_position_setpoint()
     +14%      +4   +14%      +4    Navigator::activate_set_gimbal_neutral_timer()
   +10.0%      +4 +10.0%      +4    Navigator::reset_triplets()
    +9.5%      +4  +9.5%      +4    RtlDirect::parameters_update()
    +0.8%      +2  +0.8%      +2    Navigator::updateParamsImpl()
    +6.2%      +2  +6.2%      +2    RtlTimeEstimator::updateParamsImpl()
    -0.4%      -4  -0.4%      -4    Navigator::geofence_breach_check()
  +0.0%     +63  [ = ]       0    .debug_abbrev
  +0.0%      +4  [ = ]       0    .debug_frame
  +0.0% +3.95Ki  [ = ]       0    .debug_info
  +0.0%    +392  [ = ]       0    .debug_line
     +67%      +2  [ = ]       0    [Unmapped]
    +0.0%    +390  [ = ]       0    [section .debug_line]
  +0.0%    +488  [ = ]       0    .debug_loclists
  +0.0%     +16  [ = ]       0    .debug_rnglists
  +0.0%     +64  [ = ]       0    .debug_str
  -8.8%    -376  [ = ]       0    [Unmapped]
  +0.0% +4.96Ki  +0.0%    +376    TOTAL

Updated: 2026-04-27T02:34:18

@anilkir
Copy link
Copy Markdown
Contributor Author

anilkir commented Apr 21, 2026

SIH CI:
@dakejahl you're right, time_remaining_s is by default NaN in SITL because the BAT1_CAPACITY is -1.0. If BAT1_CAPACITY param is changed, then time_remaining_s is published. I will look into this.

EDIT:
time_remaining_s requires two things to produce a valid estimate: a positive battery capacity (BAT1_CAPACITY) and a valid current mesurement.

  • Problem 1 (capacity): BAT1_CAPACITY defaults to -1.0, which gets clamped to 0.0 in the code. With 0 capacity, computeRemainingTime skips the calculation and time_remaining_s stays NaN. So this param needs to be set.

  • Problem 2 (current filter): Since current sensor is not simulated, current average filter exponentially decays to zero, making time_remaining_s useless. We can add a check to skip the current filter update, similar to the guard in sumDischarged()

  • Problem 3 (average current): BAT_AVRG_CURRENT (never updated by real current) needs to be manually set to a value (see below equation) which will result in a stable time_remaining_s driven by the SoC estimate.

BAT_AVRG_CURRENT = BAT1_CAPACITY [mAh] × 3.6 / SIM_BAT_DRAIN [s]

I think we should leave this as a follow-up to simulate the current properly in BatterySimulator and then I can add CI for these tests as well. Let me know if you're ok with this @dakejahl

Docs:
@hamishwillee Will do, updating docs is on my list, I will do that.

EDIT:
Docs are updated in 4d36039. I also added the missing entries for RTL_TYPE 4 and 5.

@anilkir anilkir force-pushed the feat/rtl-type-prioritize-home branch from c4738af to 4d36039 Compare April 21, 2026 19:58
@github-actions
Copy link
Copy Markdown

github-actions Bot commented Apr 21, 2026

/en/flight_modes/return.md

  • CurrentFileMissingAnchor: [Closest mission landing or reverse mission return](#closest-mission-landing-or-reverse-mission-return-type-rtl-type-4): anchor doesn't match any heading id or element id
  • CurrentFileMissingAnchor: [RTL_TIME_MARGIN](#RTL_TIME_MARGIN): anchor doesn't match any heading id or element id

hamishwillee
hamishwillee previously approved these changes Apr 22, 2026
Copy link
Copy Markdown
Contributor

@hamishwillee hamishwillee left a comment

Choose a reason for hiding this comment

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

Approved for the docs (thanks!). I subedited a little. This replaces my unreviewed stuff in #26783

Copy link
Copy Markdown
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.

The code looks clean and I agree with it being useful. Would consider making it the MC default (either now or once we have a bit more testing).

Comment thread src/modules/navigator/rtl.cpp
Comment thread docs/en/flight_modes/return.md Outdated
Co-authored-by: Silvan Fuhrer <silvan@auterion.com>
@anilkir anilkir requested a review from sfuhrer April 27, 2026 02:28
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.

4 participants