Merge pull request #140 from ros2/move_time

move time files to rcutils
This commit is contained in:
Dirk Thomas 2017-06-01 22:11:09 -07:00 committed by GitHub
commit 14a496696c
7 changed files with 19 additions and 332 deletions

View file

@ -17,12 +17,6 @@ if(NOT WIN32)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -Wall -Wextra")
endif()
if(WIN32)
set(time_impl_c src/rcl/time_win32.c)
else()
set(time_impl_c src/rcl/time_unix.c)
endif()
set(${PROJECT_NAME}_sources
src/rcl/client.c
src/rcl/common.c
@ -36,7 +30,6 @@ set(${PROJECT_NAME}_sources
src/rcl/service.c
src/rcl/subscription.c
src/rcl/time.c
${time_impl_c}
src/rcl/timer.c
src/rcl/validate_topic_name.c
src/rcl/wait.c

View file

@ -23,25 +23,26 @@ extern "C"
#include "rcl/macros.h"
#include "rcl/types.h"
#include "rcl/visibility_control.h"
#include "rcutils/time.h"
/// Convenience macro to convert seconds to nanoseconds.
#define RCL_S_TO_NS(seconds) (seconds * (1000 * 1000 * 1000))
#define RCL_S_TO_NS RCUTILS_S_TO_NS
/// Convenience macro to convert milliseconds to nanoseconds.
#define RCL_MS_TO_NS(milliseconds) (milliseconds * (1000 * 1000))
#define RCL_MS_TO_NS RCUTILS_MS_TO_NS
/// Convenience macro to convert microseconds to nanoseconds.
#define RCL_US_TO_NS(microseconds) (microseconds * 1000)
#define RCL_US_TO_NS RCUTILS_US_TO_NS
/// Convenience macro to convert nanoseconds to seconds.
#define RCL_NS_TO_S(nanoseconds) (nanoseconds / (1000 * 1000 * 1000))
#define RCL_NS_TO_S RCUTILS_NS_TO_S
/// Convenience macro to convert nanoseconds to milliseconds.
#define RCL_NS_TO_MS(nanoseconds) (nanoseconds / (1000 * 1000))
#define RCL_NS_TO_MS RCUTILS_NS_TO_MS
/// Convenience macro to convert nanoseconds to microseconds.
#define RCL_NS_TO_US(nanoseconds) (nanoseconds / 1000)
#define RCL_NS_TO_US RCUTILS_NS_TO_US
/// A single point in time, measured in nanoseconds since the Unix epoch.
typedef uint64_t rcl_time_point_value_t;
typedef rcutils_time_point_value_t rcl_time_point_value_t;
/// A duration of time, measured in nanoseconds.
typedef int64_t rcl_duration_value_t;
typedef rcutils_duration_value_t rcl_duration_value_t;
/// Time source type, used to indicate the source of a time measurement.
enum rcl_time_source_type_t
@ -487,68 +488,6 @@ rcl_ret_t
rcl_set_ros_time_override(rcl_time_source_t * time_source,
rcl_time_point_value_t time_value);
/// Retrieve the current time as a rcl_time_point_value_t.
/**
* This function returns the time from a system clock.
* The closest equivalent would be to std::chrono::system_clock::now();
*
* The resolution (e.g. nanoseconds vs microseconds) is not guaranteed.
*
* The now argument must point to an allocated rcl_system_time_point_t struct,
* as the result is copied into this variable.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | Yes
* Uses Atomics | No
* Lock-Free | Yes [1]
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
*
* \todo TODO(tfoote): consider moving this to rmw for more reuse
*
* \param[out] now a datafield in which the current time is stored
* \return `RCL_RET_OK` if the current time was successfully obtained, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
* \return `RCL_RET_ERROR` an unspecified error occur.
*/
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_system_time_now(rcl_time_point_value_t * now);
/// Retrieve the current time as a rcl_time_point_value_t object.
/**
* This function returns the time from a monotonically increasing clock.
* The closest equivalent would be to std::chrono::steady_clock::now();
*
* The resolution (e.g. nanoseconds vs microseconds) is not guaranteed.
*
* The now argument must point to an allocated rcl_time_point_value_t object,
* as the result is copied into this variable.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | Yes
* Uses Atomics | No
* Lock-Free | Yes [1]
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
*
* \todo TODO(tfoote): consider moving this to rmw for more reuse
*
* \param[out] now a struct in which the current time is stored
* \return `RCL_RET_OK` if the current time was successfully obtained, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
* \return `RCL_RET_ERROR` an unspecified error occur.
*/
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_steady_time_now(rcl_time_point_value_t * now);
#if __cplusplus
}
#endif

View file

@ -21,6 +21,7 @@
#include "./stdatomic_helper.h"
#include "rcl/allocator.h"
#include "rcl/error_handling.h"
#include "rcutils/time.h"
// Process default ROS time sources
static rcl_time_source_t * rcl_default_ros_time_source;
@ -40,7 +41,7 @@ rcl_ret_t
rcl_get_steady_time(void * data, rcl_time_point_value_t * current_time)
{
(void)data; // unused
return rcl_steady_time_now(current_time);
return rcutils_steady_time_now(current_time);
}
// Implementation only
@ -48,7 +49,7 @@ rcl_ret_t
rcl_get_system_time(void * data, rcl_time_point_value_t * current_time)
{
(void)data; // unused
return rcl_system_time_now(current_time);
return rcutils_system_time_now(current_time);
}
// Internal method for zeroing values on init, assumes time_source is valid

View file

@ -1,107 +0,0 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#if defined(WIN32)
# error time_unix.c is not intended to be used with win32 based systems
#endif // defined(WIN32)
#if __cplusplus
extern "C"
{
#endif
#include "rcl/time.h"
#if defined(__MACH__)
#include <mach/clock.h>
#include <mach/mach.h>
#endif // defined(__MACH__)
#include <math.h>
#include <time.h>
#include <unistd.h>
#include "./common.h"
#include "rcl/allocator.h"
#include "rcl/error_handling.h"
#if !defined(__MACH__) // Assume clock_get_time is available on OS X.
// This id an appropriate check for clock_gettime() according to:
// http://man7.org/linux/man-pages/man2/clock_gettime.2.html
# if !defined(_POSIX_TIMERS) || !_POSIX_TIMERS
# error no monotonic clock function available
# endif // !defined(_POSIX_TIMERS) || !_POSIX_TIMERS
#endif // !defined(__MACH__)
#define __WOULD_BE_NEGATIVE(seconds, subseconds) (seconds < 0 || (subseconds < 0 && seconds == 0))
rcl_ret_t
rcl_system_time_now(rcl_time_point_value_t * now)
{
RCL_CHECK_ARGUMENT_FOR_NULL(now, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator());
struct timespec timespec_now;
#if defined(__MACH__)
// On OS X use clock_get_time.
clock_serv_t cclock;
mach_timespec_t mts;
host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock);
clock_get_time(cclock, &mts);
mach_port_deallocate(mach_task_self(), cclock);
timespec_now.tv_sec = mts.tv_sec;
timespec_now.tv_nsec = mts.tv_nsec;
#else // defined(__MACH__)
// Otherwise use clock_gettime.
clock_gettime(CLOCK_REALTIME, &timespec_now);
#endif // defined(__MACH__)
if (__WOULD_BE_NEGATIVE(timespec_now.tv_sec, timespec_now.tv_nsec)) {
RCL_SET_ERROR_MSG("unexpected negative time", rcl_get_default_allocator());
return RCL_RET_ERROR;
}
*now = RCL_S_TO_NS((uint64_t)timespec_now.tv_sec) + timespec_now.tv_nsec;
return RCL_RET_OK;
}
rcl_ret_t
rcl_steady_time_now(rcl_time_point_value_t * now)
{
RCL_CHECK_ARGUMENT_FOR_NULL(now, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator());
// If clock_gettime is available or on OS X, use a timespec.
struct timespec timespec_now;
#if defined(__MACH__)
// On OS X use clock_get_time.
clock_serv_t cclock;
mach_timespec_t mts;
host_get_clock_service(mach_host_self(), SYSTEM_CLOCK, &cclock);
clock_get_time(cclock, &mts);
mach_port_deallocate(mach_task_self(), cclock);
timespec_now.tv_sec = mts.tv_sec;
timespec_now.tv_nsec = mts.tv_nsec;
#else // defined(__MACH__)
// Otherwise use clock_gettime.
#if defined(CLOCK_MONOTONIC_RAW)
clock_gettime(CLOCK_MONOTONIC_RAW, &timespec_now);
#else // defined(CLOCK_MONOTONIC_RAW)
clock_gettime(CLOCK_MONOTONIC, &timespec_now);
#endif // defined(CLOCK_MONOTONIC_RAW)
#endif // defined(__MACH__)
if (__WOULD_BE_NEGATIVE(timespec_now.tv_sec, timespec_now.tv_nsec)) {
RCL_SET_ERROR_MSG("unexpected negative time", rcl_get_default_allocator());
return RCL_RET_ERROR;
}
*now = RCL_S_TO_NS((uint64_t)timespec_now.tv_sec) + timespec_now.tv_nsec;
return RCL_RET_OK;
}
#if __cplusplus
}
#endif

