PX4-Autopilot: Tx queue overflow with HITL in Gazebo 11 and Pixhawk 4
Describe the bug
When I run HITL with Pixhawk 4, Gazebo 11 and PX4 v1.13.0-beta1 (or master), the simulation failed to Tx queue overflow
after it connects to the USB port.
To Reproduce Steps to reproduce the behavior:
- Plug the Pixhawk 4 with PX4 v1.13.0-beta1 and HITL airframe config to USB port
- Wait the Pixhawk 4 to boot
- Run the command
gzserver --verbose Tools/sitl_gazebo/worlds/hitl_iris.world
- See error:
gzserver --verbose Tools/sitl_gazebo/worlds/hitl_iris.world
Gazebo multi-robot simulator, version 11.10.2
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org
[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.1.235
[Msg] Loading world file [/home/PX4-Autopilot/Tools/sitl_gazebo/worlds/hitl_iris.world]
[Wrn] [gazebo_gps_plugin.cpp:78] [gazebo_gps_plugin]: iris::gps0 using gps topic "gps0"
[Wrn] [gazebo_gps_plugin.cpp:203] [gazebo_gps_plugin] Using default update rate of 5hz
[Msg] Connecting to PX4 SITL using serial
[Msg] Lockstep is disabled
[Msg] Using MAVLink protocol v2.0
Opened serial device /dev/ttyACM0
Tx queue overflow
Tx queue overflow
Tx queue overflow
...
Expected behavior
Gazebo should not go to this Tx queue overflow
and we should see the drone in QGC through UDP
Additional context I tried also with master branch, with new install of Ubuntu 20.04, with new Pixhawk 4 but I always get this same error. With v1.12.3 it works fine with Gazebo. Also with v1.13.0-beta1 or master HITL works fine with jmavsim so I guess the issue comes from Gazebo
About this issue
- Original URL
- State: closed
- Created 2 years ago
- Comments: 18 (8 by maintainers)
Based on what I did, I don’t think it is a problem of port, because when I used a quadrotor with four tiltable rotors, it shows overflow, but when I used a common quadrotor, everything is fine.
This issue has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:
https://discuss.px4.io/t/hil-is-not-working/29713/1
Whatever you connect to the PC first, will have
/dev/ttyACM0
and sometimes the port might still be blocked because it’s still open by QGC or something else and hence you’ll get/dev/ttyACM1
. That would explain it.If you want to avoid dealing with these instance numbers, just use the path by id which doesn’t change, e.g.:
/dev/serial/by-id/...
and put that one in the sdf.This often happens if the configured serial port is not the right one.
Hello, @julianoes,
I am still facing this problem when I am customizing my own gazebo model but connecting with Pixhawk mini.
I am using the same setting of mavlink plugin in the iris.sdf. And following what stated on the setting of HITL, the problem of :Tx queue overflow still appeared.
Any solutions or suggetion are welcomed!!!
Ok, I found the reason. This reason is that the mavlink instance on the Pixhawk’s USB is no longer running by default but is started when it detects an incoming MAVLink heartbeat. It turns out that Gazebo HITL does not send any heartbeats so then the mavlink instance on the PX4 side is not started and Gazebo just fills it’s Tx buffer.
The auto-detection happens here: https://github.com/PX4/PX4-Autopilot/blob/887fe7dba2d2d0dbdf8a2b9141f1b0de781ebc4e/platforms/nuttx/src/px4/common/cdc_acm_check.cpp#L224-L236
To fix this, I enabled sending heartbeats on the Gazebo side. However, sending a heartbeat every second was not enough, because all the buffers might get filled with HITL data in less than a second which then again leads to the situation where the mavlink instance is not started. Therefore, I’m sending the heartbeat in every iteration until we receive a heartbeat which tells us PX4 is talking back.
Fixed in https://github.com/PX4/PX4-SITL_gazebo/pull/863.