Skip to content

Conversation

sfuhrer
Copy link
Contributor

@sfuhrer sfuhrer commented Aug 15, 2025

Solved Problem

  • Systems without position estimation can only be flown in manual modes. All manual modes for copters require a constant user input to move (if you let go of the sticks they stop/level out). It's thus very cumbersome to fly long distances that way.
  • it's currently not possible to proceed flying in the set direction in a manually controlled mode if the manual control link is lost (MC and FW)

Solution

  • add new flight mode, as PX4 custom mode
  • for MC: interpret roll and pitch stick axes as "rate of change of roll/pitch tilt". This leads to a similar stick feeling as in Acro mode, though the max tilt is always respected (you cannot flip the drone). The throttle and yaw sticks are the same as in Altitude mode.
  • for FW: pitch, throttle and yaw sticks the same as in Altitude, roll stick: sets "rate of change of roll angle setpoint".
  • add option in COM_RCL_EXCEPT to discard manual control losses in this mode, though require valid manual control to enter the mode. This way one can set the course and altitude and then cover long distances without triggering failsafes if manual control is lost (enabling the data link failsafe NAV_DLL_ACT is strongly recommended for this case to avoid fly-aways)

Changelog Entry

For release notes:

Feature: Add new flight mode: Altitude Cruise

Alternatives

  • naming?

Test coverage

Partially flight tested (on MC, without manual control link loss)

Context

The original name proposed was "Cruise mode", but due to the conflict with the standard mode cruise was discarded. "Voyager" implies something similar: a mode that is meant for covering long distances in a manual mode but was deemed to abstract.
Thus the current proposal goes for "Altitude Cruise":

  • clear connection to Altitude mode
  • clear indication that it's meant for long distance, straight flights
  • still has some distinction to MAVLink standard mode "Cruise" by adding "Altitude"

Todos:

  • MC Position controller: enable to use Voyager without stick inputs (avoid it failsaving, keep tilt and altitude until new inputs arrive)
  • flight test on real drone MC
  • implement FW Flight Mode Manger changes
  • flight test FW

@sfuhrer sfuhrer requested a review from MaEtUgR August 15, 2025 14:39
@sfuhrer sfuhrer force-pushed the pr-add-voyager-mode-main branch from fda36d6 to a93676c Compare August 15, 2025 14:43
Copy link

