Skip to content

Conversation

@jonas-eschmann
Copy link
Contributor

As requested by @mrpollo here I moved the Raptor implementation from an out-of-tree module into a proper in-tree module. It uses the external mode registration.

Raptor is an end-to-end foundation policy that takes position, orientation, linear velocity and angular velocity as inputs and outputs motor commands (actuator_motors). The policy is adaptive and can control virtually any quadrotor, zero-shot. We tested it on 10 different real quadrotors (from 30g to 2.4kg). More info can be found here: https://raptor.rl.tools/.

The goal of this integration is to provide a baseline for reinforcement learning-based quadrotor control research. This module is a robust baseline as well as a starting point for researchers and practitioners to train and deploy their own end-to-end control policies.

A highlight feature of this new implementation is that the neural network weights can be loaded from the SD card and (unlike the nn_mc_control module) do not need to be compiled into the firmware. This drastically reduces the flash usage and allows testing new neural networks without re-flashing the flight controller and remotely by transferring the checkpoint via Mavlink FTP.

The policy is trained for position control (controlling the position error to zero) but as we show in the paper also performs well for trajectory tracking (by offsetting position and linear velocity with the desired values from the trajectory). Hence, this module supports receiving trajectory_setpoint. The problem is that the forwarding of the trajectory setpoint from Mavlink is hardcoded to require the offboard mode in mavlink_receiver.cpp. Because of this we propose to add a request_offboard_setpoints into the mode registration request. In combination with minimal adjustments in the commander and mode management, this allows to forward the setpoint in a configurable way.

The neural networks are trained and run using RLtools, a pure C++, dependency-free, header-only library. It was created with a major focus on stability and is maintained by me. Compared to e.g. Tensorflow Lite I expect it to cause less issues going forward due to its simplicity.

We tested the previous implementation (OOT module) extensively on three different real platforms. This implementation shares major parts of the code with that but has not been tested on a real platform, yet (I will hopefully be able to test it next week). But I tested it in the SITL and SIH. These are the steps I use to run it:

SITL

Standalone Usage (Without External Trajectory Setpoint)

Build PX4 SITL with Raptor, disable QGC requirement, and adjust the IMU_GYRO_RATEMAX to match the simulation IMU rate

make px4_sitl_raptor gz_x500
param set NAV_DLL_ACT 0
param set COM_DISARM_LAND -1 # When taking off in offboard the landing detector can cause mid-air disarms
param set IMU_GYRO_RATEMAX 250 # Just for SITL. Tested with IMU_GYRO_RATEMAX=400 on real FCUs
param set MC_RAPTOR_ENABLE 1
param set MC_RAPTOR_OFFB 0

Upload the RAPTOR checkpoint to the "SD card": Separate terminal

mavproxy.py --master udp:127.0.0.1:14540
ftp mkdir /raptor # for the real FMU use: /fs/microsd/raptor
ftp put src/modules/mc_raptor/blob/policy.tar /raptor/policy.tar

restart (ctrl+c)

make px4_sitl_raptor gz_x500
commander takeoff
commander status

Note the external mode ID of RAPTOR in the status report

commander mode ext{RAPTOR_MODE_ID}

Usage with External Trajectory Setpoint

Send Lissajous setpoints via Mavlink:

pip install px4
px4 udp:localhost:14540 track lissajous --A 2.0 --B 1.0 --duration 10 --ramp-duration 5 --takeoff 10.0 --iterations 2

SIH

make px4_fmu-v6c_raptor upload

In QGroundControl:

  • Airframes => SIH Quadrotor X
  • Settings => Comm Links => Disable Pixhawk (disable automatic USB serial connection)
mavproxy.py --master /dev/serial/by-id/usb-Auterion_PX4_FMU_v6C.x_0-if00 --out udp:localhost:14550 --out udp:localhost:13337 --out udp:localhost:13338

New terminal (optional):

./Tools/mavlink_shell.py udp:localhost:13338
param set SIH_IXX 0.005
param set SIH_IYY 0.005
param set SIH_IZZ 0.010
param set IMU_GYRO_RATEMAX 400
param save
reboot

New terminal:

./Tools/simulation/jmavsim/jmavsim_run.sh -u -p 13337 -o

bump

compiles and raptor mode appears

hovering with RAPTOR seems to work

Using Raptor to execute offboard commands works (using multirobot f03825a5795a77c5a095f799eeb8e0b646fe7176 to feed the trajectory_setpoint). Requires more testing

simplified rotmat

runtime inference frequency multiple

arming request response reflects actual readiness

adjusting to fit IMU gyro ratemax

relaxing control timing warning thresholds for SITL

Using mode registration to signal if offboard commands should be forwarded to trajectory_setpoint instead of just hardcoding vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_OFFBOARD

adopting new "request_offboard_setpoint" in raptor module

replace offboard seems good

mc_raptor: overwrite offboard parameter

separate raptor config

addendum

Raptor off by default

RAPTOR readme

Loading raptor checkpoint from tar works.

check if load was successful

refactoring: cutting out the pure C interface to allow direct testing of the policy input/output behavior from the file, without fully loading it into memory first

