ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
![]() | 1 | initial version |
Use rclpy.ok()
as a replacement for rospy.is_shutdown()
.
Using a Rate
object is a bit trickier in ROS 2, since the execution model is different. We need to make sure to ensure it updates and doesn't block forever. One option is to call "spin" (which executes ROS callbacks, including time updates) in a separate thread.
The ROS 1 example translated into ROS 2 looks something like this:
import threading
import rclpy
rclpy.init()
node = rclpy.create_node('simple_node')
# Spin in a separate thread
thread = threading.Thread(target=rclpy.spin, args=(node, ), daemon=True)
thread.start()
rate = node.create_rate(2)
try:
while rclpy.ok():
print('Help me body, you are my only hope')
rate.sleep()
except KeyboardInterrupt:
pass
rclpy.shutdown()
thread.join()
Another option is to spin in the main thread and poll the rate object to see if it is done. Something like what is done in this test, although this may be too complex for what you need.
I imagine the implementation of rclpy's Rate
could be improved so that users can avoid creating an extra thread; perhaps something worth considering.