fix(mavlink): accept offboard setpoints in offboard replacement modes#26771
fix(mavlink): accept offboard setpoints in offboard replacement modes#26771
Conversation
- 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.
|
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
left a comment
There was a problem hiding this comment.
@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.
|
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. Replacing OFFBOARD alone does not automatically enable MAVLink Offboard setpoint routing. So the intent is controlled compatibility for migration, with explicit and bounded behavior instead of implicit propagation. |
|
@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. |
|
Thanks for the clarification — I understand your point as:
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:
Which of these two directions would you consider more acceptable/preferred for mainline PX4? |
|
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 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 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. |
|
@jonas-eschmann thank you for proposing this design direction. I mapped out the same core flow you described, and the direction is aligned:
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)
Mode management layer (Commander/ModeManagement)
MAVLink routing layer (
|
|
cc @Pedro-Roque |
|
@Jaeyoung-Lim I don't see anything objectively wrong with the PR, do we want to refactor more things around it before merging? |
|
@Pedro-Roque @Jaeyoung-Lim Just to summarize the options:
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. |
|
@jonas-eschmann do you have a PR with Alternative 1? I can give it a look |
|
@Pedro-Roque not yet, Alternative 1 was included in the initial PR but we removed it to make |
|
@Pedro-Roque okay I created a PR for Alternative 1: #26949 |
Solved Problem
Fixes #26768
When an external mode replaces internal
OFFBOARD(for example RAPTOR withMC_RAPTOR_OFFB=1), standard MAVLink Offboard setpoints are parsed but not routed to internal setpoint topics because routing is gated byvehicle_status.nav_state == NAVIGATION_STATE_OFFBOARD.This blocks MAVLink/MAVROS users from using standard Offboard message flows to drive RAPTOR external references.
Solution
MavlinkReceiver:register_ext_component_requestregister_ext_component_replyunregister_ext_componentOFFBOARDOFFBOARDor external mode replacingOFFBOARD) for setpoint routing.SET_POSITION_TARGET_LOCAL_NED->trajectory_setpointSET_POSITION_TARGET_GLOBAL_INT->trajectory_setpointSET_ATTITUDE_TARGET->vehicle_attitude_setpointSET_ATTITUDE_TARGET(body-rate branch) ->vehicle_rates_setpointChangelog Entry
For release notes:
Alternatives
This PR intentionally keeps the change generic and local to MAVLink routing, avoids RAPTOR-only branching, and avoids public message/interface churn.
Test coverage
make px4_sitl_raptor gz_x500SET_POSITION_TARGET_*)Context
Changed files:
src/modules/mavlink/mavlink_receiver.hsrc/modules/mavlink/mavlink_receiver.cppsrc/modules/mc_raptor/README.md