Skip to content

fix(mavlink): reset mission sequence on platform restart#27045

Open
Sayshara wants to merge 1 commit intoPX4:mainfrom
Sayshara:fix/reset_mission_sequence_on_reboot
Open

fix(mavlink): reset mission sequence on platform restart#27045
Sayshara wants to merge 1 commit intoPX4:mainfrom
Sayshara:fix/reset_mission_sequence_on_reboot

Conversation

@Sayshara
Copy link
Copy Markdown
Contributor

Solved Problem

Fixes #14981

After a platform reboot, PX4 could restore the previously persisted mission_state.current_seq from Dataman and continue reporting the old active mission item. As a result, the vehicle could resume a stale waypoint from the previous run, for example a landing waypoint, instead of starting the mission again from the first waypoint.

Solution

Reset the persisted mission_state.current_seq to 0 during MavlinkMissionManager initialization on startup, before the mission state is republished.

This keeps the uploaded mission itself intact:

  • mission items remain stored in Dataman
  • mission count and mission identifiers remain unchanged
  • only the active mission sequence is reset

With this change, after a reboot the platform starts with the same mission, but with the current mission item reset to the first waypoint.

Changelog Entry

For release notes:

Bugfix: Reset persisted mission current waypoint to the first mission item after reboot

@github-actions
Copy link
Copy Markdown

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 72 byte (0 %)]
    FILE SIZE        VM SIZE    
 --------------  -------------- 
  +0.0%     +72  +0.0%     +72    .text
    [NEW]     +60  [NEW]     +60    CSWTCH.1971
    [NEW]     +44  [NEW]     +44    CSWTCH.2766
    +9.4%     +40  +9.4%     +40    MavlinkMissionManager::MavlinkMissionManager()
    +0.0%     +32  +0.0%     +32    [section .text]
    [NEW]     +14  [NEW]     +14    CSWTCH.3534
    [DEL]     -14  [DEL]     -14    CSWTCH.3532
    [DEL]     -44  [DEL]     -44    CSWTCH.2765
    [DEL]     -60  [DEL]     -60    CSWTCH.1970
  +0.0%     +55  [ = ]       0    .debug_abbrev
  +0.0%     +90  [ = ]       0    .debug_info
  +0.0%     +39  [ = ]       0    .debug_line
     +40%      +2  [ = ]       0    [Unmapped]
    +0.0%     +37  [ = ]       0    [section .debug_line]
  -0.0%     -11  [ = ]       0    .debug_loclists
  -0.0%      -1  [ = ]       0    .debug_rnglists
   -66.7%      -2  [ = ]       0    [Unmapped]
    +0.0%      +1  [ = ]       0    [section .debug_rnglists]
  -0.7%     -72  [ = ]       0    [Unmapped]
  +0.0%    +172  +0.0%     +72    TOTAL

px4_fmu-v6x [Total VM Diff: 64 byte (0 %)]
    FILE SIZE        VM SIZE    
 --------------  -------------- 
  +0.0%     +64  +0.0%     +64    .text
    [NEW]     +60  [NEW]     +60    CSWTCH.1971
    [NEW]     +44  [NEW]     +44    CSWTCH.2766
    +9.4%     +40  +9.4%     +40    MavlinkMissionManager::MavlinkMissionManager()
    +0.0%     +28  +0.0%     +28    [section .text]
    [NEW]     +14  [NEW]     +14    CSWTCH.3534
   -30.8%      -4 -30.8%      -4    g_nullstring
    [DEL]     -14  [DEL]     -14    CSWTCH.3532
    [DEL]     -44  [DEL]     -44    CSWTCH.2765
    [DEL]     -60  [DEL]     -60    CSWTCH.1970
  +0.0%     +55  [ = ]       0    .debug_abbrev
  +0.0%     +90  [ = ]       0    .debug_info
  +0.0%     +31  [ = ]       0    .debug_line
   -85.7%      -6  [ = ]       0    [Unmapped]
    +0.0%     +37  [ = ]       0    [section .debug_line]
  -0.0%     -11  [ = ]       0    .debug_loclists
  -0.0%      -1  [ = ]       0    .debug_rnglists
   -66.7%      -2  [ = ]       0    [Unmapped]
    +0.0%      +1  [ = ]       0    [section .debug_rnglists]
  -1.0%     -64  [ = ]       0    [Unmapped]
  +0.0%    +164  +0.0%     +64    TOTAL

Updated: 2026-04-10T12:35:24

@mrpollo
Copy link
Copy Markdown
Contributor

mrpollo commented Apr 10, 2026

Have you considered the possibility of the device rebooting mid-mission? Would this lead to undesired behavior?

@Sayshara
Copy link
Copy Markdown
Contributor Author

Have you considered the possibility of the device rebooting mid-mission? Would this lead to undesired behavior?

After a reboot the device would be in a non-mission flight mode, disarmed state, no immediate auto continuation of the mission etc.
Of course still considering the case like mid-flight landing, replacing battery and continue mission. Maybe in a future we could allow the user to resume everything autonomously with proper state.

There's a trade-off between safety and shortcuts. I think more intuitive is a fresh mission start rather than resuming a stale waypoint from the previous session.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

Drone flies towards old mission waypoint on arm, when no current=1 is set on new mission

2 participants