Skip to content

fix(mavlink): accept offboard setpoints in offboard replacement modes#26771

Open
GrooveWJH wants to merge 2 commits intoPX4:mainfrom
GrooveWJH:raptor-offboard-mavlink-support
Open

fix(mavlink): accept offboard setpoints in offboard replacement modes#26771
GrooveWJH wants to merge 2 commits intoPX4:mainfrom
GrooveWJH:raptor-offboard-mavlink-support

Conversation

@GrooveWJH
Copy link
Copy Markdown

Solved Problem

Fixes #26768

When an external mode replaces internal OFFBOARD (for example RAPTOR with MC_RAPTOR_OFFB=1), standard MAVLink Offboard setpoints are parsed but not routed to internal setpoint topics because routing is gated by vehicle_status.nav_state == NAVIGATION_STATE_OFFBOARD.

This blocks MAVLink/MAVROS users from using standard Offboard message flows to drive RAPTOR external references.

Solution

  • Added replacement-mode awareness inside MavlinkReceiver:
    • track register_ext_component_request
    • track register_ext_component_reply
    • track unregister_ext_component
    • cache which external navigation states replace internal OFFBOARD
  • Added a unified gate (OFFBOARD or external mode replacing OFFBOARD) for setpoint routing.
  • Applied the unified gate to:
    • SET_POSITION_TARGET_LOCAL_NED -> trajectory_setpoint
    • SET_POSITION_TARGET_GLOBAL_INT -> trajectory_setpoint
    • SET_ATTITUDE_TARGET -> vehicle_attitude_setpoint
    • SET_ATTITUDE_TARGET (body-rate branch) -> vehicle_rates_setpoint
  • Updated RAPTOR README to clarify that when RAPTOR replaces OFFBOARD, standard MAVLink Offboard setpoints remain accepted and routed.

Changelog Entry

For release notes:

Bugfix: Standard MAVLink Offboard setpoints are accepted when OFFBOARD is replaced by an external mode.
New parameter: none
Documentation: Updated mc_raptor README for OFFBOARD replacement behavior.

Alternatives

  • Add a new global uORB status field/message version to expose replacement mapping system-wide.
  • Implement RAPTOR-specific special handling in MAVLink receiver.

This PR intentionally keeps the change generic and local to MAVLink routing, avoids RAPTOR-only branching, and avoids public message/interface churn.

Test coverage

  • SITL validation on Ubuntu 24.04
    • Launch command: make px4_sitl_raptor gz_x500
  • MAVLink Offboard control validation
  • Observed behavior
    • In OFFBOARD-replacement mode (RAPTOR), setpoints are routed to internal setpoint topics as expected
    • Vehicle successfully performs ping-pong trajectory tracking
  • Regression boundary
    • Non-Offboard and non-Offboard-replacement modes remain gated (no safety boundary relaxation)

Context

Changed files:

  • src/modules/mavlink/mavlink_receiver.h
  • src/modules/mavlink/mavlink_receiver.cpp
  • src/modules/mc_raptor/README.md

- Track external mode registration/unregistration in MavlinkReceiver and cache which external nav states replace internal OFFBOARD.
- Use a unified Offboard-or-Offboard-replacement gate for SET_POSITION_TARGET_* and SET_ATTITUDE_TARGET routing paths.
- Keep MAVLink message definitions and RAPTOR-specific interfaces unchanged while preserving non-Offboard safety boundaries.
@GrooveWJH GrooveWJH changed the title MAVLink: accept Offboard setpoints in external modes replacing OFFBOARD fix(mavlink): accept offboard setpoints in offboard replacement modes Mar 17, 2026
@GrooveWJH
Copy link
Copy Markdown
Author

Since RAPTOR was introduced, adoption interest from application developers has grown quickly, and many teams are already evaluating real deployments. At the same time, a large portion of existing UAV applications still rely on MAVROS/MAVLink Offboard workflows. The current limitation is that when RAPTOR replaces OFFBOARD, external reference trajectories are effectively tied to the ROS 2 path, while standard MAVLink Offboard setpoints are not reliably routed into the internal control pipeline in that mode.

This change addresses that compatibility gap: without relaxing safety boundaries, it allows external modes that replace OFFBOARD to continue accepting standard MAVLink Offboard setpoints. This enables MAVROS/MAVLink users to adopt RAPTOR without re-architecting their upper-layer stack, and improves RAPTOR’s usability across existing ecosystems.

