diff --git a/topic_tools/src/throttle_node.cpp b/topic_tools/src/throttle_node.cpp index 03252f6..bd94a01 100644 --- a/topic_tools/src/throttle_node.cpp +++ b/topic_tools/src/throttle_node.cpp @@ -34,7 +34,7 @@ ThrottleNode::ThrottleNode(const rclcpp::NodeOptions & options) if (throttle_type_str == "messages") { throttle_type_ = ThrottleType::MESSAGES; msgs_per_sec_ = declare_parameter("msgs_per_sec"); - period_ = rclcpp::Rate(msgs_per_sec_).period(); + period_ = rclcpp::Rate(msgs_per_sec_).period().to_chrono(); } else if (throttle_type_str == "bytes") { throttle_type_ = ThrottleType::BYTES; bytes_per_sec_ = declare_parameter("bytes_per_sec");