Skip to content

Commit

Permalink
Fix const-ness in std::chrono::time_point construction and explicitly…
Browse files Browse the repository at this point in the history
… use std::chrono::nanoseconds as std::chrono::time_point template parameter to help compilation on macOS as its std::chrono::system_clock::time_point defaults to std::chrono::milliseconds for duration type (#848)
  • Loading branch information
light-tech authored and cwechtAtITK committed Nov 30, 2022
1 parent 1720bd9 commit aa32a04
Showing 1 changed file with 3 additions and 2 deletions.
5 changes: 3 additions & 2 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,9 @@ int main(int argc, char ** argv)

// for calculating sleep time
auto const period = std::chrono::nanoseconds(1'000'000'000 / cm->get_update_rate());
std::chrono::system_clock::time_point next_iteration_time =
std::chrono::system_clock::time_point(std::chrono::nanoseconds(cm->now().nanoseconds()));
auto const cm_now = std::chrono::nanoseconds(cm->now().nanoseconds());
std::chrono::time_point<std::chrono::system_clock, std::chrono::nanoseconds>
next_iteration_time{cm_now};

// for calculating the measured period of the loop
rclcpp::Time previous_time = cm->now();
Expand Down

0 comments on commit aa32a04

Please sign in to comment.