Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 10 additions & 6 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,17 +48,21 @@ int main(int argc, char ** argv)
}
RCLCPP_INFO(cm->get_logger(), "update rate is %d Hz", update_rate);

rclcpp::Time end_period = cm->now();

// Use nanoseconds to avoid chrono's rounding
rclcpp::Duration period(std::chrono::nanoseconds(1000000000 / update_rate));

while (rclcpp::ok())
{
std::chrono::system_clock::time_point begin = std::chrono::system_clock::now();
// wait until we hit the end of the period
end_period += period;
std::this_thread::sleep_for(std::chrono::nanoseconds((end_period - cm->now()).nanoseconds()));

// execute "real-time" update loop
cm->read();
cm->update();
cm->write();
std::chrono::system_clock::time_point end = std::chrono::system_clock::now();
std::this_thread::sleep_for(std::max(
std::chrono::nanoseconds(0),
std::chrono::nanoseconds(1000000000 / update_rate) -
std::chrono::duration_cast<std::chrono::nanoseconds>(end - begin)));
}
});

Expand Down