You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Describe the bug
I was able to reproduce the timeout reported in ros-controls/ros2_controllers#1574 locally. The issue is very intermittent and generally not reproducible on demand.
To Reproduce
Steps to reproduce the behavior:
run the unit tests for force_torque_sensor_broadcaster.
Test hangs during ForceTorqueSensorBroadcasterTest.InterfaceNames_Configure_Success.
Expected behavior
Test doesn't hang.
Environment (please complete the following information):
OS: Ubuntu
Jazzy
Additional context
gdb shows following stack when the test hung.
(gdb) bt
#0 0x000076fd5c4ecadf in __GI___clock_nanosleep (clock_id=clock_id@entry=0, flags=flags@entry=0,
req=0x7ffdbcceb530, rem=0x7ffdbcceb530) at ../sysdeps/unix/sysv/linux/clock_nanosleep.c:78
#1 0x000076fd5c4f9a27 in __GI___nanosleep (req=<optimized out>, rem=<optimized out>)
at ../sysdeps/unix/sysv/linux/nanosleep.c:25
#2 0x00005ea440439ff7 in void std::this_thread::sleep_for<long, std::ratio<1l, 1000000l> >(std::chrono::duration<long, std::ratio<1l, 1000000l> > const&) ()
#3 0x00005ea440447a93 in realtime_tools::RealtimePublisher<geometry_msgs::msg::WrenchStamped_<std::allocator<void> > >::~RealtimePublisher() ()
#4 0x00005ea4404434b8 in std::default_delete<realtime_tools::RealtimePublisher<geometry_msgs::msg::WrenchStamped_<std::allocator<void> > > >::operator()(realtime_tools::RealtimePublisher<geometry_msgs::msg::WrenchStamped_<std::allocator<void> > >*) const ()
#5 0x00005ea44043f400 in std::unique_ptr<realtime_tools::RealtimePublisher<geometry_msgs::msg::WrenchStamped_<std::allocator<void> > >, std::default_delete<realtime_tools::RealtimePublisher<geometry_msgs::msg::WrenchStamped_<std::allocator<void> > > > >::~unique_ptr() ()
#6 0x00005ea4404393b4 in force_torque_sensor_broadcaster::ForceTorqueSensorBroadcaster::~ForceTorqueSensorBroadcaster() ()
#7 0x00005ea44043f4de in FriendForceTorqueSensorBroadcaster::~FriendForceTorqueSensorBroadcaster() ()
#8 0x00005ea44043f4fe in FriendForceTorqueSensorBroadcaster::~FriendForceTorqueSensorBroadcaster() ()
#9 0x00005ea44043f53e in std::default_delete<FriendForceTorqueSensorBroadcaster>::operator()(FriendForceTorqueSensorBroadcaster*) const ()
#10 0x00005ea44043f5a2 in std::__uniq_ptr_impl<FriendForceTorqueSensorBroadcaster, std::default_delete<FriendForceTorqueSensorBroadcaster> >::reset(FriendForceTorqueSensorBroadcaster*) ()
#11 0x00005ea440439691 in std::unique_ptr<FriendForceTorqueSensorBroadcaster, std::default_delete<FriendForceTorqueSensorBroadcaster> >::reset(FriendForceTorqueSensorBroadcaster*) ()
The text was updated successfully, but these errors were encountered:
Describe the bug
I was able to reproduce the timeout reported in ros-controls/ros2_controllers#1574 locally. The issue is very intermittent and generally not reproducible on demand.
To Reproduce
Steps to reproduce the behavior:
force_torque_sensor_broadcaster
.ForceTorqueSensorBroadcasterTest.InterfaceNames_Configure_Success
.Expected behavior
Test doesn't hang.
Environment (please complete the following information):
Additional context
gdb shows following stack when the test hung.
The text was updated successfully, but these errors were encountered: