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

TimeSource and support for ROS time #210

Merged
merged 16 commits into from
Aug 3, 2018
Merged

TimeSource and support for ROS time #210

merged 16 commits into from
Aug 3, 2018

Conversation

dhood
Copy link
Member

@dhood dhood commented Jul 20, 2018

Connects to #186

Requires ros2/rcl#274

Gives nodes a clock of type ROS_TIME which will reflect the time received on /clock topic if the Time Source has had use of ROS time activated. Since parameters aren't available in python yet, there's no support for the use_sim_time parameter, but the Time Source can have ROS time activated manually by calling time_source.ros_time_is_active = True.

Support for clock jump notifiers not targeted for this PR.

@dhood dhood added the in progress Actively being worked on (Kanban column) label Jul 20, 2018
@dhood dhood self-assigned this Jul 20, 2018
@tfoote tfoote mentioned this pull request Jul 24, 2018
8 tasks
@dhood dhood changed the base branch from rclpy_time to master July 30, 2018 18:57
@dhood
Copy link
Member Author

dhood commented Jul 31, 2018

Putting this in review

The description of this PR has been updated to reflect a recent change to the code: Following discussion in ros2/rclcpp#516 I understand now that all clocks managed by a time source should have the same value for ros_time_is_active. So, I have added ros_time_is_active to the TimeSource class, and made it read-only on the ROSClock class (before clocks could individually have use of ROS time configured on them, now it is 'inherited' from the TimeSource's state).

The ROSClock class has also been added recently as a specialisation of the Clock class that provides ROS time-specific methods. A time source can still take in a clock like Clock(clock_type=ROS_TIME), but the expected usage is that it will be passed a ROSClock (that is what will be stored underneath). I did this because I thought it was cleaner than having methods that only applied for ROS time in the general Clock class (e.g. like this), but am open to alternatives.

Overall I tried to mirror the implementation in rclcpp, where possible. It diverges in the following ways:

  • Clock callbacks have not been implemented yet
  • Support for parameters isn't available in rclpy yet so the TimeSource has to have ros_time_is_active set manually as opposed to with the use_sim_time parameter
  • A ROSClock specialisation does not exist in rclcpp, but does in rclpy.
  • I aimed for the end-result from Node unable to avoid using sim time if /clock published rclcpp#515 where a subscription is only created for a Timesource if sim time is in use. That is not the current state in rclcpp however.

@dhood dhood added in review Waiting for review (Kanban column) and removed in progress Actively being worked on (Kanban column) labels Jul 31, 2018
{
PyObject * pyclock;
PyObject * pyenabled;
if (!PyArg_ParseTuple(args, "OO", &pyclock, &pyenabled)) {
Copy link
Contributor

Choose a reason for hiding this comment

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

Could use p (link here) to convert to bool automatically instead of PyObject_IsTrue() below.

Copy link
Member Author

Choose a reason for hiding this comment

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

thanks! 6a9d42b

return NULL;
}

bool enabled = PyObject_IsTrue(pyenabled);
Copy link
Contributor

Choose a reason for hiding this comment

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

Unlikely to see this happen, but I think this needs to check PyErr_Occurred() in case pyenabled is an object that raises an exception in it's implementation of __bool__().

if not clock.clock_type == ClockType.ROS_TIME:
raise ValueError('Only clocks with type ROS_TIME can be attached.')
# "Cast" to ROSClock subclass so ROS time methods can be used.
clock.__class__ = ROSClock
Copy link
Contributor

Choose a reason for hiding this comment

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

Not asking to change anything, just sharing because I think it's interesting. This led me discover that __new__ could be used to return a ROSClock instance when passed a ROS clock type.

Details
class Clock:

    def __new__(cls, *, clock_type="SYSTEM_CLOCK"):
        self = None
        if clock_type == "ROS_CLOCK":
            self = super().__new__(ROSClock)
        else:
            self = super().__new__(cls)
        self._clock_type = clock_type
        # create self._clock_handle here too
        return self

    # Can't have an __init__ because it would get passed clock_type argument
    # and ROSCLOCK doesn't wan't one
    # def __init__(self):
    #   pass

    def all_clocks_have_this(self):
        print("all clocks have this")


class ROSClock(Clock):

    # Can't have an __init__ because it would get passed clock_type argument
    # and ROSCLOCK doesn't wan't one
    # def __init__(self):
    #   pass

    def only_ros_clocks_have_this(self):
        print("Only ros clocks have this")

c1 = Clock()
c2 = Clock(clock_type="STEADY_CLOCK")
c3 = Clock(clock_type="ROS_CLOCK")

print(repr(c1))
print(repr(c2))
print(repr(c3))

c1.all_clocks_have_this()
c2.all_clocks_have_this()
c3.all_clocks_have_this()
c3.only_ros_clocks_have_this()

Copy link
Member Author

Choose a reason for hiding this comment

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

I think this approach might be better! Because there's no extra step for users to get access to ROS clock methods if they have created a ROS clock with Clock(clock_type=ClockType.ROS_TIME), they will always get a ROSClock back.

I don't immediately see any disadvantages of this (it's ok in this instance that the Clock class 'knows about' the ROSClock class), so I plan to incorporate it, thank you for the suggestion

Copy link
Member Author

Choose a reason for hiding this comment

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

Done in 9992b1f + cf38ae7, I think it's better to use now: happy you pointed this out!

# When not using sim time, ROS time should look like system time
now = clock.now()
system_now = Clock(clock_type=ClockType.SYSTEM_TIME).now()
assert (system_now.nanoseconds - now.nanoseconds) < 1e9
Copy link
Contributor

Choose a reason for hiding this comment

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

1e9 seems really small. I think this test could be flaky if the OS happens to context switch between lines 73 and 74.

Also, maybe add abs() in case there is a future bug where now is a non-zero time greater than system_now?

Copy link
Member Author

Choose a reason for hiding this comment

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

I was thinking 1sec is pretty generous already but it can't hurt to increase.

About the abs, I don't think it makes sense here, since we do expect the value of a later call to now() be greater. I'd rather catch that bug than mask it.

Copy link
Contributor

Choose a reason for hiding this comment

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

Ooops, I got this completely wrong. For some reason I thought 1e9 meant 1ns. My bad.

@dhood
Copy link
Member Author

dhood commented Aug 3, 2018

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

Copy link
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 with green CI

@dhood
Copy link
Member Author

dhood commented Aug 3, 2018

Interestingly OS X (only) is failing with ValueError: PyCapsule_GetPointer called with invalid PyCapsule object when _rclpy.rclpy_clock_set_ros_time_override_is_enabled(self._clock_handle, enabled) is called. Not sure yet what's causing that: will have to look into it before this can be merged

@dhood
Copy link
Member Author

dhood commented Aug 3, 2018

Back in action!
Will go ahead and merge this now the bug's been fixed in 6ac5bf9

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

@dhood dhood merged commit 98cdade into master Aug 3, 2018
@dhood dhood deleted the ros_time branch August 3, 2018 21:44
@dhood dhood removed the in review Waiting for review (Kanban column) label Aug 3, 2018
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.

None yet

2 participants