View file

@ -1,70 +0,0 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef WIN32
# error time_win32.c is only intended to be used with win32 based systems
#endif
#if __cplusplus
extern "C"
{
#endif
#include "rcl/time.h"
#include <windows.h>
#include "./common.h"
#include "./stdatomic_helper.h"
#include "rcl/allocator.h"
#include "rcl/error_handling.h"
rcl_ret_t
rcl_system_time_now(rcl_time_point_value_t * now)
{
RCL_CHECK_ARGUMENT_FOR_NULL(now, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator());
FILETIME ft;
GetSystemTimeAsFileTime(&ft);
ULARGE_INTEGER uli;
uli.LowPart = ft.dwLowDateTime;
uli.HighPart = ft.dwHighDateTime;
// Adjust for January 1st, 1970, see:
// https://support.microsoft.com/en-us/kb/167296
uli.QuadPart -= 116444736000000000;
// Convert to nanoseconds from 100's of nanoseconds.
*now = uli.QuadPart * 100;
return RCL_RET_OK;
}
rcl_ret_t
rcl_steady_time_now(rcl_time_point_value_t * now)
{
RCL_CHECK_ARGUMENT_FOR_NULL(now, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator());
LARGE_INTEGER cpu_frequency, performance_count;
// These should not ever fail since XP is already end of life:
// From https://msdn.microsoft.com/en-us/library/windows/desktop/ms644905(v=vs.85).aspx and
// https://msdn.microsoft.com/en-us/library/windows/desktop/ms644904(v=vs.85).aspx:
// "On systems that run Windows XP or later, the function will always succeed and will
// thus never return zero."
QueryPerformanceFrequency(&cpu_frequency);
QueryPerformanceCounter(&performance_count);
// Convert to nanoseconds before converting from ticks to avoid precision loss.
rcl_time_point_value_t intermediate = RCL_S_TO_NS(performance_count.QuadPart);
*now = intermediate / cpu_frequency.QuadPart;
return RCL_RET_OK;
}
#if __cplusplus
}
#endif

