Move stdatomic helper to rcutils (#324)
* move stdatomic_helper* to rcutils Signed-off-by: William Woodall <william@osrfoundation.org> * refactor after moving stdatomic_helper.h to rcutils Signed-off-by: William Woodall <william@osrfoundation.org>
This commit is contained in:
parent
5d12f54d13
commit
9351fd89c7
8 changed files with 43 additions and 980 deletions
|
@ -26,12 +26,12 @@ extern "C"
|
||||||
#include "rcl/expand_topic_name.h"
|
#include "rcl/expand_topic_name.h"
|
||||||
#include "rcl/remap.h"
|
#include "rcl/remap.h"
|
||||||
#include "rcutils/logging_macros.h"
|
#include "rcutils/logging_macros.h"
|
||||||
|
#include "rcutils/stdatomic_helper.h"
|
||||||
#include "rmw/error_handling.h"
|
#include "rmw/error_handling.h"
|
||||||
#include "rmw/rmw.h"
|
#include "rmw/rmw.h"
|
||||||
#include "rmw/validate_full_topic_name.h"
|
#include "rmw/validate_full_topic_name.h"
|
||||||
|
|
||||||
#include "./common.h"
|
#include "./common.h"
|
||||||
#include "./stdatomic_helper.h"
|
|
||||||
|
|
||||||
typedef struct rcl_client_impl_t
|
typedef struct rcl_client_impl_t
|
||||||
{
|
{
|
||||||
|
@ -269,14 +269,14 @@ rcl_send_request(const rcl_client_t * client, const void * ros_request, int64_t
|
||||||
}
|
}
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(ros_request, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(ros_request, RCL_RET_INVALID_ARGUMENT);
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(sequence_number, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(sequence_number, RCL_RET_INVALID_ARGUMENT);
|
||||||
*sequence_number = rcl_atomic_load_int64_t(&client->impl->sequence_number);
|
*sequence_number = rcutils_atomic_load_int64_t(&client->impl->sequence_number);
|
||||||
if (rmw_send_request(
|
if (rmw_send_request(
|
||||||
client->impl->rmw_handle, ros_request, sequence_number) != RMW_RET_OK)
|
client->impl->rmw_handle, ros_request, sequence_number) != RMW_RET_OK)
|
||||||
{
|
{
|
||||||
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
|
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
|
||||||
return RCL_RET_ERROR;
|
return RCL_RET_ERROR;
|
||||||
}
|
}
|
||||||
rcl_atomic_exchange_int64_t(&client->impl->sequence_number, *sequence_number);
|
rcutils_atomic_exchange_int64_t(&client->impl->sequence_number, *sequence_number);
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -22,10 +22,10 @@ extern "C"
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
#include "./arguments_impl.h"
|
#include "./arguments_impl.h"
|
||||||
#include "./stdatomic_helper.h"
|
|
||||||
#include "rcl/arguments.h"
|
#include "rcl/arguments.h"
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
#include "rcutils/logging_macros.h"
|
#include "rcutils/logging_macros.h"
|
||||||
|
#include "rcutils/stdatomic_helper.h"
|
||||||
#include "rmw/error_handling.h"
|
#include "rmw/error_handling.h"
|
||||||
|
|
||||||
static atomic_bool __rcl_is_initialized = ATOMIC_VAR_INIT(false);
|
static atomic_bool __rcl_is_initialized = ATOMIC_VAR_INIT(false);
|
||||||
|
@ -56,8 +56,8 @@ __clean_up_init()
|
||||||
if (NULL != global_args->impl && RCL_RET_OK != rcl_arguments_fini(global_args)) {
|
if (NULL != global_args->impl && RCL_RET_OK != rcl_arguments_fini(global_args)) {
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
}
|
}
|
||||||
rcl_atomic_store(&__rcl_instance_id, 0);
|
rcutils_atomic_store(&__rcl_instance_id, 0);
|
||||||
rcl_atomic_store(&__rcl_is_initialized, false);
|
rcutils_atomic_store(&__rcl_is_initialized, false);
|
||||||
}
|
}
|
||||||
|
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
|
@ -71,7 +71,7 @@ rcl_init(int argc, char const * const * argv, rcl_allocator_t allocator)
|
||||||
if (argc > 0) {
|
if (argc > 0) {
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
|
||||||
}
|
}
|
||||||
if (rcl_atomic_exchange_bool(&__rcl_is_initialized, true)) {
|
if (rcutils_atomic_exchange_bool(&__rcl_is_initialized, true)) {
|
||||||
RCL_SET_ERROR_MSG("rcl_init called while already initialized");
|
RCL_SET_ERROR_MSG("rcl_init called while already initialized");
|
||||||
return RCL_RET_ALREADY_INIT;
|
return RCL_RET_ALREADY_INIT;
|
||||||
}
|
}
|
||||||
|
@ -123,8 +123,8 @@ rcl_init(int argc, char const * const * argv, rcl_allocator_t allocator)
|
||||||
rcutils_logging_set_default_logger_level(global_args->impl->log_level);
|
rcutils_logging_set_default_logger_level(global_args->impl->log_level);
|
||||||
}
|
}
|
||||||
|
|
||||||
rcl_atomic_store(&__rcl_instance_id, ++__rcl_next_unique_id);
|
rcutils_atomic_store(&__rcl_instance_id, ++__rcl_next_unique_id);
|
||||||
if (rcl_atomic_load_uint64_t(&__rcl_instance_id) == 0) {
|
if (rcutils_atomic_load_uint64_t(&__rcl_instance_id) == 0) {
|
||||||
// Roll over occurred.
|
// Roll over occurred.
|
||||||
__rcl_next_unique_id--; // roll back to avoid the next call succeeding.
|
__rcl_next_unique_id--; // roll back to avoid the next call succeeding.
|
||||||
RCL_SET_ERROR_MSG("unique rcl instance ids exhausted");
|
RCL_SET_ERROR_MSG("unique rcl instance ids exhausted");
|
||||||
|
@ -152,13 +152,13 @@ rcl_shutdown()
|
||||||
uint64_t
|
uint64_t
|
||||||
rcl_get_instance_id()
|
rcl_get_instance_id()
|
||||||
{
|
{
|
||||||
return rcl_atomic_load_uint64_t(&__rcl_instance_id);
|
return rcutils_atomic_load_uint64_t(&__rcl_instance_id);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool
|
bool
|
||||||
rcl_ok()
|
rcl_ok()
|
||||||
{
|
{
|
||||||
return rcl_atomic_load_bool(&__rcl_is_initialized);
|
return rcutils_atomic_load_bool(&__rcl_is_initialized);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
|
|
|
@ -1,129 +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 RCL__STDATOMIC_HELPER_H_
|
|
||||||
#define RCL__STDATOMIC_HELPER_H_
|
|
||||||
|
|
||||||
#if !defined(_WIN32)
|
|
||||||
|
|
||||||
#if defined(__GNUC__) && __GNUC__ <= 4 && __GNUC_MINOR__ <= 9
|
|
||||||
// If GCC and below GCC-4.9, use the compatability header.
|
|
||||||
#include "stdatomic_helper/gcc/stdatomic.h"
|
|
||||||
#elif defined(__clang__) && defined(__has_feature)
|
|
||||||
#if !__has_feature(c_atomic)
|
|
||||||
// If Clang and no c_atomics (true for some older versions), use the compatability header.
|
|
||||||
#include "stdatomic_helper/gcc/stdatomic.h"
|
|
||||||
#endif
|
|
||||||
#else
|
|
||||||
#include <stdatomic.h>
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define rcl_atomic_load(object, out) (out) = atomic_load(object)
|
|
||||||
|
|
||||||
#define rcl_atomic_compare_exchange_strong(object, out, expected, desired) \
|
|
||||||
(out) = atomic_compare_exchange_strong(object, expected, desired)
|
|
||||||
|
|
||||||
#define rcl_atomic_exchange(object, out, desired) (out) = atomic_exchange(object, desired)
|
|
||||||
|
|
||||||
#define rcl_atomic_store(object, desired) atomic_store(object, desired)
|
|
||||||
|
|
||||||
#else // !defined(_WIN32)
|
|
||||||
|
|
||||||
#include "./stdatomic_helper/win32/stdatomic.h"
|
|
||||||
|
|
||||||
#define rcl_atomic_load(object, out) rcl_win32_atomic_load(object, out)
|
|
||||||
|
|
||||||
#define rcl_atomic_compare_exchange_strong(object, out, expected, desired) \
|
|
||||||
rcl_win32_atomic_compare_exchange_strong(object, out, expected, desired)
|
|
||||||
|
|
||||||
#define rcl_atomic_exchange(object, out, desired) rcl_win32_atomic_exchange(object, out, desired)
|
|
||||||
|
|
||||||
#define rcl_atomic_store(object, desired) rcl_win32_atomic_store(object, desired)
|
|
||||||
|
|
||||||
#endif // !defined(_WIN32)
|
|
||||||
|
|
||||||
static inline bool
|
|
||||||
rcl_atomic_load_bool(atomic_bool * a_bool)
|
|
||||||
{
|
|
||||||
bool result = false;
|
|
||||||
rcl_atomic_load(a_bool, result);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline int64_t
|
|
||||||
rcl_atomic_load_int64_t(atomic_int_least64_t * a_int64_t)
|
|
||||||
{
|
|
||||||
int64_t result = 0;
|
|
||||||
rcl_atomic_load(a_int64_t, result);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline uint64_t
|
|
||||||
rcl_atomic_load_uint64_t(atomic_uint_least64_t * a_uint64_t)
|
|
||||||
{
|
|
||||||
uint64_t result = 0;
|
|
||||||
rcl_atomic_load(a_uint64_t, result);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline uintptr_t
|
|
||||||
rcl_atomic_load_uintptr_t(atomic_uintptr_t * a_uintptr_t)
|
|
||||||
{
|
|
||||||
uintptr_t result = 0;
|
|
||||||
rcl_atomic_load(a_uintptr_t, result);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline bool
|
|
||||||
rcl_atomic_compare_exchange_strong_uint_least64_t(
|
|
||||||
atomic_uint_least64_t * a_uint_least64_t, uint64_t * expected, uint64_t desired)
|
|
||||||
{
|
|
||||||
bool result;
|
|
||||||
rcl_atomic_compare_exchange_strong(a_uint_least64_t, result, expected, desired);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline bool
|
|
||||||
rcl_atomic_exchange_bool(atomic_bool * a_bool, bool desired)
|
|
||||||
{
|
|
||||||
bool result;
|
|
||||||
rcl_atomic_exchange(a_bool, result, desired);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline int64_t
|
|
||||||
rcl_atomic_exchange_int64_t(atomic_int_least64_t * a_int64_t, int64_t desired)
|
|
||||||
{
|
|
||||||
int64_t result;
|
|
||||||
rcl_atomic_exchange(a_int64_t, result, desired);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline uint64_t
|
|
||||||
rcl_atomic_exchange_uint64_t(atomic_uint_least64_t * a_uint64_t, uint64_t desired)
|
|
||||||
{
|
|
||||||
uint64_t result;
|
|
||||||
rcl_atomic_exchange(a_uint64_t, result, desired);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline uintptr_t
|
|
||||||
rcl_atomic_exchange_uintptr_t(atomic_uintptr_t * a_uintptr_t, uintptr_t desired)
|
|
||||||
{
|
|
||||||
uintptr_t result;
|
|
||||||
rcl_atomic_exchange(a_uintptr_t, result, desired);
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // RCL__STDATOMIC_HELPER_H_
|
|
|
@ -1,400 +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.
|
|
||||||
|
|
||||||
/* This file was taken from:
|
|
||||||
* https://gist.github.com/nhatminhle/5181506
|
|
||||||
* It is a modification of the FreeBSD stdatomic header with some modifications
|
|
||||||
* so that it will work with gcc 4.7+ and Clang 3.1+.
|
|
||||||
* The original FreeBSD header can be found here:
|
|
||||||
* https://github.com/freebsd/freebsd/blob/release/10.2.0/sys/sys/stdatomic.h
|
|
||||||
*/
|
|
||||||
|
|
||||||
// *INDENT-OFF* (disable uncrustify)
|
|
||||||
|
|
||||||
/**** Start included file. ****/
|
|
||||||
|
|
||||||
/*
|
|
||||||
* An implementation of C11 stdatomic.h directly borrowed from FreeBSD
|
|
||||||
* (original copyright follows), with minor modifications for
|
|
||||||
* portability to other systems. Works for recent Clang (that
|
|
||||||
* implement the feature c_atomic) and GCC 4.7+; includes
|
|
||||||
* compatibility for GCC below 4.7 but I wouldn't recommend it.
|
|
||||||
*
|
|
||||||
* Caveats and limitations:
|
|
||||||
* - Only the ``_Atomic parentheses'' notation is implemented, while
|
|
||||||
* the ``_Atomic space'' one is not.
|
|
||||||
* - _Atomic types must be typedef'ed, or programs using them will
|
|
||||||
* not type check correctly (incompatible anonymous structure
|
|
||||||
* types).
|
|
||||||
* - Non-scalar _Atomic types would require runtime support for
|
|
||||||
* runtime locking, which, as far as I know, is not currently
|
|
||||||
* available on any system.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*-
|
|
||||||
* Copyright (c) 2011 Ed Schouten <ed@FreeBSD.org>
|
|
||||||
* David Chisnall <theraven@FreeBSD.org>
|
|
||||||
* All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in the
|
|
||||||
* documentation and/or other materials provided with the distribution.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
|
|
||||||
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
|
||||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
|
||||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
|
|
||||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
|
||||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
|
||||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
|
||||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
|
|
||||||
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
|
|
||||||
* SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
* $FreeBSD: src/include/stdatomic.h,v 1.10.2.2 2012/05/30 19:21:54 theraven Exp $
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifndef _STDATOMIC_H_ // NOLINT
|
|
||||||
#define _STDATOMIC_H_
|
|
||||||
|
|
||||||
#ifdef __cplusplus
|
|
||||||
// This will suppress warnings about _Bool not being defined.
|
|
||||||
typedef bool _Bool;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include <stddef.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
#if !defined(__has_feature)
|
|
||||||
#define __has_feature(x) 0
|
|
||||||
#endif
|
|
||||||
#if !defined(__has_builtin)
|
|
||||||
#define __has_builtin(x) 0
|
|
||||||
#endif
|
|
||||||
#if !defined(__GNUC_PREREQ__)
|
|
||||||
#if defined(__GNUC__) && defined(__GNUC_MINOR__)
|
|
||||||
#define __GNUC_PREREQ__(maj, min) \
|
|
||||||
((__GNUC__ << 16) + __GNUC_MINOR__ >= ((maj) << 16) + (min))
|
|
||||||
#else
|
|
||||||
#define __GNUC_PREREQ__(maj, min) 0
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if !defined(__CLANG_ATOMICS) && !defined(__GNUC_ATOMICS)
|
|
||||||
#if __has_feature(c_atomic)
|
|
||||||
#define __CLANG_ATOMICS
|
|
||||||
#elif __GNUC_PREREQ__(4, 7)
|
|
||||||
#define __GNUC_ATOMICS
|
|
||||||
#elif !defined(__GNUC__)
|
|
||||||
#error "stdatomic.h does not support your compiler"
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if !defined(__CLANG_ATOMICS)
|
|
||||||
#define _Atomic(T) struct { volatile __typeof__(T) __val; }
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.2 Initialization.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#if defined(__CLANG_ATOMICS)
|
|
||||||
#define ATOMIC_VAR_INIT(value) (value)
|
|
||||||
#define atomic_init(obj, value) __c11_atomic_init(obj, value)
|
|
||||||
#else
|
|
||||||
#define ATOMIC_VAR_INIT(value) { .__val = (value) }
|
|
||||||
#define atomic_init(obj, value) do { \
|
|
||||||
(obj)->__val = (value); \
|
|
||||||
} while (0)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Clang and recent GCC both provide predefined macros for the memory
|
|
||||||
* orderings. If we are using a compiler that doesn't define them, use the
|
|
||||||
* clang values - these will be ignored in the fallback path.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifndef __ATOMIC_RELAXED
|
|
||||||
#define __ATOMIC_RELAXED 0
|
|
||||||
#endif
|
|
||||||
#ifndef __ATOMIC_CONSUME
|
|
||||||
#define __ATOMIC_CONSUME 1
|
|
||||||
#endif
|
|
||||||
#ifndef __ATOMIC_ACQUIRE
|
|
||||||
#define __ATOMIC_ACQUIRE 2
|
|
||||||
#endif
|
|
||||||
#ifndef __ATOMIC_RELEASE
|
|
||||||
#define __ATOMIC_RELEASE 3
|
|
||||||
#endif
|
|
||||||
#ifndef __ATOMIC_ACQ_REL
|
|
||||||
#define __ATOMIC_ACQ_REL 4
|
|
||||||
#endif
|
|
||||||
#ifndef __ATOMIC_SEQ_CST
|
|
||||||
#define __ATOMIC_SEQ_CST 5
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.3 Order and consistency.
|
|
||||||
*
|
|
||||||
* The memory_order_* constants that denote the barrier behaviour of the
|
|
||||||
* atomic operations.
|
|
||||||
*/
|
|
||||||
|
|
||||||
enum memory_order {
|
|
||||||
memory_order_relaxed = __ATOMIC_RELAXED,
|
|
||||||
memory_order_consume = __ATOMIC_CONSUME,
|
|
||||||
memory_order_acquire = __ATOMIC_ACQUIRE,
|
|
||||||
memory_order_release = __ATOMIC_RELEASE,
|
|
||||||
memory_order_acq_rel = __ATOMIC_ACQ_REL,
|
|
||||||
memory_order_seq_cst = __ATOMIC_SEQ_CST
|
|
||||||
};
|
|
||||||
|
|
||||||
typedef enum memory_order memory_order;
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.4 Fences.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifdef __CLANG_ATOMICS
|
|
||||||
#define atomic_thread_fence(order) __c11_atomic_thread_fence(order)
|
|
||||||
#define atomic_signal_fence(order) __c11_atomic_signal_fence(order)
|
|
||||||
#elif defined(__GNUC_ATOMICS)
|
|
||||||
#define atomic_thread_fence(order) __atomic_thread_fence(order)
|
|
||||||
#define atomic_signal_fence(order) __atomic_signal_fence(order)
|
|
||||||
#else
|
|
||||||
#define atomic_thread_fence(order) __sync_synchronize()
|
|
||||||
#define atomic_signal_fence(order) __asm volatile ("" : : : "memory")
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.5 Lock-free property.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#if defined(__CLANG_ATOMICS)
|
|
||||||
#define atomic_is_lock_free(obj) \
|
|
||||||
__c11_atomic_is_lock_free(sizeof(obj))
|
|
||||||
#elif defined(__GNUC_ATOMICS)
|
|
||||||
#define atomic_is_lock_free(obj) \
|
|
||||||
__atomic_is_lock_free(sizeof((obj)->__val))
|
|
||||||
#else
|
|
||||||
#define atomic_is_lock_free(obj) \
|
|
||||||
(sizeof((obj)->__val) <= sizeof(void *))
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.6 Atomic integer types.
|
|
||||||
*/
|
|
||||||
|
|
||||||
typedef _Atomic(_Bool) atomic_bool;
|
|
||||||
typedef _Atomic(char) atomic_char;
|
|
||||||
typedef _Atomic(signed char) atomic_schar;
|
|
||||||
typedef _Atomic(unsigned char) atomic_uchar;
|
|
||||||
typedef _Atomic(short) atomic_short; // NOLINT
|
|
||||||
typedef _Atomic(unsigned short) atomic_ushort; // NOLINT
|
|
||||||
typedef _Atomic(int) atomic_int;
|
|
||||||
typedef _Atomic(unsigned int) atomic_uint;
|
|
||||||
typedef _Atomic(long) atomic_long; // NOLINT
|
|
||||||
typedef _Atomic(unsigned long) atomic_ulong; // NOLINT
|
|
||||||
typedef _Atomic(long long) atomic_llong; // NOLINT
|
|
||||||
typedef _Atomic(unsigned long long) atomic_ullong; // NOLINT
|
|
||||||
#if 0
|
|
||||||
typedef _Atomic(char16_t) atomic_char16_t;
|
|
||||||
typedef _Atomic(char32_t) atomic_char32_t;
|
|
||||||
#endif
|
|
||||||
typedef _Atomic(wchar_t) atomic_wchar_t;
|
|
||||||
typedef _Atomic(int_least8_t) atomic_int_least8_t;
|
|
||||||
typedef _Atomic(uint_least8_t) atomic_uint_least8_t;
|
|
||||||
typedef _Atomic(int_least16_t) atomic_int_least16_t;
|
|
||||||
typedef _Atomic(uint_least16_t) atomic_uint_least16_t;
|
|
||||||
typedef _Atomic(int_least32_t) atomic_int_least32_t;
|
|
||||||
typedef _Atomic(uint_least32_t) atomic_uint_least32_t;
|
|
||||||
typedef _Atomic(int_least64_t) atomic_int_least64_t;
|
|
||||||
typedef _Atomic(uint_least64_t) atomic_uint_least64_t;
|
|
||||||
typedef _Atomic(int_fast8_t) atomic_int_fast8_t;
|
|
||||||
typedef _Atomic(uint_fast8_t) atomic_uint_fast8_t;
|
|
||||||
typedef _Atomic(int_fast16_t) atomic_int_fast16_t;
|
|
||||||
typedef _Atomic(uint_fast16_t) atomic_uint_fast16_t;
|
|
||||||
typedef _Atomic(int_fast32_t) atomic_int_fast32_t;
|
|
||||||
typedef _Atomic(uint_fast32_t) atomic_uint_fast32_t;
|
|
||||||
typedef _Atomic(int_fast64_t) atomic_int_fast64_t;
|
|
||||||
typedef _Atomic(uint_fast64_t) atomic_uint_fast64_t;
|
|
||||||
typedef _Atomic(intptr_t) atomic_intptr_t;
|
|
||||||
typedef _Atomic(uintptr_t) atomic_uintptr_t;
|
|
||||||
typedef _Atomic(size_t) atomic_size_t;
|
|
||||||
typedef _Atomic(ptrdiff_t) atomic_ptrdiff_t;
|
|
||||||
typedef _Atomic(intmax_t) atomic_intmax_t;
|
|
||||||
typedef _Atomic(uintmax_t) atomic_uintmax_t;
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.7 Operations on atomic types.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Compiler-specific operations.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#if defined(__CLANG_ATOMICS)
|
|
||||||
#define atomic_compare_exchange_strong_explicit(object, expected, \
|
|
||||||
desired, success, failure) \
|
|
||||||
__c11_atomic_compare_exchange_strong(object, expected, desired, \
|
|
||||||
success, failure)
|
|
||||||
#define atomic_compare_exchange_weak_explicit(object, expected, \
|
|
||||||
desired, success, failure) \
|
|
||||||
__c11_atomic_compare_exchange_weak(object, expected, desired, \
|
|
||||||
success, failure)
|
|
||||||
#define atomic_exchange_explicit(object, desired, order) \
|
|
||||||
__c11_atomic_exchange(object, desired, order)
|
|
||||||
#define atomic_fetch_add_explicit(object, operand, order) \
|
|
||||||
__c11_atomic_fetch_add(object, operand, order)
|
|
||||||
#define atomic_fetch_and_explicit(object, operand, order) \
|
|
||||||
__c11_atomic_fetch_and(object, operand, order)
|
|
||||||
#define atomic_fetch_or_explicit(object, operand, order) \
|
|
||||||
__c11_atomic_fetch_or(object, operand, order)
|
|
||||||
#define atomic_fetch_sub_explicit(object, operand, order) \
|
|
||||||
__c11_atomic_fetch_sub(object, operand, order)
|
|
||||||
#define atomic_fetch_xor_explicit(object, operand, order) \
|
|
||||||
__c11_atomic_fetch_xor(object, operand, order)
|
|
||||||
#define atomic_load_explicit(object, order) \
|
|
||||||
__c11_atomic_load(object, order)
|
|
||||||
#define atomic_store_explicit(object, desired, order) \
|
|
||||||
__c11_atomic_store(object, desired, order)
|
|
||||||
#elif defined(__GNUC_ATOMICS)
|
|
||||||
#define atomic_compare_exchange_strong_explicit(object, expected, \
|
|
||||||
desired, success, failure) \
|
|
||||||
__atomic_compare_exchange_n(&(object)->__val, expected, \
|
|
||||||
desired, 0, success, failure)
|
|
||||||
#define atomic_compare_exchange_weak_explicit(object, expected, \
|
|
||||||
desired, success, failure) \
|
|
||||||
__atomic_compare_exchange_n(&(object)->__val, expected, \
|
|
||||||
desired, 1, success, failure)
|
|
||||||
#define atomic_exchange_explicit(object, desired, order) \
|
|
||||||
__atomic_exchange_n(&(object)->__val, desired, order)
|
|
||||||
#define atomic_fetch_add_explicit(object, operand, order) \
|
|
||||||
__atomic_fetch_add(&(object)->__val, operand, order)
|
|
||||||
#define atomic_fetch_and_explicit(object, operand, order) \
|
|
||||||
__atomic_fetch_and(&(object)->__val, operand, order)
|
|
||||||
#define atomic_fetch_or_explicit(object, operand, order) \
|
|
||||||
__atomic_fetch_or(&(object)->__val, operand, order)
|
|
||||||
#define atomic_fetch_sub_explicit(object, operand, order) \
|
|
||||||
__atomic_fetch_sub(&(object)->__val, operand, order)
|
|
||||||
#define atomic_fetch_xor_explicit(object, operand, order) \
|
|
||||||
__atomic_fetch_xor(&(object)->__val, operand, order)
|
|
||||||
#define atomic_load_explicit(object, order) \
|
|
||||||
__atomic_load_n(&(object)->__val, order)
|
|
||||||
#define atomic_store_explicit(object, desired, order) \
|
|
||||||
__atomic_store_n(&(object)->__val, desired, order)
|
|
||||||
#else
|
|
||||||
#define atomic_compare_exchange_strong_explicit(object, expected, \
|
|
||||||
desired, success, failure) ({ \
|
|
||||||
__typeof__((object)->__val) __v; \
|
|
||||||
_Bool __r; \
|
|
||||||
__v = __sync_val_compare_and_swap(&(object)->__val, \
|
|
||||||
*(expected), desired); \
|
|
||||||
__r = *(expected) == __v; \
|
|
||||||
*(expected) = __v; \
|
|
||||||
__r; \
|
|
||||||
})
|
|
||||||
|
|
||||||
#define atomic_compare_exchange_weak_explicit(object, expected, \
|
|
||||||
desired, success, failure) \
|
|
||||||
atomic_compare_exchange_strong_explicit(object, expected, \
|
|
||||||
desired, success, failure)
|
|
||||||
#if __has_builtin(__sync_swap)
|
|
||||||
/* Clang provides a full-barrier atomic exchange - use it if available. */
|
|
||||||
#define atomic_exchange_explicit(object, desired, order) \
|
|
||||||
__sync_swap(&(object)->__val, desired)
|
|
||||||
#else
|
|
||||||
/*
|
|
||||||
* __sync_lock_test_and_set() is only an acquire barrier in theory (although in
|
|
||||||
* practice it is usually a full barrier) so we need an explicit barrier after
|
|
||||||
* it.
|
|
||||||
*/
|
|
||||||
#define atomic_exchange_explicit(object, desired, order) ({ \
|
|
||||||
__typeof__((object)->__val) __v; \
|
|
||||||
__v = __sync_lock_test_and_set(&(object)->__val, desired); \
|
|
||||||
__sync_synchronize(); \
|
|
||||||
__v; \
|
|
||||||
})
|
|
||||||
#endif
|
|
||||||
#define atomic_fetch_add_explicit(object, operand, order) \
|
|
||||||
__sync_fetch_and_add(&(object)->__val, operand)
|
|
||||||
#define atomic_fetch_and_explicit(object, operand, order) \
|
|
||||||
__sync_fetch_and_and(&(object)->__val, operand)
|
|
||||||
#define atomic_fetch_or_explicit(object, operand, order) \
|
|
||||||
__sync_fetch_and_or(&(object)->__val, operand)
|
|
||||||
#define atomic_fetch_sub_explicit(object, operand, order) \
|
|
||||||
__sync_fetch_and_sub(&(object)->__val, operand)
|
|
||||||
#define atomic_fetch_xor_explicit(object, operand, order) \
|
|
||||||
__sync_fetch_and_xor(&(object)->__val, operand)
|
|
||||||
#define atomic_load_explicit(object, order) \
|
|
||||||
__sync_fetch_and_add(&(object)->__val, 0)
|
|
||||||
#define atomic_store_explicit(object, desired, order) do { \
|
|
||||||
__sync_synchronize(); \
|
|
||||||
(object)->__val = (desired); \
|
|
||||||
__sync_synchronize(); \
|
|
||||||
} while (0)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Convenience functions.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define atomic_compare_exchange_strong(object, expected, desired) \
|
|
||||||
atomic_compare_exchange_strong_explicit(object, expected, \
|
|
||||||
desired, memory_order_seq_cst, memory_order_seq_cst)
|
|
||||||
#define atomic_compare_exchange_weak(object, expected, desired) \
|
|
||||||
atomic_compare_exchange_weak_explicit(object, expected, \
|
|
||||||
desired, memory_order_seq_cst, memory_order_seq_cst)
|
|
||||||
#define atomic_exchange(object, desired) \
|
|
||||||
atomic_exchange_explicit(object, desired, memory_order_seq_cst)
|
|
||||||
#define atomic_fetch_add(object, operand) \
|
|
||||||
atomic_fetch_add_explicit(object, operand, memory_order_seq_cst)
|
|
||||||
#define atomic_fetch_and(object, operand) \
|
|
||||||
atomic_fetch_and_explicit(object, operand, memory_order_seq_cst)
|
|
||||||
#define atomic_fetch_or(object, operand) \
|
|
||||||
atomic_fetch_or_explicit(object, operand, memory_order_seq_cst)
|
|
||||||
#define atomic_fetch_sub(object, operand) \
|
|
||||||
atomic_fetch_sub_explicit(object, operand, memory_order_seq_cst)
|
|
||||||
#define atomic_fetch_xor(object, operand) \
|
|
||||||
atomic_fetch_xor_explicit(object, operand, memory_order_seq_cst)
|
|
||||||
#define atomic_load(object) \
|
|
||||||
atomic_load_explicit(object, memory_order_seq_cst)
|
|
||||||
#define atomic_store(object, desired) \
|
|
||||||
atomic_store_explicit(object, desired, memory_order_seq_cst)
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.8 Atomic flag type and operations.
|
|
||||||
*/
|
|
||||||
|
|
||||||
typedef atomic_bool atomic_flag;
|
|
||||||
|
|
||||||
#define ATOMIC_FLAG_INIT ATOMIC_VAR_INIT(0)
|
|
||||||
|
|
||||||
#define atomic_flag_clear_explicit(object, order) \
|
|
||||||
atomic_store_explicit(object, 0, order)
|
|
||||||
#define atomic_flag_test_and_set_explicit(object, order) \
|
|
||||||
atomic_compare_exchange_strong_explicit(object, 0, 1, order, order)
|
|
||||||
|
|
||||||
#define atomic_flag_clear(object) \
|
|
||||||
atomic_flag_clear_explicit(object, memory_order_seq_cst)
|
|
||||||
#define atomic_flag_test_and_set(object) \
|
|
||||||
atomic_flag_test_and_set_explicit(object, memory_order_seq_cst)
|
|
||||||
|
|
||||||
#endif /* !_STDATOMIC_H_ */ // NOLINT
|
|
|
@ -1,406 +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.
|
|
||||||
|
|
||||||
/*
|
|
||||||
* An implementation of C11 stdatomic.h for Win32, part borrowed from FreeBSD
|
|
||||||
* (original copyright follows), with major modifications for
|
|
||||||
* portability to Win32 systems.
|
|
||||||
*
|
|
||||||
* Caveats and limitations:
|
|
||||||
* - Only the ``_Atomic parentheses'' notation is implemented, while
|
|
||||||
* the ``_Atomic space'' one is not.
|
|
||||||
* - _Atomic types must be typedef'ed, or programs using them will
|
|
||||||
* not type check correctly (incompatible anonymous structure
|
|
||||||
* types).
|
|
||||||
* - Support is limited to 16, 32, and 64 bit types only.
|
|
||||||
* - Stripped down to only the functions used locally in rcl.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*-
|
|
||||||
* Copyright (c) 2011 Ed Schouten <ed@FreeBSD.org>
|
|
||||||
* David Chisnall <theraven@FreeBSD.org>
|
|
||||||
* All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in the
|
|
||||||
* documentation and/or other materials provided with the distribution.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND
|
|
||||||
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
|
||||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
|
||||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE
|
|
||||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
|
||||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
|
|
||||||
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
|
|
||||||
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
|
|
||||||
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
|
|
||||||
* SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
* $FreeBSD: src/include/stdatomic.h,v 1.10.2.2 2012/05/30 19:21:54 theraven Exp $
|
|
||||||
*/
|
|
||||||
|
|
||||||
#if !defined(_WIN32)
|
|
||||||
#error "this stdatomic.h does not support your compiler"
|
|
||||||
#endif // !defined(_WIN32)
|
|
||||||
|
|
||||||
#ifndef RCL__STDATOMIC_HELPER__WIN32__STDATOMIC_H_
|
|
||||||
#define RCL__STDATOMIC_HELPER__WIN32__STDATOMIC_H_
|
|
||||||
|
|
||||||
#include <Windows.h>
|
|
||||||
|
|
||||||
#include <stddef.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <stdio.h>
|
|
||||||
|
|
||||||
#include <rcutils/logging_macros.h>
|
|
||||||
|
|
||||||
// In MSVC, correct alignment of each type is already ensured.
|
|
||||||
#define _Atomic(T) struct { T __val; }
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.2 Initialization.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define ATOMIC_VAR_INIT(value) {.__val = (value)}
|
|
||||||
#define atomic_init(obj, value) do { \
|
|
||||||
(obj)->__val = (value); \
|
|
||||||
} while (0)
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Clang and recent GCC both provide predefined macros for the memory
|
|
||||||
* orderings. If we are using a compiler that doesn't define them, use the
|
|
||||||
* clang values - these will be ignored in the fallback path.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifndef __ATOMIC_RELAXED
|
|
||||||
#define __ATOMIC_RELAXED 0
|
|
||||||
#endif
|
|
||||||
#ifndef __ATOMIC_CONSUME
|
|
||||||
#define __ATOMIC_CONSUME 1
|
|
||||||
#endif
|
|
||||||
#ifndef __ATOMIC_ACQUIRE
|
|
||||||
#define __ATOMIC_ACQUIRE 2
|
|
||||||
#endif
|
|
||||||
#ifndef __ATOMIC_RELEASE
|
|
||||||
#define __ATOMIC_RELEASE 3
|
|
||||||
#endif
|
|
||||||
#ifndef __ATOMIC_ACQ_REL
|
|
||||||
#define __ATOMIC_ACQ_REL 4
|
|
||||||
#endif
|
|
||||||
#ifndef __ATOMIC_SEQ_CST
|
|
||||||
#define __ATOMIC_SEQ_CST 5
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.3 Order and consistency.
|
|
||||||
*
|
|
||||||
* The memory_order_* constants that denote the barrier behaviour of the
|
|
||||||
* atomic operations.
|
|
||||||
*/
|
|
||||||
|
|
||||||
enum memory_order
|
|
||||||
{
|
|
||||||
memory_order_relaxed = __ATOMIC_RELAXED,
|
|
||||||
memory_order_consume = __ATOMIC_CONSUME,
|
|
||||||
memory_order_acquire = __ATOMIC_ACQUIRE,
|
|
||||||
memory_order_release = __ATOMIC_RELEASE,
|
|
||||||
memory_order_acq_rel = __ATOMIC_ACQ_REL,
|
|
||||||
memory_order_seq_cst = __ATOMIC_SEQ_CST
|
|
||||||
};
|
|
||||||
|
|
||||||
typedef enum memory_order memory_order;
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.4 Fences.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define atomic_thread_fence(order) MemoryBarrier()
|
|
||||||
#define atomic_signal_fence(order) _ReadWriteBarrier()
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.5 Lock-free property.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define atomic_is_lock_free(obj) (sizeof((obj)->__val) <= sizeof(void *))
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.6 Atomic integer types.
|
|
||||||
*/
|
|
||||||
|
|
||||||
typedef _Atomic (_Bool) atomic_bool;
|
|
||||||
typedef _Atomic (char) atomic_char;
|
|
||||||
typedef _Atomic (signed char) atomic_schar;
|
|
||||||
typedef _Atomic (unsigned char) atomic_uchar;
|
|
||||||
typedef _Atomic (short) atomic_short; // NOLINT
|
|
||||||
typedef _Atomic (unsigned short) atomic_ushort; // NOLINT
|
|
||||||
typedef _Atomic (int) atomic_int;
|
|
||||||
typedef _Atomic (unsigned int) atomic_uint;
|
|
||||||
typedef _Atomic (long) atomic_long; // NOLINT
|
|
||||||
typedef _Atomic (unsigned long) atomic_ulong; // NOLINT
|
|
||||||
typedef _Atomic (long long) atomic_llong; // NOLINT
|
|
||||||
typedef _Atomic (unsigned long long) atomic_ullong; // NOLINT
|
|
||||||
#if 0
|
|
||||||
typedef _Atomic (char16_t) atomic_char16_t;
|
|
||||||
typedef _Atomic (char32_t) atomic_char32_t;
|
|
||||||
typedef _Atomic (wchar_t) atomic_wchar_t;
|
|
||||||
typedef _Atomic (int_least8_t) atomic_int_least8_t;
|
|
||||||
typedef _Atomic (uint_least8_t) atomic_uint_least8_t;
|
|
||||||
#endif
|
|
||||||
typedef _Atomic (int_least16_t) atomic_int_least16_t;
|
|
||||||
typedef _Atomic (uint_least16_t) atomic_uint_least16_t;
|
|
||||||
typedef _Atomic (int_least32_t) atomic_int_least32_t;
|
|
||||||
typedef _Atomic (uint_least32_t) atomic_uint_least32_t;
|
|
||||||
typedef _Atomic (int_least64_t) atomic_int_least64_t;
|
|
||||||
typedef _Atomic (uint_least64_t) atomic_uint_least64_t;
|
|
||||||
#if 0
|
|
||||||
typedef _Atomic (int_fast8_t) atomic_int_fast8_t;
|
|
||||||
typedef _Atomic (uint_fast8_t) atomic_uint_fast8_t;
|
|
||||||
#endif
|
|
||||||
typedef _Atomic (int_fast16_t) atomic_int_fast16_t;
|
|
||||||
typedef _Atomic (uint_fast16_t) atomic_uint_fast16_t;
|
|
||||||
typedef _Atomic (int_fast32_t) atomic_int_fast32_t;
|
|
||||||
typedef _Atomic (uint_fast32_t) atomic_uint_fast32_t;
|
|
||||||
typedef _Atomic (int_fast64_t) atomic_int_fast64_t;
|
|
||||||
typedef _Atomic (uint_fast64_t) atomic_uint_fast64_t;
|
|
||||||
typedef _Atomic (intptr_t) atomic_intptr_t;
|
|
||||||
typedef _Atomic (uintptr_t) atomic_uintptr_t;
|
|
||||||
typedef _Atomic (size_t) atomic_size_t;
|
|
||||||
typedef _Atomic (ptrdiff_t) atomic_ptrdiff_t;
|
|
||||||
typedef _Atomic (intmax_t) atomic_intmax_t;
|
|
||||||
typedef _Atomic (uintmax_t) atomic_uintmax_t;
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.7 Operations on atomic types. (pruned modified for Windows' crappy C compiler)
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define rcl_win32_atomic_compare_exchange_strong(object, out, expected, desired) \
|
|
||||||
__pragma(warning(push)) \
|
|
||||||
__pragma(warning(disable: 4244)) \
|
|
||||||
do { \
|
|
||||||
switch (sizeof(out)) { \
|
|
||||||
case sizeof(uint64_t): \
|
|
||||||
out = _InterlockedCompareExchange64((LONGLONG *) object, desired, *expected); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint32_t): \
|
|
||||||
out = _InterlockedCompareExchange((LONG *) object, desired, *expected); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint16_t): \
|
|
||||||
out = _InterlockedCompareExchange16((SHORT *) object, desired, *expected); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint8_t): \
|
|
||||||
out = _InterlockedCompareExchange8((char *) object, desired, *expected); \
|
|
||||||
break; \
|
|
||||||
default: \
|
|
||||||
RCUTILS_LOG_ERROR_NAMED( \
|
|
||||||
ROS_PACKAGE_NAME, "Unsupported integer type in atomic_compare_exchange_strong"); \
|
|
||||||
exit(-1); \
|
|
||||||
break; \
|
|
||||||
} \
|
|
||||||
} while (0); \
|
|
||||||
__pragma(warning(pop))
|
|
||||||
|
|
||||||
#define rcl_win32_atomic_compare_exchange_weak(object, out, expected, desired) \
|
|
||||||
rcl_win32_atomic_compare_exchange_strong(object, out, expected, desired)
|
|
||||||
|
|
||||||
#define rcl_win32_atomic_exchange(object, out, desired) \
|
|
||||||
__pragma(warning(push)) \
|
|
||||||
__pragma(warning(disable: 4244)) \
|
|
||||||
do { \
|
|
||||||
switch (sizeof(out)) { \
|
|
||||||
case sizeof(uint64_t): \
|
|
||||||
out = _InterlockedExchange64((LONGLONG *) object, desired); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint32_t): \
|
|
||||||
out = _InterlockedExchange((LONG *) object, desired); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint16_t): \
|
|
||||||
out = _InterlockedExchange16((SHORT *) object, desired); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint8_t): \
|
|
||||||
out = _InterlockedExchange8((char *) object, desired); \
|
|
||||||
break; \
|
|
||||||
default: \
|
|
||||||
RCUTILS_LOG_ERROR_NAMED( \
|
|
||||||
ROS_PACKAGE_NAME, "Unsupported integer type in atomic_exchange_strong"); \
|
|
||||||
exit(-1); \
|
|
||||||
break; \
|
|
||||||
} \
|
|
||||||
} while (0); \
|
|
||||||
__pragma(warning(pop))
|
|
||||||
|
|
||||||
#define rcl_win32_atomic_fetch_add(object, out, operand) \
|
|
||||||
__pragma(warning(push)) \
|
|
||||||
__pragma(warning(disable: 4244)) \
|
|
||||||
do { \
|
|
||||||
switch (sizeof(out)) { \
|
|
||||||
case sizeof(uint64_t): \
|
|
||||||
out = _InterlockedExchangeAdd64((LONGLONG *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint32_t): \
|
|
||||||
out = _InterlockedExchangeAdd((LONG *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint16_t): \
|
|
||||||
out = _InterlockedExchangeAdd16((SHORT *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint8_t): \
|
|
||||||
out = _InterlockedExchangeAdd8((char *) object, operand); \
|
|
||||||
break; \
|
|
||||||
default: \
|
|
||||||
RCUTILS_LOG_ERROR_NAMED( \
|
|
||||||
ROS_PACKAGE_NAME, "Unsupported integer type in atomic_fetch_add"); \
|
|
||||||
exit(-1); \
|
|
||||||
break; \
|
|
||||||
} \
|
|
||||||
} while (0); \
|
|
||||||
__pragma(warning(pop))
|
|
||||||
|
|
||||||
#define rcl_win32_atomic_fetch_and(object, out, operand) \
|
|
||||||
__pragma(warning(push)) \
|
|
||||||
__pragma(warning(disable: 4244)) \
|
|
||||||
do { \
|
|
||||||
switch (sizeof(out)) { \
|
|
||||||
case sizeof(uint64_t): \
|
|
||||||
out = _InterlockedAnd64((LONGLONG *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint32_t): \
|
|
||||||
out = _InterlockedAnd((LONG *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint16_t): \
|
|
||||||
out = _InterlockedAnd16((SHORT *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint8_t): \
|
|
||||||
out = _InterlockedAnd8((char *) object, operand); \
|
|
||||||
break; \
|
|
||||||
default: \
|
|
||||||
RCUTILS_LOG_ERROR_NAMED( \
|
|
||||||
ROS_PACKAGE_NAME, "Unsupported integer type in atomic_fetch_and"); \
|
|
||||||
exit(-1); \
|
|
||||||
break; \
|
|
||||||
} \
|
|
||||||
} while (0); \
|
|
||||||
__pragma(warning(pop))
|
|
||||||
|
|
||||||
#define rcl_win32_atomic_fetch_or(object, out, operand) \
|
|
||||||
__pragma(warning(push)) \
|
|
||||||
__pragma(warning(disable: 4244)) \
|
|
||||||
do { \
|
|
||||||
switch (sizeof(out)) { \
|
|
||||||
case sizeof(uint64_t): \
|
|
||||||
out = _InterlockedOr64((LONGLONG *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint32_t): \
|
|
||||||
out = _InterlockedOr((LONG *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint16_t): \
|
|
||||||
out = _InterlockedOr16((SHORT *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint8_t): \
|
|
||||||
out = _InterlockedOr8((char *) object, operand); \
|
|
||||||
break; \
|
|
||||||
default: \
|
|
||||||
RCUTILS_LOG_ERROR_NAMED( \
|
|
||||||
ROS_PACKAGE_NAME, "Unsupported integer type in atomic_fetch_or"); \
|
|
||||||
exit(-1); \
|
|
||||||
break; \
|
|
||||||
} \
|
|
||||||
} while (0); \
|
|
||||||
__pragma(warning(pop))
|
|
||||||
|
|
||||||
#define rcl_win32_atomic_fetch_sub(object, out, operand) \
|
|
||||||
rcl_win32_atomic_fetch_add(object, out, -(operand))
|
|
||||||
|
|
||||||
#define rcl_win32_atomic_fetch_xor(object, out, operand) \
|
|
||||||
__pragma(warning(push)) \
|
|
||||||
__pragma(warning(disable: 4244)) \
|
|
||||||
do { \
|
|
||||||
switch (sizeof(out)) { \
|
|
||||||
case sizeof(uint64_t): \
|
|
||||||
out = _InterlockedXor64((LONGLONG *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint32_t): \
|
|
||||||
out = _InterlockedXor((LONG *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint16_t): \
|
|
||||||
out = _InterlockedXor16((SHORT *) object, operand); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint8_t): \
|
|
||||||
out = _InterlockedXor8((char *) object, operand); \
|
|
||||||
break; \
|
|
||||||
default: \
|
|
||||||
RCUTILS_LOG_ERROR_NAMED( \
|
|
||||||
ROS_PACKAGE_NAME, "Unsupported integer type in atomic_fetch_xor"); \
|
|
||||||
exit(-1); \
|
|
||||||
break; \
|
|
||||||
} \
|
|
||||||
} while (0); \
|
|
||||||
__pragma(warning(pop))
|
|
||||||
|
|
||||||
#define rcl_win32_atomic_load(object, out) \
|
|
||||||
__pragma(warning(push)) \
|
|
||||||
__pragma(warning(disable: 4244)) \
|
|
||||||
do { \
|
|
||||||
switch (sizeof(out)) { \
|
|
||||||
case sizeof(uint64_t): \
|
|
||||||
out = _InterlockedExchangeAdd64((LONGLONG *) object, 0); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint32_t): \
|
|
||||||
out = _InterlockedExchangeAdd((LONG *) object, 0); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint16_t): \
|
|
||||||
out = _InterlockedExchangeAdd16((SHORT *) object, 0); \
|
|
||||||
break; \
|
|
||||||
case sizeof(uint8_t): \
|
|
||||||
out = _InterlockedExchangeAdd8((char *) object, 0); \
|
|
||||||
break; \
|
|
||||||
default: \
|
|
||||||
RCUTILS_LOG_ERROR_NAMED( \
|
|
||||||
ROS_PACKAGE_NAME, "Unsupported integer type in atomic_load"); \
|
|
||||||
exit(-1); \
|
|
||||||
break; \
|
|
||||||
} \
|
|
||||||
} while (0); \
|
|
||||||
__pragma(warning(pop))
|
|
||||||
|
|
||||||
#define rcl_win32_atomic_store(object, desired) \
|
|
||||||
do { \
|
|
||||||
MemoryBarrier(); \
|
|
||||||
(object)->__val = (desired); \
|
|
||||||
MemoryBarrier(); \
|
|
||||||
} while (0)
|
|
||||||
|
|
||||||
/*
|
|
||||||
* 7.17.8 Atomic flag type and operations. (disabled for now)
|
|
||||||
*/
|
|
||||||
|
|
||||||
// typedef atomic_bool atomic_flag;
|
|
||||||
|
|
||||||
// #define ATOMIC_FLAG_INIT ATOMIC_VAR_INIT(0)
|
|
||||||
|
|
||||||
// #define atomic_flag_clear_explicit(object, order) \
|
|
||||||
// atomic_store_explicit(object, 0, order)
|
|
||||||
// #define atomic_flag_test_and_set_explicit(object, order) \
|
|
||||||
// atomic_compare_exchange_strong_explicit(object, 0, 1, order, order)
|
|
||||||
|
|
||||||
// #define atomic_flag_clear(object) \
|
|
||||||
// atomic_flag_clear_explicit(object, memory_order_seq_cst)
|
|
||||||
// #define atomic_flag_test_and_set(object) \
|
|
||||||
// atomic_flag_test_and_set_explicit(object, memory_order_seq_cst)
|
|
||||||
|
|
||||||
#endif // RCL__STDATOMIC_HELPER__WIN32__STDATOMIC_H_
|
|
|
@ -18,12 +18,11 @@
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
|
||||||
#include "./common.h"
|
#include "./common.h"
|
||||||
#include "./stdatomic_helper.h"
|
|
||||||
#include "rcl/allocator.h"
|
#include "rcl/allocator.h"
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
|
#include "rcutils/stdatomic_helper.h"
|
||||||
#include "rcutils/time.h"
|
#include "rcutils/time.h"
|
||||||
|
|
||||||
|
|
||||||
// Internal storage for RCL_ROS_TIME implementation
|
// Internal storage for RCL_ROS_TIME implementation
|
||||||
typedef struct rcl_ros_clock_storage_t
|
typedef struct rcl_ros_clock_storage_t
|
||||||
{
|
{
|
||||||
|
@ -67,7 +66,7 @@ rcl_get_ros_time(void * data, rcl_time_point_value_t * current_time)
|
||||||
if (!t->active) {
|
if (!t->active) {
|
||||||
return rcl_get_system_time(data, current_time);
|
return rcl_get_system_time(data, current_time);
|
||||||
}
|
}
|
||||||
*current_time = rcl_atomic_load_uint64_t(&(t->current_time));
|
*current_time = rcutils_atomic_load_uint64_t(&(t->current_time));
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -371,7 +370,7 @@ rcl_set_ros_time_override(
|
||||||
time_jump.delta.nanoseconds = time_value - current_time;
|
time_jump.delta.nanoseconds = time_value - current_time;
|
||||||
_rcl_clock_call_callbacks(clock, &time_jump, true);
|
_rcl_clock_call_callbacks(clock, &time_jump, true);
|
||||||
}
|
}
|
||||||
rcl_atomic_store(&(storage->current_time), time_value);
|
rcutils_atomic_store(&(storage->current_time), time_value);
|
||||||
if (storage->active) {
|
if (storage->active) {
|
||||||
_rcl_clock_call_callbacks(clock, &time_jump, false);
|
_rcl_clock_call_callbacks(clock, &time_jump, false);
|
||||||
}
|
}
|
||||||
|
|
|
@ -21,9 +21,9 @@ extern "C"
|
||||||
|
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
|
|
||||||
#include "./stdatomic_helper.h"
|
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
#include "rcutils/logging_macros.h"
|
#include "rcutils/logging_macros.h"
|
||||||
|
#include "rcutils/stdatomic_helper.h"
|
||||||
#include "rcutils/time.h"
|
#include "rcutils/time.h"
|
||||||
|
|
||||||
typedef struct rcl_timer_impl_t
|
typedef struct rcl_timer_impl_t
|
||||||
|
@ -77,8 +77,8 @@ void _rcl_timer_time_jump(
|
||||||
// No time credit if clock is uninitialized
|
// No time credit if clock is uninitialized
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
const int64_t next_call_time = rcl_atomic_load_int64_t(&timer->impl->next_call_time);
|
const int64_t next_call_time = rcutils_atomic_load_int64_t(&timer->impl->next_call_time);
|
||||||
rcl_atomic_store(&timer->impl->time_credit, next_call_time - now);
|
rcutils_atomic_store(&timer->impl->time_credit, next_call_time - now);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
rcl_time_point_value_t now;
|
rcl_time_point_value_t now;
|
||||||
|
@ -86,9 +86,9 @@ void _rcl_timer_time_jump(
|
||||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to get current time in jump callback");
|
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to get current time in jump callback");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
const int64_t last_call_time = rcl_atomic_load_int64_t(&timer->impl->last_call_time);
|
const int64_t last_call_time = rcutils_atomic_load_int64_t(&timer->impl->last_call_time);
|
||||||
const int64_t next_call_time = rcl_atomic_load_int64_t(&timer->impl->next_call_time);
|
const int64_t next_call_time = rcutils_atomic_load_int64_t(&timer->impl->next_call_time);
|
||||||
const int64_t period = rcl_atomic_load_uint64_t(&timer->impl->period);
|
const int64_t period = rcutils_atomic_load_uint64_t(&timer->impl->period);
|
||||||
if (RCL_ROS_TIME_ACTIVATED == time_jump->clock_change ||
|
if (RCL_ROS_TIME_ACTIVATED == time_jump->clock_change ||
|
||||||
RCL_ROS_TIME_DEACTIVATED == time_jump->clock_change)
|
RCL_ROS_TIME_DEACTIVATED == time_jump->clock_change)
|
||||||
{
|
{
|
||||||
|
@ -97,11 +97,11 @@ void _rcl_timer_time_jump(
|
||||||
// Can't apply time credit if clock is uninitialized
|
// Can't apply time credit if clock is uninitialized
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
int64_t time_credit = rcl_atomic_exchange_int64_t(&timer->impl->time_credit, 0);
|
int64_t time_credit = rcutils_atomic_exchange_int64_t(&timer->impl->time_credit, 0);
|
||||||
if (time_credit) {
|
if (time_credit) {
|
||||||
// set times in new epoch so timer only waits the remainder of the period
|
// set times in new epoch so timer only waits the remainder of the period
|
||||||
rcl_atomic_store(&timer->impl->next_call_time, now - time_credit + period);
|
rcutils_atomic_store(&timer->impl->next_call_time, now - time_credit + period);
|
||||||
rcl_atomic_store(&timer->impl->last_call_time, now - time_credit);
|
rcutils_atomic_store(&timer->impl->last_call_time, now - time_credit);
|
||||||
}
|
}
|
||||||
} else if (next_call_time <= now) {
|
} else if (next_call_time <= now) {
|
||||||
// Post Forward jump and timer is ready
|
// Post Forward jump and timer is ready
|
||||||
|
@ -112,8 +112,8 @@ void _rcl_timer_time_jump(
|
||||||
} else if (now < last_call_time) {
|
} else if (now < last_call_time) {
|
||||||
// Post backwards time jump that went further back than 1 period
|
// Post backwards time jump that went further back than 1 period
|
||||||
// next callback should happen after 1 period
|
// next callback should happen after 1 period
|
||||||
rcl_atomic_store(&timer->impl->next_call_time, now + period);
|
rcutils_atomic_store(&timer->impl->next_call_time, now + period);
|
||||||
rcl_atomic_store(&timer->impl->last_call_time, now);
|
rcutils_atomic_store(&timer->impl->last_call_time, now);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -234,7 +234,7 @@ rcl_timer_call(rcl_timer_t * timer)
|
||||||
{
|
{
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Calling timer");
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Calling timer");
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
|
||||||
if (rcl_atomic_load_bool(&timer->impl->canceled)) {
|
if (rcutils_atomic_load_bool(&timer->impl->canceled)) {
|
||||||
RCL_SET_ERROR_MSG("timer is canceled");
|
RCL_SET_ERROR_MSG("timer is canceled");
|
||||||
return RCL_RET_TIMER_CANCELED;
|
return RCL_RET_TIMER_CANCELED;
|
||||||
}
|
}
|
||||||
|
@ -248,12 +248,12 @@ rcl_timer_call(rcl_timer_t * timer)
|
||||||
return RCL_RET_ERROR;
|
return RCL_RET_ERROR;
|
||||||
}
|
}
|
||||||
rcl_time_point_value_t previous_ns =
|
rcl_time_point_value_t previous_ns =
|
||||||
rcl_atomic_exchange_int64_t(&timer->impl->last_call_time, now);
|
rcutils_atomic_exchange_int64_t(&timer->impl->last_call_time, now);
|
||||||
rcl_timer_callback_t typed_callback =
|
rcl_timer_callback_t typed_callback =
|
||||||
(rcl_timer_callback_t)rcl_atomic_load_uintptr_t(&timer->impl->callback);
|
(rcl_timer_callback_t)rcutils_atomic_load_uintptr_t(&timer->impl->callback);
|
||||||
|
|
||||||
int64_t next_call_time = rcl_atomic_load_int64_t(&timer->impl->next_call_time);
|
int64_t next_call_time = rcutils_atomic_load_int64_t(&timer->impl->next_call_time);
|
||||||
int64_t period = rcl_atomic_load_uint64_t(&timer->impl->period);
|
int64_t period = rcutils_atomic_load_uint64_t(&timer->impl->period);
|
||||||
// always move the next call time by exactly period forward
|
// always move the next call time by exactly period forward
|
||||||
// don't use now as the base to avoid extending each cycle by the time
|
// don't use now as the base to avoid extending each cycle by the time
|
||||||
// between the timer being ready and the callback being triggered
|
// between the timer being ready and the callback being triggered
|
||||||
|
@ -271,7 +271,7 @@ rcl_timer_call(rcl_timer_t * timer)
|
||||||
next_call_time += periods_ahead * period;
|
next_call_time += periods_ahead * period;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
rcl_atomic_store(&timer->impl->next_call_time, next_call_time);
|
rcutils_atomic_store(&timer->impl->next_call_time, next_call_time);
|
||||||
|
|
||||||
if (typed_callback != NULL) {
|
if (typed_callback != NULL) {
|
||||||
int64_t since_last_call = now - previous_ns;
|
int64_t since_last_call = now - previous_ns;
|
||||||
|
@ -290,7 +290,7 @@ rcl_timer_is_ready(const rcl_timer_t * timer, bool * is_ready)
|
||||||
if (ret != RCL_RET_OK) {
|
if (ret != RCL_RET_OK) {
|
||||||
return ret; // rcl error state should already be set.
|
return ret; // rcl error state should already be set.
|
||||||
}
|
}
|
||||||
*is_ready = (time_until_next_call <= 0) && !rcl_atomic_load_bool(&timer->impl->canceled);
|
*is_ready = (time_until_next_call <= 0) && !rcutils_atomic_load_bool(&timer->impl->canceled);
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -305,7 +305,7 @@ rcl_timer_get_time_until_next_call(const rcl_timer_t * timer, int64_t * time_unt
|
||||||
return ret; // rcl error state should already be set.
|
return ret; // rcl error state should already be set.
|
||||||
}
|
}
|
||||||
*time_until_next_call =
|
*time_until_next_call =
|
||||||
rcl_atomic_load_int64_t(&timer->impl->next_call_time) - now;
|
rcutils_atomic_load_int64_t(&timer->impl->next_call_time) - now;
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -322,7 +322,7 @@ rcl_timer_get_time_since_last_call(
|
||||||
return ret; // rcl error state should already be set.
|
return ret; // rcl error state should already be set.
|
||||||
}
|
}
|
||||||
*time_since_last_call =
|
*time_since_last_call =
|
||||||
now - rcl_atomic_load_int64_t(&timer->impl->last_call_time);
|
now - rcutils_atomic_load_int64_t(&timer->impl->last_call_time);
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -331,7 +331,7 @@ rcl_timer_get_period(const rcl_timer_t * timer, int64_t * period)
|
||||||
{
|
{
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(period, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(period, RCL_RET_INVALID_ARGUMENT);
|
||||||
*period = rcl_atomic_load_uint64_t(&timer->impl->period);
|
*period = rcutils_atomic_load_uint64_t(&timer->impl->period);
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -340,7 +340,7 @@ rcl_timer_exchange_period(const rcl_timer_t * timer, int64_t new_period, int64_t
|
||||||
{
|
{
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(old_period, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(old_period, RCL_RET_INVALID_ARGUMENT);
|
||||||
*old_period = rcl_atomic_exchange_uint64_t(&timer->impl->period, new_period);
|
*old_period = rcutils_atomic_exchange_uint64_t(&timer->impl->period, new_period);
|
||||||
RCUTILS_LOG_DEBUG_NAMED(
|
RCUTILS_LOG_DEBUG_NAMED(
|
||||||
ROS_PACKAGE_NAME, "Updated timer period from '%" PRIu64 "ns' to '%" PRIu64 "ns'",
|
ROS_PACKAGE_NAME, "Updated timer period from '%" PRIu64 "ns' to '%" PRIu64 "ns'",
|
||||||
*old_period, new_period);
|
*old_period, new_period);
|
||||||
|
@ -352,7 +352,7 @@ rcl_timer_get_callback(const rcl_timer_t * timer)
|
||||||
{
|
{
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(timer, NULL);
|
RCL_CHECK_ARGUMENT_FOR_NULL(timer, NULL);
|
||||||
RCL_CHECK_FOR_NULL_WITH_MSG(timer->impl, "timer is invalid", return NULL);
|
RCL_CHECK_FOR_NULL_WITH_MSG(timer->impl, "timer is invalid", return NULL);
|
||||||
return (rcl_timer_callback_t)rcl_atomic_load_uintptr_t(&timer->impl->callback);
|
return (rcl_timer_callback_t)rcutils_atomic_load_uintptr_t(&timer->impl->callback);
|
||||||
}
|
}
|
||||||
|
|
||||||
rcl_timer_callback_t
|
rcl_timer_callback_t
|
||||||
|
@ -361,7 +361,7 @@ rcl_timer_exchange_callback(rcl_timer_t * timer, const rcl_timer_callback_t new_
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Updating timer callback");
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Updating timer callback");
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(timer, NULL);
|
RCL_CHECK_ARGUMENT_FOR_NULL(timer, NULL);
|
||||||
RCL_CHECK_FOR_NULL_WITH_MSG(timer->impl, "timer is invalid", return NULL);
|
RCL_CHECK_FOR_NULL_WITH_MSG(timer->impl, "timer is invalid", return NULL);
|
||||||
return (rcl_timer_callback_t)rcl_atomic_exchange_uintptr_t(
|
return (rcl_timer_callback_t)rcutils_atomic_exchange_uintptr_t(
|
||||||
&timer->impl->callback, (uintptr_t)new_callback);
|
&timer->impl->callback, (uintptr_t)new_callback);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -370,7 +370,7 @@ rcl_timer_cancel(rcl_timer_t * timer)
|
||||||
{
|
{
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
|
||||||
RCL_CHECK_FOR_NULL_WITH_MSG(timer->impl, "timer is invalid", return RCL_RET_TIMER_INVALID);
|
RCL_CHECK_FOR_NULL_WITH_MSG(timer->impl, "timer is invalid", return RCL_RET_TIMER_INVALID);
|
||||||
rcl_atomic_store(&timer->impl->canceled, true);
|
rcutils_atomic_store(&timer->impl->canceled, true);
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Timer canceled");
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Timer canceled");
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
@ -380,7 +380,7 @@ rcl_timer_is_canceled(const rcl_timer_t * timer, bool * is_canceled)
|
||||||
{
|
{
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
|
||||||
RCL_CHECK_ARGUMENT_FOR_NULL(is_canceled, RCL_RET_INVALID_ARGUMENT);
|
RCL_CHECK_ARGUMENT_FOR_NULL(is_canceled, RCL_RET_INVALID_ARGUMENT);
|
||||||
*is_canceled = rcl_atomic_load_bool(&timer->impl->canceled);
|
*is_canceled = rcutils_atomic_load_bool(&timer->impl->canceled);
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -394,9 +394,9 @@ rcl_timer_reset(rcl_timer_t * timer)
|
||||||
if (now_ret != RCL_RET_OK) {
|
if (now_ret != RCL_RET_OK) {
|
||||||
return now_ret; // rcl error state should already be set.
|
return now_ret; // rcl error state should already be set.
|
||||||
}
|
}
|
||||||
int64_t period = rcl_atomic_load_uint64_t(&timer->impl->period);
|
int64_t period = rcutils_atomic_load_uint64_t(&timer->impl->period);
|
||||||
rcl_atomic_store(&timer->impl->next_call_time, now + period);
|
rcutils_atomic_store(&timer->impl->next_call_time, now + period);
|
||||||
rcl_atomic_store(&timer->impl->canceled, false);
|
rcutils_atomic_store(&timer->impl->canceled, false);
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Timer successfully reset");
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Timer successfully reset");
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
|
@ -24,7 +24,6 @@ extern "C"
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
#include "./stdatomic_helper.h"
|
|
||||||
#include "rcl/error_handling.h"
|
#include "rcl/error_handling.h"
|
||||||
#include "rcl/time.h"
|
#include "rcl/time.h"
|
||||||
#include "rcutils/logging_macros.h"
|
#include "rcutils/logging_macros.h"
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue