High Stack Usage (95.0%!) and Waiting State on uxrce_dds_client task in PX4 Firmware

Dear PX4 Community Developers and Experts,

Hello everyone!

I am currently troubleshooting my real PX4 flight controller and have encountered a critical issue with the uxrce_dds_client task: it exhibits extremely high stack usage and remains in a Waiting state. This prevents me from establishing ROS 2 communication with the flight controller.

Problem Description and Symptoms:

  • I ran the offboard_control.py from px4_ros_com and found that /fmu/in has no subscribers; /fmu/out has no publishers.
  • Running ros2 topic echo /fmu/out/vehicle_status and /fmu/out/vehicle_local_position produces no output.
  • When I check the task status using the nsh> ps command, the output for uxrce_dds_client is as follows:
nsh> ps
 PID GROUP PRI POLICY   TYPE    NPX STATE    EVENT    SIGMASK   STACK   USED  FILLED COMMAND
   0     0   0 FIFO     Kthread N-- Ready              00000000 000726 000412  56.7%  Idle Task
   1     1 249 FIFO     Kthread --- Waiting  Semaphore 00000000 001224 000292  23.8%  hpwork 0x24000998
   2     2  50 FIFO     Kthread --- Waiting  Semaphore 00000000 001576 000292  18.5%  lpwork 0x240009ac
   3     3 100 FIFO     Task    --- Waiting  Semaphore 00000000 003144 002164  68.8%  nsh_main
   4     4 255 FIFO     Task    --- Waiting  Semaphore 00000000 001232 000580  47.0%  wq:manager
   5     4 205 FIFO     pthread --- Waiting  Semaphore 00000000 001896 001428  75.3%  wq:lp_default 0x81f15cc
 422   422  90 FIFO     Task    --- Waiting  Semaphore 00000000 001376 001084  78.7%  dataman
 488     4 255 FIFO     pthread --- Waiting  Semaphore 00000000 003120 002308  73.9%  wq:rate_ctrl 0x81e51b8
 746   746 237 FIFO     Task    --- Waiting  Signal    00000000 002000 001252  62.6%  ekf2 start
 491     4 253 FIFO     pthread --- Waiting  Semaphore 00000000 002368 001808  76.3%  wq:SPI1 0x81f437c
 717     4 242 FIFO     pthread --- Waiting  Semaphore 00000000 002216 001224  55.2%  wq:nav_and_controllers 0x81af980
 398     4 237 FIFO     pthread --- Waiting  Semaphore 00000000 002776 001112  40.0%  wq:hp_default 0x8197ed8
1071  1071 100 FIFO     Task    --- Waiting  Signal    00000000 002792 001948  69.7%  mavlink_if0 mavlink start -d /dev/ttyACM0 -m 2
1072  1071 175 FIFO     pthread --- Waiting  Semaphore 00000000 004776 001588  33.2%  mavlink_rcv_if0 0x30014768
 977   977 100 FIFO     Task    --- Waiting  Semaphore 00000000 009872 009396  95.1%! uxrce_dds_client start -t serial -d /dev/ttyS3 -b p:SER_TEL2_BAUD
 882   882 205 FIFO     Task    --- Waiting  Semaphore 00000000 001936 001188  61.3%  gps start -d /dev/ttyS0 -b p:SER_GPS1_BAUD
1075  1075 100 FIFO     Task    --- Running            00000000 002000 001492  74.6%  mavlink_shell
1044  1044 230 FIFO     Task    --- Waiting  Semaphore 00000000 003616 003060  84.6%! logger start -b 64 -t
1046  1044  60 FIFO     pthread --- Waiting  Semaphore 00000000 001144 000388  33.9%  log_writer_file 0x300082f0
 727     4 241 FIFO     pthread --- Waiting  Semaphore 00000000 005976 003660  61.2%  wq:INS0 0x81f4354
 984   984 105 FIFO     Task    --- Waiting  Semaphore 00000000 002104 001512  71.8%  navigator start
 505     4 243 FIFO     pthread --- Waiting  Semaphore 00000000 002312 000908  39.2%  wq:I2C4 0x81f434c
 730     4 240 FIFO     pthread --- Waiting  Semaphore 00000000 005976 003660  61.2%  wq:INS1 0x81f435c
 733   733 140 FIFO     Task    --- Waiting  Signal    00000000 003192 001524  47.7%  commander start
1054     4 236 FIFO     pthread --- Waiting  Semaphore 00000000 003600 002252  62.5%  wq:uavcan 0x81994a8
 447     4 246 FIFO     pthread --- Waiting  Semaphore 00000000 002312 000896  38.7%  wq:I2C1 0x81f4334

From the output above, it’s clear that:

  • The FILLED field shows stack usage at a critical 95.0%!, indicating an imminent or actual stack overflow, which can lead to instability or crashes.

  • The STATE field is Waiting, and the EVENT is Semaphore. This suggests the task is blocked, waiting for a specific semaphore to proceed with its execution.

  • Due to this client task not running correctly, my uxrce_dds_agent on the companion computer receives no data from the flight controller. The payload_rx counter consistently remains at 0, and ROS 2 topics fail to detect any PX4 publishers.

nsh> uxrce_dds_client status  
INFO  [uxrce_dds_client] Running, connected  
INFO  [uxrce_dds_client] Using transport:     serial  
INFO  [uxrce_dds_client] Payload tx:          66341 B/s  
INFO  [uxrce_dds_client] Payload rx:          0 B/s  
INFO  [uxrce_dds_client] timesync converged: true  uxrce_dds_client: cycle: 10707 events, 45043309us elapsed, 4206.90us avg, min 102us max 92283us 4310.698us rms  
uxrce_dds_client: cycle interval: 10712 events, 4206.94us avg, min 103us max 92284us 4310.532us rms

My Environment Configuration:

■ Flight Controller Hardware & PX4 Firmware: Holybro Pixhawk 6C with PX4 v1.15.4 stable.

■ QGroundControl Version: QGC 5.0.3.

■ DDS Agent: I am running eProsima Micro-XRCE-DDS Agent on an Orange Pi AI Pro (downloaded via snap: v1.0.2+git138.0aea832).

■ Connection Method: The flight controller’s TELEM2 port (GND, TX, RX) is connected to the Orange Pi AI Pro’s UART2 port (GND, RX, TX) using a GH1.25 to DuPont female cable.

PX4 Parameter Configuration:

  • MAV_0_CONFIG and MAV_1_CONFIG are disabled.
  • SER_TEL2_BAUD: 921600.
  • UXRCE_DDS_CONFIG: TELEM2.

Troubleshooting Steps I’ve Already Taken:

  • Attempted to use a source-compiled v2.4.2 Micro-XRCE-DDS Agent, with the same result.

  • Confirmed that the serial connection (wiring) and baud rate settings are correct.

  • Tested both manual startup and auto-startup methods for the uxrce_dds_client task, as well as trying other baud rates:
    1
    3

Manual start:
2

  • The micro_ros_agent (eProsima Agent) starts successfully on the Orange Pi. However, when performing uxrce_dds_client status checks from the MAVLink console (or via nsh> ps), the output consistently shows payload_rx as 0.

  • Checked the PX4 boot logs ( Manual start), but did not find any explicitly clear error messages pointing to the failure reason for uxrce_dds_client, other than its eventual Waiting state.

My Key Questions and Request for Help:

  • Does 95.0%! stack usage unequivocally mean a stack overflow has occurred or is imminent? In your opinion, is this stack issue the direct cause of it Waiting on Semaphore, or is the Waiting state itself leading to such high stack consumption?

  • What are the recommended methods to diagnose or optimize the stack usage of uxrce_dds_client within PX4 firmware?

  • Are there ways to further investigate the specific reason it’s Waiting on Semaphore?

  • Is the Waiting state indeed the reason why payload_rx remains at 0?

  • Any advice on how to resolve the uxrce_dds_client stack overflow, its waiting state, and the persistent payload_rx equals 0 issue would be immensely helpful. Thank you for your time and expertise!

This topic was automatically closed 90 days after the last reply. New replies are no longer allowed.