Skip to content

time operators#351

Merged
Karsten1987 merged 10 commits intomasterfrom
time_operators
Aug 8, 2017
Merged

time operators#351
Karsten1987 merged 10 commits intomasterfrom
time_operators

Conversation

@Karsten1987
Copy link
Copy Markdown
Contributor

@Karsten1987 Karsten1987 commented Aug 6, 2017

connects to #352

@Karsten1987 Karsten1987 added the in review Waiting for review (Kanban column) label Aug 6, 2017
@Karsten1987 Karsten1987 self-assigned this Aug 6, 2017
Time(const builtin_interfaces::msg::Time & time_msg) // NOLINT
: rcl_time_(get_empty_time_point())
{
rcl_time_.nanoseconds = RCL_S_TO_NS(time_msg.sec);
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.

this overlap the comments in ros2/rcutils#44 but nothing prevents time_msg.sec to be negative here. (same everywhere below)

Time(int32_t seconds, uint32_t nanoseconds)
: rcl_time_(get_empty_time_point())
{
uint64_t ns = RCL_S_TO_NS(static_cast<uint64_t>(seconds));
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.

Doesn't this need to check if seconds is negative?

Same below.

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.

should be corrected, however I only found one spot, where it was missing. Where's the other one?

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.

Nvm, all other static_casts have a check like if (seconds < 0) { before.

rcl_time_.nanoseconds = nanoseconds;
}

Time(const builtin_interfaces::msg::Time & time_msg) // NOLINT
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.

Why does this require NOLINT?

Copy link
Copy Markdown
Contributor Author

@Karsten1987 Karsten1987 Aug 7, 2017

Choose a reason for hiding this comment

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

lint wants it to be explicit, however as it's used as a copy constructor it can't be explicit (code won't compile wo/).

@Karsten1987
Copy link
Copy Markdown
Contributor Author

Karsten1987 commented Aug 8, 2017

OK, so I think that's up for a final review.
I ended up splitting the file into a .hpp and .cpp, got rid of the template functions and extended the tests for type and overflow checking.

Given the underlying c API, I decided to write only one class Time which takes the respective timesource as parameter, defaulting to RCL_SYSTEM_TIME. I propose leaving that API as is for now until we have more concrete use cases (e.g. sim time) in which we might want to reconsider.

CI:
linux: Build Status
mac: Build Status
win: Build Status


if (ret != RCL_RET_OK) {
rclcpp::exceptions::throw_from_rcl_error(
ret, "could not initialize time source: ");
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 the : is redundant:

if (!prefix.empty()) {
formated_prefix += ": ";
}

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.

Here and below.

rcl_time_(init_time_point(rcl_time_source_))
{
if (seconds < 0) {
throw std::runtime_error("can't convert a negative time msg to rclcpp::Time");
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 would recommend this message instead, which I think is more to the point:

"cannot store a negative time point in rclcpp::Time"

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.

Also below in at least one more place.

throw std::runtime_error("can't convert a negative time msg to rclcpp::Time");
}

uint64_t ns = RCL_S_TO_NS(static_cast<uint64_t>(seconds));
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.

nitpick: you could assign this directly into rcl_time_.nanoseconds which is also a uint64_t.

Time::operator==(const rclcpp::Time & rhs) const
{
if (rcl_time_.time_source->type != rhs.rcl_time_.time_source->type) {
throw std::runtime_error("can't compare times with different time sources");
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 need to have a better overview of how this class should work. For example, I think that the fact that you cannot compare two Time objects with different sources is a runtime error is very inconvenient. Ideally it would be a compiler error when you try to compare a "system based" time point and a "steady based" time point. This pattern makes more sense when you're abstracting "system based" time point from "ROS based" time point because they have the same reference point. We might need to rethink the way it is setup in rcl as well to reflect this.

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.

Agreed. I don't know if there should be three different time classes around. Open for opinions. I just basically need the default time class (and their operators) as for now.


auto ns = rcl_time_.nanoseconds + rhs.rcl_time_.nanoseconds;
if (ns < rcl_time_.nanoseconds) {
throw std::runtime_error("addition leads to uint64_t overflow");
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.


auto ns = rcl_time_.nanoseconds - rhs.rcl_time_.nanoseconds;
if (ns > rcl_time_.nanoseconds) {
throw std::runtime_error("subtraction leads to uint64_t underflow");
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.

FAIL();
} catch (const std::exception &) {
SUCCEED();
}
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.

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.

Below too.

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.

woooaaaah, that's so cool that you can actually put a complete block of code in it. thanks for that. didn't know it :)

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.

If the invoked code is supposed to raise a specific exception I would suggest to use EXPECT_THROW rather than EXPECT_ANY_THROW.

Copy link
Copy Markdown
Member

@wjwwood wjwwood left a comment

Choose a reason for hiding this comment

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

+1, my comments were addressed to my satisfaction (though there were some things pointed out in the meeting that I missed)

Copy link
Copy Markdown
Contributor

@tfoote tfoote left a comment

Choose a reason for hiding this comment

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

LGTM. I fixed the clcok typo.

@Karsten1987 Karsten1987 merged commit def973e into master Aug 8, 2017
@Karsten1987 Karsten1987 deleted the time_operators branch August 8, 2017 22:18
@Karsten1987 Karsten1987 removed the in review Waiting for review (Kanban column) label Aug 8, 2017
@mikaelarguedas
Copy link
Copy Markdown
Member

typo 2: 2c33365

@dhood
Copy link
Copy Markdown
Member

dhood commented Aug 14, 2017

@Karsten1987 these tests are failing on windows debug nightlies: http://ci.ros2.org/job/nightly_win_deb/568/testReport/junit/(root)/TestTime/operators/

nnmm pushed a commit to ApexAI/rclcpp that referenced this pull request Jul 9, 2022
…ation_tests_against_rmw_implementations

Enable test_action_communication to compile against available rmw
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.

6 participants