add visibility control macros to rcl
This commit is contained in:
parent
654ded894f
commit
43c1824909
19 changed files with 274 additions and 48 deletions
|
@ -40,6 +40,9 @@ macro(target)
|
||||||
if(NOT WIN32)
|
if(NOT WIN32)
|
||||||
set_target_properties(${PROJECT_NAME}${target_suffix} PROPERTIES COMPILE_FLAGS "-std=c11")
|
set_target_properties(${PROJECT_NAME}${target_suffix} PROPERTIES COMPILE_FLAGS "-std=c11")
|
||||||
endif()
|
endif()
|
||||||
|
# Causes the visibility macros to use dllexport rather than dllimport,
|
||||||
|
# which is appropriate when building the dll but not consuming it.
|
||||||
|
target_compile_definitions(${PROJECT_NAME}${target_suffix} PRIVATE "RCL_BUILDING_LIBRARY")
|
||||||
|
|
||||||
install(
|
install(
|
||||||
TARGETS ${PROJECT_NAME}${target_suffix}
|
TARGETS ${PROJECT_NAME}${target_suffix}
|
||||||
|
|
|
@ -21,6 +21,7 @@ extern "C"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "rcl/types.h"
|
#include "rcl/types.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
/// Encapsulation of an allocator.
|
/// Encapsulation of an allocator.
|
||||||
/* To use malloc, free, and realloc use rcl_get_default_allocator(). */
|
/* To use malloc, free, and realloc use rcl_get_default_allocator(). */
|
||||||
|
@ -50,6 +51,7 @@ typedef struct rcl_allocator_t
|
||||||
* This function is thread-safe.
|
* This function is thread-safe.
|
||||||
* This function is lock-free.
|
* This function is lock-free.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_allocator_t
|
rcl_allocator_t
|
||||||
rcl_get_default_allocator();
|
rcl_get_default_allocator();
|
||||||
|
|
||||||
|
|
|
@ -21,6 +21,7 @@ extern "C"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "rcl/node.h"
|
#include "rcl/node.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
/// Internal rcl guard condition implementation struct.
|
/// Internal rcl guard condition implementation struct.
|
||||||
struct rcl_guard_condition_impl_t;
|
struct rcl_guard_condition_impl_t;
|
||||||
|
@ -39,6 +40,7 @@ typedef struct rcl_guard_condition_options_t
|
||||||
} rcl_guard_condition_options_t;
|
} rcl_guard_condition_options_t;
|
||||||
|
|
||||||
/// Return a rcl_guard_condition_t struct with members set to NULL.
|
/// Return a rcl_guard_condition_t struct with members set to NULL.
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_guard_condition_t
|
rcl_guard_condition_t
|
||||||
rcl_get_zero_initialized_guard_condition();
|
rcl_get_zero_initialized_guard_condition();
|
||||||
|
|
||||||
|
@ -81,6 +83,7 @@ rcl_get_zero_initialized_guard_condition();
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_guard_condition_init(
|
rcl_guard_condition_init(
|
||||||
rcl_guard_condition_t * guard_condition,
|
rcl_guard_condition_t * guard_condition,
|
||||||
|
@ -102,6 +105,7 @@ rcl_guard_condition_init(
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or
|
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition, rcl_node_t * node);
|
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition, rcl_node_t * node);
|
||||||
|
|
||||||
|
@ -110,6 +114,7 @@ rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition, rcl_node_t * n
|
||||||
* This function is thread-safe.
|
* This function is thread-safe.
|
||||||
* This function is lock-free.
|
* This function is lock-free.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_guard_condition_options_t
|
rcl_guard_condition_options_t
|
||||||
rcl_guard_condition_get_default_options();
|
rcl_guard_condition_get_default_options();
|
||||||
|
|
||||||
|
@ -130,6 +135,7 @@ rcl_guard_condition_get_default_options();
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or
|
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_guard_condition_trigger(const rcl_guard_condition_t * guard_condition);
|
rcl_guard_condition_trigger(const rcl_guard_condition_t * guard_condition);
|
||||||
|
|
||||||
|
@ -144,6 +150,7 @@ rcl_guard_condition_trigger(const rcl_guard_condition_t * guard_condition);
|
||||||
* \param[in] guard_condition pointer to the rcl guard_condition
|
* \param[in] guard_condition pointer to the rcl guard_condition
|
||||||
* \return rmw guard_condition handle if successful, otherwise NULL
|
* \return rmw guard_condition handle if successful, otherwise NULL
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rmw_guard_condition_t *
|
rmw_guard_condition_t *
|
||||||
rcl_guard_condition_get_rmw_guard_condition_handle(const rcl_guard_condition_t * guard_condition);
|
rcl_guard_condition_get_rmw_guard_condition_handle(const rcl_guard_condition_t * guard_condition);
|
||||||
|
|
||||||
|
|
|
@ -24,6 +24,7 @@ extern "C"
|
||||||
|
|
||||||
#include "rcl/allocator.h"
|
#include "rcl/allocator.h"
|
||||||
#include "rcl/types.h"
|
#include "rcl/types.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
#define RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID SIZE_MAX
|
#define RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID SIZE_MAX
|
||||||
|
|
||||||
|
@ -57,6 +58,7 @@ typedef struct rcl_node_options_t
|
||||||
} rcl_node_options_t;
|
} rcl_node_options_t;
|
||||||
|
|
||||||
/// Return a rcl_node_t struct with members initialized to NULL.
|
/// Return a rcl_node_t struct with members initialized to NULL.
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_node_t
|
rcl_node_t
|
||||||
rcl_get_zero_initialized_node();
|
rcl_get_zero_initialized_node();
|
||||||
|
|
||||||
|
@ -103,6 +105,7 @@ rcl_get_zero_initialized_node();
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_node_init(rcl_node_t * node, const char * name, const rcl_node_options_t * options);
|
rcl_node_init(rcl_node_t * node, const char * name, const rcl_node_options_t * options);
|
||||||
|
|
||||||
|
@ -120,10 +123,12 @@ rcl_node_init(rcl_node_t * node, const char * name, const rcl_node_options_t * o
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or
|
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_node_fini(rcl_node_t * node);
|
rcl_node_fini(rcl_node_t * node);
|
||||||
|
|
||||||
/// Return the default node options in a rcl_node_options_t.
|
/// Return the default node options in a rcl_node_options_t.
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_node_options_t
|
rcl_node_options_t
|
||||||
rcl_node_get_default_options();
|
rcl_node_get_default_options();
|
||||||
|
|
||||||
|
@ -140,6 +145,7 @@ rcl_node_get_default_options();
|
||||||
* \param[in] node pointer to the node
|
* \param[in] node pointer to the node
|
||||||
* \return name string if successful, otherwise NULL
|
* \return name string if successful, otherwise NULL
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
const char *
|
const char *
|
||||||
rcl_node_get_name(const rcl_node_t * node);
|
rcl_node_get_name(const rcl_node_t * node);
|
||||||
|
|
||||||
|
@ -156,6 +162,7 @@ rcl_node_get_name(const rcl_node_t * node);
|
||||||
* \param[in] node pointer to the node
|
* \param[in] node pointer to the node
|
||||||
* \return options struct if successful, otherwise NULL
|
* \return options struct if successful, otherwise NULL
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
const rcl_node_options_t *
|
const rcl_node_options_t *
|
||||||
rcl_node_get_options(const rcl_node_t * node);
|
rcl_node_get_options(const rcl_node_t * node);
|
||||||
|
|
||||||
|
@ -177,6 +184,7 @@ rcl_node_get_options(const rcl_node_t * node);
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or
|
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_node_get_domain_id(const rcl_node_t * node, size_t * domain_id);
|
rcl_node_get_domain_id(const rcl_node_t * node, size_t * domain_id);
|
||||||
|
|
||||||
|
@ -193,6 +201,7 @@ rcl_node_get_domain_id(const rcl_node_t * node, size_t * domain_id);
|
||||||
* \param[in] node pointer to the rcl node
|
* \param[in] node pointer to the rcl node
|
||||||
* \return rmw node handle if successful, otherwise NULL
|
* \return rmw node handle if successful, otherwise NULL
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rmw_node_t *
|
rmw_node_t *
|
||||||
rcl_node_get_rmw_node_handle(const rcl_node_t * node);
|
rcl_node_get_rmw_node_handle(const rcl_node_t * node);
|
||||||
|
|
||||||
|
@ -211,6 +220,7 @@ rcl_node_get_rmw_node_handle(const rcl_node_t * node);
|
||||||
* \param[in] node pointer to the rcl node
|
* \param[in] node pointer to the rcl node
|
||||||
* \return rcl instance id captured at node creation or 0 if there was an error
|
* \return rcl instance id captured at node creation or 0 if there was an error
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
uint64_t
|
uint64_t
|
||||||
rcl_node_get_rcl_instance_id(const rcl_node_t * node);
|
rcl_node_get_rcl_instance_id(const rcl_node_t * node);
|
||||||
|
|
||||||
|
|
|
@ -23,6 +23,7 @@ extern "C"
|
||||||
#include "rosidl_generator_c/message_type_support.h"
|
#include "rosidl_generator_c/message_type_support.h"
|
||||||
|
|
||||||
#include "rcl/node.h"
|
#include "rcl/node.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
/// Internal rcl publisher implementation struct.
|
/// Internal rcl publisher implementation struct.
|
||||||
struct rcl_publisher_impl_t;
|
struct rcl_publisher_impl_t;
|
||||||
|
@ -49,6 +50,7 @@ typedef struct rcl_publisher_options_t
|
||||||
* It's also possible to use calloc() instead of this if the rcl_publisher is
|
* It's also possible to use calloc() instead of this if the rcl_publisher is
|
||||||
* being allocated on the heap.
|
* being allocated on the heap.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_publisher_t
|
rcl_publisher_t
|
||||||
rcl_get_zero_initialized_publisher();
|
rcl_get_zero_initialized_publisher();
|
||||||
|
|
||||||
|
@ -123,6 +125,7 @@ rcl_get_zero_initialized_publisher();
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory fails, or
|
* RCL_RET_BAD_ALLOC if allocating memory fails, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_publisher_init(
|
rcl_publisher_init(
|
||||||
rcl_publisher_t * publisher,
|
rcl_publisher_t * publisher,
|
||||||
|
@ -146,10 +149,12 @@ rcl_publisher_init(
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_publisher_fini(rcl_publisher_t * publisher, rcl_node_t * node);
|
rcl_publisher_fini(rcl_publisher_t * publisher, rcl_node_t * node);
|
||||||
|
|
||||||
/// Return the default publisher options in a rcl_publisher_options_t.
|
/// Return the default publisher options in a rcl_publisher_options_t.
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_publisher_options_t
|
rcl_publisher_options_t
|
||||||
rcl_publisher_get_default_options();
|
rcl_publisher_get_default_options();
|
||||||
|
|
||||||
|
@ -197,6 +202,7 @@ rcl_publisher_get_default_options();
|
||||||
* RCL_RET_PUBLISHER_INVALID if the publisher is invalid, or
|
* RCL_RET_PUBLISHER_INVALID if the publisher is invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_publish(const rcl_publisher_t * publisher, const void * ros_message);
|
rcl_publish(const rcl_publisher_t * publisher, const void * ros_message);
|
||||||
|
|
||||||
|
@ -216,6 +222,7 @@ rcl_publish(const rcl_publisher_t * publisher, const void * ros_message);
|
||||||
* \param[in] publisher pointer to the publisher
|
* \param[in] publisher pointer to the publisher
|
||||||
* \return name string if successful, otherwise NULL
|
* \return name string if successful, otherwise NULL
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
const char *
|
const char *
|
||||||
rcl_publisher_get_topic_name(const rcl_publisher_t * publisher);
|
rcl_publisher_get_topic_name(const rcl_publisher_t * publisher);
|
||||||
|
|
||||||
|
@ -235,6 +242,7 @@ rcl_publisher_get_topic_name(const rcl_publisher_t * publisher);
|
||||||
* \param[in] publisher pointer to the publisher
|
* \param[in] publisher pointer to the publisher
|
||||||
* \return options struct if successful, otherwise NULL
|
* \return options struct if successful, otherwise NULL
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
const rcl_publisher_options_t *
|
const rcl_publisher_options_t *
|
||||||
rcl_publisher_get_options(const rcl_publisher_t * publisher);
|
rcl_publisher_get_options(const rcl_publisher_t * publisher);
|
||||||
|
|
||||||
|
@ -258,6 +266,7 @@ rcl_publisher_get_options(const rcl_publisher_t * publisher);
|
||||||
* \param[in] publisher pointer to the rcl publisher
|
* \param[in] publisher pointer to the rcl publisher
|
||||||
* \return rmw publisher handle if successful, otherwise NULL
|
* \return rmw publisher handle if successful, otherwise NULL
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rmw_publisher_t *
|
rmw_publisher_t *
|
||||||
rcl_publisher_get_rmw_publisher_handle(const rcl_publisher_t * publisher);
|
rcl_publisher_get_rmw_publisher_handle(const rcl_publisher_t * publisher);
|
||||||
|
|
||||||
|
|
|
@ -24,6 +24,7 @@ extern "C"
|
||||||
#include "rcl/publisher.h"
|
#include "rcl/publisher.h"
|
||||||
#include "rcl/subscription.h"
|
#include "rcl/subscription.h"
|
||||||
#include "rcl/types.h"
|
#include "rcl/types.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
/// Global initialization of rcl.
|
/// Global initialization of rcl.
|
||||||
/* Unless otherwise noted, this must be called before using any rcl functions.
|
/* Unless otherwise noted, this must be called before using any rcl functions.
|
||||||
|
@ -52,6 +53,7 @@ extern "C"
|
||||||
* RCL_RET_ALREADY_INIT if rcl_init has already been called, or
|
* RCL_RET_ALREADY_INIT if rcl_init has already been called, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_init(int argc, char ** argv, rcl_allocator_t allocator);
|
rcl_init(int argc, char ** argv, rcl_allocator_t allocator);
|
||||||
|
|
||||||
|
@ -73,16 +75,19 @@ rcl_init(int argc, char ** argv, rcl_allocator_t allocator);
|
||||||
* \return RCL_RET_OK if shutdown is successful, otherwise RCL_RET_ERROR or
|
* \return RCL_RET_OK if shutdown is successful, otherwise RCL_RET_ERROR or
|
||||||
* RCL_RET_NOT_INIT if rcl_init has not yet been called
|
* RCL_RET_NOT_INIT if rcl_init has not yet been called
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_shutdown();
|
rcl_shutdown();
|
||||||
|
|
||||||
/// Returns an uint64_t number that is unique for the latest rcl_init call.
|
/// Returns an uint64_t number that is unique for the latest rcl_init call.
|
||||||
/* If called before rcl_init or after rcl_shutdown then 0 will be returned. */
|
/* If called before rcl_init or after rcl_shutdown then 0 will be returned. */
|
||||||
|
RCL_PUBLIC
|
||||||
uint64_t
|
uint64_t
|
||||||
rcl_get_instance_id();
|
rcl_get_instance_id();
|
||||||
|
|
||||||
/// Return true until rcl_shutdown is called, then false.
|
/// Return true until rcl_shutdown is called, then false.
|
||||||
/* This function is thread safe. */
|
/* This function is thread safe. */
|
||||||
|
RCL_PUBLIC
|
||||||
bool
|
bool
|
||||||
rcl_ok();
|
rcl_ok();
|
||||||
|
|
||||||
|
|
|
@ -23,6 +23,7 @@ extern "C"
|
||||||
#include "rosidl_generator_c/message_type_support.h"
|
#include "rosidl_generator_c/message_type_support.h"
|
||||||
|
|
||||||
#include "rcl/node.h"
|
#include "rcl/node.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
/// Internal rcl implementation struct.
|
/// Internal rcl implementation struct.
|
||||||
struct rcl_subscription_impl_t;
|
struct rcl_subscription_impl_t;
|
||||||
|
@ -51,6 +52,7 @@ typedef struct rcl_subscription_options_t
|
||||||
* It's also possible to use calloc() instead of this if the rcl_subscription_t
|
* It's also possible to use calloc() instead of this if the rcl_subscription_t
|
||||||
* is being allocated on the heap.
|
* is being allocated on the heap.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_subscription_t
|
rcl_subscription_t
|
||||||
rcl_get_zero_initialized_subscription();
|
rcl_get_zero_initialized_subscription();
|
||||||
|
|
||||||
|
@ -124,6 +126,7 @@ rcl_get_zero_initialized_subscription();
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_subscription_init(
|
rcl_subscription_init(
|
||||||
rcl_subscription_t * subscription,
|
rcl_subscription_t * subscription,
|
||||||
|
@ -149,10 +152,12 @@ rcl_subscription_init(
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or
|
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node);
|
rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node);
|
||||||
|
|
||||||
/// Return the default subscription options in a rcl_subscription_options_t.
|
/// Return the default subscription options in a rcl_subscription_options_t.
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_subscription_options_t
|
rcl_subscription_options_t
|
||||||
rcl_subscription_get_default_options();
|
rcl_subscription_get_default_options();
|
||||||
|
|
||||||
|
@ -198,6 +203,7 @@ rcl_subscription_get_default_options();
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_take(
|
rcl_take(
|
||||||
const rcl_subscription_t * subscription,
|
const rcl_subscription_t * subscription,
|
||||||
|
@ -221,6 +227,7 @@ rcl_take(
|
||||||
* \param[in] subscription the pointer to the subscription
|
* \param[in] subscription the pointer to the subscription
|
||||||
* \return name string if successful, otherwise NULL
|
* \return name string if successful, otherwise NULL
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
const char *
|
const char *
|
||||||
rcl_subscription_get_topic_name(const rcl_subscription_t * subscription);
|
rcl_subscription_get_topic_name(const rcl_subscription_t * subscription);
|
||||||
|
|
||||||
|
@ -240,6 +247,7 @@ rcl_subscription_get_topic_name(const rcl_subscription_t * subscription);
|
||||||
* \param[in] subscription pointer to the subscription
|
* \param[in] subscription pointer to the subscription
|
||||||
* \return options struct if successful, otherwise NULL
|
* \return options struct if successful, otherwise NULL
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
const rcl_subscription_options_t *
|
const rcl_subscription_options_t *
|
||||||
rcl_subscription_get_options(const rcl_subscription_t * subscription);
|
rcl_subscription_get_options(const rcl_subscription_t * subscription);
|
||||||
|
|
||||||
|
@ -258,6 +266,7 @@ rcl_subscription_get_options(const rcl_subscription_t * subscription);
|
||||||
* \param[in] subscription pointer to the rcl subscription
|
* \param[in] subscription pointer to the rcl subscription
|
||||||
* \return rmw subscription handle if successful, otherwise NULL
|
* \return rmw subscription handle if successful, otherwise NULL
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rmw_subscription_t *
|
rmw_subscription_t *
|
||||||
rcl_subscription_get_rmw_subscription_handle(const rcl_subscription_t * subscription);
|
rcl_subscription_get_rmw_subscription_handle(const rcl_subscription_t * subscription);
|
||||||
|
|
||||||
|
|
|
@ -21,6 +21,7 @@ extern "C"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "rcl/types.h"
|
#include "rcl/types.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
#define RCL_S_TO_NS(seconds) (seconds * 1000000000)
|
#define RCL_S_TO_NS(seconds) (seconds * 1000000000)
|
||||||
#define RCL_MS_TO_NS(milliseconds) (milliseconds * 1000000)
|
#define RCL_MS_TO_NS(milliseconds) (milliseconds * 1000000)
|
||||||
|
@ -91,6 +92,7 @@ typedef struct rcl_duration_t
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_system_time_point_now(rcl_system_time_point_t * now);
|
rcl_system_time_point_now(rcl_system_time_point_t * now);
|
||||||
|
|
||||||
|
@ -114,6 +116,7 @@ rcl_system_time_point_now(rcl_system_time_point_t * now);
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_steady_time_point_now(rcl_steady_time_point_t * now);
|
rcl_steady_time_point_now(rcl_steady_time_point_t * now);
|
||||||
|
|
||||||
|
|
|
@ -50,6 +50,7 @@ typedef struct rcl_timer_t
|
||||||
typedef void (* rcl_timer_callback_t)(rcl_timer_t *, uint64_t);
|
typedef void (* rcl_timer_callback_t)(rcl_timer_t *, uint64_t);
|
||||||
|
|
||||||
/// Return a zero initialized timer.
|
/// Return a zero initialized timer.
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_timer_t
|
rcl_timer_t
|
||||||
rcl_get_zero_initialized_timer();
|
rcl_get_zero_initialized_timer();
|
||||||
|
|
||||||
|
@ -110,6 +111,7 @@ rcl_get_zero_initialized_timer();
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_timer_init(
|
rcl_timer_init(
|
||||||
rcl_timer_t * timer,
|
rcl_timer_t * timer,
|
||||||
|
@ -133,6 +135,7 @@ rcl_timer_init(
|
||||||
* \return RCL_RET_OK if the timer was finalized successfully, or
|
* \return RCL_RET_OK if the timer was finalized successfully, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_timer_fini(rcl_timer_t * timer);
|
rcl_timer_fini(rcl_timer_t * timer);
|
||||||
|
|
||||||
|
@ -165,6 +168,7 @@ rcl_timer_fini(rcl_timer_t * timer);
|
||||||
* RCL_RET_TIMER_CANCELED if the timer has been canceled, or
|
* RCL_RET_TIMER_CANCELED if the timer has been canceled, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_timer_call(rcl_timer_t * timer);
|
rcl_timer_call(rcl_timer_t * timer);
|
||||||
|
|
||||||
|
@ -188,6 +192,7 @@ rcl_timer_call(rcl_timer_t * timer);
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_timer_is_ready(const rcl_timer_t * timer, bool * is_ready);
|
rcl_timer_is_ready(const rcl_timer_t * timer, bool * is_ready);
|
||||||
|
|
||||||
|
@ -216,6 +221,7 @@ rcl_timer_is_ready(const rcl_timer_t * timer, bool * is_ready);
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_timer_get_time_until_next_call(const rcl_timer_t * timer, int64_t * time_until_next_call);
|
rcl_timer_get_time_until_next_call(const rcl_timer_t * timer, int64_t * time_until_next_call);
|
||||||
|
|
||||||
|
@ -241,6 +247,7 @@ rcl_timer_get_time_until_next_call(const rcl_timer_t * timer, int64_t * time_unt
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_timer_get_time_since_last_call(const rcl_timer_t * timer, uint64_t * time_since_last_call);
|
rcl_timer_get_time_since_last_call(const rcl_timer_t * timer, uint64_t * time_since_last_call);
|
||||||
|
|
||||||
|
@ -260,6 +267,7 @@ rcl_timer_get_time_since_last_call(const rcl_timer_t * timer, uint64_t * time_si
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_timer_get_period(const rcl_timer_t * timer, uint64_t * period);
|
rcl_timer_get_period(const rcl_timer_t * timer, uint64_t * period);
|
||||||
|
|
||||||
|
@ -283,6 +291,7 @@ rcl_timer_get_period(const rcl_timer_t * timer, uint64_t * period);
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_timer_exchange_period(const rcl_timer_t * timer, uint64_t new_period, uint64_t * old_period);
|
rcl_timer_exchange_period(const rcl_timer_t * timer, uint64_t new_period, uint64_t * old_period);
|
||||||
|
|
||||||
|
@ -298,6 +307,7 @@ rcl_timer_exchange_period(const rcl_timer_t * timer, uint64_t new_period, uint64
|
||||||
* \param[in] timer handle to the timer from the callback should be returned
|
* \param[in] timer handle to the timer from the callback should be returned
|
||||||
* \return function pointer to the callback, or NULL if an error occurred
|
* \return function pointer to the callback, or NULL if an error occurred
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_timer_callback_t
|
rcl_timer_callback_t
|
||||||
rcl_timer_get_callback(const rcl_timer_t * timer);
|
rcl_timer_get_callback(const rcl_timer_t * timer);
|
||||||
|
|
||||||
|
@ -315,6 +325,7 @@ rcl_timer_get_callback(const rcl_timer_t * timer);
|
||||||
* \param[in] new_callback the callback to be exchanged into the timer
|
* \param[in] new_callback the callback to be exchanged into the timer
|
||||||
* \return function pointer to the old callback, or NULL if an error occurred
|
* \return function pointer to the old callback, or NULL if an error occurred
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_timer_callback_t
|
rcl_timer_callback_t
|
||||||
rcl_timer_exchange_callback(rcl_timer_t * timer, const rcl_timer_callback_t new_callback);
|
rcl_timer_exchange_callback(rcl_timer_t * timer, const rcl_timer_callback_t new_callback);
|
||||||
|
|
||||||
|
@ -335,6 +346,7 @@ rcl_timer_exchange_callback(rcl_timer_t * timer, const rcl_timer_callback_t new_
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_timer_cancel(rcl_timer_t * timer);
|
rcl_timer_cancel(rcl_timer_t * timer);
|
||||||
|
|
||||||
|
@ -355,6 +367,7 @@ rcl_timer_cancel(rcl_timer_t * timer);
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_timer_is_canceled(const rcl_timer_t * timer, bool * is_canceled);
|
rcl_timer_is_canceled(const rcl_timer_t * timer, bool * is_canceled);
|
||||||
|
|
||||||
|
@ -373,6 +386,7 @@ rcl_timer_is_canceled(const rcl_timer_t * timer, bool * is_canceled);
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_timer_reset(rcl_timer_t * timer);
|
rcl_timer_reset(rcl_timer_t * timer);
|
||||||
|
|
||||||
|
|
58
rcl/include/rcl/visibility_control.h
Normal file
58
rcl/include/rcl/visibility_control.h
Normal file
|
@ -0,0 +1,58 @@
|
||||||
|
// Copyright 2014 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__VISIBILITY_CONTROL_H_
|
||||||
|
#define RCL__VISIBILITY_CONTROL_H_
|
||||||
|
|
||||||
|
#if __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
|
||||||
|
// https://gcc.gnu.org/wiki/Visibility
|
||||||
|
|
||||||
|
#if defined _WIN32 || defined __CYGWIN__
|
||||||
|
#ifdef __GNUC__
|
||||||
|
#define RCL_EXPORT __attribute__ ((dllexport))
|
||||||
|
#define RCL_IMPORT __attribute__ ((dllimport))
|
||||||
|
#else
|
||||||
|
#define RCL_EXPORT __declspec(dllexport)
|
||||||
|
#define RCL_IMPORT __declspec(dllimport)
|
||||||
|
#endif
|
||||||
|
#ifdef RCL_BUILDING_DLL
|
||||||
|
#define RCL_PUBLIC RCL_EXPORT
|
||||||
|
#else
|
||||||
|
#define RCL_PUBLIC RCL_IMPORT
|
||||||
|
#endif
|
||||||
|
#define RCL_PUBLIC_TYPE RCL_PUBLIC
|
||||||
|
#define RCL_LOCAL
|
||||||
|
#else
|
||||||
|
#define RCL_EXPORT __attribute__ ((visibility("default")))
|
||||||
|
#define RCL_IMPORT
|
||||||
|
#if __GNUC__ >= 4
|
||||||
|
#define RCL_PUBLIC __attribute__ ((visibility("default")))
|
||||||
|
#define RCL_LOCAL __attribute__ ((visibility("hidden")))
|
||||||
|
#else
|
||||||
|
#define RCL_PUBLIC
|
||||||
|
#define RCL_LOCAL
|
||||||
|
#endif
|
||||||
|
#define RCL_PUBLIC_TYPE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // RCL__VISIBILITY_CONTROL_H_
|
|
@ -27,6 +27,7 @@ extern "C"
|
||||||
#include "rcl/guard_condition.h"
|
#include "rcl/guard_condition.h"
|
||||||
#include "rcl/timer.h"
|
#include "rcl/timer.h"
|
||||||
#include "rcl/types.h"
|
#include "rcl/types.h"
|
||||||
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
struct rcl_wait_set_impl_t;
|
struct rcl_wait_set_impl_t;
|
||||||
|
|
||||||
|
@ -47,6 +48,7 @@ typedef struct rcl_wait_set_t
|
||||||
} rcl_wait_set_t;
|
} rcl_wait_set_t;
|
||||||
|
|
||||||
/// Return a rcl_wait_set_t struct with members set to NULL.
|
/// Return a rcl_wait_set_t struct with members set to NULL.
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_wait_set_t
|
rcl_wait_set_t
|
||||||
rcl_get_zero_initialized_wait_set();
|
rcl_get_zero_initialized_wait_set();
|
||||||
|
|
||||||
|
@ -90,6 +92,7 @@ rcl_get_zero_initialized_wait_set();
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_init(
|
rcl_wait_set_init(
|
||||||
rcl_wait_set_t * wait_set,
|
rcl_wait_set_t * wait_set,
|
||||||
|
@ -117,6 +120,7 @@ rcl_wait_set_init(
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_fini(rcl_wait_set_t * wait_set);
|
rcl_wait_set_fini(rcl_wait_set_t * wait_set);
|
||||||
|
|
||||||
|
@ -133,6 +137,7 @@ rcl_wait_set_fini(rcl_wait_set_t * wait_set);
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * allocator);
|
rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * allocator);
|
||||||
|
|
||||||
|
@ -151,6 +156,7 @@ rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * al
|
||||||
* RCL_RET_WAIT_SET_FULL if the subscription set is full, or
|
* RCL_RET_WAIT_SET_FULL if the subscription set is full, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_add_subscription(
|
rcl_wait_set_add_subscription(
|
||||||
rcl_wait_set_t * wait_set,
|
rcl_wait_set_t * wait_set,
|
||||||
|
@ -171,6 +177,7 @@ rcl_wait_set_add_subscription(
|
||||||
* RCL_RET_WAIT_SET_INVALID if the wait set is zero initialized, or
|
* RCL_RET_WAIT_SET_INVALID if the wait set is zero initialized, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_clear_subscriptions(rcl_wait_set_t * wait_set);
|
rcl_wait_set_clear_subscriptions(rcl_wait_set_t * wait_set);
|
||||||
|
|
||||||
|
@ -199,6 +206,7 @@ rcl_wait_set_clear_subscriptions(rcl_wait_set_t * wait_set);
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* RCL_RET_ERROR if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_resize_subscriptions(rcl_wait_set_t * wait_set, size_t size);
|
rcl_wait_set_resize_subscriptions(rcl_wait_set_t * wait_set, size_t size);
|
||||||
|
|
||||||
|
@ -206,6 +214,7 @@ rcl_wait_set_resize_subscriptions(rcl_wait_set_t * wait_set, size_t size);
|
||||||
/* This function behaves exactly the same as for subscriptions.
|
/* This function behaves exactly the same as for subscriptions.
|
||||||
* \see rcl_wait_set_add_subscription
|
* \see rcl_wait_set_add_subscription
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_add_guard_condition(
|
rcl_wait_set_add_guard_condition(
|
||||||
rcl_wait_set_t * wait_set,
|
rcl_wait_set_t * wait_set,
|
||||||
|
@ -215,6 +224,7 @@ rcl_wait_set_add_guard_condition(
|
||||||
/* This function behaves exactly the same as for subscriptions.
|
/* This function behaves exactly the same as for subscriptions.
|
||||||
* \see rcl_wait_set_clear_subscriptions
|
* \see rcl_wait_set_clear_subscriptions
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_clear_guard_conditions(rcl_wait_set_t * wait_set);
|
rcl_wait_set_clear_guard_conditions(rcl_wait_set_t * wait_set);
|
||||||
|
|
||||||
|
@ -222,6 +232,7 @@ rcl_wait_set_clear_guard_conditions(rcl_wait_set_t * wait_set);
|
||||||
/* This function behaves exactly the same as for subscriptions.
|
/* This function behaves exactly the same as for subscriptions.
|
||||||
* \see rcl_wait_set_resize_subscriptions
|
* \see rcl_wait_set_resize_subscriptions
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_resize_guard_conditions(rcl_wait_set_t * wait_set, size_t size);
|
rcl_wait_set_resize_guard_conditions(rcl_wait_set_t * wait_set, size_t size);
|
||||||
|
|
||||||
|
@ -229,6 +240,7 @@ rcl_wait_set_resize_guard_conditions(rcl_wait_set_t * wait_set, size_t size);
|
||||||
/* This function behaves exactly the same as for subscriptions.
|
/* This function behaves exactly the same as for subscriptions.
|
||||||
* \see rcl_wait_set_add_subscription
|
* \see rcl_wait_set_add_subscription
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_add_timer(
|
rcl_wait_set_add_timer(
|
||||||
rcl_wait_set_t * wait_set,
|
rcl_wait_set_t * wait_set,
|
||||||
|
@ -238,6 +250,7 @@ rcl_wait_set_add_timer(
|
||||||
/* This function behaves exactly the same as for subscriptions.
|
/* This function behaves exactly the same as for subscriptions.
|
||||||
* \see rcl_wait_set_clear_subscriptions
|
* \see rcl_wait_set_clear_subscriptions
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_clear_timers(rcl_wait_set_t * wait_set);
|
rcl_wait_set_clear_timers(rcl_wait_set_t * wait_set);
|
||||||
|
|
||||||
|
@ -245,6 +258,7 @@ rcl_wait_set_clear_timers(rcl_wait_set_t * wait_set);
|
||||||
/* This function behaves exactly the same as for subscriptions.
|
/* This function behaves exactly the same as for subscriptions.
|
||||||
* \see rcl_wait_set_resize_subscriptions
|
* \see rcl_wait_set_resize_subscriptions
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait_set_resize_timers(rcl_wait_set_t * wait_set, size_t size);
|
rcl_wait_set_resize_timers(rcl_wait_set_t * wait_set, size_t size);
|
||||||
|
|
||||||
|
@ -337,6 +351,7 @@ rcl_wait_set_resize_timers(rcl_wait_set_t * wait_set, size_t size);
|
||||||
* RCL_RET_TIMEOUT if the timeout expired before something was ready, or
|
* RCL_RET_TIMEOUT if the timeout expired before something was ready, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_wait(rcl_wait_set_t * wait_set, int64_t timeout);
|
rcl_wait(rcl_wait_set_t * wait_set, int64_t timeout);
|
||||||
|
|
||||||
|
|
|
@ -34,6 +34,9 @@ rcl_impl_getenv(const char * env_name, const char ** env_value)
|
||||||
*env_value = NULL;
|
*env_value = NULL;
|
||||||
#if !defined(WIN32)
|
#if !defined(WIN32)
|
||||||
*env_value = getenv(env_name);
|
*env_value = getenv(env_name);
|
||||||
|
if (*env_value == NULL) {
|
||||||
|
*env_value = "";
|
||||||
|
}
|
||||||
#else
|
#else
|
||||||
size_t required_size;
|
size_t required_size;
|
||||||
errno_t ret = getenv_s(&required_size, __env_buffer, sizeof(__env_buffer), env_name);
|
errno_t ret = getenv_s(&required_size, __env_buffer, sizeof(__env_buffer), env_name);
|
||||||
|
|
|
@ -31,19 +31,20 @@ extern "C"
|
||||||
error_statement; \
|
error_statement; \
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Retrieve the value of the given environment variable if it exists, or NULL.
|
/// Retrieve the value of the given environment variable if it exists, or "".
|
||||||
/* The returned char is only valid until the next time this function is called,
|
/* The returned cstring is only valid until the next time this function is
|
||||||
* because the returned char * is a direct pointer to the static storage.
|
* called, because it is a direct pointer to the static storage.
|
||||||
* The returned value char * variable should never have free() called on it.
|
* The returned value char * variable should never have free() called on it.
|
||||||
|
* If the environment variable is not set, an empty string will be returned.
|
||||||
*
|
*
|
||||||
* Environment variable values will be truncated at 2048 characters on Windows.
|
* Environment variables will be truncated at 2048 characters on Windows.
|
||||||
*
|
*
|
||||||
* This function does not allocate heap memory, but the system calls might.
|
* This function does not allocate heap memory, but the system calls might.
|
||||||
* This function is not thread-safe.
|
* This function is not thread-safe.
|
||||||
* This function is not lock-free.
|
* This function is not lock-free.
|
||||||
*
|
*
|
||||||
* \param[in] env_name the name of the environment variable
|
* \param[in] env_name the name of the environment variable
|
||||||
* \param[out] env_value pointer to the value cstring
|
* \param[out] env_value pointer to the value cstring, or "" if unset
|
||||||
* \return RCL_RET_OK if the value is retrieved successfully, or
|
* \return RCL_RET_OK if the value is retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* RCL_RET_ERROR an unspecified error occur.
|
||||||
|
|
|
@ -16,8 +16,11 @@ if(AMENT_ENABLE_TESTING)
|
||||||
set_target_properties(${PROJECT_NAME}_memory_tools PROPERTIES COMPILE_FLAGS "-std=c++11")
|
set_target_properties(${PROJECT_NAME}_memory_tools PROPERTIES COMPILE_FLAGS "-std=c++11")
|
||||||
endif()
|
endif()
|
||||||
target_link_libraries(${PROJECT_NAME}_memory_tools ${GTEST_LIBRARIES} ${extra_test_libraries})
|
target_link_libraries(${PROJECT_NAME}_memory_tools ${GTEST_LIBRARIES} ${extra_test_libraries})
|
||||||
|
target_compile_definitions(${PROJECT_NAME}_memory_tools
|
||||||
|
PRIVATE "RCL_MEMORY_TOOLS_BUILDING_DLL")
|
||||||
list(APPEND extra_test_libraries ${PROJECT_NAME}_memory_tools)
|
list(APPEND extra_test_libraries ${PROJECT_NAME}_memory_tools)
|
||||||
|
|
||||||
|
if(NOT WIN32)
|
||||||
ament_add_gtest(test_memory_tools test_memory_tools.cpp ENV ${extra_memory_tools_env})
|
ament_add_gtest(test_memory_tools test_memory_tools.cpp ENV ${extra_memory_tools_env})
|
||||||
if(TARGET test_memory_tools)
|
if(TARGET test_memory_tools)
|
||||||
target_include_directories(test_memory_tools PUBLIC
|
target_include_directories(test_memory_tools PUBLIC
|
||||||
|
@ -29,6 +32,7 @@ if(AMENT_ENABLE_TESTING)
|
||||||
endif()
|
endif()
|
||||||
target_link_libraries(test_memory_tools ${PROJECT_NAME} ${extra_test_libraries})
|
target_link_libraries(test_memory_tools ${PROJECT_NAME} ${extra_test_libraries})
|
||||||
endif()
|
endif()
|
||||||
|
endif()
|
||||||
|
|
||||||
ament_add_gtest(test_allocator rcl/test_allocator.cpp ENV ${extra_memory_tools_env})
|
ament_add_gtest(test_allocator rcl/test_allocator.cpp ENV ${extra_memory_tools_env})
|
||||||
if(TARGET test_allocator)
|
if(TARGET test_allocator)
|
||||||
|
|
|
@ -48,7 +48,7 @@ void stop_memory_checking()
|
||||||
/******************************************************************************
|
/******************************************************************************
|
||||||
* End Apple
|
* End Apple
|
||||||
*****************************************************************************/
|
*****************************************************************************/
|
||||||
#elif defined(WIN32)
|
// #elif defined(WIN32)
|
||||||
/******************************************************************************
|
/******************************************************************************
|
||||||
* Begin Windows
|
* Begin Windows
|
||||||
*****************************************************************************/
|
*****************************************************************************/
|
||||||
|
@ -61,13 +61,37 @@ void stop_memory_checking()
|
||||||
#else
|
#else
|
||||||
// Default case: do nothing.
|
// Default case: do nothing.
|
||||||
|
|
||||||
|
#include "./memory_tools.hpp"
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
void start_memory_checking()
|
void start_memory_checking()
|
||||||
{
|
{
|
||||||
MALLOC_PRINTF("starting memory checking... not available\n");
|
printf("starting memory checking... not available\n");
|
||||||
}
|
}
|
||||||
void stop_memory_checking()
|
void stop_memory_checking()
|
||||||
{
|
{
|
||||||
MALLOC_PRINTF("stopping memory checking... not available\n");
|
printf("stopping memory checking... not available\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void assert_no_malloc_begin() {}
|
||||||
|
|
||||||
|
void assert_no_malloc_end() {}
|
||||||
|
|
||||||
|
void set_on_unepexcted_malloc_callback(UnexpectedCallbackType callback) {}
|
||||||
|
|
||||||
|
void assert_no_realloc_begin() {}
|
||||||
|
|
||||||
|
void assert_no_realloc_end() {}
|
||||||
|
|
||||||
|
void set_on_unepexcted_realloc_callback(UnexpectedCallbackType callback) {}
|
||||||
|
|
||||||
|
void assert_no_free_begin() {}
|
||||||
|
|
||||||
|
void assert_no_free_end() {}
|
||||||
|
|
||||||
|
void set_on_unepexcted_free_callback(UnexpectedCallbackType callback) {}
|
||||||
|
|
||||||
|
void memory_checking_thread_init() {}
|
||||||
|
|
||||||
#endif // !defined(WIN32)
|
#endif // !defined(WIN32)
|
||||||
|
|
|
@ -19,35 +19,89 @@
|
||||||
#ifndef MEMORY_TOOLS_HPP_
|
#ifndef MEMORY_TOOLS_HPP_
|
||||||
#define MEMORY_TOOLS_HPP_
|
#define MEMORY_TOOLS_HPP_
|
||||||
|
|
||||||
#include <gtest/gtest.h>
|
|
||||||
#include <stddef.h>
|
#include <stddef.h>
|
||||||
|
|
||||||
#include <functional>
|
#include <functional>
|
||||||
|
|
||||||
|
// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
|
||||||
|
// https://gcc.gnu.org/wiki/Visibility
|
||||||
|
|
||||||
|
#if defined _WIN32 || defined __CYGWIN__
|
||||||
|
#ifdef __GNUC__
|
||||||
|
#define RCL_MEMORY_TOOLS_EXPORT __attribute__ ((dllexport))
|
||||||
|
#define RCL_MEMORY_TOOLS_IMPORT __attribute__ ((dllimport))
|
||||||
|
#else
|
||||||
|
#define RCL_MEMORY_TOOLS_EXPORT __declspec(dllexport)
|
||||||
|
#define RCL_MEMORY_TOOLS_IMPORT __declspec(dllimport)
|
||||||
|
#endif
|
||||||
|
#ifdef RCL_MEMORY_TOOLS_BUILDING_DLL
|
||||||
|
#define RCL_MEMORY_TOOLS_PUBLIC RCL_MEMORY_TOOLS_EXPORT
|
||||||
|
#else
|
||||||
|
#define RCL_MEMORY_TOOLS_PUBLIC RCL_MEMORY_TOOLS_IMPORT
|
||||||
|
#endif
|
||||||
|
#define RCL_MEMORY_TOOLS_PUBLIC_TYPE RCL_MEMORY_TOOLS_PUBLIC
|
||||||
|
#define RCL_MEMORY_TOOLS_LOCAL
|
||||||
|
#else
|
||||||
|
#define RCL_MEMORY_TOOLS_EXPORT __attribute__ ((visibility("default")))
|
||||||
|
#define RCL_MEMORY_TOOLS_IMPORT
|
||||||
|
#if __GNUC__ >= 4
|
||||||
|
#define RCL_MEMORY_TOOLS_PUBLIC __attribute__ ((visibility("default")))
|
||||||
|
#define RCL_MEMORY_TOOLS_LOCAL __attribute__ ((visibility("hidden")))
|
||||||
|
#else
|
||||||
|
#define RCL_MEMORY_TOOLS_PUBLIC
|
||||||
|
#define RCL_MEMORY_TOOLS_LOCAL
|
||||||
|
#endif
|
||||||
|
#define RCL_MEMORY_TOOLS_PUBLIC_TYPE
|
||||||
|
#endif
|
||||||
|
|
||||||
typedef std::function<void ()> UnexpectedCallbackType;
|
typedef std::function<void ()> UnexpectedCallbackType;
|
||||||
|
|
||||||
void start_memory_checking();
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
|
void
|
||||||
|
start_memory_checking();
|
||||||
|
|
||||||
#define ASSERT_NO_MALLOC(statements) \
|
#define ASSERT_NO_MALLOC(statements) \
|
||||||
assert_no_malloc_begin(); statements; assert_no_malloc_end();
|
assert_no_malloc_begin(); statements; assert_no_malloc_end();
|
||||||
void assert_no_malloc_begin();
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
void assert_no_malloc_end();
|
void
|
||||||
void set_on_unepexcted_malloc_callback(UnexpectedCallbackType callback);
|
assert_no_malloc_begin();
|
||||||
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
|
void
|
||||||
|
assert_no_malloc_end();
|
||||||
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
|
void
|
||||||
|
set_on_unepexcted_malloc_callback(UnexpectedCallbackType callback);
|
||||||
|
|
||||||
#define ASSERT_NO_REALLOC(statements) \
|
#define ASSERT_NO_REALLOC(statements) \
|
||||||
assert_no_realloc_begin(); statements; assert_no_realloc_end();
|
assert_no_realloc_begin(); statements; assert_no_realloc_end();
|
||||||
void assert_no_realloc_begin();
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
void assert_no_realloc_end();
|
void
|
||||||
void set_on_unepexcted_realloc_callback(UnexpectedCallbackType callback);
|
assert_no_realloc_begin();
|
||||||
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
|
void
|
||||||
|
assert_no_realloc_end();
|
||||||
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
|
void
|
||||||
|
set_on_unepexcted_realloc_callback(UnexpectedCallbackType callback);
|
||||||
|
|
||||||
#define ASSERT_NO_FREE(statements) \
|
#define ASSERT_NO_FREE(statements) \
|
||||||
assert_no_free_begin(); statements; assert_no_free_end();
|
assert_no_free_begin(); statements; assert_no_free_end();
|
||||||
void assert_no_free_begin();
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
void assert_no_free_end();
|
void
|
||||||
void set_on_unepexcted_free_callback(UnexpectedCallbackType callback);
|
assert_no_free_begin();
|
||||||
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
|
void
|
||||||
|
assert_no_free_end();
|
||||||
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
|
void
|
||||||
|
set_on_unepexcted_free_callback(UnexpectedCallbackType callback);
|
||||||
|
|
||||||
void stop_memory_checking();
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
|
void
|
||||||
|
stop_memory_checking();
|
||||||
|
|
||||||
void memory_checking_thread_init();
|
RCL_MEMORY_TOOLS_PUBLIC
|
||||||
|
void
|
||||||
|
memory_checking_thread_init();
|
||||||
|
|
||||||
#endif // MEMORY_TOOLS_HPP_
|
#endif // MEMORY_TOOLS_HPP_
|
||||||
|
|
|
@ -49,6 +49,10 @@ public:
|
||||||
/* Tests the default allocator.
|
/* Tests the default allocator.
|
||||||
*/
|
*/
|
||||||
TEST_F(TestAllocatorFixture, test_default_allocator_normal) {
|
TEST_F(TestAllocatorFixture, test_default_allocator_normal) {
|
||||||
|
#ifdef WIN32
|
||||||
|
printf("Allocator tests disabled on Windows.\n");
|
||||||
|
return;
|
||||||
|
#endif
|
||||||
ASSERT_NO_MALLOC(
|
ASSERT_NO_MALLOC(
|
||||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
)
|
)
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
#include "../../src/rcl/common.h"
|
#include "../../src/rcl/common.h"
|
||||||
|
#include "../../src/rcl/common.c"
|
||||||
|
|
||||||
/* Tests the default allocator.
|
/* Tests the default allocator.
|
||||||
*
|
*
|
||||||
|
@ -31,21 +32,21 @@ TEST(TestCommon, test_getenv) {
|
||||||
const char * env;
|
const char * env;
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
ret = rcl_impl_getenv("NORMAL_TEST", NULL);
|
ret = rcl_impl_getenv("NORMAL_TEST", NULL);
|
||||||
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
ret = rcl_impl_getenv(NULL, &env);
|
ret = rcl_impl_getenv(NULL, &env);
|
||||||
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
ret = rcl_impl_getenv("SHOULD_NOT_EXIST_TEST", &env);
|
ret = rcl_impl_getenv("SHOULD_NOT_EXIST_TEST", &env);
|
||||||
EXPECT_EQ(ret, RCL_RET_OK);
|
EXPECT_EQ(RCL_RET_OK, ret);
|
||||||
EXPECT_EQ(env, nullptr) << std::string(env);
|
EXPECT_EQ("", std::string(env)) << std::string(env);
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
ret = rcl_impl_getenv("NORMAL_TEST", &env);
|
ret = rcl_impl_getenv("NORMAL_TEST", &env);
|
||||||
EXPECT_EQ(ret, RCL_RET_OK);
|
EXPECT_EQ(RCL_RET_OK, ret);
|
||||||
ASSERT_NE(env, nullptr);
|
ASSERT_NE(nullptr, env);
|
||||||
EXPECT_EQ(std::string(env), "foo");
|
EXPECT_EQ("foo", std::string(env));
|
||||||
ret = rcl_impl_getenv("EMPTY_TEST", &env);
|
ret = rcl_impl_getenv("EMPTY_TEST", &env);
|
||||||
EXPECT_EQ(ret, RCL_RET_OK);
|
EXPECT_EQ(RCL_RET_OK, ret);
|
||||||
ASSERT_NE(env, nullptr);
|
ASSERT_NE(nullptr, env);
|
||||||
EXPECT_EQ(std::string(env), "");
|
EXPECT_EQ("", std::string(env));
|
||||||
}
|
}
|
||||||
|
|
|
@ -96,14 +96,14 @@ TEST_F(TestTimeFixture, test_rcl_steady_time_point_now) {
|
||||||
stop_memory_checking();
|
stop_memory_checking();
|
||||||
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe();
|
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe();
|
||||||
EXPECT_NE(now.nanoseconds, 0);
|
EXPECT_NE(now.nanoseconds, 0);
|
||||||
// Compare to std::chrono::steady_clock time (within a second).
|
// Compare to std::chrono::steady_clock difference of two times (within a second).
|
||||||
now = {0};
|
now = {0};
|
||||||
ret = rcl_steady_time_point_now(&now);
|
ret = rcl_steady_time_point_now(&now);
|
||||||
{
|
|
||||||
std::chrono::steady_clock::time_point now_sc = std::chrono::steady_clock::now();
|
std::chrono::steady_clock::time_point now_sc = std::chrono::steady_clock::now();
|
||||||
auto now_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(now_sc.time_since_epoch());
|
rcl_steady_time_point_t later;
|
||||||
int64_t now_ns_int = now_ns.count();
|
ret = rcl_steady_time_point_now(&later);
|
||||||
int64_t now_diff = now.nanoseconds - now_ns_int;
|
std::chrono::steady_clock::time_point later_sc = std::chrono::steady_clock::now();
|
||||||
EXPECT_LE(llabs(now_diff), RCL_MS_TO_NS(1000)) << "steady_clock differs";
|
uint64_t steady_diff = later.nanoseconds - now.nanoseconds;
|
||||||
}
|
uint64_t sc_diff = (now_sc - later_sc).count();
|
||||||
|
EXPECT_LE(llabs(steady_diff - sc_diff), RCL_MS_TO_NS(1000)) << "steady_clock differs";
|
||||||
}
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue