Px4+uxrce+zenoh_bridge_ros2dds

I’m trying to set up interoperability between the uxrce_agent and zenoh_bridge_ros2dds.

The problem: PX4 topics have INVALID topic type hash and BEST_EFFORT QoS. The zenoh_bridge_ros2dds bridge detects the PX4 topics, but data from them does not flow through the bridge into Zenoh — even though the keys are created and can be subscribed to.

However, if I start publishing my own messages to any PX4 topic with QoS=BEST_EFFORT, I begin receiving both my messages AND the messages sent by the flight controller in Zenoh. If QoS != BEST_EFFORT, I only see my own messages in Zenoh.

As I understand it, the CycloneDDS instance bundled inside zenoh_bridge_ros2dds is discarding data from PX4 topics. I tried configuring CycloneDDS via an XML file, but apparently the latest bridge version uses CycloneDDS 0.10.x, while the parameter I need — //CycloneDDS/Domain/Compatibility/IgnoreTypeInformation — seems to be available only in 0.11.x.

I would be over the moon if you could help! :folded_hands:

Hi @fj17,

Are you aware that PX4 has native Zenoh support built in? Since v1.17, there’s a zenoh module using Zenoh-Pico that runs directly on the FMU and talks to a Zenoh router without going through DDS at all.

The architecture is:

PX4 (Zenoh-Pico) → Zenoh router (rmw_zenohd) → ROS 2 (rmw_zenoh)

This skips the uXRCE-DDS agent and CycloneDDS entirely, which would avoid the type hash and QoS issues you’re hitting.

To set it up:

  1. Make sure your board config has CONFIG_MODULES_ZENOH=y (several boards include it by default, and SITL has px4_sitl_zenoh)
  2. Set ZENOH_ENABLE=1 on PX4
  3. Configure the network endpoint: zenoh config net client tcp/<companion_ip>:7447
  4. On the companion, run ros2 run rmw_zenoh_cpp rmw_zenohd and set RMW_IMPLEMENTATION=rmw_zenoh_cpp

More details in the docs

Let us know how it goes!

Thank you @rroche for your detailed answer!

Yes, I’ve heard about that approach, but I read that Zenoh-Pico in PX4 currently only works over Ethernet. Or am I mistaken? My flight controller doesn’t have Ethernet capability yet, unfortunately. So I thought that it’s not for me yet.

If I can’t get the bridge working, I’ll probably start exploring that direction anyway.

Thanks again for the suggestion! :folded_hands:

Hello everyone!

At our lab, we were trying out the zenoh module with the latest v.1.17.0-rc2 version on a Holybro Pixhawk 6X, but didn’t have any success connecting it with the companion PC over Ethernet. The companion was pingable and it seems the zenoh module discovered the rmw_zenohd but shortly after we started the zenoh module via MAVLink Shell, the system crashed and indicated that by beeping. QGrundControl was showing that there is a crash dump (see attached pdf).

fault_2026_04_23_11_29_37.pdf (94.2 KB)

@rroche I was wondering if the dev team encountered that crash after enabling the zenoh module as well? I’ve followed the documented steps for setting it up.

I appreciate any help since I’m really clueless on what to do to get it to work.

Thanks!

As far as i know yes, theres significant bandwidth constraints you need to take into account there

Thats not great @robin-mueller do you have any way to grab the ulog file for us? it would help tremendously

The error occurred when PX4 was disarmed (so no ulog file) and the zenoh client was started manually via MAVLink Shell. We tried arming PX4 and then starting zenoh. We downloaded the ulog after system crash and automatic reboot. I cannot upload the file here, where should I post it?

you can upload here https://logs.px4.io and share a link!

Thanks! Here it is: https://review.px4.io/plot_app?log=a2c14879-7d9c-4d9c-956d-1cdee1b6c061

Can you also share this file? /fs/microsd/fault_2026_04_24_11_23_46.log

Extremely helpful, turns out theres already a fix on the main branch, and I’m backporting to the v1.17 release. Thanks for reporting

Thanks for the clarification! Hopefully we get zenoh to work with this afterall :heart_eyes:

So I’m coming back on this @rroche (we should probably move this to a different place) because I cannot register a custom mode from ROS 2 Jazzy using zenoh. It seems that nothing is published through /fmu/out/register_ext_component_reply. Here is the topic info

$ ros2 topic info /fmu/out/register_ext_component_reply -v
Type: px4_msgs/msg/RegisterExtComponentReply

Publisher count: 1

Node name: px4_0006000000003436333634325103002a
Node namespace: /
Topic type: px4_msgs/msg/RegisterExtComponentReply
Topic type hash: RIHS01_cc8fe5e12b0cc58c2c976a5bcdfac5af3fa39f1b0b74c8073285dcbe6e62ed90
Endpoint type: PUBLISHER
GID: 2c.f9.53.48.1c.5b.57.71.81.92.73.50.78.bd.76.89
QoS profile:
  Reliability: RELIABLE
  History (Depth): KEEP_LAST (7)
  Durability: VOLATILE
  Lifespan: Infinite
  Deadline: Infinite
  Liveliness: AUTOMATIC
  Liveliness lease duration: Infinite

Subscription count: 1

Node name: set_actuators_node
Node namespace: /
Topic type: px4_msgs/msg/RegisterExtComponentReply
Topic type hash: RIHS01_cc8fe5e12b0cc58c2c976a5bcdfac5af3fa39f1b0b74c8073285dcbe6e62ed90
Endpoint type: SUBSCRIPTION
GID: 6b.0a.14.92.42.00.fa.ed.05.38.17.d7.42.4c.78.2b
QoS profile:
  Reliability: BEST_EFFORT
  History (Depth): KEEP_LAST (1)
  Durability: VOLATILE
  Lifespan: Infinite
  Deadline: Infinite
  Liveliness: AUTOMATIC
  Liveliness lease duration: Infinite

This is the default subscriber using px4-ros2-interface-lib. I’ve also tried matching the QoS exactly but that didn’t make a difference: Nothing is coming from PX4.

Other topics like /fmu/out/sensor_combined seem to be fine.

Any idea? I’m on the release/v1.17 branch

Actually it seems that the uORB topic register_ext_component_reply doesn’t exist … Here is the list of all uORB topics

$ uorb status
TOPIC NAME                          INST #SUB #Q SIZE PATH
actuator_armed                         0   10  1   16 /obj/actuator_armed0
actuator_controls_status_0             0    0  1   24 /obj/actuator_controls_status_00
actuator_motors                        0    3  1   72 /obj/actuator_motors0
actuator_outputs                       0    2  1   80 /obj/actuator_outputs0
actuator_outputs                       1    1  1   80 /obj/actuator_outputs1
actuator_servos                        0    1  1   48 /obj/actuator_servos0
actuator_servos_trim                   0    0  1   40 /obj/actuator_servos_trim0
adc_report                             0    1  1   96 /obj/adc_report0
arming_check_reply                     0    0  4  232 /obj/arming_check_reply0
autotune_attitude_control_status       0    3  1  104 /obj/autotune_attitude_control_status0
aux_global_position                    0    2  1   72 /obj/aux_global_position0
battery_status                         0    8  1  168 /obj/battery_status0
config_control_setpoints               0    0  1   24 /obj/config_control_setpoints0
config_overrides_request               0    0  4   16 /obj/config_overrides_request0
control_allocator_status               0    3  1   56 /obj/control_allocator_status0
control_allocator_status               1    1  1   56 /obj/control_allocator_status1
cpuload                                0    4  1   16 /obj/cpuload0
dataman_request                        0    1  1   80 /obj/dataman_request0
dataman_response                       0    6  1   72 /obj/dataman_response0
distance_sensor                        0    4  1   56 /obj/distance_sensor0
distance_sensor_mode_change_request    0    1  1   16 /obj/distance_sensor_mode_change_request0
ekf2_timestamps                        0    0  1   24 /obj/ekf2_timestamps0
estimator_aid_src_aux_global_position  0    1  1   96 /obj/estimator_aid_src_aux_global_position0
estimator_aid_src_baro_hgt             0    1  1   64 /obj/estimator_aid_src_baro_hgt0
estimator_aid_src_fake_hgt             0    0  1   64 /obj/estimator_aid_src_fake_hgt0
estimator_aid_src_fake_pos             0    0  1   96 /obj/estimator_aid_src_fake_pos0
estimator_aid_src_gnss_hgt             0    1  1   64 /obj/estimator_aid_src_gnss_hgt0
estimator_aid_src_gnss_pos             0    1  1   96 /obj/estimator_aid_src_gnss_pos0
estimator_aid_src_gnss_vel             0    1  1  120 /obj/estimator_aid_src_gnss_vel0
estimator_aid_src_gravity              0    1  1  120 /obj/estimator_aid_src_gravity0
estimator_aid_src_mag                  0    1  1  120 /obj/estimator_aid_src_mag0
estimator_aid_src_optical_flow         0    1  1   96 /obj/estimator_aid_src_optical_flow0
estimator_aid_src_rng_hgt              0    1  1   64 /obj/estimator_aid_src_rng_hgt0
estimator_baro_bias                    0    1  1   40 /obj/estimator_baro_bias0
estimator_event_flags                  0    1  1   40 /obj/estimator_event_flags0
estimator_gnss_hgt_bias                0    1  1   40 /obj/estimator_gnss_hgt_bias0
estimator_gps_status                   0    1  1   40 /obj/estimator_gps_status0
estimator_innovation_test_ratios       0    1  1  144 /obj/estimator_innovation_test_ratios0
estimator_innovation_variances         0    1  1  144 /obj/estimator_innovation_variances0
estimator_innovations                  0    1  1  144 /obj/estimator_innovations0
estimator_optical_flow_vel             0    1  1  104 /obj/estimator_optical_flow_vel0
estimator_sensor_bias                  0    5  1  120 /obj/estimator_sensor_bias0
estimator_states                       0    1  1  216 /obj/estimator_states0
estimator_status                       0    7  1  136 /obj/estimator_status0
estimator_status_flags                 0    4  1  104 /obj/estimator_status_flags0
event                                  0    2 16   40 /obj/event0
failsafe_flags                         0    2  1   96 /obj/failsafe_flags0
failure_detector_status                0    2  1   24 /obj/failure_detector_status0
geofence_status                        0    2  1   16 /obj/geofence_status0
goto_setpoint                          0    2  1   40 /obj/goto_setpoint0
health_report                          0    1  1   64 /obj/health_report0
input_rc                               0    3  1   72 /obj/input_rc0
landing_gear                           0    0  1   16 /obj/landing_gear0
led_control                            0    1  8   16 /obj/led_control0
log_message                            0    1  4  136 /obj/log_message0
magnetometer_bias_estimate             0    2  1   64 /obj/magnetometer_bias_estimate0
manual_control_input                   0    1  1   72 /obj/manual_control_input0
manual_control_input                   1    1  1   72 /obj/manual_control_input1
manual_control_setpoint                0    8  1   72 /obj/manual_control_setpoint0
mavlink_log                            0    1  8  136 /obj/mavlink_log0
mission                                0    5  1   40 /obj/mission0
mode_completed                         0    1  1   16 /obj/mode_completed0
navigator_status                       0    2  1   16 /obj/navigator_status0
obstacle_distance                      0    0  1  168 /obj/obstacle_distance0
offboard_control_mode                  0    3  1   16 /obj/offboard_control_mode0
onboard_computer_status                0    1  1  240 /obj/onboard_computer_status0
parameter_update                       0   45  1   40 /obj/parameter_update0
ping                                   0    0  1   32 /obj/ping0
position_setpoint_triplet              0    3  1  248 /obj/position_setpoint_triplet0
px4io_status                           0    1  1  144 /obj/px4io_status0
rate_ctrl_status                       0    1  1   24 /obj/rate_ctrl_status0
rc_channels                            0    0  1  128 /obj/rc_channels0
register_ext_component_request         0    0  2   56 /obj/register_ext_component_request0
rtl_status                             0    1  1   16 /obj/rtl_status0
rtl_time_estimate                      0    3  1   24 /obj/rtl_time_estimate0
safety_button                          0    1  2   16 /obj/safety_button0
sensor_accel                           0    6  8   48 /obj/sensor_accel0
sensor_accel                           1    5  8   48 /obj/sensor_accel1
sensor_accel                           2    5  8   48 /obj/sensor_accel2
sensor_accel_fifo                      0    0  1  224 /obj/sensor_accel_fifo0
sensor_accel_fifo                      1    0  1  224 /obj/sensor_accel_fifo1
sensor_accel_fifo                      2    0  1  224 /obj/sensor_accel_fifo2
sensor_baro                            0    4  4   32 /obj/sensor_baro0
sensor_baro                            1    3  4   32 /obj/sensor_baro1
sensor_combined                        0    3  1   48 /obj/sensor_combined0
sensor_gps                             0    3  1  152 /obj/sensor_gps0
sensor_gyro                            0    7  8   48 /obj/sensor_gyro0
sensor_gyro                            1    5  8   48 /obj/sensor_gyro1
sensor_gyro                            2    5  8   48 /obj/sensor_gyro2
sensor_gyro_fifo                       0    0  4  224 /obj/sensor_gyro_fifo0
sensor_gyro_fifo                       1    0  4  224 /obj/sensor_gyro_fifo1
sensor_gyro_fifo                       2    1  4  224 /obj/sensor_gyro_fifo2
sensor_mag                             0    4  4   40 /obj/sensor_mag0
sensor_mag                             1    4  4   40 /obj/sensor_mag1
sensor_optical_flow                    0    2  1   72 /obj/sensor_optical_flow0
sensor_preflight_mag                   0    2  1   16 /obj/sensor_preflight_mag0
sensor_selection                       0   10  1   16 /obj/sensor_selection0
sensors_status_baro                    0    0  1   64 /obj/sensors_status_baro0
sensors_status_imu                     0    2  1   96 /obj/sensors_status_imu0
sensors_status_mag                     0    0  1   64 /obj/sensors_status_mag0
system_power                           0    3  1   48 /obj/system_power0
takeoff_status                         0    3  1   16 /obj/takeoff_status0
task_stack_info                        0    0  2   40 /obj/task_stack_info0
telemetry_status                       0    2  1   88 /obj/telemetry_status0
trajectory_setpoint                    0    3  1   64 /obj/trajectory_setpoint0
transponder_report                     0    2 16   80 /obj/transponder_report0
tune_control                           0    1  4   24 /obj/tune_control0
unregister_ext_component               0    0  1   40 /obj/unregister_ext_component0
vehicle_acceleration                   0    2  1   32 /obj/vehicle_acceleration0
vehicle_air_data                       0    7  1   40 /obj/vehicle_air_data0
vehicle_angular_velocity               0    8  1   40 /obj/vehicle_angular_velocity0
vehicle_attitude                       0   12  1   56 /obj/vehicle_attitude0
vehicle_attitude_setpoint              0    3  1   40 /obj/vehicle_attitude_setpoint0
vehicle_command                        0    9  8   56 /obj/vehicle_command0
vehicle_command_ack                    0    4  4   24 /obj/vehicle_command_ack0
vehicle_command_mode_executor          0    1  8   56 /obj/vehicle_command_mode_executor0
vehicle_constraints                    0    2  1   24 /obj/vehicle_constraints0
vehicle_control_mode                   0   16  1   24 /obj/vehicle_control_mode0
vehicle_gps_position                   0   11  1  152 /obj/vehicle_gps_position0
vehicle_imu                            0    4  1   64 /obj/vehicle_imu0
vehicle_imu                            1    3  1   64 /obj/vehicle_imu1
vehicle_imu                            2    3  1   64 /obj/vehicle_imu2
vehicle_imu_status                     0    5  1  136 /obj/vehicle_imu_status0
vehicle_imu_status                     1    3  1  136 /obj/vehicle_imu_status1
vehicle_imu_status                     2    3  1  136 /obj/vehicle_imu_status2
vehicle_land_detected                  0   15  1   24 /obj/vehicle_land_detected0
vehicle_local_position                 0   20  1  192 /obj/vehicle_local_position0
vehicle_local_position_setpoint        0    2  1   64 /obj/vehicle_local_position_setpoint0
vehicle_magnetometer                   0    3  1   40 /obj/vehicle_magnetometer0
vehicle_mocap_odometry                 0    0  1  112 /obj/vehicle_mocap_odometry0
vehicle_odometry                       0    1  1  112 /obj/vehicle_odometry0
vehicle_optical_flow                   0    3  1   64 /obj/vehicle_optical_flow0
vehicle_rates_setpoint                 0    3  1   40 /obj/vehicle_rates_setpoint0
vehicle_status                         0   34  1   80 /obj/vehicle_status0
vehicle_thrust_setpoint                0    5  1   32 /obj/vehicle_thrust_setpoint0
vehicle_torque_setpoint                0    3  1   32 /obj/vehicle_torque_setpoint0
vehicle_visual_odometry                0    1  1  112 /obj/vehicle_visual_odometry0
yaw_estimator_status                   0    1  1  112 /obj/yaw_estimator_status0

EDIT:

So the problem turned out to be that custom modes are not supported in builds using the CONSTRAINED_FLASH toolchain flag (as px4_fmu-v6x_zenoh is using). My workaround for now is to disable the gimbal module. With that modification I’m able to upload (barely) to Pixhawk 6X:

[1737/1740] Linking CXX executable px4_fmu-v6x_zenoh.elf
Memory region         Used Size  Region Size  %age Used
        ITCM_RAM:           0 B        64 KB      0.00%
           FLASH:     1959580 B      1920 KB     99.67%
       DTCM1_RAM:           0 B        64 KB      0.00%
       DTCM2_RAM:           0 B        64 KB      0.00%
        AXI_SRAM:      105756 B       512 KB     20.17%
           SRAM1:           0 B       128 KB      0.00%
           SRAM2:           0 B       128 KB      0.00%
           SRAM3:           0 B        32 KB      0.00%
           SRAM4:          2 KB        64 KB      3.12%
          BKPRAM:           0 B         4 KB      0.00%
[1739/1740] uploading px4

I think this should be fixed for the 1.17 release. On main a promising PR has been merged module_base: remove CRTP template pattern to reduce flash bloat by dakejahl · Pull Request #26476 · PX4/PX4-Autopilot · GitHub

But it seems to be quite an effort to backport. Would be the right direction though.

EDIT AGAIN:

Even when successfully flashed, the mode manager in PX4 1.17 seems to cause a spike in RAM usage which leads to PX4 silently crashing or at least not responding. So even without CONSTRAINED_FLASH (which does bring back a reply when registering custom PX4 modes from ROS 2 using px4-ros2-interface-lib), I’m not able to successfully execute my custom mode. The custom mode crashes a few seconds due to no heartbeat from PX4.

When streaming dmesg in parallel, I can see that PX4 briefly reports “high RAM usage: 8800%” (ish).

I’ve switched to using the MicroXRCE-DDS Bridge again, since zenoh seems not usable for custom PX4 modes at the moment. Am I missing something? Is anyone having the same issue?