Skip to content

Use ControllerManager node clock for control loop timepoints#542

Merged
destogl merged 3 commits intoros-controls:masterfrom
schornakj:fix/controller-manager-update-timestamp
Sep 27, 2021
Merged

Use ControllerManager node clock for control loop timepoints#542
destogl merged 3 commits intoros-controls:masterfrom
schornakj:fix/controller-manager-update-timestamp

Conversation

@schornakj
Copy link
Copy Markdown
Contributor

@schornakj schornakj commented Sep 24, 2021

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_time ROS 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.

Copy link
Copy Markdown
Member

@destogl destogl left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

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()),
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should/can we use here simply:

Suggested change
std::chrono::duration_cast<std::chrono::nanoseconds>(begin.time_since_epoch()).count()),
cm->now(),

Copy link
Copy Markdown
Contributor Author

@schornakj schornakj Sep 27, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

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.

Copy link
Copy Markdown
Member

@bmagyar bmagyar left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

in general I very much like this but agree with @destogl 's comment.

...also please run precommit at the end ;)

@schornakj
Copy link
Copy Markdown
Contributor Author

schornakj commented Sep 27, 2021

in general I very much like this but agree with @destogl 's comment.

...also please run precommit at the end ;)

@bmagyar I addressed the feedback and cleaned up some of the very verbose code. I also made sure to run pre-commit!

Copy link
Copy Markdown
Member

@destogl destogl left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for PR and the fast follow-up!

@destogl destogl merged commit d5c9d66 into ros-controls:master Sep 27, 2021
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>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants