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
17 changes: 7 additions & 10 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,25 +40,22 @@ int main(int argc, char ** argv)
std::thread cm_thread([cm]() {
RCLCPP_INFO(cm->get_logger(), "update rate is %d Hz", cm->get_update_rate());

std::chrono::system_clock::time_point timepoint_start = std::chrono::system_clock::now();
std::chrono::system_clock::time_point begin = timepoint_start;
rclcpp::Time begin = cm->now();

// Use nanoseconds to avoid chrono's rounding
std::this_thread::sleep_for(std::chrono::nanoseconds(1000000000 / cm->get_update_rate()));
while (rclcpp::ok())
{
std::chrono::system_clock::time_point begin_last = begin;
begin = std::chrono::system_clock::now();
rclcpp::Time begin_last = begin;
begin = cm->now();
cm->read();
cm->update(
rclcpp::Time(
std::chrono::duration_cast<std::chrono::nanoseconds>(begin - timepoint_start).count()),
rclcpp::Duration(std::chrono::duration_cast<std::chrono::nanoseconds>(begin - begin_last)));
cm->update(begin, begin - begin_last);
cm->write();
std::chrono::system_clock::time_point end = std::chrono::system_clock::now();
rclcpp::Time end = cm->now();
std::this_thread::sleep_for(std::max(
std::chrono::nanoseconds(0),
std::chrono::nanoseconds(1000000000 / cm->get_update_rate()) -
std::chrono::duration_cast<std::chrono::nanoseconds>(end - begin)));
std::chrono::nanoseconds(end.nanoseconds() - begin.nanoseconds())));
}
});

Expand Down