@Jaeyoung-Lim @jonas-eschmann

Copy link
Copy Markdown
Member

@Jaeyoung-Lim Jaeyoung-Lim left a comment

Choose a reason for hiding this comment

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

@GrooveWJH What would be the motivation of using offboard instead of the external flight mode registration? While I understand the intent of this PR, supporting offboard mode for flight mode registration would have implications that propagate throughout the flight stack that may introduce corner cases.

@GrooveWJH
Copy link
Copy Markdown
Author

@Jaeyoung-Lim

Thanks for the review.

Our motivation is migration compatibility: many RAPTOR users already have MAVROS/MAVLink Offboard pipelines, and when RAPTOR replaces OFFBOARD, that standard setpoint path currently breaks.

I agree that inferring behavior purely from “replace OFFBOARD” can be too implicit and may create corner cases for other external modes.
A better upstream direction is an explicit opt-in contract:

Replacing OFFBOARD alone does not automatically enable MAVLink Offboard setpoint routing.
An external mode must explicitly declare it wants standard Offboard setpoint intake.
MAVLink routing is enabled only when that explicit flag is present.
Non-Offboard and non-opted-in modes remain unchanged.

So the intent is controlled compatibility for migration, with explicit and bounded behavior instead of implicit propagation.
If this direction is preferred, I can rework the PR accordingly.

@Jaeyoung-Lim
Copy link
Copy Markdown
Member

@GrooveWJH If the existing pipeline is on ROS 1, ROS 1 is EOL since 2025 May so I don't think this is something that should be handled on the upstream side of PX4. If the existing pipeline is on ROS 2, this should require quite minimal modification to use the flight mode registration.

The reason why RAPTOR was implemented with flight mode registration was because the intent was not to replace the low level controls, so it can be safely tested.

If you want to use RAPTOR to use external setpoints, I think a better approach would be to make RAPTOR receive external setpoints, rather than modifying offboard mode itself.

@GrooveWJH
Copy link
Copy Markdown
Author

@Jaeyoung-Lim

Thanks for the clarification — I understand your point as:

  • We should avoid changing generic OFFBOARD semantics/routing.
  • Compatibility for RAPTOR should be scoped inside RAPTOR-specific boundaries.
  • In other words, this should not propagate behavior changes across the broader flight stack.

That makes sense to me from an upstream safety/maintenance perspective.

Given that, I see two viable directions that can both achieve the user goal (feeding external references while using RAPTOR mode), without changing global OFFBOARD behavior:

  1. RAPTOR-specific input path in PX4

    • Add a RAPTOR-scoped external setpoint intake path and keep routing logic local to RAPTOR.
  2. External bridge conversion path

    • Keep PX4 unchanged and convert MAVROS/MAVLink setpoints externally into the RAPTOR-consumable path (e.g. ROS 2/uXRCE-DDS trajectory_setpoint pipeline).

Which of these two directions would you consider more acceptable/preferred for mainline PX4?
Or do you have a better suggestion?

@jonas-eschmann
Copy link
Copy Markdown
Contributor

Hi @GrooveWJH thanks for raising this issue! And thanks @Jaeyoung-Lim for engaging it!

I also recently thought that I should revisit this and probably create a PR to enable this. The original RAPTOR PR had that functionality but we stripped it to make it more clear that the PR is fully self-contained and does not impact any other parts of the system.

The way I implemented it initially is to add a request_offboard_setpoints flag to the mode registration. Since the mavlink_receiver does not interact with the mode registration (and I think it is better to not entangle it with it), I added an accepts_offboard_setpoints to the vehicle_status which is also the authoritative source for the current mode for the mavlink_receiver.

In my opinion this is the cleanest way to do it.

Alternatively, the least invasive change would just be:

diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 4e01ca36832..5690fe35c75 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -1133,7 +1133,7 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
 			vehicle_status_s vehicle_status{};
 			_vehicle_status_sub.copy(&vehicle_status);
 
