Skip to content

Commit 73551ef

Browse files
Guard condition to check node clock is not zero, to suppress "No clock received" error from ros2_control. (#1027)
Added guard condition to check node clock is not zero, to suppress "No clock received" error from ros2_control.
1 parent 9d870d1 commit 73551ef

File tree

2 files changed

+3
-1
lines changed

2 files changed

+3
-1
lines changed

webots_ros2_control/src/Ros2Control.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,7 @@ namespace webots_ros2_control {
9090
void Ros2Control::step() {
9191
const int nowMs = wb_robot_get_time() * 1000.0;
9292
const int periodMs = nowMs - mLastControlUpdateMs;
93-
if (periodMs >= mControlPeriodMs) {
93+
if (periodMs >= mControlPeriodMs && mNode->get_clock()->now() != rclcpp::Time(0, 0, mNode->get_clock()->get_clock_type())) {
9494
const rclcpp::Duration dt = rclcpp::Duration::from_seconds(mControlPeriodMs / 1000.0);
9595
mControllerManager->read(mNode->get_clock()->now(), dt);
9696

webots_ros2_driver/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,8 @@ find_package(yaml-cpp REQUIRED)
3232

3333
if($ENV{ROS_DISTRO} MATCHES "humble")
3434
find_package(Python 3.10 EXACT REQUIRED COMPONENTS Development)
35+
elseif($ENV{ROS_DISTRO} MATCHES "iron")
36+
find_package(Python 3.10 EXACT REQUIRED COMPONENTS Development)
3537
elseif($ENV{ROS_DISTRO} MATCHES "jazzy")
3638
find_package(Python 3.12 EXACT REQUIRED COMPONENTS Development)
3739
elseif($ENV{ROS_DISTRO} MATCHES "rolling")

0 commit comments

Comments
 (0)