Skip to content

Conversation

@xznhj8129
Copy link
Contributor

@xznhj8129 xznhj8129 commented Nov 29, 2025

User description

This is an experimental addition to be able to set the navigation altitude target without RC. It's implemented as an MSP command, Programming operator and Mavlink (MAV_CMD_DO_CHANGE_ALTITUDE).

This isn't final, i'm showing the general concept, specifics like exact way to check for altitude control state and how to actually set the altitude target may be wrong; this is a first draft and no time to test immediately

How it works is a dual-purpose get/set MSP message MSP2_INAV_ALT_TARGET; empty request to get current target, data in request to set the new target.
It only works if:

  • Baro enabled
  • Altitude is controlled by Nav (Alt hold, Poshold, WP, RTH)
  • Not landing
  • Valid altitude estimate

Dual purpose get/set MSP is a thing i'm not sure about, if we want to maintain seperate GET/SET messages or combine them as general rule.

We use geoAltitudeDatumFlag_e as a reference frame flag, so default is NAV_WP_TAKEOFF_DATUM (0).

bool navigationSetAltitudeTargetWithDatum(geoAltitudeDatumFlag_e datumFlag, int32_t targetAltitudeCm)
{
    const navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags();
    if (!(stateFlags & NAV_CTL_ALT) || (stateFlags & NAV_CTL_LAND) || navigationIsExecutingAnEmergencyLanding() || posControl.flags.estAltStatus == EST_NONE) {
        return false;
    }

    float targetAltitudeLocalCm;
    switch (datumFlag) {
    case NAV_WP_TAKEOFF_DATUM:
        targetAltitudeLocalCm = (float)targetAltitudeCm;
        break;
    case NAV_WP_MSL_DATUM:
        if (!posControl.gpsOrigin.valid) {
            return false;
        }
        targetAltitudeLocalCm = (float)(targetAltitudeCm - posControl.gpsOrigin.alt);
        break;
    case NAV_WP_TERRAIN_DATUM:
    default:
        return false;
    }

    updateClimbRateToAltitudeController(0.0f, targetAltitudeLocalCm, ROC_TO_ALT_TARGET);
    return true;
}

With the enum, we can set different altitude frames: ASL, Takeoff (default), or, in the future, AGL.

Programming Framework supports new logic operator LOGIC_CONDITION_SET_ALTITUDE_TARGET through the same navigation function, allowing you to do that too.

MAVLink also handles it with MAV_CMD_DO_CHANGE_ALTITUDE via COMMAND_INT with frame GLOBAL and GLOBAL_RELATIVE

Comments encouraged


PR Type

Enhancement, New Feature


Description

This description is generated by an AI tool. It may have inaccuracies

  • Add altitude target setting via MSP, MAVLink, and Programming Framework

  • Implement navigationSetAltitudeTargetWithDatum() function supporting multiple altitude reference frames

  • Support MAV_CMD_DO_CHANGE_ALTITUDE MAVLink command with frame conversion logic

  • Add LOGIC_CONDITION_SET_ALTITUDE_TARGET operator for automation rules

  • Extend altitude datum enum with NAV_WP_TERRAIN_DATUM for future terrain-relative support

  • Update documentation generation regex and regenerate enum/message references


Diagram Walkthrough

flowchart LR
  A["User/GCS"] -->|MAVLink CMD| B["mavlink.c"]
  A -->|MSP Message| C["fc_msp.c"]
  A -->|Logic Condition| D["logic_condition.c"]
  B -->|Call| E["navigationSetAltitudeTargetWithDatum"]
  C -->|Call| E
  D -->|Call| E
  E -->|Set Target| F["Altitude Controller"]
  E -->|Validate| G["State Checks"]
Loading

File Walkthrough

Relevant files
Enhancement
6 files
mavlink.c
Handle MAVLink altitude change command                                     
+41/-2   
navigation.c
Implement altitude target setting function                             
+27/-0   
navigation.h
Add altitude datum enum and function declaration                 
+3/-1     
fc_msp.c
Handle MSP altitude target command                                             
+17/-0   
logic_condition.c
Add altitude target logic condition operator                         
+4/-0     
logic_condition.h
Define altitude target logic condition enum                           
+1/-0     
Configuration changes
1 files
msp_protocol_v2_inav.h
Define MSP2 altitude target message code                                 
+2/-0     
Documentation
6 files
gen_enum_md.py
Fix enum parsing regex for named enums                                     
+1/-1     
inav_enums_ref.md
Regenerate enum reference documentation                                   
+345/-1 
msp_ref.md
Add altitude target MSP command documentation                       
+15/-1   
msp_messages.json
Add altitude target message schema definition                       
+26/-0   
msp_messages.checksum
Update message schema checksum                                                     
+1/-1     
rev
Increment MSP documentation revision                                         
+1/-1     
Additional files
2 files
inav_enums.json +4130/-0
original_msp_ref.md +0/-1     

@xznhj8129 xznhj8129 changed the base branch from master to maintenance-9.x January 6, 2026 17:58
@xznhj8129 xznhj8129 marked this pull request as ready for review January 6, 2026 17:58
@qodo-code-review
Copy link
Contributor

PR Compliance Guide 🔍

All compliance sections have been disabled in the configurations.

@xznhj8129
Copy link
Contributor Author

Tested functionality and works in althold, cruise and poshold; ignored in RTH, i think this is ready to merge

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.

1 participant