Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix for issue #77 #78

Merged
merged 4 commits into from Apr 2, 2018
Merged

fix for issue #77 #78

merged 4 commits into from Apr 2, 2018

Conversation

BrutusTT
Copy link
Contributor

see #77

@@ -56,7 +56,7 @@ namespace ros {
if (sec64 < INT_MIN || sec64 > INT_MAX)
throw std::runtime_error("Duration is out of dual 32-bit range");
sec = (int32_t)sec64;
nsec = (int32_t)((d - (double)sec)*1000000000);
nsec = (int32_t)((d - (double)sec)*10000000000/10);
Copy link
Member

Choose a reason for hiding this comment

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

The approach to multiply it with an order of magnitude more and then divide again doesn't looks like a good approach.

Can you please try to use a rounding function (e.g. nearbyint) instead and confirm that it still addressed your problem.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

yes, nearbyint does the job.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I updated the PR accordingly

@dirk-thomas
Copy link
Member

Thank you for the patch and for updating it.

@dirk-thomas dirk-thomas merged commit d5d914c into ros:kinetic-devel Apr 2, 2018
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

2 participants