View file

@ -21,6 +21,7 @@ extern "C"
#include "./common.h"
#include "./stdatomic_helper.h"
#include "rcutils/time.h"
typedef struct rcl_timer_impl_t
{
@ -62,7 +63,7 @@ rcl_timer_init(
return RCL_RET_ALREADY_INIT;
}
rcl_time_point_value_t now_steady;
rcl_ret_t now_ret = rcl_steady_time_now(&now_steady);
rcl_ret_t now_ret = rcutils_steady_time_now(&now_steady);
if (now_ret != RCL_RET_OK) {
return now_ret; // rcl error state should already be set.
}
@ -105,7 +106,7 @@ rcl_timer_call(rcl_timer_t * timer)
return RCL_RET_TIMER_CANCELED;
}
rcl_time_point_value_t now_steady;
rcl_ret_t now_ret = rcl_steady_time_now(&now_steady);
rcl_ret_t now_ret = rcutils_steady_time_now(&now_steady);
if (now_ret != RCL_RET_OK) {
return now_ret; // rcl error state should already be set.
}
@ -149,7 +150,7 @@ rcl_timer_get_time_until_next_call(const rcl_timer_t * timer, int64_t * time_unt
}
RCL_CHECK_ARGUMENT_FOR_NULL(time_until_next_call, RCL_RET_INVALID_ARGUMENT, *allocator);
rcl_time_point_value_t now;
rcl_ret_t ret = rcl_steady_time_now(&now);
rcl_ret_t ret = rcutils_steady_time_now(&now);
if (ret != RCL_RET_OK) {
return ret; // rcl error state should already be set.
}
@ -171,7 +172,7 @@ rcl_timer_get_time_since_last_call(
}
RCL_CHECK_ARGUMENT_FOR_NULL(time_since_last_call, RCL_RET_INVALID_ARGUMENT, *allocator);
rcl_time_point_value_t now;
rcl_ret_t ret = rcl_steady_time_now(&now);
rcl_ret_t ret = rcutils_steady_time_now(&now);
if (ret != RCL_RET_OK) {
return ret; // rcl error state should already be set.
}
@ -255,7 +256,7 @@ rcl_timer_reset(rcl_timer_t * timer)
RCL_CHECK_FOR_NULL_WITH_MSG(
timer->impl, "timer is invalid", return RCL_RET_TIMER_INVALID, rcl_get_default_allocator());
rcl_time_point_value_t now;
rcl_ret_t now_ret = rcl_steady_time_now(&now);
rcl_ret_t now_ret = rcutils_steady_time_now(&now);
if (now_ret != RCL_RET_OK) {
return now_ret; // rcl error state should already be set.
}

