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

add Duration::seconds #536

Merged
merged 2 commits into from
Aug 20, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions rclcpp/include/rclcpp/duration.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,13 @@ class Duration
rcl_duration_value_t
nanoseconds() const;

/// \return the duration in seconds as a floating point number.
/// \warning Depending on sizeof(double) there could be significant precision loss.
/// When an exact time is required use nanoseconds() instead.
RCLCPP_PUBLIC
double
seconds() const;

private:
rcl_duration_t rcl_duration_;
};
Expand Down
6 changes: 6 additions & 0 deletions rclcpp/src/rclcpp/duration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,4 +214,10 @@ Duration::nanoseconds() const
return rcl_duration_.nanoseconds;
}

double
Duration::seconds() const
{
return std::chrono::duration<double>(std::chrono::nanoseconds(rcl_duration_.nanoseconds)).count();
Copy link
Member

Choose a reason for hiding this comment

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

in tf2 we convert to seconds in a convoluted way to improve accuracy: see ros2/geometry2#34. This allows for tests going to- and from- seconds to pass: https://github.com/ros2/geometry2/blob/a275730813b9cf55943f3f05d57aaee51b32944a/tf2/test/simple_tf2_core.cpp#L177. We may want to consider that here

Copy link
Member Author

@dirk-thomas dirk-thomas Aug 17, 2018

Choose a reason for hiding this comment

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

The current line in the patch matches the content of the same function in the Time class. I am not sure how the referenced issue applies here since the computation is not complex in any way (in contrast to durationToSec in geometry)?

Can you please propose the specific code you would prefer to implement this method.

Copy link
Member

Choose a reason for hiding this comment

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

I recommend you use https://github.com/ros2/geometry2/blob/7dafb4d6c0c7025dfeeed3cef336113c62601dac/tf2/include/tf2/time.h#L74..L84 to make the computation more complex and more accurate.

Copy link
Member Author

Choose a reason for hiding this comment

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

Got it now. The goal is to increase the precision.

It would be good to share that implementation somehow between the various places where we do convert integer nanoseconds into double seconds. That function should probably live in rcutils and would then be used here in rclcpp as well as geometry2. Since that exceeds the scope of this patch I would keep that for a separate set of PRs. (Also a test demonstrating that the precision is increased would be good for that function.)

Copy link
Member

Choose a reason for hiding this comment

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

yeah, I imagine the precision is not expected to be perfect anyway, but the improvement is there for when we want it. can be an enhancement.

}

} // namespace rclcpp