Use ControllerManager node clock for control loop timepoints#542
Merged
destogl merged 3 commits intoros-controls:masterfrom Sep 27, 2021
Merged
Conversation
destogl
reviewed
Sep 24, 2021
Member
destogl
left a comment
There was a problem hiding this comment.
This looks reasonable. Just small thing to clarify.
| cm->update( | ||
| rclcpp::Time( | ||
| std::chrono::duration_cast<std::chrono::nanoseconds>(begin - timepoint_start).count()), | ||
| std::chrono::duration_cast<std::chrono::nanoseconds>(begin.time_since_epoch()).count()), |
Member
There was a problem hiding this comment.
Should/can we use here simply:
Suggested change
| std::chrono::duration_cast<std::chrono::nanoseconds>(begin.time_since_epoch()).count()), | |
| cm->now(), |
Contributor
Author
There was a problem hiding this comment.
It's not exactly the same as what you suggested, but I was able to significantly simpify this by storing the update timepoints as rclcpp::Time instead of std::chrono::duration.
Contributor
Author
destogl
approved these changes
Sep 27, 2021
Member
destogl
left a comment
There was a problem hiding this comment.
Thanks for PR and the fast follow-up!
pac48
pushed a commit
to pac48/ros2_control
that referenced
this pull request
Jan 26, 2024
(cherry picked from commit 42f6c14) Co-authored-by: Christoph Fröhlich <christophfroehlich@users.noreply.github.com>
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment
Add this suggestion to a batch that can be applied as a single commit.This suggestion is invalid because no changes were made to the code.Suggestions cannot be applied while the pull request is closed.Suggestions cannot be applied while viewing a subset of changes.Only one suggestion per line can be applied in a batch.Add this suggestion to a batch that can be applied as a single commit.Applying suggestions on deleted lines is not supported.You must change the existing code in this line in order to create a valid suggestion.Outdated suggestions cannot be applied.This suggestion has been applied or marked resolved.Suggestions cannot be applied from pending reviews.Suggestions cannot be applied on multi-line comments.Suggestions cannot be applied while the pull request is queued to merge.Suggestion cannot be applied right now. Please check back later.
In the current version of
ros2_control_node.cpp, this line (from #520) incorrectly calculates a timepoint that is relative to the time when the controller manager node was initialized, where it should instead use either the actual epoch time for real hardware or the simulated time when running in Gazebo or another simulated context. When a controller plugin publishes ROS messages (for example, when the JointStateBroadcaster publishes JointState messages), it uses these incorrect timestamps in the message headers, which causes problems downstream with TF lookups and perception calculations.This PR changes the calculated timepoint to be correct relative to the start of the epoch.
This PR also changes the control loop to use the ControllerManager ROS node's clock as the time source instead of the system clock, which allows switching between simulated and real time through the
use_sim_timeROS parameter. Prior to the API update the controller plugins used ROS time, so the end result here should be the same as how it was before.