-			if (vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_OFFBOARD) {
+			if (vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_OFFBOARD || (vehicle_status.nav_state >= vehicle_status_s::NAVIGATION_STATE_EXTERNAL1 && vehicle_status.nav_state <= vehicle_status_s::NAVIGATION_STATE_EXTERNAL8)) {
 				// only publish setpoint once in OFFBOARD
 				setpoint.timestamp = hrt_absolute_time();
 				_trajectory_setpoint_pub.publish(setpoint);

I think this is also fine because it only affects modes running inside PX4 that use the external mode registration. And to my knowledge this is only mc_nn_control (who have also signalled that they would benefit from being able to receive trajectory_setpoint) and mc_raptor.

I agree with @GrooveWJH that this is important for the usability. And before everyone creates their own hacks to enable it, it would be better to support it in a standard way.
@Jaeyoung-Lim please let me know how you would like to proceed with this.

@GrooveWJH
Copy link
Copy Markdown
Author

@jonas-eschmann thank you for proposing this design direction. I mapped out the same core flow you described, and the direction is aligned:

request_offboard_setpoints -> vehicle_status.accepts_offboard_setpoints -> mavlink_receiver

One engineering observation: this is the cleanest architecture, but in PX4 mainline it is not a small change. It needs coordinated updates across multiple layers to be complete.

Message layer (versioned uORB)

  • Add request_offboard_setpoints to RegisterExtComponentRequest
  • Add accepts_offboard_setpoints to VehicleStatus
  • Bump corresponding MESSAGE_VERSIONs

Mode management layer (Commander/ModeManagement)

  • Store this capability at external mode registration time
  • Compute runtime accepts_offboard_setpoints from the currently active mode
  • Publish it through vehicle_status from Commander

MAVLink routing layer (mavlink_receiver)

  • Remove the initial PR approach where mavlink_receiver directly subscribed to and tracked mode registration state (register_ext_component_request/reply, unregister_ext_component) locally.
  • Route SET_POSITION_TARGET_* / SET_ATTITUDE_TARGET only based on vehicle_status.accepts_offboard_setpoints

Compatibility layer (translation / px4_msgs_old)

  • Add corresponding old-message versions and translation steps
  • Keep ROS2/translation_node version compatibility intact

After re-evaluating this, I think the larger change surface may still be justified. As external modes become more common in real deployments, formalizing this capability as an explicit contract in mainline interfaces should be more maintainable long-term than module-specific compatibility logic.

If you guys support this direction, I will continue and submit a concrete patch set for review.

@mrpollo
Copy link
Copy Markdown
Contributor

mrpollo commented Mar 18, 2026

cc @Pedro-Roque

@GrooveWJH
Copy link
Copy Markdown
Author

cc
@dagar
@bkueng

@mrpollo mrpollo requested a review from Pedro-Roque March 18, 2026 21:29
@Pedro-Roque
Copy link
Copy Markdown
Member

@Jaeyoung-Lim I don't see anything objectively wrong with the PR, do we want to refactor more things around it before merging?

@jonas-eschmann
Copy link
Copy Markdown
Contributor

@Pedro-Roque @Jaeyoung-Lim Just to summarize the options:

Approach Pros Cons
GrooveWJH PR: The Mavlink Receiver observes the external modes through the request topics No modifications to vehicle status The Mavlink receiver gets entangled with the mode registration
Alternative 1: request_offboard_setpoints in the external mode registration. This needs to be reflected in the vehicle_status because that is the main source determining the behavior of the mavlink_receiver.cpp Cleanest long-term solution   adds flag to vehicle_status
Alternative 2: Make mavlink_receiver.cpp always emit trajectory_setpoint for external mode IDs one-line fix  If there is ever an in-source mode that uses the external mode registration but also generates trajectory_setpoint itself, they could be conflicting. AFAIK currently only mc_raptor and mc_nn_control use the external mode registration from the inside and for external modes it does not matter anyways, so this is not an issue

I am strongly for fixing this and allowing people to use Mavlink setpoints for modes using the external mode registration. Out of the three options I would personally prefer them in this order: Alternative 1, Alternative 2, GrooveWJH PR.

@Pedro-Roque
Copy link
Copy Markdown
Member

@jonas-eschmann do you have a PR with Alternative 1? I can give it a look

@jonas-eschmann
Copy link
Copy Markdown
Contributor

@Pedro-Roque not yet, Alternative 1 was included in the initial PR but we removed it to make mc_raptor self contained for it to be merged. I'll try to create a PR by EOD

@jonas-eschmann
Copy link
Copy Markdown
Contributor

@Pedro-Roque okay I created a PR for Alternative 1: #26949

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.

[Bug] MAVLink/MAVROS Offboard setpoints ignored when OFFBOARD is replaced by external mode

5 participants