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

Time, Duration, Clock wrapping rcl #209

Merged
merged 26 commits into from
Jul 26, 2018
Merged

Time, Duration, Clock wrapping rcl #209

merged 26 commits into from
Jul 26, 2018

Conversation

dhood
Copy link
Member

@dhood dhood commented Jul 18, 2018

connects to #186

Still a work-in-progress but input is welcome.

The scope of this PR is the first few steps of #186 (comment). It excludes TimeSource/ROS time implementation to avoid the PR getting too large.

@dhood dhood added the in progress Actively being worked on (Kanban column) label Jul 18, 2018
@dhood dhood self-assigned this Jul 18, 2018
return NULL;
}

rcl_time_point_t * time_point = (rcl_time_point_t *) PyMem_Malloc(sizeof(rcl_time_point_t));
Copy link
Contributor

Choose a reason for hiding this comment

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

Need to check time_point before using. If PyMem_Malloc() fails then time_point will be NULL.

time_point->nanoseconds = nanoseconds;
time_point->clock_type = clock_type;

return PyCapsule_New(time_point, "rcl_time_point_t", NULL);
Copy link
Contributor

Choose a reason for hiding this comment

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

This should have a PyCapsule_Destructor to free time_point if the capsule gets garbage collected.

void _rclpy_destroy_time_point(PyObject * pycapsule)
{
    PyMem_Free(PyCapsule_GetPointer(pycapsule, "rcl_time_point_t"));
}
...
PyCapsule_New(time_point, "rcl_time_point_t", _rclpy_destroy_time_point);

The rest of rclpy is not using capsule destructors, but that's a bug imo.

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 for the pointer!! hadn't seen that before. 2c8ba12

