Skip to content

Implement validity checks for time points#1018

Merged
methylDragon merged 2 commits intoros2:rollingfrom
methylDragon:ch3/time-valid
Nov 8, 2022
Merged

Implement validity checks for time points#1018
methylDragon merged 2 commits intoros2:rollingfrom
methylDragon:ch3/time-valid

Conversation

@methylDragon
Copy link
Copy Markdown
Contributor

@methylDragon methylDragon commented Nov 8, 2022

Precursor for ros2/rclcpp#2040

Codifies the notion of zero-time being invalid as defined in the design docs, will be used in downstream rclcpp validity checks.

One question I had was whether a time point with non-zero time but associated with an uninitialized clock type should also be uninitialized? I interpreted the docs to mean that all that matters is the time point value.

@methylDragon
Copy link
Copy Markdown
Contributor Author

methylDragon commented Nov 8, 2022

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Windows Build Status

@methylDragon methylDragon marked this pull request as ready for review November 8, 2022 03:58
@methylDragon methylDragon requested a review from sloretz November 8, 2022 03:59
Signed-off-by: methylDragon <methylDragon@gmail.com>
Copy link
Copy Markdown
Contributor

@sloretz sloretz left a comment

Choose a reason for hiding this comment

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

LGTM once linter is happy

}

bool
rcl_time_point_value_valid(rcl_time_point_value_t time_point_value)
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.

The code looks correct, but I doubt this function will be used much. I would recommend having just the other one.

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.

Interestingly enough, rcl_clock_get_now only allows you to get an rcl_time_point_value_t, so I was provisioning this one for that usage path.

Signed-off-by: methylDragon <methylDragon@gmail.com>
@methylDragon
Copy link
Copy Markdown
Contributor Author

@ros-pull-request-builder retest this please

@methylDragon methylDragon merged commit e47ed58 into ros2:rolling Nov 8, 2022
@methylDragon methylDragon deleted the ch3/time-valid branch November 8, 2022 19:57
Comment on lines +211 to +214
rcl_time_point_t uninitialized;
(void) uninitialized;
// Not reliably detectable due to random values.
// ASSERT_FALSE(rcl_clock_valid(&uninitialized));
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.

As we talked about in person @methylDragon, we should just not have stuff in the tests like this (I know you're copying from the clock tests, but I consider them to be not ideal as well) and instead we should document that using uninitialized values with any of our functions is undefined behavior, e.g.:

* The rcl_node_t given must be allocated and zero initialized.
* Passing an rcl_node_t which has already had this function called on it, more
* recently than rcl_node_fini, will fail.
* An allocated rcl_node_t with uninitialized memory is undefined behavior.

Node is just an example, we should ideally document that all structures have to be zero initialized before being used (unless we have specific cases where we want to avoid that for performance reasons).

I don't see the rcl_..._zero_initialized_...() like functions for time/clock objects. We should probably clean them up to have these, again unless there are specific scenarios where we want to avoid that for performance reasons. Like it might be ok to use an uninitialized time point if passing it to get time (which is write only maybe). Avoiding an unnecessary initialization state. But functions that read the struct, like "is valid" should definitely be documented to not work with uninitialized values. In which case we don't need commented blocks like these in the tests.

Copy link
Copy Markdown
Collaborator

@fujitatomoya fujitatomoya left a comment

Choose a reason for hiding this comment

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

according to the comment #1018 (comment), i think you already have consensus of this change, right. that is okay but it seems that this needs to be fixed.

bool
rcl_time_point_value_valid(rcl_time_point_value_t time_point_value)
{
return time_point_value > 0;
Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

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

I think this implementation should be in rcutils?

/// Check if the time point is valid.
/**
* This function returns true if the time point appears to be valid.
* It will check that the type is not uninitialized, and that the time point value is non-zero.
Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

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

it does not seem to check the clock_type is initialized or not...?

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.

Oh, I meant it as check if the struct pointer (not the clock type) is initialized..

}

bool
rcl_time_point_valid(rcl_time_point_t * time_point)
Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

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

even if rcl_clock_type_t is RCL_CLOCK_UNINITIALIZED, this will return true if time_point->nanoseconds is greater than zero.

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.

One question I had was whether a time point with non-zero time but associated with an uninitialized clock type should also be uninitialized? I interpreted the docs to mean that all that matters is the time point value.

That's as intended, this is meant to check for time point validity wrt. the docs. The rclcpp clock validity check ends up checking for clock validity in addition to time validity. I think I can raise this in the next ROS meeting regarding this 🤔

rcl_time_point_t valid, invalid;

valid.nanoseconds = 1000;
valid.clock_type = RCL_ROS_TIME;
Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

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

missing test case for RCL_CLOCK_UNINITIALIZED, so that we can detect that implementation is not completed?

methylDragon added a commit to methylDragon/rcl that referenced this pull request Dec 5, 2022
Signed-off-by: methylDragon <methylDragon@gmail.com>
methylDragon added a commit to methylDragon/rcl that referenced this pull request Dec 5, 2022
Signed-off-by: methylDragon <methylDragon@gmail.com>
methylDragon added a commit to methylDragon/rcl that referenced this pull request Dec 5, 2022
Signed-off-by: methylDragon <methylDragon@gmail.com>
methylDragon added a commit to methylDragon/rcl that referenced this pull request Dec 5, 2022
methylDragon added a commit to methylDragon/rcl that referenced this pull request Dec 5, 2022
This reverts commit e47ed58.

Signed-off-by: methylDragon <methylDragon@gmail.com>
methylDragon added a commit to methylDragon/rcl that referenced this pull request Dec 5, 2022
Signed-off-by: methylDragon <methylDragon@gmail.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.

4 participants