github-actions bot commented Aug 15, 2025

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 792 byte (0.04 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%    +792  +0.0%    +792    .text
  [NEW]    +260  [NEW]    +260    StickTiltXY::generateAccelerationSetpointsForAltitudeCruise()
  [NEW]    +100  [NEW]    +100    FlightTaskAltitudeCruise
 -99.3%     +88 -99.3%     +88    [37 Others]
  [NEW]     +66  [NEW]     +66    FlightTaskManualAltitude::_updateXYSetpoint()
  [NEW]     +56  [NEW]     +56    FlightTaskAltitudeCruise::_updateXYSetpoint()
   +11%     +52   +11%     +52    FlightModeManager::start_flight_task()
  +0.0%     +52  +0.0%     +52    g_cromfs_image
  +2.1%     +44  +2.1%     +44    Commander::custom_command()
  [NEW]     +40  [NEW]     +40    FlightTaskAltitudeCruise::~FlightTaskAltitudeCruise()
  +2.2%     +32  +2.2%     +32    Failsafe::checkStateAndMode()
  [NEW]     +32  [NEW]     +32    FlightTaskManualAltitude::_updateYawSetpoint()
  [NEW]     +28  [NEW]     +28    FlightTaskAltitudeCruise::FlightTaskAltitudeCruise()
   +13%     +24   +13%     +24    Failsafe::checkModeFallback()
  +0.0%     +24  +0.0%     +24    [section .text]
  +3.4%     +20  +3.4%     +20    FixedWingModeManager::control_manual_position()
  [NEW]     +20  [NEW]     +20    FlightTaskAltitudeCruise::reActivate()
  +1.5%     +16  +1.5%     +16    matrix::Matrix<>::operator=()
  -1.5%     -28  -1.5%     -28    FixedWingModeManager::Run()
 -31.8%     -28 -31.8%     -28    FixedWingModeManager::manual_control_setpoint_poll()
 -17.1%     -28 -17.1%     -28    StickTiltXY::generateAccelerationSetpoints()
 -69.6%     -78 -69.6%     -78    FlightTaskManualAltitude::_updateSetpoints()
+0.1% +2.88Ki  [ = ]       0    .debug_abbrev
+0.2%    +344  [ = ]       0    .debug_aranges
+0.2%    +956  [ = ]       0    .debug_frame
+0.3% +86.4Ki  [ = ]       0    .debug_info
+0.2% +8.10Ki  [ = ]       0    .debug_line
 -14.3%      -1  [ = ]       0    [Unmapped]
  +0.2% +8.10Ki  [ = ]       0    [section .debug_line]
+0.2% +7.25Ki  [ = ]       0    .debug_loclists
+0.1%    +832  [ = ]       0    .debug_rnglists
+0.0%    +895  [ = ]       0    .debug_str
+0.8%      +2  [ = ]       0    .shstrtab
+0.1%    +542  [ = ]       0    .strtab
  [NEW]      +7  [ = ]       0    C.53.0
  [DEL]      -7  [ = ]       0    C.54.0
  [NEW]     +31  [ = ]       0    FlightTaskAltitudeCruise
  [NEW]     +68  [ = ]       0    FlightTaskAltitudeCruise::FlightTaskAltitudeCruise()
  [NEW]     +51  [ = ]       0    FlightTaskAltitudeCruise::_updateXYSetpoint()
  [NEW]     +44  [ = ]       0    FlightTaskAltitudeCruise::reActivate()
  [NEW]    +102  [ = ]       0    FlightTaskAltitudeCruise::~FlightTaskAltitudeCruise()
  [NEW]     +51  [ = ]       0    FlightTaskManualAltitude::_updateXYSetpoint()
  [NEW]     +52  [ = ]       0    FlightTaskManualAltitude::_updateYawSetpoint()
  [NEW]     +89  [ = ]       0    StickTiltXY::generateAccelerationSetpointsForAltitudeCruise()
  [NEW]     +25  [ = ]       0    StickTiltXY::reset()
  +0.1%     +29  [ = ]       0    [section .strtab]
   +48%     +16  [ = ]       0    ___Z12get_orb_meta6ORB_ID_veneer
 -50.0%     -16  [ = ]       0    __memcpy_veneer
+0.1%    +432  [ = ]       0    .symtab
  [NEW]     +32  [ = ]       0    C.53.0
  [DEL]     -32  [ = ]       0    C.54.0
  -3.8%     -16  [ = ]       0    Commander::handle_command()
  +100%     +32  [ = ]       0    EKFGSF_yaw::fuseVelocity()
 -33.3%     -16  [ = ]       0    FixedWingModeManager::manual_control_setpoint_poll()
   +17%     +16  [ = ]       0    FlightModeManager::_initTask()
  [NEW]     +48  [ = ]       0    FlightTaskAltitudeCruise
  [NEW]     +64  [ = ]       0    FlightTaskAltitudeCruise::FlightTaskAltitudeCruise()
  [NEW]     +32  [ = ]       0    FlightTaskAltitudeCruise::_updateXYSetpoint()
  [NEW]     +32  [ = ]       0    FlightTaskAltitudeCruise::reActivate()
  [NEW]     +96  [ = ]       0    FlightTaskAltitudeCruise::~FlightTaskAltitudeCruise()
  +100%     +16  [ = ]       0    FlightTaskDescend::updateParamsImpl()
  [NEW]     +32  [ = ]       0    FlightTaskManualAltitude::_updateXYSetpoint()
  [NEW]     +32  [ = ]       0    FlightTaskManualAltitude::_updateYawSetpoint()
  +100%     +16  [ = ]       0    MavlinkStreamAutopilotStateForGimbalDevice::send()
 -25.0%     -16  [ = ]       0    MavlinkStreamBatteryInfo::send()
  [NEW]     +48  [ = ]       0    StickTiltXY::generateAccelerationSetpointsForAltitudeCruise()
  [NEW]     +32  [ = ]       0    StickTiltXY::reset()
 -14.3%     -16  [ = ]       0    Sticks::~Sticks()
 -98.2%     +32  [ = ]       0    [3 Others]
  -0.3%     -32  [ = ]       0    [section .symtab]
-9.0%    -792  [ = ]       0    [Unmapped]
+0.2%  +108Ki  +0.0%    +792    TOTAL

px4_fmu-v6x [Total VM Diff: 792 byte (0.04 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%    +792  +0.0%    +792    .text
  [NEW]    +260  [NEW]    +260    StickTiltXY::generateAccelerationSetpointsForAltitudeCruise()
  [NEW]    +100  [NEW]    +100    FlightTaskAltitudeCruise
 -99.2%    +100 -99.2%    +100    [38 Others]
  [NEW]     +66  [NEW]     +66    FlightTaskManualAltitude::_updateXYSetpoint()
  [NEW]     +56  [NEW]     +56    FlightTaskAltitudeCruise::_updateXYSetpoint()
   +11%     +52   +11%     +52    FlightModeManager::start_flight_task()
  +2.1%     +44  +2.1%     +44    Commander::custom_command()
  [NEW]     +40  [NEW]     +40    FlightTaskAltitudeCruise::~FlightTaskAltitudeCruise()
  +2.2%     +32  +2.2%     +32    Failsafe::checkStateAndMode()
  [NEW]     +32  [NEW]     +32    FlightTaskManualAltitude::_updateYawSetpoint()
  +0.0%     +32  +0.0%     +32    [section .text]
  +0.0%     +32  +0.0%     +32    g_cromfs_image
  [NEW]     +28  [NEW]     +28    FlightTaskAltitudeCruise::FlightTaskAltitudeCruise()
   +13%     +24   +13%     +24    Failsafe::checkModeFallback()
  +3.4%     +20  +3.4%     +20    FixedWingModeManager::control_manual_position()
  [NEW]     +20  [NEW]     +20    FlightTaskAltitudeCruise::reActivate()
  +1.5%     +16  +1.5%     +16    matrix::Matrix<>::operator=()
  -1.5%     -28  -1.5%     -28    FixedWingModeManager::Run()
 -31.8%     -28 -31.8%     -28    FixedWingModeManager::manual_control_setpoint_poll()
 -17.1%     -28 -17.1%     -28    StickTiltXY::generateAccelerationSetpoints()
 -69.6%     -78 -69.6%     -78    FlightTaskManualAltitude::_updateSetpoints()
+0.2% +2.88Ki  [ = ]       0    .debug_abbrev
+0.2%    +344  [ = ]       0    .debug_aranges
+0.2%    +956  [ = ]       0    .debug_frame
+0.3% +86.0Ki  [ = ]       0    .debug_info
+0.2% +8.10Ki  [ = ]       0    .debug_line
  [DEL]      -1  [ = ]       0    [Unmapped]
  +0.2% +8.10Ki  [ = ]       0    [section .debug_line]
+0.2% +7.37Ki  [ = ]       0    .debug_loclists
+0.1%    +831  [ = ]       0    .debug_rnglists
 -33.3%      -1  [ = ]       0    [Unmapped]
  +0.1%    +832  [ = ]       0    [section .debug_rnglists]
+0.0%    +895  [ = ]       0    .debug_str
-0.8%      -2  [ = ]       0    .shstrtab
+0.1%    +542  [ = ]       0    .strtab
  [NEW]      +7  [ = ]       0    C.53.0
  [DEL]      -7  [ = ]       0    C.54.0
  [NEW]     +31  [ = ]       0    FlightTaskAltitudeCruise
  [NEW]     +68  [ = ]       0    FlightTaskAltitudeCruise::FlightTaskAltitudeCruise()
  [NEW]     +51  [ = ]       0    FlightTaskAltitudeCruise::_updateXYSetpoint()
  [NEW]     +44  [ = ]       0    FlightTaskAltitudeCruise::reActivate()
  [NEW]    +102  [ = ]       0    FlightTaskAltitudeCruise::~FlightTaskAltitudeCruise()
  [NEW]     +51  [ = ]       0    FlightTaskManualAltitude::_updateXYSetpoint()
  [NEW]     +52  [ = ]       0    FlightTaskManualAltitude::_updateYawSetpoint()
  [NEW]     +89  [ = ]       0    StickTiltXY::generateAccelerationSetpointsForAltitudeCruise()
  [NEW]     +25  [ = ]       0    StickTiltXY::reset()
  +0.1%     +29  [ = ]       0    [section .strtab]
+0.1%    +432  [ = ]       0    .symtab
  [NEW]     +32  [ = ]       0    C.53.0
  [DEL]     -32  [ = ]       0    C.54.0
  -3.8%     -16  [ = ]       0    Commander::handle_command()
 -50.0%     -32  [ = ]       0    EKFGSF_yaw::fuseVelocity()
 -33.3%     -16  [ = ]       0    FixedWingModeManager::manual_control_setpoint_poll()
   +17%     +16  [ = ]       0    FlightModeManager::_initTask()
  [NEW]     +48  [ = ]       0    FlightTaskAltitudeCruise
  [NEW]     +64  [ = ]       0    FlightTaskAltitudeCruise::FlightTaskAltitudeCruise()
  [NEW]     +32  [ = ]       0    FlightTaskAltitudeCruise::_updateXYSetpoint()
  [NEW]     +32  [ = ]       0    FlightTaskAltitudeCruise::reActivate()
  [NEW]     +96  [ = ]       0    FlightTaskAltitudeCruise::~FlightTaskAltitudeCruise()
  +100%     +16  [ = ]       0    FlightTaskDescend::updateParamsImpl()
  [NEW]     +32  [ = ]       0    FlightTaskManualAltitude::_updateXYSetpoint()
  [NEW]     +32  [ = ]       0    FlightTaskManualAltitude::_updateYawSetpoint()
  +100%     +16  [ = ]       0    MavlinkStreamAutopilotStateForGimbalDevice::send()
 -25.0%     -16  [ = ]       0    MavlinkStreamBatteryInfo::send()
  [NEW]     +48  [ = ]       0    StickTiltXY::generateAccelerationSetpointsForAltitudeCruise()
  [NEW]     +32  [ = ]       0    StickTiltXY::reset()
 -14.3%     -16  [ = ]       0    Sticks::~Sticks()
 -98.1%     +32  [ = ]       0    [1 Others]
  +0.3%     +32  [ = ]       0    [section .symtab]
-13.3%    -792  [ = ]       0    [Unmapped]
+0.2%  +108Ki  +0.0%    +792    TOTAL

Updated: 2025-08-29T13:33:11

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

"hockey puck mode" 😆

@dagar
Copy link
Member

dagar commented Aug 16, 2025

Coast or drift?

@hamishwillee
Copy link
Contributor

Docs when you're done please.

@sfuhrer
Copy link
Contributor Author

sfuhrer commented Aug 20, 2025

Coast or drift?

Both are valid options. What I don't like about them:

  • coast: could imply a "power-off" flight, like a glide. And for fixed-wing it doesn't give any hint on how it distinguishes from the current Altitude mode (the extinguishers are: you can disable manual control loss failsafe and you can setup a roll angle against the wind cross wind that is kept)
  • drift: MC: agree more catchy, but for FW the actual opposite is the case, it drifts less (due to reason explained above)

@sfuhrer sfuhrer force-pushed the pr-add-voyager-mode-main branch from 967982b to 0d9a806 Compare August 21, 2025 15:40
@sfuhrer sfuhrer marked this pull request as ready for review August 21, 2025 15:40
@sfuhrer sfuhrer force-pushed the pr-add-voyager-mode-main branch from 0d9a806 to aa38cec Compare August 21, 2025 16:18
MaEtUgR
MaEtUgR previously approved these changes Aug 21, 2025
Copy link
Member

@MaEtUgR MaEtUgR left a comment

Choose a reason for hiding this comment

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

Nice!
The only nit-picks I'd have are the name Voyager which I'd prefer Cruise, Drift, Coast, ... just because of intuitiveness but it's up for discussion. And I'll have to clean up the inheritance structure of the tasks but this pr is in line with the current architecture.

@MaEtUgR
Copy link
Member

MaEtUgR commented Aug 21, 2025

Ouch CI is real. The deadzone for the stick library is currently a multicopter parameter. Short term we could make that part optional e.g. only calculate the deazone expo things if the parameter exists and longer term the deadzone is probably a more global thing that depends on the input and not on the multicopter use case. The expo of course is use case dependent. I haven't thought about that sorry.
https://github.com/PX4/PX4-Autopilot/actions/runs/17132740115/job/48601079770?pr=25435#step:8:10550

@dakejahl
Copy link
Contributor

I like "cruise mode" and the mavlink spec says it should not be used for multicopters unless PRd to update. Should we just update the mavlink spec? I do think it's most suitable. Unless "cruise mode" as-is in the mavlink spec serves a slightly different purpose?

@github-actions github-actions bot added the Documentation 📑 Anything improving the documentation of the code / ecosystem label Aug 29, 2025
@sfuhrer sfuhrer force-pushed the pr-add-voyager-mode-main branch from 0f540ea to b399a4a Compare August 29, 2025 09:33
sfuhrer and others added 9 commits August 29, 2025 11:34
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
…siveness

Signed-off-by: Silvan <silvan@auterion.com>
Signed-off-by: Silvan <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
@sfuhrer sfuhrer force-pushed the pr-add-voyager-mode-main branch from b399a4a to bb0fad6 Compare August 29, 2025 09:34
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
@sfuhrer sfuhrer changed the title Add new flight mode: Altitude Voyager Add new flight mode: Altitude Cruise Aug 29, 2025
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
@sfuhrer sfuhrer force-pushed the pr-add-voyager-mode-main branch from be4bd4e to 20c5890 Compare August 29, 2025 13:25
Copy link

/en/flight_modes_mc/manual_altitude_cruise.md

  • PageNotInTOC: Page not in Table of Contents (/home/runner/work/PX4-Autopilot/PX4-Autopilot/docs/en/SUMMARY.md)

@sfuhrer
Copy link
Contributor Author

sfuhrer commented Aug 29, 2025

@MaEtUgR @dagar @dakejahl @bresch are you all good with calling it "Altitude Cruise"? The "Voyager" was a bit too abstract.
Altitude Cruise seems like the best compromise:

  • clear connection to Altitude mode
  • clear indication that it's meant for long distance, straight flights
  • still has some distinction to MAVLink standard mode "Cruise" by adding "Altitude"

@dakejahl
Copy link
Contributor

Altitude Cruise sounds good to me!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Documentation 📑 Anything improving the documentation of the code / ecosystem
Projects
None yet
Development

Successfully merging this pull request may close these issues.

6 participants