/// Returns the nanoseconds value of the time point
/**
* Raises ValueError if pytime_point is not a time point capsule
* Raises RuntimeError if the time point valule cannot be retrieved
Copy link
Contributor

Choose a reason for hiding this comment

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

valule -> value

Copy link
Contributor

Choose a reason for hiding this comment

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

Where is RuntimeError raised?


duration->nanoseconds = nanoseconds;

return PyCapsule_New(duration, "rcl_duration_t", NULL);
Copy link
Contributor

Choose a reason for hiding this comment

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

Same capsule destructor needed here

return NULL;
}

rcl_clock_t * clock = (rcl_clock_t *)PyMem_Malloc(sizeof(rcl_clock_t));
Copy link
Contributor

Choose a reason for hiding this comment

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

check if clock is NULL or is this relying on rcl_clock_init to do that?

Copy link
Contributor

Choose a reason for hiding this comment

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

resolved

return NULL;
}

return PyCapsule_New(clock, "rcl_clock_t", NULL);
Copy link
Contributor

Choose a reason for hiding this comment

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

Need capsule destructor here too

return NULL;
}

rcl_time_point_t * time_point = (rcl_time_point_t *) PyMem_Malloc(sizeof(rcl_time_point_t));
Copy link
Contributor

Choose a reason for hiding this comment

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

Need to check for NULL

Copy link
Contributor

Choose a reason for hiding this comment

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

return NULL;
}

return PyCapsule_New(time_point, "rcl_time_point_t", NULL);
Copy link
Contributor

Choose a reason for hiding this comment

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

Capsule destructor needed


def test_time_operators(self):
time1 = Time(nanoseconds=1, clock_type=ClockType.STEADY_TIME)
time2 = time1
Copy link
Contributor

Choose a reason for hiding this comment

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

What is this supposed to test? Assignment makes time2 and time1 be references to the same instance of Time.

>>> t1 = Time(nanoseconds=1)
>>> t2 = t1
>>> id(t2)
140468253530040
>>> id(t1)
140468253530040
>>> id(t2) == id(t1)
True

Copy link
Member Author

Choose a reason for hiding this comment

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

ah, my intent was more to check how the copies interacted. Updated in 5a1430e

@dhood
Copy link
Member Author

dhood commented Jul 19, 2018

Putting this in review:

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

@dhood dhood added in review Waiting for review (Kanban column) and removed in progress Actively being worked on (Kanban column) labels Jul 19, 2018
@dhood
Copy link
Member Author

dhood commented Jul 20, 2018

CI without typo in args:

  • 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. My comments are about code that could be removed, but don't change anything.

}

unsigned PY_LONG_LONG nanoseconds = PyLong_AsUnsignedLongLong(pylong_nanoseconds);
if ((unsigned PY_LONG_LONG)-1 == nanoseconds && PyErr_Occurred()) {
Copy link
Contributor

Choose a reason for hiding this comment

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

nit, PyErr_Occurred() alone is enough to justify returning NULL.

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 must have been following how to adapt to overflow errors, which we're not doing. Check relaxed in 69e838f

}

unsigned PY_LONG_LONG nanoseconds = PyLong_AsUnsignedLongLong(pylong_nanoseconds);
if ((unsigned PY_LONG_LONG)-1 == nanoseconds && PyErr_Occurred()) {
Copy link
Contributor

Choose a reason for hiding this comment

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

nit, same as above

duration = Duration(nanoseconds=-1)

def test_time_operators(self):
# Check that modifying the original doesn't affect a copy
Copy link
Contributor

Choose a reason for hiding this comment

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

This code doesn't make a copy; though, I don't think a copy test is necessary.

        # make a reference to a new instance of Time() (instance 1) called time1
        time1 = Time(nanoseconds=2, clock_type=ClockType.SYSTEM_TIME)
        # make another reference to (instance 1) called time2
        time2 = time1
        # make time 1 a reference to a new instance of Time() (instance 2)
        time1 = Time(nanoseconds=1, clock_type=ClockType.STEADY_TIME)

Which is the same as

        time2 = Time(nanoseconds=2, clock_type=ClockType.SYSTEM_TIME)
        time1 = Time(nanoseconds=1, clock_type=ClockType.STEADY_TIME)

A copy would need to be created with copy.copy() or copy.deepcopy(). A shallow copy test isn't necessary because Time appears to be immutable.

import copy
# make a reference to a new instance of Time() (instance 1) called time1
time1 = Time(nanoseconds=2, clock_type=ClockType.SYSTEM_TIME)
# make a reference to a new instance of Time() (instance 2) called time2 whose members have been shallow copied from time1.
time2 = copy.copy(Time(nanoseconds=2, clock_type=ClockType.SYSTEM_TIME))
# Not implemented, time properties don't have setter's
# time2.nanoseconds = 5
# time2.clock_type = ClockType.ROS_TIME
# If time was mutable this would fail because time2._time_handle and time1._time_handle are references to the same pycapsule
# assert time2.nanosseconds != time1.nanoseconds

and a deepcopy test isn't needed because Time() doesn't support it (would need to implement __getstate__() or __setstate__())

# 
time2 = copy.deepcopy(time1)
Traceback (most recent call last):
  File "<stdin>", line 1, in <module>
  File "/usr/lib/python3.6/copy.py", line 180, in deepcopy
    y = _reconstruct(x, memo, *rv)
  File "/usr/lib/python3.6/copy.py", line 280, in _reconstruct
    state = deepcopy(state, memo)
  File "/usr/lib/python3.6/copy.py", line 150, in deepcopy
    y = copier(x, memo)
  File "/usr/lib/python3.6/copy.py", line 240, in _deepcopy_dict
    y[deepcopy(key, memo)] = deepcopy(value, memo)
  File "/usr/lib/python3.6/copy.py", line 169, in deepcopy
    rv = reductor(4)
TypeError: can't pickle PyCapsule objects

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'm with you that this wasn't really testing anything of interest; removed in 81d5568 thanks!

@tfoote tfoote mentioned this pull request Jul 24, 2018
8 tasks
rcl_ret_t ret_clock = rcl_clock_fini(clock);
PyMem_Free(clock);
if (ret_clock != RCL_RET_OK) {
PyErr_Format(PyExc_RuntimeError,
Copy link
Member Author

Choose a reason for hiding this comment

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

@sloretz I had overlooked that I wasn't calling fini on the clock (added in 0cbbc52).

If something goes wrong in the fini when it gets garbage collected it will cause this sort of output:

RuntimeError: Failed to fini 'rcl_clock_t': error not set

During handling of the above exception, another exception occurred:

self = <contextlib._GeneratorContextManager object at 0x7f1210674cf8>, type = None, value = None, traceback = None

    def __exit__(self, type, value, traceback):
        if type is None:
            try:
>               next(self.gen)
E               SystemError: PyEval_EvalFrameEx returned a result with an error set

/usr/lib/python3.5/contextlib.py:66: SystemError
----------- generated xml file: /home/dhood/ros2_ws/build/rclpy/test_results/rclpy/rclpytests.xunit.xml -----------
============================================ 2 failed in 0.06 seconds =============================================
Exception ignored in: 'garbage collection'
RuntimeError: Failed to fini 'rcl_clock_t': error not set
Fatal Python error: unexpected exception during garbage collection

Current thread 0x00007f1216872700 (most recent call first):
Aborted (core dumped)

I think if there was an issue then this will certainly let the user know about it. Since you were the one that mentioned adding the destructor for garbage collection, I wonder if you've read about any other approaches to signalling issues in the destructor, or if this is the way to go?

Copy link
Contributor

Choose a reason for hiding this comment

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

Wow, the user can't miss that. Does PyErr_WarnEx() cause a fatal error as well?

I haven't read about other approaches. The only example I found in the cpython repo is this capsule destructor in ctypes which is seems to be silent about errors.

Copy link
Member Author

@dhood dhood Jul 26, 2018

Choose a reason for hiding this comment

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

Using PyErr_WarnFormat, you end up getting something like:

----------- generated xml file: /home/dhood/ros2_ws/build/rclpy/test_results/rclpy/rclpytests.xunit.xml -----------
================================================ warnings summary =================================================
src/ros2/rclpy/rclpy/test/test_clock.py::TestClock::test_clock_construction
  /home/dhood/ros2_ws/src/ros2/rclpy/rclpy/test/test_clock.py:33: RuntimeWarning: Failed to fini 'rcl_clock_t': error not set
    clock = Clock(clock_type=ClockType.STEADY_TIME)
  /home/dhood/ros2_ws/src/ros2/rclpy/rclpy/test/test_clock.py:35: RuntimeWarning: Failed to fini 'rcl_clock_t': error not set
    clock = Clock(clock_type=ClockType.SYSTEM_TIME)
  /usr/lib/python3.5/unittest/case.py:600: RuntimeWarning: Failed to fini 'rcl_clock_t': error not set
    testMethod()

src/ros2/rclpy/rclpy/test/test_clock.py::TestClock::test_clock_now
  /home/dhood/ros2_ws/src/ros2/rclpy/rclpy/test/test_clock.py:53: RuntimeWarning: Failed to fini 'rcl_clock_t': error not set
    clock = Clock(clock_type=ClockType.STEADY_TIME)
  /usr/lib/python3.5/unittest/case.py:600: RuntimeWarning: Failed to fini 'rcl_clock_t': error not set
    testMethod()

-- Docs: http://doc.pytest.org/en/latest/warnings.html
====================================== 2 passed, 5 warnings in 0.03 seconds =======================================

But I think now it's misleading because it doesn't make mention of the garbage collector so the line numbers are confusing. We do raise exceptions if there are fini errors usually, so if there aren't any alternatives in between, now I think that the exception is the right thing even if it's perhaps a bit extreme...

@dhood
Copy link
Member Author

dhood commented Jul 26, 2018

@sloretz from discussion in ros2/rclcpp#525, this implementation needs to allow negative Time and Durations, which currently it doesn't. My thinking, to assist reviewing, is to merge this PR with its current implementation (negative Time and Duration not supported) and create a followup that supports negatives, so that it's just the diff that needs to be reviewed incrementally. sound good?

@sloretz
Copy link
Contributor

sloretz commented Jul 26, 2018

@dhood Sounds good to me

@dhood
Copy link
Member Author

dhood commented Jul 26, 2018

Thanks!

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

@dhood dhood merged commit 5ed7ca2 into master Jul 26, 2018
@dhood dhood removed the in review Waiting for review (Kanban column) label Jul 26, 2018
@dhood dhood mentioned this pull request Jul 27, 2018
@dhood dhood deleted the rclpy_time branch July 30, 2018 23:46
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