-
Notifications
You must be signed in to change notification settings - Fork 469
Open
Labels
Description
Generated by Generative AI
No response
Operating System:
Linux 6.8.0-59-generic #61~22.04.1-Ubuntu x86_64 x86_64 x86_64 GNU/Linux
ROS version or commit hash:
jazzy and rolling
RMW implementation (if applicable):
No response
RMW Configuration (if applicable):
No response
Client library (if applicable):
rclcpp
'ros2 doctor --report' output
ros2 doctor --report
# ros2 doctor --report
/opt/ros/jazzy/lib/python3.12/site-packages/ros2doctor/api/__init__.py: 162: UserWarning: Fail to call PackageReport class functions.
NETWORK CONFIGURATION
inet : 127.0.0.1
inet4 : ['127.0.0.1']
inet6 : ['::1']
netmask : 255.0.0.0
device : lo
flags : 73<RUNNING,LOOPBACK,UP>
mtu : 65536
inet : 192.168.9.120
inet4 : ['192.168.9.120']
ether : 68:7a:64:de:8d:e8
inet6 : ['fe80::83e1:63ec:44f2:f7f3%wlp0s20f3']
netmask : 255.255.255.0
device : wlp0s20f3
flags : 4163<RUNNING,BROADCAST,MULTICAST,UP>
mtu : 1500
broadcast : 192.168.9.255
inet : 172.31.0.1
inet4 : ['172.31.0.1']
ether : 02:42:00:5a:eb:e9
netmask : 255.255.255.0
device : docker0
flags : 4099<BROADCAST,MULTICAST,UP>
mtu : 1500
broadcast : 172.31.0.255
ether : ac:1a:3d:2d:70:57
device : enp0s31f6
flags : 4099<BROADCAST,MULTICAST,UP>
mtu : 1500
PLATFORM INFORMATION
system : Linux
platform info : Linux-6.8.0-59-generic-x86_64-with-glibc2.39
release : 6.8.0-59-generic
processor : x86_64
QOS COMPATIBILITY LIST
compatibility status : No publisher/subscriber pairs found
RMW MIDDLEWARE
middleware name : rmw_cyclonedds_cpp
ROS 2 INFORMATION
distribution name : jazzy
distribution type : ros2
distribution status : active
release platforms : {'debian': ['bookworm'], 'rhel': ['9'], 'ubuntu': ['noble']}
TOPIC LIST
topic : none
publisher count : 0
subscriber count : 0
Steps to reproduce issue
Found in MoveIt #3484 calling rate.sleep() after the node has been requested to shutdown causes rclcpp to crash. Guarding the sleep call with if (rclcpp::ok())
fixes the issue.
Expected behavior
rate.sleep() returns successfully even when rclcpp::ok()
is false
and allows the node to cleanly shut down.
Actual behavior
node crashes on shutdown
1: [move_group-3] terminate called after throwing an instance of 'std::runtime_error'
1: [move_group-3] what(): context cannot be slept with because it's invalid
1: [move_group-3] Stack trace (most recent call last) in thread 818677:
...
1: [move_group-3] > 552: rate.sleep();
1: [move_group-3] 553: }
1: [move_group-3] 554: } while (publish_planning_scene_);
1: [move_group-3] 555: }
1: [move_group-3] #9 Object "/opt/ros/jazzy/lib/librclcpp.so", at 0x799ca6b4c480, in rclcpp::Rate::sleep()
1: [move_group-3] #8 Object "/opt/ros/jazzy/lib/librclcpp.so", at 0x799ca6aa0238, in rclcpp::Clock::sleep_for(rclcpp::Duration, std::shared_ptr<rclcpp::Context>)
1: [move_group-3] #7 Object "/opt/ros/jazzy/lib/librclcpp.so", at 0x799ca6a64fdf, in
1: [move_group-3] #6 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.33", at 0x799ca67c3390, in __cxa_throw
1: [move_group-3] #5 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.33", at 0x799ca67ada54, in std::terminate()
1: [move_group-3] #4 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.33", at 0x799ca67c30d9, in
1: [move_group-3] #3 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.33", at 0x799ca67adff4, in
1: [move_group-3] #2 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x799ca64f08fe, in abort
1: [move_group-3] #1 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x799ca650d27d, in raise
1: [move_group-3] #0 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x799ca6566b2c, in pthread_kill
1: [move_group-3] Aborted (Signal sent by tkill() 818586 0)
Additional information
No response