View file

@ -54,76 +54,6 @@ public:
}
};
// Tests the rcl_system_time_now() function.
TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_rcl_system_time_now) {
assert_no_realloc_begin();
rcl_ret_t ret;
// Check for invalid argument error condition (allowed to alloc).
ret = rcl_system_time_now(nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string_safe();
rcl_reset_error();
assert_no_malloc_begin();
assert_no_free_begin();
// Check for normal operation (not allowed to alloc).
rcl_time_point_value_t now = 0;
ret = rcl_system_time_now(&now);
assert_no_malloc_end();
assert_no_realloc_end();
assert_no_free_end();
stop_memory_checking();
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe();
EXPECT_NE(now, 0u);
// Compare to std::chrono::system_clock time (within a second).
now = 0;
ret = rcl_system_time_now(&now);
{
std::chrono::system_clock::time_point now_sc = std::chrono::system_clock::now();
auto now_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(now_sc.time_since_epoch());
int64_t now_ns_int = now_ns.count();
int64_t now_diff = now - now_ns_int;
const int k_tolerance_ms = 1000;
EXPECT_LE(llabs(now_diff), RCL_MS_TO_NS(k_tolerance_ms)) << "system_clock differs";
}
}
// Tests the rcl_steady_time_now() function.
TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_rcl_steady_time_now) {
assert_no_realloc_begin();
rcl_ret_t ret;
// Check for invalid argument error condition (allowed to alloc).
ret = rcl_steady_time_now(nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string_safe();
rcl_reset_error();
assert_no_malloc_begin();
assert_no_free_begin();
// Check for normal operation (not allowed to alloc).
rcl_time_point_value_t now = 0;
ret = rcl_steady_time_now(&now);
assert_no_malloc_end();
assert_no_realloc_end();
assert_no_free_end();
stop_memory_checking();
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe();
EXPECT_NE(now, 0u);
// Compare to std::chrono::steady_clock difference of two times (within a second).
now = 0;
ret = rcl_steady_time_now(&now);
std::chrono::steady_clock::time_point now_sc = std::chrono::steady_clock::now();
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe();
// Wait for a little while.
std::this_thread::sleep_for(std::chrono::milliseconds(100));
// Then take a new timestamp with each and compare.
rcl_time_point_value_t later;
ret = rcl_steady_time_now(&later);
std::chrono::steady_clock::time_point later_sc = std::chrono::steady_clock::now();
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe();
int64_t steady_diff = later - now;
int64_t sc_diff =
std::chrono::duration_cast<std::chrono::nanoseconds>(later_sc - now_sc).count();
const int k_tolerance_ms = 1;
EXPECT_LE(llabs(steady_diff - sc_diff), RCL_MS_TO_NS(k_tolerance_ms)) << "steady_clock differs";
}
// Tests the rcl_set_ros_time_override() function.
TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_rcl_ros_time_set_override) {
rcl_time_source_t * ros_time_source = rcl_get_default_ros_time_source();
@ -256,7 +186,7 @@ TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_rcl_init_for_time_so
// EXPECT_NE(now.nanoseconds, 0u);
// // Compare to std::chrono::system_clock time (within a second).
// now = {0};
// ret = rcl_system_time_now(&now);
// ret = rcutils_system_time_now(&now);
// {
// std::chrono::system_clock::time_point now_sc = std::chrono::system_clock::now();
// auto now_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(