Skip to content

Commit 9b29d75

Browse files
authored
Move clock availability check to controller manager thread (ros-controls#2654) (ros-controls#2660)
1 parent a2e5819 commit 9b29d75

File tree

1 file changed

+4
-4
lines changed

1 file changed

+4
-4
lines changed

controller_manager/src/ros2_control_node.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -70,10 +70,6 @@ int main(int argc, char ** argv)
7070
}
7171
}
7272

73-
// wait for the clock to be available
74-
cm->get_clock()->wait_until_started();
75-
cm->get_clock()->sleep_for(rclcpp::Duration::from_seconds(1.0 / cm->get_update_rate()));
76-
7773
RCLCPP_INFO(cm->get_logger(), "update rate is %d Hz", cm->get_update_rate());
7874
const bool manage_overruns = cm->get_parameter_or<bool>("overruns.manage", true);
7975
RCLCPP_INFO(
@@ -126,6 +122,10 @@ int main(int argc, char ** argv)
126122
thread_priority);
127123
}
128124

125+
// wait for the clock to be available
126+
cm->get_clock()->wait_until_started();
127+
cm->get_clock()->sleep_for(rclcpp::Duration::from_seconds(1.0 / cm->get_update_rate()));
128+
129129
// for calculating sleep time
130130
auto const period = std::chrono::nanoseconds(1'000'000'000 / cm->get_update_rate());
131131

0 commit comments

Comments
 (0)