Skip to content

Spin timer improvement#646

Closed
AndyZe wants to merge 3 commits intoros-controls:masterfrom
AndyZe:andyz/better_spin_timer
Closed

Spin timer improvement#646
AndyZe wants to merge 3 commits intoros-controls:masterfrom
AndyZe:andyz/better_spin_timer

Conversation

@AndyZe
Copy link
Copy Markdown
Contributor

@AndyZe AndyZe commented Feb 12, 2022

Move begin_last = begin; inside the period measurement. This should make the control loop period measurement more accurate because all of the work in the control loop will now be accounted for.

Partial fix to #644 but it is not a complete fix.

@AndyZe AndyZe changed the title Spin timer improvements Spin timer improvement Feb 12, 2022
for (auto loaded_controller : rt_controller_list)
{
// TODO(v-lopez) we could cache this information
// https://github.com/ros-controls/ros2_control/issues/153
Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

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

This issue was closed

while (rclcpp::ok())
{
rclcpp::Time begin_last = begin;
begin = cm->now();
Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

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

Start the timer right at the beginning of the new iteration

Copy link
Copy Markdown
Contributor

@jackcenter jackcenter left a comment

Choose a reason for hiding this comment

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

I think this is an improvement, but I had one comment on the loop implementation that I'd be interested to know your thoughts on.

cm->write();
rclcpp::Time end = cm->now();
end = cm->now();
std::this_thread::sleep_for(std::max(
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

This looks like it would cause the time to drift each loop since it's sleeping for a fixed amount of time instead of until the end of the period. Would ros::rate work here? Or setting a hard end time at the beginning of each loop based on the original start? I can test that out if it seems like a reasonable approach.

Copy link
Copy Markdown
Contributor Author

@AndyZe AndyZe Feb 15, 2022

Choose a reason for hiding this comment

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

If you look at L35, there's a comment about why rclcpp::Rate::sleep() isn't used.

What's here seems fine to me but please feel free to test out your other idea. 👍 This still isn't working as well as I'd hope for. (It's not clear if this bit of code is the cause, though)

while (rclcpp::ok())
{
rclcpp::Time begin_last = begin;
begin = cm->now();
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

This does seem like a better order.

@jackcenter
Copy link
Copy Markdown
Contributor

I added some testing data for this PR to PR #647.

@destogl
Copy link
Copy Markdown
Member

destogl commented Feb 16, 2022

Replaced by #647 that seems to work better.

@destogl destogl closed this Feb 16, 2022
Comment on lines 51 to 52
begin = cm->now();
cm->read();
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.

I think we should rather use something like this:

Suggested change
begin = cm->now();
cm->read();
cm->read();
begin = cm->now();

In this case, only update method is not counted in the period. This is not 100% exact when having multiple controller but closer to the real value.

pac48 pushed a commit to pac48/ros2_control that referenced this pull request Jan 26, 2024
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