adapter not needed anymore

ripping out test observation mode (not used in a long time)

fixing warnings

bump RLtools to fix the remaining warnings

Loading RAPTOR checkpoint from sdcard seems to work on FMU-6C

embedding Raptor policy into flash works again

also printing checkpoint name when using the embedded policy

cleaner handling of the checkpoint name

back to reading from file

ripping out visual odometry checks

cleaner

more debug but no success

bump rlt

bump

pre next rebase

we can publish the no angvel update because we latch onto it with the scheduled work item anyways

this kind of runs on the 6c

still bad

SIH almost flying

saving stale traj setpoint yaw

new error. timestamp not the problem anymore

bump rlt; SIH works with executor

shaping up

bumping blob (include tar checkpoint)

cleaning up

fixing formatting

update readme
bump

compiles and raptor mode appears

hovering with RAPTOR seems to work

Using Raptor to execute offboard commands works (using multirobot f03825a5795a77c5a095f799eeb8e0b646fe7176 to feed the trajectory_setpoint). Requires more testing

simplified rotmat

runtime inference frequency multiple

arming request response reflects actual readiness

adjusting to fit IMU gyro ratemax

relaxing control timing warning thresholds for SITL

Using mode registration to signal if offboard commands should be forwarded to trajectory_setpoint instead of just hardcoding vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_OFFBOARD

adopting new "request_offboard_setpoint" in raptor module

replace offboard seems good

mc_raptor: overwrite offboard parameter

separate raptor config

addendum

Raptor off by default

RAPTOR readme

Loading raptor checkpoint from tar works.

check if load was successful

refactoring: cutting out the pure C interface to allow direct testing of the policy input/output behavior from the file, without fully loading it into memory first

adapter not needed anymore

ripping out test observation mode (not used in a long time)

fixing warnings

bump RLtools to fix the remaining warnings

Loading RAPTOR checkpoint from sdcard seems to work on FMU-6C

embedding Raptor policy into flash works again

also printing checkpoint name when using the embedded policy

cleaner handling of the checkpoint name

back to reading from file

ripping out visual odometry checks

cleaner

more debug but no success

bump rlt

bump

pre next rebase

we can publish the no angvel update because we latch onto it with the scheduled work item anyways

this kind of runs on the 6c

still bad

SIH almost flying

saving stale traj setpoint yaw

new error. timestamp not the problem anymore

bump rlt; SIH works with executor

shaping up

bumping blob (include tar checkpoint)

cleaning up

fixing formatting

update readme

updating gitignore
@mrpollo mrpollo requested a review from hamishwillee December 12, 2025 02:25

if (vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_OFFBOARD) {
// only publish setpoint once in OFFBOARD
if (vehicle_status.accepts_offboard_setpoints) {
Copy link
Contributor

Choose a reason for hiding this comment

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

So your raptor is implemented an external mode like offboard and you still want to publish trajectory setpoints? As long as this still works for offboard this is OK.

I don't understand what Raptor is - foundation policy sounds like some kind of corporate or academic doublespeak. Can you please explain it in little words (I'm a tech writer).

What does it do, who would want to use it, how can they enable it.

This also needs docs enough to answer that.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Yes exactly, it uses the mode registration to register a new mode. I think this is the cleanest way to separate it from the other parts of the control stack and it was also requested by @AlexKlimaj here .

We chose the term "foundation policy" because the way it is trained and the way it works resembles foundation models. "Policy" is the standard term in the reinforcement learning community, it is equivalent to "controller" in the robotics community.

What does it do:
The idea is to have an adaptive policy, that can quickly adapt to any quadrotor by observing its response and adapting its control behavior. The goal is to get rid of the requirement for PID tuning and to be more robust wrt. disturbances or other changes in the dynamics. It is an end-to-end policy, meaning it takes state information (position, orientation, linear velocity, angular velocity) as input and directly outputs motor commands (actuator motors). Please refer to this video: https://www.youtube.com/watch?v=hVzdWRFTX3k and for more details to the paper: https://arxiv.org/abs/2509.11481

Who would want to use it:
Mainly academic use at this point (which is only the beginning), e.g. as a baseline for alternative control methods, but possibly also some commercial use-cases, where, e.g. the hardware (or payload) is changed often and the cost for tuning the controllers is prohibitive.

How can they enable it:
Please refer to the instructions: #26082 (comment). But I also plan to make a short video that shows how to use it step-by-step on a Holybro x500 v2 for the documentation.

I hope I find time to work on the docs in the next days. I'm conducting real-world flight tests for this PR right now

Copy link
Contributor

Choose a reason for hiding this comment

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

Thanks very much. So this sounds a bit like https://docs.px4.io/main/en/advanced/neural_networks to me. That's just an observation, but it does mean we need to think about positioning this, and if they have overlap, grouping them.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Sorry for the late response but I wanted to do some more thorough real-world testing. I have added documentation in docs/en/advanced/raptor.md, including an interactive playground to test the RAPTOR policy in simulation as well as a trajectory parameter generator app. Please let me know what you think

@@ -0,0 +1,10 @@
# TOPICS raptor_input
Copy link
Contributor

Choose a reason for hiding this comment

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

All of these uorb topics need documentation to the current standard. That is still a work in progress - see #25878

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Thanks for letting me know! I have added documentation, please let me know if it meets the current standard

Copy link
Contributor

Choose a reason for hiding this comment

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

Thanks very much. You followed the rules pretty well, but some of them changed in the last week and I haven't updated the PR. Example see https://github.com/PX4/PX4-Autopilot/pull/26082/files#r2629315765

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Thank you! I have updated the RaptorStatus.msg to follow the same formatting conventions that you proposed for RaptorInput.msg

@@ -0,0 +1,72 @@
# RAPTOR
Copy link
Contributor

Choose a reason for hiding this comment

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

FWIW this is the sort of stuff you'd have in the docs, then link to the docs from here if you need a readme.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Added docs in docs/en/advanced/raptor.md

@Jaeyoung-Lim
Copy link
Member

@SindreMHegre Could you have a look?

@SindreMHegre
Copy link
Contributor

SindreMHegre commented Dec 18, 2025

@SindreMHegre Could you have a look?

@Jaeyoung-Lim I think I have time for this tomorrow, will take a look then. But this sounds really promising, adding SD card storage of the network and sending setpoints over Mavlink are huge upgrades over my work! I tried a bit on the setpoints but weren't able to within the time limit of my work.

Copy link
Contributor

@SindreMHegre SindreMHegre left a comment

Choose a reason for hiding this comment

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

I did not have time to look into the details of the actual mc_raptor.cpp and hpp files. But it looks a lot like my module. I think it's really nice to have both options so I think its best to merge the documentation somewhat in the top script and then divide into to sub files for module specific information. If you have any specific questions @jonas-eschmann don't hesitate to ask, and it looks like you've already looked at the mc_nn_module, but if you need the full history you can find it here. It would be really cool to get the possibility to send mavlink setpoints to the mc_nn_module as well, but I can try to ping the lab at NTNU if it's not a quick fix possible to integrate into this PR. The same goes for storing the networks on the SD card, super usefull upgrade that would be great for the mc_nn_control. I still thinks mc_nn_control still has a place in PX4, as it supports using different frameworks and could still be used for other things than control! Really nice to see the possibilities for NNs in PX4 expand and improve!!!!

CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_LIB_RL_TOOLS=y
CONFIG_MODULES_MC_RAPTOR=y
Copy link
Contributor

Choose a reason for hiding this comment

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

Alphabetically sorted?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Good point! I wasn't aware they should be sorted. I sorted ./boards/sitl/raptor.px4board and boards/px4/fmu-v6c/raptor.px4board

Comment on lines 44 to 45
CONFIG_LIB_RL_TOOLS=y
CONFIG_MODULES_MC_RAPTOR=y
Copy link
Contributor

Choose a reason for hiding this comment

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

alphabetically sorted?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Sorted in e4ad0a


uint8 executor_in_charge # Current mode executor in charge (0=Autopilot)

bool accepts_offboard_setpoints # True if the current mode accepts offboard trajectory setpoints via MAVLink
Copy link
Contributor

Choose a reason for hiding this comment

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

shouldn't message version be bumped here as well?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Thanks a lot for the hint! I bumped the version and archived the old one

@SindreMHegre
Copy link
Contributor

Also, if this can be used on Ubuntu versions prior to 24, then it should be clear in the docs, as the mc_nn_control module does not, so for those on older versions it would be great with a plug and play neural module

@Jaeyoung-Lim
Copy link
Member

@SindreMHegre Wouldn't it be better to make the Aerial gym training work with the dynamic loading of neural networks?

For me I think it might be a good opportunity to get rid of the tfmicro dependency, and the convoluted CMake hacks we had to go through if we can make them share the neural network infrastructure.

@github-actions
Copy link

No flaws found

@jonas-eschmann
Copy link
Contributor Author

jonas-eschmann commented Dec 30, 2025

@SindreMHegre Thanks a lot for the review! Your implementation, particularly using the external mode registration, was very useful as a guide! We have had an out-of-tree module solution (one-line modification to PX4 to use actuator_motors from our module's topic + out-of-tree modules that handle trajectory generation, inference etc.) for two years now but for upstreaming using the external mode registration is much cleaner!

Also, if this can be used on Ubuntu versions prior to 24, then it should be clear in the docs, as the mc_nn_control module does not, so for those on older versions it would be great with a plug and play neural module

This should work on any OS/version, as long as the C++ compiler supports C++17 (GCC/Clang/MSVC releases from 2017/2018 onwards).

In the meantime, I have also conducted extensive outdoor flying tests using mc_raptor for control (up to 17 m/s) and it is very reliable. I experienced zero hiccups and no crashes and think it is really stable and easy to use at this point.

Figure Eight Tracking Plot

Line Tracking Plot

Videos (links to YouTube):

Line Tracking Video

Figure Eight Tracking Video

I have also added relatively extensive documentation in docs/en/advanced/raptor.md

@Jaeyoung-Lim Please let me know how to proceed

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.

4 participants